From 678914be25d8e0c39caae0c02f98fe8cb946dd03 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 6 Jul 2017 14:00:58 -0500 Subject: [PATCH 001/112] Patch M23 to work around Simplify3D bug Addressing #7227 --- Marlin/Marlin_main.cpp | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 6f52f208d..a2bd4a384 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -6256,7 +6256,11 @@ inline void gcode_M17() { /** * M23: Open a file */ - inline void gcode_M23() { card.openFile(parser.string_arg, true); } + inline void gcode_M23() { + // Simplify3D includes the size, so zero out all spaces (#7227) + for (char *fn = parser.string_arg; *fn; ++fn) if (*fn == ' ') *fn = '\0'; + card.openFile(parser.string_arg, true); + } /** * M24: Start or Resume SD Print From 11c589c3ec0cd996f2a58ec07421d086aad30991 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 6 Jul 2017 14:06:39 -0500 Subject: [PATCH 002/112] Fix compile issue with G38 Fixes #7250 --- .travis.yml | 2 +- Marlin/Marlin_main.cpp | 4 ++-- Marlin/gcode.cpp | 2 +- Marlin/gcode.h | 2 +- 4 files changed, 5 insertions(+), 5 deletions(-) diff --git a/.travis.yml b/.travis.yml index f12b1e891..f3ccc3247 100644 --- a/.travis.yml +++ b/.travis.yml @@ -109,7 +109,7 @@ script: - restore_configs - opt_enable NUM_SERVOS Z_ENDSTOP_SERVO_NR Z_SERVO_ANGLES DEACTIVATE_SERVOS_AFTER_MOVE - opt_enable AUTO_BED_LEVELING_3POINT DEBUG_LEVELING_FEATURE EEPROM_SETTINGS EEPROM_CHITCHAT - - opt_enable_adv EXTENDED_CAPABILITIES_REPORT AUTO_REPORT_TEMPERATURES AUTOTEMP + - opt_enable_adv EXTENDED_CAPABILITIES_REPORT AUTO_REPORT_TEMPERATURES AUTOTEMP G38_PROBE_TARGET - build_marlin # # Test MESH_BED_LEVELING feature, with LCD diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index a2bd4a384..9fba4e1d2 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -10528,8 +10528,8 @@ void process_next_command() { #if ENABLED(G38_PROBE_TARGET) case 38: // G38.2 & G38.3 - if (subcode == 2 || subcode == 3) - gcode_G38(subcode == 2); + if (parser.subcode == 2 || parser.subcode == 3) + gcode_G38(parser.subcode == 2); break; #endif diff --git a/Marlin/gcode.cpp b/Marlin/gcode.cpp index 85b3a194c..edeb00e22 100644 --- a/Marlin/gcode.cpp +++ b/Marlin/gcode.cpp @@ -46,7 +46,7 @@ char *GCodeParser::command_ptr, char GCodeParser::command_letter; int GCodeParser::codenum; #if USE_GCODE_SUBCODES - int GCodeParser::subcode; + uint8_t GCodeParser::subcode; #endif #if ENABLED(FASTER_GCODE_PARSER) diff --git a/Marlin/gcode.h b/Marlin/gcode.h index 7b5857640..ace84d8de 100644 --- a/Marlin/gcode.h +++ b/Marlin/gcode.h @@ -91,7 +91,7 @@ public: static char command_letter; // G, M, or T static int codenum; // 123 #if USE_GCODE_SUBCODES - static int subcode; // .1 + static uint8_t subcode; // .1 #endif #if ENABLED(DEBUG_GCODE_PARSER) From c6d430670aa338b500cc79c341a6cbf540f3c82d Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 6 Jul 2017 14:17:54 -0500 Subject: [PATCH 003/112] Clear SHOW_BOOTSCREEN with no LCD --- Marlin/Conditionals_LCD.h | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/Marlin/Conditionals_LCD.h b/Marlin/Conditionals_LCD.h index deb89fb51..4dcda59cd 100644 --- a/Marlin/Conditionals_LCD.h +++ b/Marlin/Conditionals_LCD.h @@ -307,7 +307,10 @@ #endif #endif - #ifndef BOOTSCREEN_TIMEOUT + // Boot screens + #if DISABLED(ULTRA_LCD) + #undef SHOW_BOOTSCREEN + #elif !defined(BOOTSCREEN_TIMEOUT) #define BOOTSCREEN_TIMEOUT 2500 #endif From fc9ce65095ba125e0400a3fc8b8f8b708d8ff9da Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 6 Jul 2017 16:26:13 -0500 Subject: [PATCH 004/112] Add `BUSY_WHILE_HEATING` for hosts that need it --- Marlin/Configuration.h | 1 + Marlin/Marlin_main.cpp | 24 ++++++++++++++----- .../Anet/A6/Configuration.h | 1 + .../CL-260/Configuration.h | 1 + .../Cartesio/Configuration.h | 1 + .../Felix/Configuration.h | 1 + .../Felix/DUAL/Configuration.h | 1 + .../FolgerTech-i3-2020/Configuration.h | 1 + .../Hephestos/Configuration.h | 1 + .../Hephestos_2/Configuration.h | 1 + .../Infitary-i3-M508/Configuration.h | 1 + .../K8200/Configuration.h | 1 + .../K8400/Configuration.h | 1 + .../K8400/Dual-head/Configuration.h | 1 + .../M150/Configuration.h | 1 + .../RepRapWorld/Megatronics/Configuration.h | 1 + .../RigidBot/Configuration.h | 1 + .../SCARA/Configuration.h | 1 + .../TAZ4/Configuration.h | 1 + .../TinyBoy2/Configuration.h | 1 + .../WITBOX/Configuration.h | 1 + .../adafruit/ST7565/Configuration.h | 1 + .../FLSUN/auto_calibrate/Configuration.h | 1 + .../delta/FLSUN/kossel_mini/Configuration.h | 1 + .../delta/generic/Configuration.h | 1 + .../delta/kossel_mini/Configuration.h | 1 + .../delta/kossel_pro/Configuration.h | 1 + .../delta/kossel_xl/Configuration.h | 1 + .../gCreate_gMax1.5+/Configuration.h | 1 + .../makibox/Configuration.h | 1 + .../tvrrug/Round2/Configuration.h | 1 + .../wt150/Configuration.h | 1 + 32 files changed, 49 insertions(+), 6 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 46bc9aeaf..08e495e96 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -1002,6 +1002,7 @@ // #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 BUSY_WHILE_HEATING // Some hosts require "busy" messages even during heating // // M100 Free Memory Watcher diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 9fba4e1d2..64911ee9e 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -7302,7 +7302,9 @@ inline void gcode_M109() { wait_for_heatup = true; millis_t now, next_temp_ms = 0, next_cool_check_ms = 0; - KEEPALIVE_STATE(NOT_BUSY); + #if DISABLED(BUSY_WHILE_HEATING) + KEEPALIVE_STATE(NOT_BUSY); + #endif #if ENABLED(PRINTER_EVENT_LEDS) const float start_temp = thermalManager.degHotend(target_extruder); @@ -7385,7 +7387,9 @@ inline void gcode_M109() { #endif } - KEEPALIVE_STATE(IN_HANDLER); + #if DISABLED(BUSY_WHILE_HEATING) + KEEPALIVE_STATE(IN_HANDLER); + #endif } #if HAS_TEMP_BED @@ -7429,7 +7433,9 @@ inline void gcode_M109() { wait_for_heatup = true; millis_t now, next_temp_ms = 0, next_cool_check_ms = 0; - KEEPALIVE_STATE(NOT_BUSY); + #if DISABLED(BUSY_WHILE_HEATING) + KEEPALIVE_STATE(NOT_BUSY); + #endif target_extruder = active_extruder; // for print_heaterstates @@ -7504,7 +7510,9 @@ inline void gcode_M109() { } while (wait_for_heatup && TEMP_BED_CONDITIONS); if (wait_for_heatup) LCD_MESSAGEPGM(MSG_BED_DONE); - KEEPALIVE_STATE(IN_HANDLER); + #if DISABLED(BUSY_WHILE_HEATING) + KEEPALIVE_STATE(IN_HANDLER); + #endif } #endif // HAS_TEMP_BED @@ -8818,11 +8826,15 @@ inline void gcode_M303() { if (WITHIN(e, 0, HOTENDS - 1)) target_extruder = e; - KEEPALIVE_STATE(NOT_BUSY); // don't send "busy: processing" messages during autotune output + #if DISABLED(BUSY_WHILE_HEATING) + KEEPALIVE_STATE(NOT_BUSY); + #endif thermalManager.PID_autotune(temp, e, c, u); - KEEPALIVE_STATE(IN_HANDLER); + #if DISABLED(BUSY_WHILE_HEATING) + KEEPALIVE_STATE(IN_HANDLER); + #endif #else SERIAL_ERROR_START(); SERIAL_ERRORLNPGM(MSG_ERR_M303_DISABLED); diff --git a/Marlin/example_configurations/Anet/A6/Configuration.h b/Marlin/example_configurations/Anet/A6/Configuration.h index c007dfd87..93a0ba564 100644 --- a/Marlin/example_configurations/Anet/A6/Configuration.h +++ b/Marlin/example_configurations/Anet/A6/Configuration.h @@ -1158,6 +1158,7 @@ // #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 BUSY_WHILE_HEATING // Some hosts require "busy" messages even during heating // // M100 Free Memory Watcher diff --git a/Marlin/example_configurations/CL-260/Configuration.h b/Marlin/example_configurations/CL-260/Configuration.h index 368ac8583..9f0a82ac7 100644 --- a/Marlin/example_configurations/CL-260/Configuration.h +++ b/Marlin/example_configurations/CL-260/Configuration.h @@ -999,6 +999,7 @@ // #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 BUSY_WHILE_HEATING // Some hosts require "busy" messages even during heating // // M100 Free Memory Watcher diff --git a/Marlin/example_configurations/Cartesio/Configuration.h b/Marlin/example_configurations/Cartesio/Configuration.h index 18e5c7bbc..e086f3c96 100644 --- a/Marlin/example_configurations/Cartesio/Configuration.h +++ b/Marlin/example_configurations/Cartesio/Configuration.h @@ -996,6 +996,7 @@ // #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 BUSY_WHILE_HEATING // Some hosts require "busy" messages even during heating // // M100 Free Memory Watcher diff --git a/Marlin/example_configurations/Felix/Configuration.h b/Marlin/example_configurations/Felix/Configuration.h index dac548dcd..a5a060395 100644 --- a/Marlin/example_configurations/Felix/Configuration.h +++ b/Marlin/example_configurations/Felix/Configuration.h @@ -980,6 +980,7 @@ // #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 BUSY_WHILE_HEATING // Some hosts require "busy" messages even during heating // // M100 Free Memory Watcher diff --git a/Marlin/example_configurations/Felix/DUAL/Configuration.h b/Marlin/example_configurations/Felix/DUAL/Configuration.h index 9289dafb7..5a9fa5185 100644 --- a/Marlin/example_configurations/Felix/DUAL/Configuration.h +++ b/Marlin/example_configurations/Felix/DUAL/Configuration.h @@ -980,6 +980,7 @@ // #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 BUSY_WHILE_HEATING // Some hosts require "busy" messages even during heating // // M100 Free Memory Watcher diff --git a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h index 0bc709730..9efdf996f 100644 --- a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h +++ b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h @@ -1002,6 +1002,7 @@ // //#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 BUSY_WHILE_HEATING // Some hosts require "busy" messages even during heating // // M100 Free Memory Watcher diff --git a/Marlin/example_configurations/Hephestos/Configuration.h b/Marlin/example_configurations/Hephestos/Configuration.h index f5e915c31..c1501dbc2 100644 --- a/Marlin/example_configurations/Hephestos/Configuration.h +++ b/Marlin/example_configurations/Hephestos/Configuration.h @@ -988,6 +988,7 @@ // #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 BUSY_WHILE_HEATING // Some hosts require "busy" messages even during heating // // M100 Free Memory Watcher diff --git a/Marlin/example_configurations/Hephestos_2/Configuration.h b/Marlin/example_configurations/Hephestos_2/Configuration.h index 31d3e90c4..805ee35ec 100644 --- a/Marlin/example_configurations/Hephestos_2/Configuration.h +++ b/Marlin/example_configurations/Hephestos_2/Configuration.h @@ -991,6 +991,7 @@ // #define HOST_KEEPALIVE_FEATURE // Disable this if your host doesn't like keepalive messages #define DEFAULT_KEEPALIVE_INTERVAL 10 // Number of seconds between "busy" messages. Set with M113. +#define BUSY_WHILE_HEATING // Some hosts require "busy" messages even during heating // // M100 Free Memory Watcher diff --git a/Marlin/example_configurations/Infitary-i3-M508/Configuration.h b/Marlin/example_configurations/Infitary-i3-M508/Configuration.h index 1abb8f8f0..10bf51ee9 100644 --- a/Marlin/example_configurations/Infitary-i3-M508/Configuration.h +++ b/Marlin/example_configurations/Infitary-i3-M508/Configuration.h @@ -985,6 +985,7 @@ // #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 BUSY_WHILE_HEATING // Some hosts require "busy" messages even during heating // // M100 Free Memory Watcher diff --git a/Marlin/example_configurations/K8200/Configuration.h b/Marlin/example_configurations/K8200/Configuration.h index 170a018fc..dfc27e976 100644 --- a/Marlin/example_configurations/K8200/Configuration.h +++ b/Marlin/example_configurations/K8200/Configuration.h @@ -1027,6 +1027,7 @@ // #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 BUSY_WHILE_HEATING // Some hosts require "busy" messages even during heating // // M100 Free Memory Watcher diff --git a/Marlin/example_configurations/K8400/Configuration.h b/Marlin/example_configurations/K8400/Configuration.h index e647c8dd2..65633a769 100644 --- a/Marlin/example_configurations/K8400/Configuration.h +++ b/Marlin/example_configurations/K8400/Configuration.h @@ -998,6 +998,7 @@ // #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 BUSY_WHILE_HEATING // Some hosts require "busy" messages even during heating // // M100 Free Memory Watcher diff --git a/Marlin/example_configurations/K8400/Dual-head/Configuration.h b/Marlin/example_configurations/K8400/Dual-head/Configuration.h index 4fdebe88a..16ee469ad 100644 --- a/Marlin/example_configurations/K8400/Dual-head/Configuration.h +++ b/Marlin/example_configurations/K8400/Dual-head/Configuration.h @@ -998,6 +998,7 @@ // #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 BUSY_WHILE_HEATING // Some hosts require "busy" messages even during heating // // M100 Free Memory Watcher diff --git a/Marlin/example_configurations/M150/Configuration.h b/Marlin/example_configurations/M150/Configuration.h index 9ff8c97bb..d3d496eaa 100644 --- a/Marlin/example_configurations/M150/Configuration.h +++ b/Marlin/example_configurations/M150/Configuration.h @@ -1025,6 +1025,7 @@ // #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 BUSY_WHILE_HEATING // Some hosts require "busy" messages even during heating // // M100 Free Memory Watcher diff --git a/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h b/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h index 40ce7aee3..c6234d659 100644 --- a/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h +++ b/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h @@ -998,6 +998,7 @@ // #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 BUSY_WHILE_HEATING // Some hosts require "busy" messages even during heating // // M100 Free Memory Watcher diff --git a/Marlin/example_configurations/RigidBot/Configuration.h b/Marlin/example_configurations/RigidBot/Configuration.h index a51bfc7cf..dd88d90ef 100644 --- a/Marlin/example_configurations/RigidBot/Configuration.h +++ b/Marlin/example_configurations/RigidBot/Configuration.h @@ -996,6 +996,7 @@ // #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 BUSY_WHILE_HEATING // Some hosts require "busy" messages even during heating // // M100 Free Memory Watcher diff --git a/Marlin/example_configurations/SCARA/Configuration.h b/Marlin/example_configurations/SCARA/Configuration.h index f9e9de755..a12b3393f 100644 --- a/Marlin/example_configurations/SCARA/Configuration.h +++ b/Marlin/example_configurations/SCARA/Configuration.h @@ -1010,6 +1010,7 @@ // #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 BUSY_WHILE_HEATING // Some hosts require "busy" messages even during heating // // M100 Free Memory Watcher diff --git a/Marlin/example_configurations/TAZ4/Configuration.h b/Marlin/example_configurations/TAZ4/Configuration.h index 470a4ad73..825e7fab7 100644 --- a/Marlin/example_configurations/TAZ4/Configuration.h +++ b/Marlin/example_configurations/TAZ4/Configuration.h @@ -1017,6 +1017,7 @@ // #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 BUSY_WHILE_HEATING // Some hosts require "busy" messages even during heating // // M100 Free Memory Watcher diff --git a/Marlin/example_configurations/TinyBoy2/Configuration.h b/Marlin/example_configurations/TinyBoy2/Configuration.h index a5a7cf47e..07ac3077e 100644 --- a/Marlin/example_configurations/TinyBoy2/Configuration.h +++ b/Marlin/example_configurations/TinyBoy2/Configuration.h @@ -1054,6 +1054,7 @@ // #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 BUSY_WHILE_HEATING // Some hosts require "busy" messages even during heating // // M100 Free Memory Watcher diff --git a/Marlin/example_configurations/WITBOX/Configuration.h b/Marlin/example_configurations/WITBOX/Configuration.h index 266a1ae2b..97b628a5f 100644 --- a/Marlin/example_configurations/WITBOX/Configuration.h +++ b/Marlin/example_configurations/WITBOX/Configuration.h @@ -988,6 +988,7 @@ // #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 BUSY_WHILE_HEATING // Some hosts require "busy" messages even during heating // // M100 Free Memory Watcher diff --git a/Marlin/example_configurations/adafruit/ST7565/Configuration.h b/Marlin/example_configurations/adafruit/ST7565/Configuration.h index 19f2021c6..990b09543 100644 --- a/Marlin/example_configurations/adafruit/ST7565/Configuration.h +++ b/Marlin/example_configurations/adafruit/ST7565/Configuration.h @@ -998,6 +998,7 @@ // #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 BUSY_WHILE_HEATING // Some hosts require "busy" messages even during heating // // M100 Free Memory Watcher diff --git a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h index c336127b3..ff5c5a7fd 100644 --- a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h +++ b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h @@ -1122,6 +1122,7 @@ // #define HOST_KEEPALIVE_FEATURE // Disable this if your host doesn't like keepalive messages #define DEFAULT_KEEPALIVE_INTERVAL 5 // Number of seconds between "busy" messages. Set with M113. +#define BUSY_WHILE_HEATING // Some hosts require "busy" messages even during heating // // M100 Free Memory Watcher diff --git a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h index eaa3364ee..f5d022738 100644 --- a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h +++ b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h @@ -1117,6 +1117,7 @@ // #define HOST_KEEPALIVE_FEATURE // Disable this if your host doesn't like keepalive messages #define DEFAULT_KEEPALIVE_INTERVAL 5 // Number of seconds between "busy" messages. Set with M113. +#define BUSY_WHILE_HEATING // Some hosts require "busy" messages even during heating // // M100 Free Memory Watcher diff --git a/Marlin/example_configurations/delta/generic/Configuration.h b/Marlin/example_configurations/delta/generic/Configuration.h index 36ae17e97..3dcee31c6 100644 --- a/Marlin/example_configurations/delta/generic/Configuration.h +++ b/Marlin/example_configurations/delta/generic/Configuration.h @@ -1107,6 +1107,7 @@ // #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 BUSY_WHILE_HEATING // Some hosts require "busy" messages even during heating // // M100 Free Memory Watcher diff --git a/Marlin/example_configurations/delta/kossel_mini/Configuration.h b/Marlin/example_configurations/delta/kossel_mini/Configuration.h index c1e674909..1880f5ba9 100644 --- a/Marlin/example_configurations/delta/kossel_mini/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_mini/Configuration.h @@ -1110,6 +1110,7 @@ // #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 BUSY_WHILE_HEATING // Some hosts require "busy" messages even during heating // // M100 Free Memory Watcher diff --git a/Marlin/example_configurations/delta/kossel_pro/Configuration.h b/Marlin/example_configurations/delta/kossel_pro/Configuration.h index 59fe5dc42..34ac25c39 100644 --- a/Marlin/example_configurations/delta/kossel_pro/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_pro/Configuration.h @@ -1115,6 +1115,7 @@ // #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 BUSY_WHILE_HEATING // Some hosts require "busy" messages even during heating // // M100 Free Memory Watcher diff --git a/Marlin/example_configurations/delta/kossel_xl/Configuration.h b/Marlin/example_configurations/delta/kossel_xl/Configuration.h index 0b682d3d6..bba2d9d9b 100644 --- a/Marlin/example_configurations/delta/kossel_xl/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_xl/Configuration.h @@ -1173,6 +1173,7 @@ // #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 BUSY_WHILE_HEATING // Some hosts require "busy" messages even during heating // // M100 Free Memory Watcher diff --git a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h index 6667ef147..d7404f478 100644 --- a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h +++ b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h @@ -1014,6 +1014,7 @@ // //#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 BUSY_WHILE_HEATING // Some hosts require "busy" messages even during heating // // M100 Free Memory Watcher diff --git a/Marlin/example_configurations/makibox/Configuration.h b/Marlin/example_configurations/makibox/Configuration.h index e45e8d2e6..0c317fc51 100644 --- a/Marlin/example_configurations/makibox/Configuration.h +++ b/Marlin/example_configurations/makibox/Configuration.h @@ -1001,6 +1001,7 @@ // #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 BUSY_WHILE_HEATING // Some hosts require "busy" messages even during heating // // M100 Free Memory Watcher diff --git a/Marlin/example_configurations/tvrrug/Round2/Configuration.h b/Marlin/example_configurations/tvrrug/Round2/Configuration.h index 9edc8914c..ea2aed618 100644 --- a/Marlin/example_configurations/tvrrug/Round2/Configuration.h +++ b/Marlin/example_configurations/tvrrug/Round2/Configuration.h @@ -993,6 +993,7 @@ // #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 BUSY_WHILE_HEATING // Some hosts require "busy" messages even during heating // // M100 Free Memory Watcher diff --git a/Marlin/example_configurations/wt150/Configuration.h b/Marlin/example_configurations/wt150/Configuration.h index d9c4b4a2f..7487dcee5 100644 --- a/Marlin/example_configurations/wt150/Configuration.h +++ b/Marlin/example_configurations/wt150/Configuration.h @@ -1004,6 +1004,7 @@ // #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 BUSY_WHILE_HEATING // Some hosts require "busy" messages even during heating // // M100 Free Memory Watcher From f713f25fa5f3d8ef6fbf0c3c12d45b6cef5c93f1 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 6 Jul 2017 21:24:30 -0500 Subject: [PATCH 005/112] Clean up excess whitespace --- Marlin/Marlin_main.cpp | 8 +++---- .../FLSUN/auto_calibrate/Configuration.h | 2 +- .../delta/FLSUN/kossel_mini/Configuration.h | 2 +- .../delta/generic/Configuration.h | 2 +- .../delta/kossel_mini/Configuration.h | 2 +- .../delta/kossel_pro/Configuration.h | 2 +- .../delta/kossel_xl/Configuration.h | 2 +- Marlin/pins_PRINTRBOARD_REVF.h | 24 +++++++++---------- buildroot/share/git/mfup | 4 ++-- 9 files changed, 24 insertions(+), 24 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 64911ee9e..e33db937e 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -5280,7 +5280,7 @@ void home_all_axes() { gcode_G28(true); } #if DISABLED(PROBE_MANUALLY) home_offset[Z_AXIS] -= probe_pt(dx, dy, stow_after_each, 1, false); // 1st probe to set height #endif - + do { float z_at_pt[13] = { 0.0 }; @@ -5380,7 +5380,7 @@ void home_all_axes() { gcode_G28(true); } #if ENABLED(PROBE_MANUALLY) test_precision = 0.00; // forced end #endif - + switch (probe_points) { case 1: test_precision = 0.00; // forced end @@ -6259,7 +6259,7 @@ inline void gcode_M17() { inline void gcode_M23() { // Simplify3D includes the size, so zero out all spaces (#7227) for (char *fn = parser.string_arg; *fn; ++fn) if (*fn == ' ') *fn = '\0'; - card.openFile(parser.string_arg, true); + card.openFile(parser.string_arg, true); } /** @@ -12877,7 +12877,7 @@ void kill(const char* lcd_msg) { #if defined(ACTION_ON_KILL) SERIAL_ECHOLNPGM("//action:" ACTION_ON_KILL); #endif - + #if HAS_POWER_SWITCH SET_INPUT(PS_ON_PIN); #endif diff --git a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h index ff5c5a7fd..52acb8871 100644 --- a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h +++ b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h @@ -497,7 +497,7 @@ // Horizontal distance bridged by diagonal push rods when effector is centered. #define DELTA_RADIUS 101.0 //mm Get this value from auto calibrate - + // Trim adjustments for individual towers // tower angle corrections for X and Y tower / rotate XYZ so Z tower angle = 0 // measured in degrees anticlockwise looking from above the printer diff --git a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h index f5d022738..ec2e2b313 100644 --- a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h +++ b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h @@ -497,7 +497,7 @@ // Horizontal distance bridged by diagonal push rods when effector is centered. #define DELTA_RADIUS 101.0 //mm Get this value from auto calibrate - + // Trim adjustments for individual towers // tower angle corrections for X and Y tower / rotate XYZ so Z tower angle = 0 // measured in degrees anticlockwise looking from above the printer diff --git a/Marlin/example_configurations/delta/generic/Configuration.h b/Marlin/example_configurations/delta/generic/Configuration.h index 3dcee31c6..f69074b61 100644 --- a/Marlin/example_configurations/delta/generic/Configuration.h +++ b/Marlin/example_configurations/delta/generic/Configuration.h @@ -487,7 +487,7 @@ // Horizontal distance bridged by diagonal push rods when effector is centered. #define DELTA_RADIUS 124.0 //mm Get this value from auto calibrate - + // Trim adjustments for individual towers // tower angle corrections for X and Y tower / rotate XYZ so Z tower angle = 0 // measured in degrees anticlockwise looking from above the printer diff --git a/Marlin/example_configurations/delta/kossel_mini/Configuration.h b/Marlin/example_configurations/delta/kossel_mini/Configuration.h index 1880f5ba9..5118929cd 100644 --- a/Marlin/example_configurations/delta/kossel_mini/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_mini/Configuration.h @@ -487,7 +487,7 @@ // Horizontal distance bridged by diagonal push rods when effector is centered. #define DELTA_RADIUS 105.2 //mm Get this value from auto calibrate - + // Trim adjustments for individual towers // tower angle corrections for X and Y tower / rotate XYZ so Z tower angle = 0 // measured in degrees anticlockwise looking from above the printer diff --git a/Marlin/example_configurations/delta/kossel_pro/Configuration.h b/Marlin/example_configurations/delta/kossel_pro/Configuration.h index 34ac25c39..383413346 100644 --- a/Marlin/example_configurations/delta/kossel_pro/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_pro/Configuration.h @@ -473,7 +473,7 @@ // Horizontal distance bridged by diagonal push rods when effector is centered. #define DELTA_RADIUS 152.357 //mm Get this value from auto calibrate - + // Trim adjustments for individual towers // tower angle corrections for X and Y tower / rotate XYZ so Z tower angle = 0 // measured in degrees anticlockwise looking from above the printer diff --git a/Marlin/example_configurations/delta/kossel_xl/Configuration.h b/Marlin/example_configurations/delta/kossel_xl/Configuration.h index bba2d9d9b..6dfbf7792 100644 --- a/Marlin/example_configurations/delta/kossel_xl/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_xl/Configuration.h @@ -491,7 +491,7 @@ // Horizontal distance bridged by diagonal push rods when effector is centered. #define DELTA_RADIUS 174.1 //mm Get this value from auto calibrate - + // Trim adjustments for individual towers // tower angle corrections for X and Y tower / rotate XYZ so Z tower angle = 0 // measured in degrees anticlockwise looking from above the printer diff --git a/Marlin/pins_PRINTRBOARD_REVF.h b/Marlin/pins_PRINTRBOARD_REVF.h index 3adeb1203..0f1772c84 100644 --- a/Marlin/pins_PRINTRBOARD_REVF.h +++ b/Marlin/pins_PRINTRBOARD_REVF.h @@ -32,9 +32,9 @@ * * Teensyduino - http://www.pjrc.com/teensy/teensyduino.html * Installation instructions are at the above URL. - * + * * Select Teensy++ 2.0 in Arduino IDE from the 'Tools -> Boards' menu - * + * * Note: With Teensyduino extension, the Arduino IDE will report 130048 bytes of program storage space available, * but there is actually only 122880 bytes due to the larger DFU bootloader shipped by default on all Printrboard RevF. * @@ -99,8 +99,8 @@ #define DAC_STEPPER_CURRENT // Set default drive strength percents if not already defined - X, Y, Z, E axis -#ifndef DAC_MOTOR_CURRENT_DEFAULT - #define DAC_MOTOR_CURRENT_DEFAULT { 70, 70, 50, 70 } +#ifndef DAC_MOTOR_CURRENT_DEFAULT + #define DAC_MOTOR_CURRENT_DEFAULT { 70, 70, 50, 70 } #endif // Number of channels available for DAC @@ -170,17 +170,17 @@ #if ENABLED(MINIPANEL) #if ENABLED(USE_INTERNAL_SD) - // PIN FASTIO PIN# ATUSB90 PIN# Teensy2.0++ PIN# - #define SDSS 20 // 10 B0 + // PIN FASTIO PIN# ATUSB90 PIN# Teensy2.0++ PIN# + #define SDSS 20 // 10 B0 #define SD_DETECT_PIN -1 // no auto-detect SD insertion on built-in Printrboard SD reader #else - // PIN FASTIO PIN# ATUSB90 PIN# Teensy2.0++ PIN# Printrboard RevF Conn. MKSLCD12864 PIN# + // PIN FASTIO PIN# ATUSB90 PIN# Teensy2.0++ PIN# Printrboard RevF Conn. MKSLCD12864 PIN# #define SDSS 11 // 36 C1 EXP2-13 EXP2-07 #define SD_DETECT_PIN 9 // 34 E1 EXP2-11 EXP2-04 #endif - - // PIN FASTIO PIN# ATUSB90 PIN# Teensy2.0++ PIN# Printrboard RevF Conn. MKSLCD12864 PIN# - #define DOGLCD_A0 4 // 29 D4 EXP2-05 EXP1-04 + + // PIN FASTIO PIN# ATUSB90 PIN# Teensy2.0++ PIN# Printrboard RevF Conn. MKSLCD12864 PIN# + #define DOGLCD_A0 4 // 29 D4 EXP2-05 EXP1-04 #define DOGLCD_CS 5 // 30 D5 EXP2-06 EXP1-05 #define BTN_ENC 6 // 31 D6 EXP2-07 EXP1-09 #define BEEPER_PIN 7 // 32 D7 EXP2-08 EXP1-10 @@ -190,8 +190,8 @@ //#define LCD_BACKLIGHT_PIN 43 // 56 F5 EXP1-12 Not Implemented //#define SCK 21 // 11 B1 ICSP-04 EXP2-09 //#define MOSI 22 // 12 B2 ICSP-03 EXP2-05 - //#define MISO 23 // 13 B3 ICSP-06 EXP2-05 - + //#define MISO 23 // 13 B3 ICSP-06 EXP2-05 + // encoder connections present #define BLEN_A 0 #define BLEN_B 1 diff --git a/buildroot/share/git/mfup b/buildroot/share/git/mfup index cd65c46cc..df2da87b2 100755 --- a/buildroot/share/git/mfup +++ b/buildroot/share/git/mfup @@ -2,10 +2,10 @@ # # mfup # -# - Fetch latest upstream and replace the PR Target branch with +# - Fetch latest upstream and replace the PR Target branch with # - Rebase the (current or specified) branch on the PR Target # - Force-push the branch to 'origin' -# - +# - # [[ $# < 2 ]] || { echo "Usage: `basename $0` [branch]" 1>&2 ; exit 1; } From c7732db99d94c6d00f1835fb4494d4c1b11e500d Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 6 Jul 2017 21:25:56 -0500 Subject: [PATCH 006/112] Fix: Use of digitalRead, digitalWrite breaks on AT90USB --- Marlin/Marlin_main.cpp | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index e33db937e..2d157e54f 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -5854,7 +5854,7 @@ inline void gcode_G92() { WRITE(SPINDLE_LASER_ENABLE_PIN, !SPINDLE_LASER_ENABLE_INVERT); // turn spindle off delay_for_power_down(); } - digitalWrite(SPINDLE_DIR_PIN, rotation_dir); + WRITE(SPINDLE_DIR_PIN, rotation_dir); #endif /** @@ -6569,10 +6569,10 @@ inline void gcode_M42() { for (uint8_t i = 0; i < 4; i++) { servo[probe_index].move(z_servo_angle[0]); //deploy safe_delay(500); - deploy_state = digitalRead(PROBE_TEST_PIN); + deploy_state = READ(PROBE_TEST_PIN); servo[probe_index].move(z_servo_angle[1]); //stow safe_delay(500); - stow_state = digitalRead(PROBE_TEST_PIN); + stow_state = READ(PROBE_TEST_PIN); } if (probe_inverting != deploy_state) SERIAL_PROTOCOLLNPGM("WARNING - INVERTING setting probably backwards"); @@ -6607,9 +6607,9 @@ inline void gcode_M42() { if (0 == j % (500 * 1)) // keep cmd_timeout happy refresh_cmd_timeout(); - if (deploy_state != digitalRead(PROBE_TEST_PIN)) { // probe triggered + if (deploy_state != READ(PROBE_TEST_PIN)) { // probe triggered - for (probe_counter = 1; probe_counter < 50 && deploy_state != digitalRead(PROBE_TEST_PIN); ++probe_counter) + for (probe_counter = 1; probe_counter < 50 && deploy_state != READ(PROBE_TEST_PIN); ++probe_counter) safe_delay(2); if (probe_counter == 50) @@ -9876,9 +9876,9 @@ inline void gcode_M907() { if (USEABLE_HARDWARE_PWM(CASE_LIGHT_PIN)) { analogWrite(CASE_LIGHT_PIN, INVERT_CASE_LIGHT ? 255 - case_light_brightness : case_light_brightness ); } - else digitalWrite(CASE_LIGHT_PIN, INVERT_CASE_LIGHT ? LOW : HIGH ); + else WRITE(CASE_LIGHT_PIN, INVERT_CASE_LIGHT ? LOW : HIGH); } - else digitalWrite(CASE_LIGHT_PIN, INVERT_CASE_LIGHT ? HIGH : LOW); + else WRITE(CASE_LIGHT_PIN, INVERT_CASE_LIGHT ? HIGH : LOW); } #endif // HAS_CASE_LIGHT From 5ef1e5ef6086b8c5f4bd8952977afa45f7b7fad1 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 6 Jul 2017 21:47:50 -0500 Subject: [PATCH 007/112] Tweaks for M43 --- Marlin/Marlin_main.cpp | 22 +++++++++++----------- Marlin/fastio_AT90USB.h | 4 ++++ 2 files changed, 15 insertions(+), 11 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 2d157e54f..c224d1774 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -6474,20 +6474,20 @@ inline void gcode_M42() { else { report_pin_state_extended(pin, I_flag, true, "Pulsing "); #if AVR_AT90USB1286_FAMILY // Teensy IDEs don't know about these pins so must use FASTIO - if (pin == 46) { - SET_OUTPUT(46); + if (pin == TEENSY_E2) { + SET_OUTPUT(TEENSY_E2); for (int16_t j = 0; j < repeat; j++) { - WRITE(46, 0); safe_delay(wait); - WRITE(46, 1); safe_delay(wait); - WRITE(46, 0); safe_delay(wait); + WRITE(TEENSY_E2, LOW); safe_delay(wait); + WRITE(TEENSY_E2, HIGH); safe_delay(wait); + WRITE(TEENSY_E2, LOW); safe_delay(wait); } } - else if (pin == 47) { - SET_OUTPUT(47); + else if (pin == TEENSY_E3) { + SET_OUTPUT(TEENSY_E3); for (int16_t j = 0; j < repeat; j++) { - WRITE(47, 0); safe_delay(wait); - WRITE(47, 1); safe_delay(wait); - WRITE(47, 0); safe_delay(wait); + WRITE(TEENSY_E3, LOW); safe_delay(wait); + WRITE(TEENSY_E3, HIGH); safe_delay(wait); + WRITE(TEENSY_E3, LOW); safe_delay(wait); } } else @@ -6671,7 +6671,7 @@ inline void gcode_M42() { if (parser.seen('E')) { endstop_monitor_flag = parser.value_bool(); SERIAL_PROTOCOLPGM("endstop monitor "); - SERIAL_PROTOCOL(endstop_monitor_flag ? "en" : "dis"); + serialprintPGM(endstop_monitor_flag ? PSTR("en") : PSTR("dis")); SERIAL_PROTOCOLLNPGM("abled"); return; } diff --git a/Marlin/fastio_AT90USB.h b/Marlin/fastio_AT90USB.h index c643291f7..68463e18a 100644 --- a/Marlin/fastio_AT90USB.h +++ b/Marlin/fastio_AT90USB.h @@ -382,6 +382,10 @@ #define DIO47_WPORT PORTE #define DIO47_PWM NULL #define DIO47_DDR DDRE + +#define TEENSY_E2 46 +#define TEENSY_E3 47 + //-- end not supported by Teensyduino #undef PA0 From 9248a90a4c83a38a50eb48c7b6841917f233d698 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 6 Jul 2017 22:47:37 -0500 Subject: [PATCH 008/112] Assign -1 to LCD_PINS_D4-7 if not defined --- Marlin/pins.h | 13 +++++++++++++ Marlin/pins_CHEAPTRONIC.h | 4 ---- Marlin/pins_MINITRONICS.h | 4 ---- Marlin/pins_SAV_MKI.h | 4 ---- 4 files changed, 13 insertions(+), 12 deletions(-) diff --git a/Marlin/pins.h b/Marlin/pins.h index 2a0b92aa9..817c9dae4 100644 --- a/Marlin/pins.h +++ b/Marlin/pins.h @@ -470,6 +470,19 @@ #define Z_MIN_PIN -1 #endif +#ifndef LCD_PINS_D4 + #define LCD_PINS_D4 -1 +#endif +#ifndef LCD_PINS_D5 + #define LCD_PINS_D5 -1 +#endif +#ifndef LCD_PINS_D6 + #define LCD_PINS_D6 -1 +#endif +#ifndef LCD_PINS_D7 + #define LCD_PINS_D7 -1 +#endif + // // Dual X-carriage, Dual Y, Dual Z support // diff --git a/Marlin/pins_CHEAPTRONIC.h b/Marlin/pins_CHEAPTRONIC.h index d1da32cd8..a354a279b 100644 --- a/Marlin/pins_CHEAPTRONIC.h +++ b/Marlin/pins_CHEAPTRONIC.h @@ -81,10 +81,6 @@ // 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 // Cheaptronic v1.0 doesn't support keypad #define BTN_EN1 -1 diff --git a/Marlin/pins_MINITRONICS.h b/Marlin/pins_MINITRONICS.h index fbdf7cbb6..f224f200b 100644 --- a/Marlin/pins_MINITRONICS.h +++ b/Marlin/pins_MINITRONICS.h @@ -118,10 +118,6 @@ #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 diff --git a/Marlin/pins_SAV_MKI.h b/Marlin/pins_SAV_MKI.h index b1ed0bd8c..84646cc4c 100755 --- a/Marlin/pins_SAV_MKI.h +++ b/Marlin/pins_SAV_MKI.h @@ -155,10 +155,6 @@ #define BEEPER_PIN -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 #if ENABLED(SAV_3DLCD) // For LCD SHIFT register LCD From 61be28133d2e9e21df3cbf13a4a7022494c57101 Mon Sep 17 00:00:00 2001 From: essgcee Date: Thu, 6 Jul 2017 15:43:00 +0100 Subject: [PATCH 009/112] Support for Creality CR-10 Creality board is a Melzi / Sanguinololu variant, but using different pins for LCD control (and maybe other minor variations) --- Marlin/boards.h | 3 +- .../Creality/CR-10/Configuration.h | 1642 +++++++++++++++++ Marlin/pins.h | 6 +- Marlin/pins_MELZI_CREALITY.h | 100 + Marlin/pins_SANGUINOLOLU_11.h | 2 +- 5 files changed, 1749 insertions(+), 4 deletions(-) create mode 100644 Marlin/example_configurations/Creality/CR-10/Configuration.h create mode 100644 Marlin/pins_MELZI_CREALITY.h diff --git a/Marlin/boards.h b/Marlin/boards.h index 13c9ab887..cec937980 100644 --- a/Marlin/boards.h +++ b/Marlin/boards.h @@ -54,9 +54,10 @@ #define BOARD_SANGUINOLOLU_11 6 // Sanguinololu < 1.2 #define BOARD_SANGUINOLOLU_12 62 // Sanguinololu 1.2 and above #define BOARD_MELZI 63 // Melzi +#define BOARD_MELZI_MAKR3D 66 // Melzi with ATmega1284 (MaKr3d version) +#define BOARD_MELZI_CREALITY 89 // Melzi Creality3D board (for CR-10 etc) #define BOARD_STB_11 64 // STB V1.1 #define BOARD_AZTEEG_X1 65 // Azteeg X1 -#define BOARD_MELZI_MAKR3D 66 // Melzi with ATmega1284 (MaKr3d version) #define BOARD_AZTEEG_X3 67 // Azteeg X3 #define BOARD_AZTEEG_X3_PRO 68 // Azteeg X3 Pro #define BOARD_ANET_10 69 // Anet 1.0 (Melzi clone) diff --git a/Marlin/example_configurations/Creality/CR-10/Configuration.h b/Marlin/example_configurations/Creality/CR-10/Configuration.h new file mode 100644 index 000000000..caec496f9 --- /dev/null +++ b/Marlin/example_configurations/Creality/CR-10/Configuration.h @@ -0,0 +1,1642 @@ +/** + * 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 . + * + */ + +/** + * Configuration.h + * + * Basic settings such as: + * + * - Type of electronics + * - Type of temperature sensor + * - Printer geometry + * - Endstop configuration + * - LCD controller + * - Extra features + * + * Advanced settings can be found in Configuration_adv.h + * + */ +#ifndef CONFIGURATION_H +#define CONFIGURATION_H +#define CONFIGURATION_H_VERSION 010100 + +//=========================================================================== +//============================= Getting Started ============================= +//=========================================================================== + +/** + * Here are some standard links for getting your machine calibrated: + * + * http://reprap.org/wiki/Calibration + * http://youtu.be/wAL9d7FgInk + * http://calculator.josefprusa.cz + * http://reprap.org/wiki/Triffid_Hunter%27s_Calibration_Guide + * http://www.thingiverse.com/thing:5573 + * https://sites.google.com/site/repraplogphase/calibration-of-your-reprap + * http://www.thingiverse.com/thing:298812 + */ + +//=========================================================================== +//============================= DELTA Printer =============================== +//=========================================================================== +// For a Delta printer start with one of the configuration files in the +// example_configurations/delta directory and customize for your machine. +// + +//=========================================================================== +//============================= SCARA Printer =============================== +//=========================================================================== +// For a SCARA printer start with the configuration files in +// example_configurations/SCARA and customize for your machine. +// + +// @section info + +// User-specified version info of this build to display in [Pronterface, etc] terminal window during +// startup. Implementation of an idea by Prof Braino to inform user that any changes made to this +// 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 bootup in line 1 +//#define STRING_SPLASH_LINE2 WEBSITE_URL // will be shown during bootup in line 2 + +// +// *** VENDORS PLEASE READ ***************************************************** +// +// Marlin now allow you to have a vendor boot image to be displayed on machine +// start. When SHOW_CUSTOM_BOOTSCREEN is defined Marlin will first show your +// custom boot image and then the default Marlin boot image is shown. +// +// We suggest for you to take advantage of this new feature and keep the Marlin +// boot image unmodified. For an example have a look at the bq Hephestos 2 +// example configuration folder. +// +//#define SHOW_CUSTOM_BOOTSCREEN +// @section machine + +/** + * 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 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 +//#define BLUETOOTH + +// The following define selects which electronics board you have. +// Please choose the name from boards.h that matches your setup +#ifndef MOTHERBOARD + #define MOTHERBOARD BOARD_MELZI_CREALITY +#endif + +// Optional custom name for your RepStrap or other custom machine +// Displayed in the LCD "Ready" message +#define CUSTOM_MACHINE_NAME "CR-10" + +// 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 "00000000-0000-0000-0000-000000000000" + +// @section extruder + +// This defines the number of extruders +// :[1, 2, 3, 4, 5] +#define EXTRUDERS 1 + +// For Cyclops or any "multi-extruder" that shares a single nozzle. +//#define SINGLENOZZLE + +/** + * Průša MK2 Single Nozzle Multi-Material Multiplexer, and variants. + * + * This device allows one stepper driver on a control board to drive + * two to eight stepper motors, one at a time, in a manner suitable + * for extruders. + * + * This option only allows the multiplexer to switch on tool-change. + * Additional options to configure custom E moves are pending. + */ +//#define MK2_MULTIPLEXER +#if ENABLED(MK2_MULTIPLEXER) + // Override the default DIO selector pins here, if needed. + // Some pins files may provide defaults for these pins. + //#define E_MUX0_PIN 40 // Always Required + //#define E_MUX1_PIN 42 // Needed for 3 to 8 steppers + //#define E_MUX2_PIN 44 // Needed for 5 to 8 steppers +#endif + +// A dual extruder that uses a single stepper motor +//#define SWITCHING_EXTRUDER +#if ENABLED(SWITCHING_EXTRUDER) + #define SWITCHING_EXTRUDER_SERVO_NR 0 + #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1[, E2, E3] + #if EXTRUDERS > 3 + #define SWITCHING_EXTRUDER_E23_SERVO_NR 1 + #endif +#endif + +// A dual-nozzle that uses a servomotor to raise/lower one of the nozzles +//#define SWITCHING_NOZZLE +#if ENABLED(SWITCHING_NOZZLE) + #define SWITCHING_NOZZLE_SERVO_NR 0 + #define SWITCHING_NOZZLE_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 + //#define HOTEND_OFFSET_Z { 0.0, 0.0 } +#endif + +/** + * "Mixing Extruder" + * - Adds a new code, M165, to set the current mix factors. + * - Extends the stepping routines to move multiple steppers in proportion to the mix. + * - Optional support for Repetier Firmware M163, M164, and virtual extruder. + * - This implementation supports only a single extruder. + * - Enable DIRECT_MIXING_IN_G1 for Pia Taubert's reference implementation + */ +//#define MIXING_EXTRUDER +#if ENABLED(MIXING_EXTRUDER) + #define MIXING_STEPPERS 2 // Number of steppers in your mixing extruder + #define MIXING_VIRTUAL_TOOLS 16 // Use the Virtual Tool method with M163 and M164 + //#define DIRECT_MIXING_IN_G1 // Allow ABCDHI mix factors in G1 movement commands +#endif + +// Offset of the extruders (uncomment if using more than one and relying on firmware to position when changing). +// The offset has to be X=0, Y=0 for the extruder 0 hotend (default extruder). +// For the other hotends it is their distance from the extruder 0 hotend. +//#define 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 + +// @section machine + +/** + * 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 + +#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 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 + * 75 : 100k Generic Silicon Heat Pad with NTC 100K MGB18-104F39050L32 thermistor + * + * 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_4 0 +#define TEMP_SENSOR_BED 5 + +// 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 + +// Extruder temperature must be close to target for this long before M109 returns success +#define TEMP_RESIDENCY_TIME 10 // (seconds) +#define TEMP_HYSTERESIS 3 // (degC) range of +/- temperatures considered "close" to the target one +#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 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. + +// The minimal temperature defines the temperature below which the heater will not be enabled It is used +// to check that the wiring to the thermistor is not broken. +// Otherwise this would lead to the heater being powered on all the time. +#define HEATER_0_MINTEMP 5 +#define HEATER_1_MINTEMP 5 +#define HEATER_2_MINTEMP 5 +#define HEATER_3_MINTEMP 5 +#define HEATER_4_MINTEMP 5 +#define BED_MINTEMP 5 + +// When temperature exceeds max temp, your heater will be switched off. +// This feature exists to protect your hotend from overheating accidentally, but *NOT* from thermistor short/failure! +// You should use MINTEMP for thermistor short/failure protection. +#define HEATER_0_MAXTEMP 275 +#define HEATER_1_MAXTEMP 275 +#define HEATER_2_MAXTEMP 275 +#define HEATER_3_MAXTEMP 275 +#define HEATER_4_MAXTEMP 275 +#define BED_MAXTEMP 120 + +//=========================================================================== +//============================= PID Settings ================================ +//=========================================================================== +// PID Tuning Guide here: http://reprap.org/wiki/PID_Tuning + +// Comment the following line to disable PID and enable bang-bang. +#define PIDTEMP +#define BANG_MAX 255 // limits current to nozzle while in bang-bang mode; 255=full current +#define PID_MAX BANG_MAX // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current +#if ENABLED(PIDTEMP) + //#define PID_AUTOTUNE_MENU // Add PID Autotune to the LCD "Temperature" menu to run M303 and apply the result. + //#define PID_DEBUG // Sends debug data to the serial port. + //#define PID_OPENLOOP 1 // Puts PID in open loop. M104/M140 sets the output power from 0 to PID_MAX + //#define SLOW_PWM_HEATERS // PWM with very low frequency (roughly 0.125Hz=8s) and minimum state time of approximately 1s useful for heaters driven by a relay + //#define PID_PARAMS_PER_HOTEND // Uses separate PID parameters for each extruder (useful for mismatched extruders) + // 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 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 + +// Stock CR-10 tuned for 70C + #define DEFAULT_Kp 22.57 + #define DEFAULT_Ki 1.72 + #define DEFAULT_Kd 73.96 + +// Ultimaker + //#define DEFAULT_Kp 22.2 + //#define DEFAULT_Ki 1.08 + //#define DEFAULT_Kd 114 + + // MakerGear + //#define DEFAULT_Kp 7.0 + //#define DEFAULT_Ki 0.1 + //#define DEFAULT_Kd 12 + + // Mendel Parts V9 on 12V + //#define DEFAULT_Kp 63.0 + //#define DEFAULT_Ki 2.25 + //#define DEFAULT_Kd 440 + +#endif // PIDTEMP + +//=========================================================================== +//============================= PID > Bed Temperature Control =============== +//=========================================================================== +// Select PID or bang-bang with PIDTEMPBED. If bang-bang, BED_LIMIT_SWITCHING will enable hysteresis +// +// Uncomment this to enable PID on the bed. It uses the same frequency PWM as the extruder. +// If your PID_dT is the default, and correct for your hardware/configuration, that means 7.689Hz, +// which is fine for driving a square wave into a resistive load and does not significantly impact you FET heating. +// This also works fine on a Fotek SSR-10DA Solid State Relay into a 250W heater. +// If your configuration is significantly different than this and you don't understand the issues involved, you probably +// shouldn't use bed PID until someone else verifies your hardware works. +// If this is enabled, find your own PID constants below. +#define PIDTEMPBED + +//#define BED_LIMIT_SWITCHING + +// This sets the max power delivered to the bed, and replaces the HEATER_BED_DUTY_CYCLE_DIVIDER option. +// all forms of bed control obey this (PID, bang-bang, bang-bang with hysteresis) +// setting this to anything other than 255 enables a form of PWM to the bed just like HEATER_BED_DUTY_CYCLE_DIVIDER did, +// so you shouldn't use it unless you are OK with PWM on your bed. (see the comment on enabling PIDTEMPBED) +#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current + +#if ENABLED(PIDTEMPBED) + + //#define PID_BED_DEBUG // Sends debug data to the serial port. + + //Stock CR-10 Bed Tuned for 70C + #define DEFAULT_bedKp 426.68 + #define DEFAULT_bedKi 78.92 + #define DEFAULT_bedKd 576.71 + + //120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+) + //from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10) + //#define DEFAULT_bedKp 10.00 + //#define DEFAULT_bedKi .023 + //#define DEFAULT_bedKd 305.4 + + //120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+) + //from pidautotune + //#define DEFAULT_bedKp 97.1 + //#define DEFAULT_bedKi 1.41 + //#define DEFAULT_bedKd 1675.16 + + // FIND YOUR OWN: "M303 E-1 C8 S90" to run autotune on the bed at 90 degreesC for 8 cycles. +#endif // PIDTEMPBED + +// @section extruder + +// 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 + +// 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 1000 + +//=========================================================================== +//======================== Thermal Runaway Protection ======================= +//=========================================================================== + +/** + * Thermal Protection protects your printer from damage and fire if a + * thermistor falls out or temperature sensors fail in any way. + * + * The issue: If a thermistor falls out or a temperature sensor fails, + * Marlin can no longer sense the actual temperature. Since a disconnected + * thermistor reads as a low temperature, the firmware will keep the heater on. + * + * If you get "Thermal Runaway" or "Heating failed" errors the + * details can be tuned in Configuration_adv.h + */ + +#define THERMAL_PROTECTION_HOTENDS // Enable thermal protection for all extruders +#define THERMAL_PROTECTION_BED // Enable thermal protection for the heated bed + +//=========================================================================== +//============================= Mechanical Settings ========================= +//=========================================================================== + +// @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 + +//=========================================================================== +//============================== Endstop Settings =========================== +//=========================================================================== + +// @section homing + +// Specify here all the endstop connectors that are connected to any endstop or probe. +// Almost all printers will be using one per axis. Probes will use one or more of the +// extra connectors. Leave undefined any used for non-endstop and non-probe purposes. +#define USE_XMIN_PLUG +#define USE_YMIN_PLUG +#define USE_ZMIN_PLUG +//#define USE_XMAX_PLUG +//#define USE_YMAX_PLUG +//#define USE_ZMAX_PLUG + +// coarse Endstop Settings +//#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors + +#if DISABLED(ENDSTOPPULLUPS) + // fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined + //#define ENDSTOPPULLUP_XMAX + //#define ENDSTOPPULLUP_YMAX + //#define ENDSTOPPULLUP_ZMAX + //#define ENDSTOPPULLUP_XMIN + //#define ENDSTOPPULLUP_YMIN + //#define ENDSTOPPULLUP_ZMIN + //#define ENDSTOPPULLUP_ZMIN_PROBE +#endif + +// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup). +#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 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 probe. + +// 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 + * + * Note that if EEPROM is enabled, saved values will override these. + */ + +/** + * With this option each E stepper can have its own factors for the + * following movement settings. If fewer factors are given than the + * total number of extruders, the last value applies to the rest. + */ +//#define DISTINCT_E_FACTORS + +/** + * Default Axis Steps Per Unit (steps/mm) + * Override with M92 + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] + */ +#define DEFAULT_AXIS_STEPS_PER_UNIT { 80, 80, 400, 95 } + +/** + * Default Max Feed Rate (mm/s) + * Override with M203 + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] + */ +#define DEFAULT_MAX_FEEDRATE { 500, 500, 15, 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[, E4]]]] + */ +#define DEFAULT_MAX_ACCELERATION { 3000, 3000, 100, 5000 } + +/** + * 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 500 // E acceleration for retracts +#define DEFAULT_TRAVEL_ACCELERATION 1000 // X, Y, Z acceleration for travel (non printing) moves + +/** + * Default Jerk (mm/s) + * Override with M205 X Y Z E + * + * "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 2.7 +#define DEFAULT_EJERK 5.0 + + +//=========================================================================== +//============================= Z Probe Options ============================= +//=========================================================================== +// @section probes + +// +// See http://marlinfw.org/configuration/probes.html +// + +/** + * Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN + * + * Enable this option for a probe connected to the Z Min endstop pin. + */ +#define Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN + +/** + * Z_MIN_PROBE_ENDSTOP + * + * Enable this option for a probe connected to any pin except Z-Min. + * (By default Marlin assumes the Z-Max endstop pin.) + * To use a custom Z Probe pin, set Z_MIN_PROBE_PIN below. + * + * - The simplest option is to use a free endstop connector. + * - Use 5V for powered (usually inductive) sensors. + * + * - RAMPS 1.3/1.4 boards may use the 5V, GND, and Aux4->D32 pin: + * - For simple switches connect... + * - normally-closed switches to GND and D32. + * - normally-open switches to 5V and D32. + * + * WARNING: Setting the wrong pin may have unexpected and potentially + * disastrous consequences. Use with caution and do your homework. + * + */ +//#define Z_MIN_PROBE_ENDSTOP + +/** + * Probe Type + * + * Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, etc. + * You must activate one of these to use Auto Bed Leveling below. + */ + +/** + * The "Manual Probe" provides a means to do "Auto" Bed Leveling without a probe. + * Use G29 repeatedly, adjusting the Z height at each point with movement commands + * or (with LCD_BED_LEVELING) the LCD controller. + */ +//#define PROBE_MANUALLY + +/** + * A Fix-Mounted Probe either doesn't deploy or needs manual deployment. + * (e.g., an inductive probe or a nozzle-based probe-switch.) + */ +//#define FIX_MOUNTED_PROBE + +/** + * Z Servo Probe, such as an endstop switch on a rotating arm. + */ +//#define Z_ENDSTOP_SERVO_NR 0 // Defaults to SERVO 0 connector. +//#define Z_SERVO_ANGLES {70,0} // Z Servo Deploy and Stow angles + +/** + * The BLTouch probe uses a Hall effect sensor and emulates a servo. + */ +//#define BLTOUCH +#if ENABLED(BLTOUCH) + //#define BLTOUCH_DELAY 375 // (ms) Enable and increase if needed +#endif + +/** + * Enable if probing seems unreliable. Heaters and/or fans - consistent with the + * options selected below - will be disabled during probing so as to minimize + * potential EM interference by quieting/silencing the source of the 'noise' (the change + * in current flowing through the wires). This is likely most useful to users of the + * BLTouch probe, but may also help those with inductive or other probe types. + */ +//#define PROBING_HEATERS_OFF // Turn heaters off when probing +//#define PROBING_FANS_OFF // Turn fans off when probing + +// A probe that is deployed and stowed with a solenoid pin (SOL1_PIN) +//#define SOLENOID_PROBE + +// A sled-mounted probe like those designed by Charles Bell. +//#define Z_PROBE_SLED +//#define SLED_DOCKING_OFFSET 5 // The extra distance the X axis must travel to pickup the sled. 0 should be fine but you can push it further if you'd like. + +// +// For Z_PROBE_ALLEN_KEY see the Delta example configurations. +// + +/** + * Z Probe to nozzle (X,Y) offset, relative to (0, 0). + * X and Y offsets must be integers. + * + * In the following example the X and Y offsets are both positive: + * #define X_PROBE_OFFSET_FROM_EXTRUDER 10 + * #define Y_PROBE_OFFSET_FROM_EXTRUDER 10 + * + * +-- BACK ---+ + * | | + * L | (+) P | R <-- probe (20,20) + * E | | I + * F | (-) N (+) | G <-- nozzle (10,10) + * T | | H + * | (-) | T + * | | + * O-- FRONT --+ + * (0,0) + */ +#define X_PROBE_OFFSET_FROM_EXTRUDER 10 // X offset: -left +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 + +// Speed for the first approach when double-probing (with PROBE_DOUBLE_TOUCH) +#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z + +// Speed for the "accurate" probe of each point +#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2) + +// Use double touch for probing +#define PROBE_DOUBLE_TOUCH + +/** + * 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 10 // Z Clearance between probe points + +// For M851 give a range for adjusting the Z probe offset +#define Z_PROBE_OFFSET_RANGE_MIN -20 +#define Z_PROBE_OFFSET_RANGE_MAX 20 + +// Enable the M48 repeatability test to test probe accuracy +//#define Z_MIN_PROBE_REPEATABILITY_TEST + +// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1 +// :{ 0:'Low', 1:'High' } +#define X_ENABLE_ON 0 +#define Y_ENABLE_ON 0 +#define Z_ENABLE_ON 0 +#define E_ENABLE_ON 0 // For all extruders + +// Disables axis stepper immediately when it's not being used. +// 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 +// Warn on display about possibly reduced accuracy +//#define DISABLE_REDUCED_ACCURACY_WARNING + +// @section extruder + +#define DISABLE_E false // For all extruders +#define DISABLE_INACTIVE_EXTRUDER true // Keep only the active extruder enabled. + +// @section machine + +// Invert the stepper direction. Change (or reverse the motor connector) if an axis goes the wrong way. +#define INVERT_X_DIR true +#define INVERT_Y_DIR true +#define INVERT_Z_DIR false + +// Enable this option for Toshiba stepper drivers +//#define CONFIG_STEPPERS_TOSHIBA + +// @section extruder + +// For direct drive extruder v9 set to true, for geared extruder set to false. +#define INVERT_E0_DIR true +#define INVERT_E1_DIR false +#define INVERT_E2_DIR false +#define INVERT_E3_DIR false +#define INVERT_E4_DIR false + +// @section homing + +//#define Z_HOMING_HEIGHT 5 // (in mm) Minimal z height before homing (G28) for Z clearance above the bed, clamps, ... + // Be sure you have this distance over your Z_MAX_POS in case. + +// Direction of endstops when homing; 1=MAX, -1=MIN +// :[-1,1] +#define X_HOME_DIR -1 +#define Y_HOME_DIR -1 +#define Z_HOME_DIR -1 + +// @section machine + +// Travel limits after homing (units are in mm) +#define X_MIN_POS 0 +#define Y_MIN_POS 0 +#define Z_MIN_POS 0 +#define X_MAX_POS 300 +#define Y_MAX_POS 300 +#define Z_MAX_POS 400 + +// If enabled, axes won't move below MIN_POS in response to movement commands. +#define MIN_SOFTWARE_ENDSTOPS +// If enabled, axes won't move above MAX_POS in response to movement commands. +#define MAX_SOFTWARE_ENDSTOPS + +/** + * Filament Runout Sensor + * A mechanical or opto endstop is used to check for the presence of filament. + * + * RAMPS-based boards use SERVO3_PIN. + * For other boards you may need to define FIL_RUNOUT_PIN. + * By default the firmware assumes HIGH = has filament, LOW = ran out + */ +//#define FILAMENT_RUNOUT_SENSOR +#if ENABLED(FILAMENT_RUNOUT_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 + +//=========================================================================== +//=============================== Bed Leveling ============================== +//=========================================================================== +// @section bedlevel + +/** + * Choose one of the options below to enable G29 Bed Leveling. The parameters + * and behavior of G29 will change depending on your selection. + * + * If using a Probe for Z Homing, enable Z_SAFE_HOMING also! + * + * - AUTO_BED_LEVELING_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. + * + * - AUTO_BED_LEVELING_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. + * + * - AUTO_BED_LEVELING_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. + * + * - AUTO_BED_LEVELING_UBL (Unified Bed Leveling) + * A comprehensive bed leveling system combining the features and benefits + * of other systems. UBL also includes integrated Mesh Generation, Mesh + * Validation and Mesh Editing systems. Currently, UBL is only checked out + * for Cartesian Printers. That said, it was primarily designed to correct + * poor quality Delta Printers. If you feel adventurous and have a Delta, + * please post an issue if something doesn't work correctly. Initially, + * you will need to set a reduced bed size so you have a rectangular area + * to test on. + * + * - MESH_BED_LEVELING + * Probe a grid manually + * The result is a mesh, suitable for large or uneven beds. (See BILINEAR.) + * For machines without a probe, Mesh Bed Leveling provides a method to perform + * leveling in steps so you can manually adjust the Z height at each grid-point. + * With an LCD controller the process is guided step-by-step. + */ +//#define AUTO_BED_LEVELING_3POINT +//#define AUTO_BED_LEVELING_LINEAR +//#define AUTO_BED_LEVELING_BILINEAR +//#define AUTO_BED_LEVELING_UBL +//#define MESH_BED_LEVELING + +/** + * 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(MESH_BED_LEVELING) || ENABLED(AUTO_BED_LEVELING_BILINEAR) || ENABLED(AUTO_BED_LEVELING_UBL) + // 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 + +#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR) + + // Set the number of grid points per dimension. + #define GRID_MAX_POINTS_X 3 + #define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X + + // 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 + + // The Z probe minimum outer margin (to validate G29 parameters). + #define MIN_PROBE_EDGE 10 + + // Probe along the Y axis, advancing X after each column + //#define PROBE_Y_FIRST + + #if ENABLED(AUTO_BED_LEVELING_BILINEAR) + + // Beyond the probed grid, continue the implied tilt? + // Default is to maintain the height of the nearest edge. + //#define EXTRAPOLATE_BEYOND_GRID + + // + // Experimental Subdivision of the grid by Catmull-Rom method. + // Synthesizes intermediate points to produce a more detailed mesh. + // + //#define ABL_BILINEAR_SUBDIVISION + #if ENABLED(ABL_BILINEAR_SUBDIVISION) + // Number of subdivisions between probe points + #define BILINEAR_SUBDIVISIONS 3 + #endif + + #endif + +#elif ENABLED(AUTO_BED_LEVELING_3POINT) + + // 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 + +#elif ENABLED(AUTO_BED_LEVELING_UBL) + + //=========================================================================== + //========================= Unified Bed Leveling ============================ + //=========================================================================== + + #define UBL_MESH_INSET 1 // Mesh inset margin on print area + #define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited. + #define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X + + #define UBL_PROBE_PT_1_X 39 // Probing points for 3-Point leveling of the mesh + #define UBL_PROBE_PT_1_Y 180 + #define UBL_PROBE_PT_2_X 39 + #define UBL_PROBE_PT_2_Y 20 + #define UBL_PROBE_PT_3_X 180 + #define UBL_PROBE_PT_3_Y 20 + + #define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation + #define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle + +#elif ENABLED(MESH_BED_LEVELING) + + //=========================================================================== + //=================================== Mesh ================================== + //=========================================================================== + + #define MESH_INSET 10 // Mesh inset margin on print area + #define GRID_MAX_POINTS_X 3 // Don't use more than 7 points per axis, implementation limited. + #define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X + + //#define MESH_G28_REST_ORIGIN // After homing all axes ('G28' or 'G28 XYZ') rest Z at Z_MIN_POS + +#endif // BED_LEVELING + +/** + * Use the LCD controller for bed leveling + * Requires MESH_BED_LEVELING or PROBE_MANUALLY + */ +//#define LCD_BED_LEVELING + +#if ENABLED(LCD_BED_LEVELING) + #define MBL_Z_STEP 0.025 // Step size while manually probing Z axis. + #define LCD_PROBE_Z_RANGE 4 // Z Range centered on Z_MIN_POS for LCD Z adjustment +#endif + +/** + * 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 + +// The center of the bed is at (X=0, Y=0) +//#define BED_CENTER_AT_0_0 + +// Manually set the home position. Leave these undefined for automatic settings. +// For DELTA this is the top-center of the Cartesian print volume. +//#define MANUAL_X_HOME_POS 0 +//#define MANUAL_Y_HOME_POS 0 +//#define MANUAL_Z_HOME_POS 0 + +// Use "Z Safe Homing" to avoid homing with a Z probe outside the bed area. +// +// With this feature enabled: +// +// - Allow Z homing only after X and Y homing AND stepper drivers still enabled. +// - If stepper drivers time out, it will need X and Y homing again before Z homing. +// - Move the Z probe (or nozzle) to a defined XY point before Z Homing when homing all axes (G28). +// - Prevent Z homing when the Z probe is outside bed area. +//#define Z_SAFE_HOMING + +#if ENABLED(Z_SAFE_HOMING) + #define Z_SAFE_HOMING_X_POINT ((X_MIN_POS + X_MAX_POS) / 2) // X point for Z homing when homing all axis (G28). + #define Z_SAFE_HOMING_Y_POINT ((Y_MIN_POS + Y_MAX_POS) / 2) // Y point for Z homing when homing all axis (G28). +#endif + +// Homing speeds (mm/m) +#define HOMING_FEEDRATE_XY (50*60) +#define HOMING_FEEDRATE_Z (4*60) + +//============================================================================= +//============================= Additional Features =========================== +//============================================================================= + +// @section extras + +// +// EEPROM +// +// The microcontroller can store settings in the EEPROM, e.g. max velocity... +// M500 - stores parameters in EEPROM +// 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 + +#if ENABLED(EEPROM_SETTINGS) + //#define DISABLE_M503 // Saves ~2700 bytes of PROGMEM. Disable for release! + #define EEPROM_CHITCHAT // Print a report on M500. Please keep turned on. +#endif + +// +// Host Keepalive +// +// 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. + +// +// M100 Free Memory Watcher +// +//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose + +// +// G20/G21 Inch mode support +// +//#define INCH_MODE_SUPPORT + +// +// M149 Set temperature units support +// +//#define TEMPERATURE_UNITS_SUPPORT + +// @section temperature + +// Preheat Constants +#define PREHEAT_1_TEMP_HOTEND 200 +#define PREHEAT_1_TEMP_BED 70 +#define PREHEAT_1_FAN_SPEED 0 // Value from 0 to 255 + +#define PREHEAT_2_TEMP_HOTEND 240 +#define PREHEAT_2_TEMP_BED 110 +#define PREHEAT_2_FAN_SPEED 0 // Value from 0 to 255 + +/** + * Nozzle Park -- EXPERIMENTAL + * + * Park the nozzle at the given XYZ position on idle or G27. + * + * The "P" parameter controls the action applied to the Z axis: + * + * P0 (Default) If Z is below park Z raise the nozzle. + * P1 Raise the nozzle always to Z-park height. + * P2 Raise the nozzle by Z-park amount, limited to Z_MAX_POS. + */ +//#define NOZZLE_PARK_FEATURE + +#if ENABLED(NOZZLE_PARK_FEATURE) + // Specify a park position as { X, Y, Z } + #define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 } +#endif + +/** + * Clean Nozzle Feature -- EXPERIMENTAL + * + * Adds the G12 command to perform a nozzle cleaning process. + * + * Parameters: + * P Pattern + * S Strokes / Repetitions + * T Triangles (P1 only) + * + * Patterns: + * P0 Straight line (default). This process requires a sponge type material + * at a fixed bed location. "S" specifies strokes (i.e. back-forth motions) + * between the start / end points. + * + * P1 Zig-zag pattern between (X0, Y0) and (X1, Y1), "T" specifies the + * number of zig-zag triangles to do. "S" defines the number of strokes. + * Zig-zags are done in whichever is the narrower dimension. + * For example, "G12 P1 S1 T3" will execute: + * + * -- + * | (X0, Y1) | /\ /\ /\ | (X1, Y1) + * | | / \ / \ / \ | + * A | | / \ / \ / \ | + * | | / \ / \ / \ | + * | (X0, Y0) | / \/ \/ \ | (X1, Y0) + * -- +--------------------------------+ + * |________|_________|_________| + * T1 T2 T3 + * + * P2 Circular pattern with middle at NOZZLE_CLEAN_CIRCLE_MIDDLE. + * "R" specifies the radius. "S" specifies the stroke count. + * Before starting, the nozzle moves to NOZZLE_CLEAN_START_POINT. + * + * Caveats: The ending Z should be the same as starting Z. + * Attention: EXPERIMENTAL. G-code arguments may change. + * + */ +//#define NOZZLE_CLEAN_FEATURE + +#if ENABLED(NOZZLE_CLEAN_FEATURE) + // Default number of pattern repetitions + #define NOZZLE_CLEAN_STROKES 12 + + // Default number of triangles + #define NOZZLE_CLEAN_TRIANGLES 3 + + // Specify positions as { X, Y, Z } + #define NOZZLE_CLEAN_START_POINT { 30, 30, (Z_MIN_POS + 1)} + #define NOZZLE_CLEAN_END_POINT {100, 60, (Z_MIN_POS + 1)} + + // Circular pattern radius + #define NOZZLE_CLEAN_CIRCLE_RADIUS 6.5 + // Circular pattern circle fragments number + #define NOZZLE_CLEAN_CIRCLE_FN 10 + // Middle point of circle + #define NOZZLE_CLEAN_CIRCLE_MIDDLE NOZZLE_CLEAN_START_POINT + + // Moves the nozzle to the initial position + #define NOZZLE_CLEAN_GOBACK +#endif + +/** + * Print Job Timer + * + * Automatically start and stop the print job timer on M104/M109/M190. + * + * M104 (hotend, no wait) - high temp = none, low temp = stop timer + * M109 (hotend, wait) - high temp = start timer, low temp = stop timer + * M190 (bed, wait) - high temp = start timer, low temp = none + * + * The timer can also be controlled with the following commands: + * + * M75 - Start the print job timer + * M76 - Pause the print job timer + * M77 - Stop the print job timer + */ +//#define PRINTJOB_TIMER_AUTOSTART + +/** + * Print Counter + * + * Track statistical data such as: + * + * - Total print jobs + * - Total successful print jobs + * - Total failed print jobs + * - Total time printing + * + * View the current statistics with M78. + */ +//#define PRINTCOUNTER + +//============================================================================= +//============================= LCD and SD support ============================ +//============================================================================= + +// @section lcd + +/** + * LCD LANGUAGE + * + * Select the language to display on the LCD. These languages are available: + * + * en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr, + * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, + * zh_CN, zh_TW, test + * + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } + */ +#define LCD_LANGUAGE en + +/** + * LCD Character Set + * + * Note: This option is NOT applicable to Graphical Displays. + * + * All character-based LCDs provide ASCII plus one of these + * language extensions: + * + * - JAPANESE ... the most common + * - WESTERN ... with more accented characters + * - CYRILLIC ... for the Russian language + * + * To determine the language extension installed on your controller: + * + * - Compile and upload with LCD_LANGUAGE set to 'test' + * - Click the controller to view the LCD menu + * - The LCD will display Japanese, Western, or Cyrillic text + * + * See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language + * + * :['JAPANESE', 'WESTERN', 'CYRILLIC'] + */ +#define DISPLAY_CHARSET_HD44780 JAPANESE + +/** + * LCD TYPE + * + * Enable ULTRA_LCD for a 16x2, 16x4, 20x2, or 20x4 character-based LCD. + * Enable DOGLCD for a 128x64 (ST7565R) Full Graphical Display. + * (These options will be enabled automatically for most displays.) + * + * IMPORTANT: The U8glib library is required for Full Graphic Display! + * https://github.com/olikraus/U8glib_Arduino + */ +//#define ULTRA_LCD // Character based +//#define DOGLCD // Full graphics display + +/** + * SD CARD + * + * SD Card support is disabled by default. If your controller has an SD slot, + * you must uncomment the following option or it won't work. + * + */ +#define SDSUPPORT + +/** + * SD CARD: SPI SPEED + * + * Enable one of the following items for a slower SPI transfer speed. + * This may be required to resolve "volume init" errors. + */ +//#define SPI_SPEED SPI_HALF_SPEED +//#define SPI_SPEED SPI_QUARTER_SPEED +//#define SPI_SPEED SPI_EIGHTH_SPEED + +/** + * SD CARD: ENABLE CRC + * + * Use CRC checks and retries on the SD communication. + */ +//#define SD_CHECK_AND_RETRY + +// +// ENCODER SETTINGS +// +// 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 4 + +// +// Use this option to override the number of step signals required to +// move between next/prev menu items. +// +#define ENCODER_STEPS_PER_MENU_ITEM 1 + +/** + * Encoder Direction Options + * + * Test your encoder's behavior first with both options disabled. + * + * Reversed Value Edit and Menu Nav? Enable REVERSE_ENCODER_DIRECTION. + * Reversed Menu Navigation only? Enable REVERSE_MENU_DIRECTION. + * Reversed Value Editing only? Enable BOTH options. + */ + +// +// This option reverses the encoder direction everywhere. +// +// Set this option if CLOCKWISE causes values to DECREASE +// +//#define REVERSE_ENCODER_DIRECTION + +// +// This option reverses the encoder direction for navigating LCD menus. +// +// If CLOCKWISE normally moves DOWN this makes it go UP. +// If CLOCKWISE normally moves UP this makes it go DOWN. +// +//#define REVERSE_MENU_DIRECTION + +// +// Individual Axis Homing +// +// Add individual axis homing items (Home X, Home Y, and Home Z) to the LCD menu. +// +//#define INDIVIDUAL_AXIS_HOMING_MENU + +// +// SPEAKER/BUZZER +// +// If you have a speaker that can produce tones, enable it here. +// By default Marlin assumes you have a buzzer with a fixed frequency. +// +#define SPEAKER + +// +// The duration and frequency for the UI feedback sound. +// Set these to 0 to disable audio feedback in the LCD menus. +// +// Note: Test audio output with the G-Code: +// M300 S P +// +//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100 +//#define LCD_FEEDBACK_FREQUENCY_HZ 1000 + +// +// CONTROLLER TYPE: Standard +// +// Marlin supports a wide variety of controllers. +// Enable one of the following options to specify your controller. +// + +// +// ULTIMAKER Controller. +// +//#define ULTIMAKERCONTROLLER + +// +// ULTIPANEL as seen on Thingiverse. +// +//#define ULTIPANEL + +// +// Cartesio UI +// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface +// +//#define CARTESIO_UI + +// +// PanelOne from T3P3 (via RAMPS 1.4 AUX2/AUX3) +// http://reprap.org/wiki/PanelOne +// +//#define PANEL_ONE + +// +// MaKr3d Makr-Panel with graphic controller and SD support. +// http://reprap.org/wiki/MaKr3d_MaKrPanel +// +//#define MAKRPANEL + +// +// ReprapWorld Graphical LCD +// https://reprapworld.com/?products_details&products_id/1218 +// +//#define REPRAPWORLD_GRAPHICAL_LCD + +// +// Activate one of these if you have a Panucatt Devices +// Viki 2.0 or mini Viki with Graphic LCD +// http://panucatt.com +// +//#define VIKI2 +//#define miniVIKI + +// +// Adafruit ST7565 Full Graphic Controller. +// https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/ +// +//#define ELB_FULL_GRAPHIC_CONTROLLER + +// +// RepRapDiscount Smart Controller. +// http://reprap.org/wiki/RepRapDiscount_Smart_Controller +// +// Note: Usually sold with a white PCB. +// +//#define REPRAP_DISCOUNT_SMART_CONTROLLER + +// +// GADGETS3D G3D LCD/SD Controller +// http://reprap.org/wiki/RAMPS_1.3/1.4_GADGETS3D_Shield_with_Panel +// +// Note: Usually sold with a blue PCB. +// +//#define G3D_PANEL + +// +// RepRapDiscount FULL GRAPHIC Smart Controller +// http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller +// +#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER + +// +// MakerLab Mini Panel with graphic +// controller and SD support - http://reprap.org/wiki/Mini_panel +// +//#define MINIPANEL + +// +// RepRapWorld REPRAPWORLD_KEYPAD v1.1 +// http://reprapworld.com/?products_details&products_id=202&cPath=1591_1626 +// +// REPRAPWORLD_KEYPAD_MOVE_STEP sets how much should the robot move when a key +// is pressed, a value of 10.0 means 10mm per click. +// +//#define REPRAPWORLD_KEYPAD +//#define REPRAPWORLD_KEYPAD_MOVE_STEP 1.0 + +// +// RigidBot Panel V1.0 +// http://www.inventapart.com/ +// +//#define RIGIDBOT_PANEL + +// +// BQ LCD Smart Controller shipped by +// default with the BQ Hephestos 2 and Witbox 2. +// +//#define BQ_LCD_SMART_CONTROLLER + +// +// ANET_10 Controller supported displays. +// +//#define ANET_KEYPAD_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin. + // This LCD is known to be susceptible to electrical interference + // which scrambles the display. Pressing any button clears it up. +//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6 + // A clone of the RepRapDiscount full graphics display but with + // different pins/wiring (see pins_ANET_10.h). + +// +// LCD for Melzi Card with Graphical LCD +// +//#define LCD_FOR_MELZI + +// +// CONTROLLER TYPE: I2C +// +// Note: These controllers require the installation of Arduino's LiquidCrystal_I2C +// library. For more info: https://github.com/kiyoshigawa/LiquidCrystal_I2C +// + +// +// Elefu RA Board Control Panel +// http://www.elefu.com/index.php?route=product/product&product_id=53 +// +//#define RA_CONTROL_PANEL + +// +// Sainsmart YW Robot (LCM1602) LCD Display +// +// Note: This controller requires F.Malpartida's LiquidCrystal_I2C library +// https://bitbucket.org/fmalpartida/new-liquidcrystal/wiki/Home +// +//#define LCD_I2C_SAINSMART_YWROBOT + +// +// Generic LCM1602 LCD adapter +// +//#define LCM1602 + +// +// PANELOLU2 LCD with status LEDs, +// separate encoder and click inputs. +// +// Note: This controller requires Arduino's LiquidTWI2 library v1.2.3 or later. +// For more info: https://github.com/lincomatic/LiquidTWI2 +// +// Note: The PANELOLU2 encoder click input can either be directly connected to +// a pin (if BTN_ENC defined to != -1) or read through I2C (when BTN_ENC == -1). +// +//#define LCD_I2C_PANELOLU2 + +// +// Panucatt VIKI LCD with status LEDs, +// integrated click & L/R/U/D buttons, separate encoder inputs. +// +//#define LCD_I2C_VIKI + +// +// SSD1306 OLED full graphics generic display +// +//#define U8GLIB_SSD1306 + +// +// SAV OLEd LCD module support using either SSD1306 or SH1106 based LCD modules +// +//#define SAV_3DGLCD +#if ENABLED(SAV_3DGLCD) + //#define U8GLIB_SSD1306 + #define U8GLIB_SH1106 +#endif + +// +// CONTROLLER TYPE: Shift register panels +// +// 2 wire Non-latching LCD SR from https://goo.gl/aJJ4sH +// LCD configuration: http://reprap.org/wiki/SAV_3D_LCD +// +//#define SAV_3DLCD + +// +// TinyBoy2 128x64 OLED / Encoder Panel +// +//#define OLED_PANEL_TINYBOY2 + +//============================================================================= +//=============================== Extra Features ============================== +//============================================================================= + +// @section extras + +// Increase the FAN PWM frequency. Removes the PWM noise but increases heating in the FET/Arduino +//#define FAST_PWM_FAN + +// Use software PWM to drive the fan, as for the heaters. This uses a very low frequency +// which is not as annoying as with the hardware PWM. On the other hand, if this frequency +// is too low, you should also increment SOFT_PWM_SCALE. +//#define FAN_SOFT_PWM + +// Incrementing this by 1 will double the software PWM frequency, +// affecting heaters, and the fan if FAN_SOFT_PWM is enabled. +// However, control resolution will be halved for each increment; +// at zero value, there are 128 effective control positions. +#define SOFT_PWM_SCALE 0 + +// If SOFT_PWM_SCALE is set to a value higher than 0, dithering can +// be used to mitigate the associated resolution loss. If enabled, +// some of the PWM cycles are stretched so on average the desired +// duty cycle is attained. +//#define SOFT_PWM_DITHER + +// Temperature status LEDs that display the hotend and bed temperature. +// If all hotends, bed temperature, and target temperature are under 54C +// then the BLUE led is on. Otherwise the RED led is on. (1C hysteresis) +//#define TEMP_STAT_LEDS + +// M240 Triggers a camera by emulating a Canon RC-1 Remote +// Data from: http://www.doc-diy.net/photo/rc-1_hacked/ +//#define PHOTOGRAPH_PIN 23 + +// SkeinForge sends the wrong arc g-codes when using Arc Point as fillet procedure +//#define SF_ARC_FIX + +// Support for the BariCUDA Paste Extruder +//#define BARICUDA + +// Support for BlinkM/CyzRgb +//#define BLINKM + +// Support for PCA9632 PWM LED driver +//#define PCA9632 + +/** + * RGB LED / LED Strip Control + * + * Enable support for an RGB LED connected to 5V digital pins, or + * an RGB Strip connected to MOSFETs controlled by digital pins. + * + * Adds the M150 command to set the LED (or LED strip) color. + * If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of + * luminance values can be set from 0 to 255. + * + * *** CAUTION *** + * LED Strips require a MOFSET Chip between PWM lines and LEDs, + * as the Arduino cannot handle the current the LEDs will require. + * Failure to follow this precaution can destroy your Arduino! + * *** CAUTION *** + * + */ +//#define RGB_LED +//#define RGBW_LED +#if ENABLED(RGB_LED) || ENABLED(RGBW_LED) + #define RGB_LED_R_PIN 34 + #define RGB_LED_G_PIN 43 + #define RGB_LED_B_PIN 35 + #define RGB_LED_W_PIN -1 +#endif + +/** + * Printer Event LEDs + * + * During printing, the LEDs will reflect the printer status: + * + * - Gradually change from blue to violet as the heated bed gets to target temp + * - Gradually change from violet to red as the hotend gets to temperature + * - Change to white to illuminate work surface + * - Change to green once print has finished + * - Turn off after the print has finished and the user has pushed a button + */ +#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) + #define PRINTER_EVENT_LEDS +#endif + +/*********************************************************************\ +* R/C SERVO support +* Sponsored by TrinityLabs, Reworked by codexmas +**********************************************************************/ + +// Number of servos +// +// If you select a configuration below, this will receive a default value and does not need to be set manually +// set it manually if you have more servos than extruders and wish to manually control some +// leaving it undefined or defining as 0 will disable the servo subsystem +// If unsure, leave commented / disabled +// +//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command + +// Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle. +// 300ms is a good value but you can try less delay. +// If the servo can't reach the requested position, increase it. +#define SERVO_DELAY 300 + +// Servo deactivation +// +// With this option servos are powered only during movement, then turned off to prevent jitter. +//#define DEACTIVATE_SERVOS_AFTER_MOVE + +/** + * Filament Width Sensor + * + * Measures the filament width in real-time and adjusts + * flow rate to compensate for any irregularities. + * + * Also allows the measured filament diameter to set the + * extrusion rate, so the slicer only has to specify the + * volume. + * + * Only a single extruder is supported at this time. + * + * 34 RAMPS_14 : Analog input 5 on the AUX2 connector + * 81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E) + * 301 RAMBO : Analog input 3 + * + * Note: May require analog pins to be defined for other boards. + */ +//#define FILAMENT_WIDTH_SENSOR + +#define DEFAULT_NOMINAL_FILAMENT_DIA 1.75 // (mm) Diameter of the filament generally used (3.0 or 1.75mm), also used in the slicer. Used to validate sensor reading. +#define DEFAULT_STDDEV_FILAMENT_DIA 0.05 // Typical estimate for cheap filament +//#define DEFAULT_STDDEV_FILAMENT_DIA 0.02 // Typical advertised for higher quality filament + +#if ENABLED(FILAMENT_WIDTH_SENSOR) + #define FILAMENT_SENSOR_EXTRUDER_NUM 0 // Index of the extruder that has the filament sensor (0,1,2,3) + #define MEASUREMENT_DELAY_CM 14 // (cm) The distance from the filament sensor to the melting chamber + + #define MEASURED_UPPER_LIMIT (DEFAULT_NOMINAL_FILAMENT_DIA+4*DEFAULT_STDDEV_FILAMENT_DIA) // (mm) Upper limit used to validate sensor reading + #define MEASURED_LOWER_LIMIT (DEFAULT_NOMINAL_FILAMENT_DIA-4*DEFAULT_STDDEV_FILAMENT_DIA) // (mm) Lower limit used to validate sensor reading + #define MAX_MEASUREMENT_DELAY 20 // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM. + + #define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially + + // Display filament width on the LCD status line. Status messages will expire after 5 seconds. + //#define FILAMENT_LCD_DISPLAY +#endif + +#endif // CONFIGURATION_H diff --git a/Marlin/pins.h b/Marlin/pins.h index 2a0b92aa9..f635808ed 100644 --- a/Marlin/pins.h +++ b/Marlin/pins.h @@ -97,12 +97,14 @@ #include "pins_SANGUINOLOLU_12.h" #elif MB(MELZI) #include "pins_MELZI.h" +#elif MB(MELZI_MAKR3D) + #include "pins_MELZI_MAKR3D.h" +#elif MB(MELZI_CREALITY) + #include "pins_MELZI_CREALITY.h" #elif MB(STB_11) #include "pins_STB_11.h" #elif MB(AZTEEG_X1) #include "pins_AZTEEG_X1.h" -#elif MB(MELZI_MAKR3D) - #include "pins_MELZI_MAKR3D.h" #elif MB(AZTEEG_X3) #include "pins_AZTEEG_X3.h" #elif MB(AZTEEG_X3_PRO) diff --git a/Marlin/pins_MELZI_CREALITY.h b/Marlin/pins_MELZI_CREALITY.h new file mode 100644 index 000000000..d08bba1c3 --- /dev/null +++ b/Marlin/pins_MELZI_CREALITY.h @@ -0,0 +1,100 @@ +/** + * 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 . + * + */ + +/** + * Melzi (Creality) pin assignments + */ + +#define BOARD_NAME "Melzi Creality" + +#ifdef __AVR_ATmega1284P__ + #define LARGE_FLASH true +#endif + +// For the stock CR-10 use the REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER +// option for the display in Configuration.h + +#define SANGUINOLOLU_V_1_2 +#include "pins_SANGUINOLOLU_11.h" + +#undef LCD_SDSS +#undef LED_PIN + +#undef LCD_PINS_RS +#undef LCD_PINS_ENABLE + +#define LCD_PINS_RS 28 // st9720 CS +#define LCD_PINS_ENABLE 17 // st9720 DAT + +#undef LCD_PINS_D4 +#undef LCD_PINS_D5 +#undef LCD_PINS_D6 +#undef LCD_PINS_D7 + +#define LCD_PINS_D4 30 // st9720 CLK + +/** + PIN: 0 Port: B0 E0_DIR_PIN protected + PIN: 1 Port: B1 E0_STEP_PIN protected + PIN: 2 Port: B2 Z_DIR_PIN protected + PIN: 3 Port: B3 Z_STEP_PIN protected + PIN: 4 Port: B4 AVR_SS_PIN protected + . FAN_PIN protected + . SS_PIN protected + PIN: 5 Port: B5 AVR_MOSI_PIN Output = 1 + . MOSI_PIN Output = 1 + PIN: 6 Port: B6 AVR_MISO_PIN Input = 0 TIMER3A PWM: 0 WGM: 1 COM3A: 0 CS: 3 TCCR3A: 1 TCCR3B: 3 TIMSK3: 0 + . MISO_PIN Input = 0 + PIN: 7 Port: B7 AVR_SCK_PIN Output = 0 TIMER3B PWM: 0 WGM: 1 COM3B: 0 CS: 3 TCCR3A: 1 TCCR3B: 3 TIMSK3: 0 + . SCK_PIN Output = 0 + PIN: 8 Port: D0 RXD Input = 1 + PIN: 9 Port: D1 TXD Input = 0 + PIN: 10 Port: D2 BTN_EN2 Input = 1 + PIN: 11 Port: D3 BTN_EN1 Input = 1 + PIN: 12 Port: D4 HEATER_BED_PIN protected + PIN: 13 Port: D5 HEATER_0_PIN protected + PIN: 14 Port: D6 E0_ENABLE_PIN protected + . X_ENABLE_PIN protected + . Y_ENABLE_PIN protected + PIN: 15 Port: D7 X_STEP_PIN protected + PIN: 16 Port: C0 BTN_ENC Input = 1 + . SCL Input = 1 + PIN: 17 Port: C1 LCD_PINS_ENABLE Output = 0 + . SDA Output = 0 + PIN: 18 Port: C2 X_MIN_PIN protected + . X_STOP_PIN protected + PIN: 19 Port: C3 Y_MIN_PIN protected + . Y_STOP_PIN protected + PIN: 20 Port: C4 Z_MIN_PIN protected + . Z_STOP_PIN protected + PIN: 21 Port: C5 X_DIR_PIN protected + PIN: 22 Port: C6 Y_STEP_PIN protected + PIN: 23 Port: C7 Y_DIR_PIN protected + PIN: 24 Port: A7 TEMP_0_PIN protected + PIN: 25 Port: A6 TEMP_BED_PIN protected + PIN: 26 Port: A5 Z_ENABLE_PIN protected + PIN: 27 Port: A4 BEEPER_PIN Output = 0 + PIN: 28 Port: A3 LCD_PINS_RS Output = 0 + PIN: 29 Port: A2 Input = 0 + PIN: 30 Port: A1 LCD_PINS_D4 Output = 1 + PIN: 31 Port: A0 SDSS Output = 1 +*/ diff --git a/Marlin/pins_SANGUINOLOLU_11.h b/Marlin/pins_SANGUINOLOLU_11.h index e6769f533..0691fb321 100644 --- a/Marlin/pins_SANGUINOLOLU_11.h +++ b/Marlin/pins_SANGUINOLOLU_11.h @@ -59,7 +59,7 @@ #define BOARD_NAME "Sanguinololu <1.2" #endif -#define IS_MELZI (MB(MELZI) || MB(MELZI_MAKR3D)) +#define IS_MELZI (MB(MELZI) || MB(MELZI_MAKR3D) || MB(MELZI_CREALITY)) // // Limit Switches From 2065591daf1396040a50727939377e57639128a8 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Jo=C3=A3o=20Br=C3=A1zio?= Date: Thu, 6 Jul 2017 18:10:06 +0100 Subject: [PATCH 010/112] Add support for BQ heated bed kit with Hephestos 2 --- Marlin/Conditionals_post.h | 12 ++- Marlin/Marlin_main.cpp | 18 ++-- .../Hephestos_2/Configuration.h | 82 ++++++++++--------- .../Hephestos_2/Configuration_adv.h | 12 +-- .../Hephestos_2/README.md | 7 ++ Marlin/pins_BQ_ZUM_MEGA_3D.h | 9 ++ Marlin/temperature.cpp | 24 +++--- Marlin/ultralcd_impl_DOGM.h | 21 +++-- 8 files changed, 115 insertions(+), 70 deletions(-) diff --git a/Marlin/Conditionals_post.h b/Marlin/Conditionals_post.h index 4f7272f93..ba7a862ea 100644 --- a/Marlin/Conditionals_post.h +++ b/Marlin/Conditionals_post.h @@ -616,8 +616,18 @@ #else #define WRITE_HEATER_0(v) WRITE_HEATER_0P(v) #endif + + /** + * Heated bed requires settings + */ #if HAS_HEATER_BED - #define WRITE_HEATER_BED(v) WRITE(HEATER_BED_PIN, v) + #ifndef MAX_BED_POWER + #define MAX_BED_POWER 255 + #endif + #ifndef HEATER_BED_INVERTING + #define HEATER_BED_INVERTING false + #endif + #define WRITE_HEATER_BED(v) WRITE(HEATER_BED_PIN, (v) ^ HEATER_BED_INVERTING) #endif /** diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index c224d1774..26775212a 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -2312,10 +2312,10 @@ static void clean_up_after_endstop_or_probe_move() { const float nx = lx - (X_PROBE_OFFSET_FROM_EXTRUDER), ny = ly - (Y_PROBE_OFFSET_FROM_EXTRUDER); - if (printable) + if (printable) { if (!position_is_reachable_by_probe_xy(lx, ly)) return NAN; - else - if (!position_is_reachable_xy(nx, ny)) return NAN; + } + else if (!position_is_reachable_xy(nx, ny)) return NAN; const float old_feedrate_mm_s = feedrate_mm_s; @@ -4308,7 +4308,7 @@ void home_all_axes() { gcode_G28(true); } #endif ABL_VAR int left_probe_bed_position, right_probe_bed_position, front_probe_bed_position, back_probe_bed_position; - ABL_VAR float xGridSpacing, yGridSpacing; + ABL_VAR float xGridSpacing = 0, yGridSpacing = 0; #if ENABLED(AUTO_BED_LEVELING_LINEAR) ABL_VAR uint8_t abl_grid_points_x = GRID_MAX_POINTS_X, @@ -7081,6 +7081,10 @@ inline void gcode_M104() { #endif const int8_t e=-2 ) { + #if !(HAS_TEMP_BED && HAS_TEMP_HOTEND) && HOTENDS <= 1 + UNUSED(e); + #endif + SERIAL_PROTOCOLCHAR(' '); SERIAL_PROTOCOLCHAR( #if HAS_TEMP_BED && HAS_TEMP_HOTEND @@ -12735,13 +12739,13 @@ 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) - oldstatus = E0_ENABLE_READ; + const bool oldstatus = E0_ENABLE_READ; enable_E0(); #else // !SWITCHING_EXTRUDER + bool oldstatus; switch (active_extruder) { - case 0: oldstatus = E0_ENABLE_READ; enable_E0(); break; + default: oldstatus = E0_ENABLE_READ; enable_E0(); break; #if E_STEPPERS > 1 case 1: oldstatus = E1_ENABLE_READ; enable_E1(); break; #if E_STEPPERS > 2 diff --git a/Marlin/example_configurations/Hephestos_2/Configuration.h b/Marlin/example_configurations/Hephestos_2/Configuration.h index 805ee35ec..33d609654 100644 --- a/Marlin/example_configurations/Hephestos_2/Configuration.h +++ b/Marlin/example_configurations/Hephestos_2/Configuration.h @@ -20,24 +20,23 @@ * */ +#ifndef CONFIGURATION_H +#define CONFIGURATION_H +#define CONFIGURATION_H_VERSION 010100 + +//=========================================================================== +//================================= README ================================== +//=========================================================================== + /** - * Configuration.h - * - * Basic settings such as: - * - * - Type of electronics - * - Type of temperature sensor - * - Printer geometry - * - Endstop configuration - * - LCD controller - * - Extra features + * BQ Hephestos 2 Configuration * - * Advanced settings can be found in Configuration_adv.h + * This configuration supports the standard Hephestos 2 with or without the + * heated bed kit featured at https://store.bq.com/en/heated-bed-kit-hephestos2 * + * Enable the following option to activate all functionality related to the heated bed. */ -#ifndef CONFIGURATION_H -#define CONFIGURATION_H -#define CONFIGURATION_H_VERSION 010100 +//#define HEPHESTOS2_HEATED_BED_KIT //=========================================================================== //============================= Getting Started ============================= @@ -269,7 +268,13 @@ #define TEMP_SENSOR_2 0 #define TEMP_SENSOR_3 0 #define TEMP_SENSOR_4 0 -#define TEMP_SENSOR_BED 0 + +#if ENABLED(HEPHESTOS2_HEATED_BED_KIT) + #define TEMP_SENSOR_BED 70 + #define HEATER_BED_INVERTING true +#else + #define TEMP_SENSOR_BED 0 +#endif // Dummy thermistor constant temperature readings, for use with 998 and 999 #define DUMMY_THERMISTOR_998_VALUE 25 @@ -293,7 +298,7 @@ // The minimal temperature defines the temperature below which the heater will not be enabled It is used // to check that the wiring to the thermistor is not broken. // Otherwise this would lead to the heater being powered on all the time. -#define HEATER_0_MINTEMP 15 +#define HEATER_0_MINTEMP 5 #define HEATER_1_MINTEMP 5 #define HEATER_2_MINTEMP 5 #define HEATER_3_MINTEMP 5 @@ -303,12 +308,12 @@ // When temperature exceeds max temp, your heater will be switched off. // This feature exists to protect your hotend from overheating accidentally, but *NOT* from thermistor short/failure! // You should use MINTEMP for thermistor short/failure protection. -#define HEATER_0_MAXTEMP 250 +#define HEATER_0_MAXTEMP 275 #define HEATER_1_MAXTEMP 275 #define HEATER_2_MAXTEMP 275 #define HEATER_3_MAXTEMP 275 #define HEATER_4_MAXTEMP 275 -#define BED_MAXTEMP 150 +#define BED_MAXTEMP 110 //=========================================================================== //============================= PID Settings ================================ @@ -362,7 +367,10 @@ // all forms of bed control obey this (PID, bang-bang, bang-bang with hysteresis) // setting this to anything other than 255 enables a form of PWM to the bed just like HEATER_BED_DUTY_CYCLE_DIVIDER did, // so you shouldn't use it unless you are OK with PWM on your bed. (see the comment on enabling PIDTEMPBED) -//#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current + +#if ENABLED(HEPHESTOS2_HEATED_BED_KIT) + #define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current +#endif #if ENABLED(PIDTEMPBED) @@ -414,7 +422,7 @@ */ #define THERMAL_PROTECTION_HOTENDS // Enable thermal protection for all extruders -//#define THERMAL_PROTECTION_BED // Enable thermal protection for the heated bed +#define THERMAL_PROTECTION_BED // Enable thermal protection for the heated bed //=========================================================================== //============================= Mechanical Settings ========================= @@ -499,14 +507,14 @@ * Override with M92 * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ -#define DEFAULT_AXIS_STEPS_PER_UNIT { 160, 160, 8000, 204 } +#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[, E4]]]] */ -#define DEFAULT_MAX_FEEDRATE { 250, 250, 2, 200 } +#define DEFAULT_MAX_FEEDRATE { 167, 167, 3.3, 167 } /** * Default Max Acceleration (change/s) change = mm/s @@ -514,7 +522,7 @@ * Override with M201 * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ -#define DEFAULT_MAX_ACCELERATION { 800, 800, 20, 1000 } +#define DEFAULT_MAX_ACCELERATION { 1000, 1000, 100, 3000 } /** * Default Acceleration (change/s) change = mm/s @@ -524,8 +532,8 @@ * M204 R Retract Acceleration * M204 T Travel Acceleration */ -#define DEFAULT_ACCELERATION 800 // X, Y, Z and E acceleration for printing moves -#define DEFAULT_RETRACT_ACCELERATION 1000 // E acceleration for retracts +#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 /** @@ -536,8 +544,8 @@ * 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_XJERK 20.0 +#define DEFAULT_YJERK 20.0 #define DEFAULT_ZJERK 0.4 #define DEFAULT_EJERK 1.0 @@ -654,7 +662,7 @@ */ #define X_PROBE_OFFSET_FROM_EXTRUDER 34 // X offset: -left +right [of the nozzle] #define Y_PROBE_OFFSET_FROM_EXTRUDER 15 // Y offset: -front +behind [the nozzle] -#define Z_PROBE_OFFSET_FROM_EXTRUDER 0 // Z offset: -below +above [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 @@ -690,7 +698,7 @@ #define Z_PROBE_OFFSET_RANGE_MAX 0 // Enable the M48 repeatability test to test probe accuracy -//#define Z_MIN_PROBE_REPEATABILITY_TEST +#define Z_MIN_PROBE_REPEATABILITY_TEST // For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1 // :{ 0:'Low', 1:'High' } @@ -817,7 +825,7 @@ */ //#define AUTO_BED_LEVELING_3POINT //#define AUTO_BED_LEVELING_LINEAR -//#define AUTO_BED_LEVELING_BILINEAR +#define AUTO_BED_LEVELING_BILINEAR //#define AUTO_BED_LEVELING_UBL //#define MESH_BED_LEVELING @@ -839,12 +847,12 @@ // Set the number of grid points per dimension. #define GRID_MAX_POINTS_X 3 - #define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X + #define GRID_MAX_POINTS_Y 4 // Set the boundaries for probing (where the probe can reach). - #define LEFT_PROBE_BED_POSITION X_MIN_POS + X_PROBE_OFFSET_FROM_EXTRUDER + #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 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) // The Z probe minimum outer margin (to validate G29 parameters). @@ -1011,12 +1019,12 @@ // @section temperature // Preheat Constants -#define PREHEAT_1_TEMP_HOTEND 210 -#define PREHEAT_1_TEMP_BED 70 +#define PREHEAT_1_TEMP_HOTEND 205 +#define PREHEAT_1_TEMP_BED 50 #define PREHEAT_1_FAN_SPEED 0 // Value from 0 to 255 -#define PREHEAT_2_TEMP_HOTEND 240 -#define PREHEAT_2_TEMP_BED 110 +#define PREHEAT_2_TEMP_HOTEND 245 +#define PREHEAT_2_TEMP_BED 50 #define PREHEAT_2_FAN_SPEED 0 // Value from 0 to 255 /** diff --git a/Marlin/example_configurations/Hephestos_2/Configuration_adv.h b/Marlin/example_configurations/Hephestos_2/Configuration_adv.h index 8ee2095aa..7748bbf3c 100644 --- a/Marlin/example_configurations/Hephestos_2/Configuration_adv.h +++ b/Marlin/example_configurations/Hephestos_2/Configuration_adv.h @@ -161,8 +161,8 @@ // then extrude some filament every couple of SECONDS. #define EXTRUDER_RUNOUT_PREVENT #if ENABLED(EXTRUDER_RUNOUT_PREVENT) - #define EXTRUDER_RUNOUT_MINTEMP 190 - #define EXTRUDER_RUNOUT_SECONDS 30 + #define EXTRUDER_RUNOUT_MINTEMP 170 + #define EXTRUDER_RUNOUT_SECONDS 60 #define EXTRUDER_RUNOUT_SPEED 1500 // mm/m #define EXTRUDER_RUNOUT_EXTRUDE 5 // mm #endif @@ -369,7 +369,7 @@ #define DEFAULT_MINIMUMFEEDRATE 0.0 // minimum feedrate #define DEFAULT_MINTRAVELFEEDRATE 0.0 -//#define HOME_AFTER_DEACTIVATE // Require rehoming after steppers are deactivated +#define HOME_AFTER_DEACTIVATE // Require rehoming after steppers are deactivated // @section lcd @@ -447,7 +447,7 @@ #define LCD_INFO_MENU // Scroll a longer status message into view -//#define STATUS_MESSAGE_SCROLLING +#define STATUS_MESSAGE_SCROLLING // On the Info Screen, display XY with one decimal place when possible #define LCD_DECIMAL_SMALL_XY @@ -720,7 +720,7 @@ // enter the serial receive buffer, so they cannot be blocked. // Currently handles M108, M112, M410 // Does not work on boards using AT90USB (USBCON) processors! -//#define EMERGENCY_PARSER +#define EMERGENCY_PARSER // Bad Serial-connections can miss a received command by sending an 'ok' // Therefore some clients abort after 30 seconds in a timeout. @@ -729,7 +729,7 @@ //#define NO_TIMEOUTS 1000 // Milliseconds // Some clients will have this feature soon. This could make the NO_TIMEOUTS unnecessary. -//#define ADVANCED_OK +#define ADVANCED_OK // @section fwretract diff --git a/Marlin/example_configurations/Hephestos_2/README.md b/Marlin/example_configurations/Hephestos_2/README.md index d51f22276..cbe9965ee 100644 --- a/Marlin/example_configurations/Hephestos_2/README.md +++ b/Marlin/example_configurations/Hephestos_2/README.md @@ -5,11 +5,18 @@ NOTE: The look and feel of the Hephestos 2 while navigating the LCD menu will ch ## Changelog * 2016/03/01 - Initial release + * 2016/03/21 - Activated 4-point auto leveling by default Updated miscellaneous z-probe values + * 2016/06/21 - Disabled hot bed related options Activated software endstops SD printing now disables the heater when finished + * 2016/07/13 - Update the `DEFAULT_AXIS_STEPS_PER_UNIT` for the Z axis Increased the `DEFAULT_XYJERK` + * 2016/12/13 - Configuration updated. + + * 2017/07/06 - Configuration updated to the latest Marlin version. + Added support for the official BQ heated bed kit. diff --git a/Marlin/pins_BQ_ZUM_MEGA_3D.h b/Marlin/pins_BQ_ZUM_MEGA_3D.h index 84722f11c..f20f9b54d 100644 --- a/Marlin/pins_BQ_ZUM_MEGA_3D.h +++ b/Marlin/pins_BQ_ZUM_MEGA_3D.h @@ -107,3 +107,12 @@ #define Z_MIN_PIN 19 // IND_S_5V #define Z_MAX_PIN 18 // Z-MIN Label #endif + + +// +// This pin is used by the official Hephestos 2 heated bed upgrade kit +// +#if ENABLED(HEPHESTOS2_HEATED_BED_KIT) + #undef HEATER_BED_PIN + #define HEATER_BED_PIN 8 +#endif diff --git a/Marlin/temperature.cpp b/Marlin/temperature.cpp index a4fdcf985..deaa79ce8 100644 --- a/Marlin/temperature.cpp +++ b/Marlin/temperature.cpp @@ -1721,33 +1721,33 @@ void Temperature::isr() { #endif } else { - if (soft_pwm_count_0 <= pwm_count_tmp) WRITE_HEATER_0(0); + if (soft_pwm_count_0 <= pwm_count_tmp) WRITE_HEATER_0(LOW); #if HOTENDS > 1 - if (soft_pwm_count_1 <= pwm_count_tmp) WRITE_HEATER_1(0); + if (soft_pwm_count_1 <= pwm_count_tmp) WRITE_HEATER_1(LOW); #if HOTENDS > 2 - if (soft_pwm_count_2 <= pwm_count_tmp) WRITE_HEATER_2(0); + if (soft_pwm_count_2 <= pwm_count_tmp) WRITE_HEATER_2(LOW); #if HOTENDS > 3 - if (soft_pwm_count_3 <= pwm_count_tmp) WRITE_HEATER_3(0); + if (soft_pwm_count_3 <= pwm_count_tmp) WRITE_HEATER_3(LOW); #if HOTENDS > 4 - if (soft_pwm_count_4 <= pwm_count_tmp) WRITE_HEATER_4(0); + if (soft_pwm_count_4 <= pwm_count_tmp) WRITE_HEATER_4(LOW); #endif // HOTENDS > 4 #endif // HOTENDS > 3 #endif // HOTENDS > 2 #endif // HOTENDS > 1 #if HAS_HEATER_BED - if (soft_pwm_count_BED <= pwm_count_tmp) WRITE_HEATER_BED(0); + if (soft_pwm_count_BED <= pwm_count_tmp) WRITE_HEATER_BED(LOW); #endif #if ENABLED(FAN_SOFT_PWM) #if HAS_FAN0 - if (soft_pwm_count_fan[0] <= pwm_count_tmp) WRITE_FAN(0); + if (soft_pwm_count_fan[0] <= pwm_count_tmp) WRITE_FAN(LOW); #endif #if HAS_FAN1 - if (soft_pwm_count_fan[1] <= pwm_count_tmp) WRITE_FAN1(0); + if (soft_pwm_count_fan[1] <= pwm_count_tmp) WRITE_FAN1(LOW); #endif #if HAS_FAN2 - if (soft_pwm_count_fan[2] <= pwm_count_tmp) WRITE_FAN2(0); + if (soft_pwm_count_fan[2] <= pwm_count_tmp) WRITE_FAN2(LOW); #endif #endif } @@ -1856,13 +1856,13 @@ void Temperature::isr() { #endif } #if HAS_FAN0 - if (soft_pwm_count_fan[0] <= pwm_count_tmp) WRITE_FAN(0); + if (soft_pwm_count_fan[0] <= pwm_count_tmp) WRITE_FAN(LOW); #endif #if HAS_FAN1 - if (soft_pwm_count_fan[1] <= pwm_count_tmp) WRITE_FAN1(0); + if (soft_pwm_count_fan[1] <= pwm_count_tmp) WRITE_FAN1(LOW); #endif #if HAS_FAN2 - if (soft_pwm_count_fan[2] <= pwm_count_tmp) WRITE_FAN2(0); + if (soft_pwm_count_fan[2] <= pwm_count_tmp) WRITE_FAN2(LOW); #endif #endif // FAN_SOFT_PWM diff --git a/Marlin/ultralcd_impl_DOGM.h b/Marlin/ultralcd_impl_DOGM.h index a11c9afeb..28848cdeb 100644 --- a/Marlin/ultralcd_impl_DOGM.h +++ b/Marlin/ultralcd_impl_DOGM.h @@ -369,20 +369,24 @@ FORCE_INLINE void _draw_centered_temp(const int16_t temp, const uint8_t x, const } FORCE_INLINE void _draw_heater_status(const uint8_t x, const int8_t heater, const bool blink) { + #if !HEATER_IDLE_HANDLER + UNUSED(blink); + #endif + #if HAS_TEMP_BED - bool isBed = heater < 0; + const bool isBed = heater < 0; #else - const bool isBed = false; + constexpr bool isBed = false; #endif if (PAGE_UNDER(7)) { #if HEATER_IDLE_HANDLER const bool is_idle = (!isBed ? thermalManager.is_heater_idle(heater) : - #if HAS_TEMP_BED - thermalManager.is_bed_idle() - #else - false - #endif + #if HAS_TEMP_BED + thermalManager.is_bed_idle() + #else + false + #endif ); if (blink || !is_idle) @@ -852,12 +856,15 @@ static void lcd_implementation_status_screen() { #define DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(_type, _name, _strFunc) \ inline void lcd_implementation_drawmenu_setting_edit_ ## _name (const bool sel, const uint8_t row, const char* pstr, const char* pstr2, _type * const data, ...) { \ + UNUSED(pstr2); \ lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, _strFunc(*(data))); \ } \ inline void lcd_implementation_drawmenu_setting_edit_callback_ ## _name (const bool sel, const uint8_t row, const char* pstr, const char* pstr2, _type * const data, ...) { \ + UNUSED(pstr2); \ lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, _strFunc(*(data))); \ } \ inline void lcd_implementation_drawmenu_setting_edit_accessor_ ## _name (const bool sel, const uint8_t row, const char* pstr, const char* pstr2, _type (*pget)(), void (*pset)(_type), ...) { \ + UNUSED(pstr2); UNUSED(pset); \ lcd_implementation_drawmenu_setting_edit_generic(sel, row, pstr, _strFunc(pget())); \ } \ typedef void _name##_void From 6be369f3eacad705a49680f9f2edb5238f4e746a Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 7 Jul 2017 04:45:14 -0500 Subject: [PATCH 011/112] Add some config names to AUTHOR --- Marlin/example_configurations/Felix/Configuration.h | 2 +- Marlin/example_configurations/Felix/DUAL/Configuration.h | 2 +- Marlin/example_configurations/RigidBot/Configuration.h | 2 +- Marlin/example_configurations/TAZ4/Configuration.h | 2 +- Marlin/example_configurations/TinyBoy2/Configuration.h | 2 +- Marlin/example_configurations/wt150/Configuration.h | 2 +- 6 files changed, 6 insertions(+), 6 deletions(-) diff --git a/Marlin/example_configurations/Felix/Configuration.h b/Marlin/example_configurations/Felix/Configuration.h index a5a060395..3c83423fd 100644 --- a/Marlin/example_configurations/Felix/Configuration.h +++ b/Marlin/example_configurations/Felix/Configuration.h @@ -74,7 +74,7 @@ // User-specified version info of this build to display in [Pronterface, etc] terminal window during // startup. Implementation of an idea by Prof Braino to inform user that any changes made to this // build by the user have been successfully uploaded into firmware. -#define STRING_CONFIG_H_AUTHOR "(none, default config)" // Who made the changes. +#define STRING_CONFIG_H_AUTHOR "(none, Felix)" // Who made the changes. #define SHOW_BOOTSCREEN #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 diff --git a/Marlin/example_configurations/Felix/DUAL/Configuration.h b/Marlin/example_configurations/Felix/DUAL/Configuration.h index 5a9fa5185..015398267 100644 --- a/Marlin/example_configurations/Felix/DUAL/Configuration.h +++ b/Marlin/example_configurations/Felix/DUAL/Configuration.h @@ -74,7 +74,7 @@ // User-specified version info of this build to display in [Pronterface, etc] terminal window during // startup. Implementation of an idea by Prof Braino to inform user that any changes made to this // build by the user have been successfully uploaded into firmware. -#define STRING_CONFIG_H_AUTHOR "(none, default config)" // Who made the changes. +#define STRING_CONFIG_H_AUTHOR "(none, Felix/DUAL)" // Who made the changes. #define SHOW_BOOTSCREEN #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 diff --git a/Marlin/example_configurations/RigidBot/Configuration.h b/Marlin/example_configurations/RigidBot/Configuration.h index dd88d90ef..f8c6e921b 100644 --- a/Marlin/example_configurations/RigidBot/Configuration.h +++ b/Marlin/example_configurations/RigidBot/Configuration.h @@ -74,7 +74,7 @@ // User-specified version info of this build to display in [Pronterface, etc] terminal window during // startup. Implementation of an idea by Prof Braino to inform user that any changes made to this // build by the user have been successfully uploaded into firmware. -#define STRING_CONFIG_H_AUTHOR "(none, default config)" // Who made the changes. +#define STRING_CONFIG_H_AUTHOR "(none, RigidBot)" // Who made the changes. #define SHOW_BOOTSCREEN #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 diff --git a/Marlin/example_configurations/TAZ4/Configuration.h b/Marlin/example_configurations/TAZ4/Configuration.h index 825e7fab7..43b52cdb6 100644 --- a/Marlin/example_configurations/TAZ4/Configuration.h +++ b/Marlin/example_configurations/TAZ4/Configuration.h @@ -74,7 +74,7 @@ // User-specified version info of this build to display in [Pronterface, etc] terminal window during // startup. Implementation of an idea by Prof Braino to inform user that any changes made to this // 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 STRING_CONFIG_H_AUTHOR "(Aleph Objects Inc, TAZ)" // Who made the changes. #define SHOW_BOOTSCREEN #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 diff --git a/Marlin/example_configurations/TinyBoy2/Configuration.h b/Marlin/example_configurations/TinyBoy2/Configuration.h index 07ac3077e..cbcd267b0 100644 --- a/Marlin/example_configurations/TinyBoy2/Configuration.h +++ b/Marlin/example_configurations/TinyBoy2/Configuration.h @@ -90,7 +90,7 @@ // User-specified version info of this build to display in [Pronterface, etc] terminal window during // startup. Implementation of an idea by Prof Braino to inform user that any changes made to this // build by the user have been successfully uploaded into firmware. -#define STRING_CONFIG_H_AUTHOR "(StefanB, default config)" // Who made the changes. +#define STRING_CONFIG_H_AUTHOR "(StefanB, TinyBoy2)" // Who made the changes. #define SHOW_BOOTSCREEN #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 diff --git a/Marlin/example_configurations/wt150/Configuration.h b/Marlin/example_configurations/wt150/Configuration.h index 7487dcee5..e26923620 100644 --- a/Marlin/example_configurations/wt150/Configuration.h +++ b/Marlin/example_configurations/wt150/Configuration.h @@ -74,7 +74,7 @@ // User-specified version info of this build to display in [Pronterface, etc] terminal window during // startup. Implementation of an idea by Prof Braino to inform user that any changes made to this // build by the user have been successfully uploaded into firmware. -#define STRING_CONFIG_H_AUTHOR "(none, default config)" // Who made the changes. +#define STRING_CONFIG_H_AUTHOR "(none, wt150)" // Who made the changes. #define SHOW_BOOTSCREEN #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 From 186580b55fe7a9cf8e9c4e0fb7bf1be2333055f6 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 7 Jul 2017 04:03:27 -0500 Subject: [PATCH 012/112] Arrange example configurations by vendor --- .../{ => AlephObjects}/TAZ4/Configuration.h | 0 .../{ => AlephObjects}/TAZ4/Configuration_adv.h | 0 .../{ => AliExpress}/CL-260/Configuration.h | 2 +- .../example_configurations/{ => AliExpress}/CL-260/README.txt | 2 +- .../example_configurations/{ => BQ}/Hephestos/Configuration.h | 0 .../{ => BQ}/Hephestos/Configuration_adv.h | 0 .../example_configurations/{ => BQ}/Hephestos_2/Configuration.h | 0 .../{ => BQ}/Hephestos_2/Configuration_adv.h | 0 Marlin/example_configurations/{ => BQ}/Hephestos_2/README.md | 0 .../example_configurations/{ => BQ}/Hephestos_2/_Bootscreen.h | 0 Marlin/example_configurations/{ => BQ}/WITBOX/Configuration.h | 0 .../example_configurations/{ => BQ}/WITBOX/Configuration_adv.h | 0 .../{FolgerTech-i3-2020 => Folger Tech/i3-2020}/Configuration.h | 0 .../i3-2020}/Configuration_adv.h | 0 .../{Infitary-i3-M508 => Infitary/i3-M508}/Configuration.h | 0 .../{Infitary-i3-M508 => Infitary/i3-M508}/Configuration_adv.h | 0 Marlin/example_configurations/{ => Malyan}/M150/Configuration.h | 0 .../{ => Malyan}/M150/Configuration_adv.h | 0 Marlin/example_configurations/{ => Malyan}/M150/README.md | 0 Marlin/example_configurations/{ => Malyan}/M150/_Bootscreen.h | 0 .../example_configurations/{ => Velleman}/K8200/Configuration.h | 0 .../{ => Velleman}/K8200/Configuration_adv.h | 0 Marlin/example_configurations/{ => Velleman}/K8200/README.md | 0 .../example_configurations/{ => Velleman}/K8400/Configuration.h | 0 .../{ => Velleman}/K8400/Configuration_adv.h | 0 .../{ => Velleman}/K8400/Dual-head/Configuration.h | 0 Marlin/example_configurations/{ => Velleman}/K8400/README.md | 0 .../{gCreate_gMax1.5+ => gCreate/gMax1.5+}/Configuration.h | 0 .../{gCreate_gMax1.5+ => gCreate/gMax1.5+}/Configuration_adv.h | 0 .../{gCreate_gMax1.5+ => gCreate/gMax1.5+}/_Bootscreen.h | 0 30 files changed, 2 insertions(+), 2 deletions(-) rename Marlin/example_configurations/{ => AlephObjects}/TAZ4/Configuration.h (100%) rename Marlin/example_configurations/{ => AlephObjects}/TAZ4/Configuration_adv.h (100%) rename Marlin/example_configurations/{ => AliExpress}/CL-260/Configuration.h (99%) rename Marlin/example_configurations/{ => AliExpress}/CL-260/README.txt (89%) rename Marlin/example_configurations/{ => BQ}/Hephestos/Configuration.h (100%) rename Marlin/example_configurations/{ => BQ}/Hephestos/Configuration_adv.h (100%) rename Marlin/example_configurations/{ => BQ}/Hephestos_2/Configuration.h (100%) rename Marlin/example_configurations/{ => BQ}/Hephestos_2/Configuration_adv.h (100%) rename Marlin/example_configurations/{ => BQ}/Hephestos_2/README.md (100%) rename Marlin/example_configurations/{ => BQ}/Hephestos_2/_Bootscreen.h (100%) rename Marlin/example_configurations/{ => BQ}/WITBOX/Configuration.h (100%) rename Marlin/example_configurations/{ => BQ}/WITBOX/Configuration_adv.h (100%) rename Marlin/example_configurations/{FolgerTech-i3-2020 => Folger Tech/i3-2020}/Configuration.h (100%) rename Marlin/example_configurations/{FolgerTech-i3-2020 => Folger Tech/i3-2020}/Configuration_adv.h (100%) rename Marlin/example_configurations/{Infitary-i3-M508 => Infitary/i3-M508}/Configuration.h (100%) rename Marlin/example_configurations/{Infitary-i3-M508 => Infitary/i3-M508}/Configuration_adv.h (100%) rename Marlin/example_configurations/{ => Malyan}/M150/Configuration.h (100%) rename Marlin/example_configurations/{ => Malyan}/M150/Configuration_adv.h (100%) rename Marlin/example_configurations/{ => Malyan}/M150/README.md (100%) rename Marlin/example_configurations/{ => Malyan}/M150/_Bootscreen.h (100%) rename Marlin/example_configurations/{ => Velleman}/K8200/Configuration.h (100%) rename Marlin/example_configurations/{ => Velleman}/K8200/Configuration_adv.h (100%) rename Marlin/example_configurations/{ => Velleman}/K8200/README.md (100%) rename Marlin/example_configurations/{ => Velleman}/K8400/Configuration.h (100%) rename Marlin/example_configurations/{ => Velleman}/K8400/Configuration_adv.h (100%) rename Marlin/example_configurations/{ => Velleman}/K8400/Dual-head/Configuration.h (100%) rename Marlin/example_configurations/{ => Velleman}/K8400/README.md (100%) rename Marlin/example_configurations/{gCreate_gMax1.5+ => gCreate/gMax1.5+}/Configuration.h (100%) rename Marlin/example_configurations/{gCreate_gMax1.5+ => gCreate/gMax1.5+}/Configuration_adv.h (100%) rename Marlin/example_configurations/{gCreate_gMax1.5+ => gCreate/gMax1.5+}/_Bootscreen.h (100%) diff --git a/Marlin/example_configurations/TAZ4/Configuration.h b/Marlin/example_configurations/AlephObjects/TAZ4/Configuration.h similarity index 100% rename from Marlin/example_configurations/TAZ4/Configuration.h rename to Marlin/example_configurations/AlephObjects/TAZ4/Configuration.h diff --git a/Marlin/example_configurations/TAZ4/Configuration_adv.h b/Marlin/example_configurations/AlephObjects/TAZ4/Configuration_adv.h similarity index 100% rename from Marlin/example_configurations/TAZ4/Configuration_adv.h rename to Marlin/example_configurations/AlephObjects/TAZ4/Configuration_adv.h diff --git a/Marlin/example_configurations/CL-260/Configuration.h b/Marlin/example_configurations/AliExpress/CL-260/Configuration.h similarity index 99% rename from Marlin/example_configurations/CL-260/Configuration.h rename to Marlin/example_configurations/AliExpress/CL-260/Configuration.h index 9f0a82ac7..e72d15b5a 100644 --- a/Marlin/example_configurations/CL-260/Configuration.h +++ b/Marlin/example_configurations/AliExpress/CL-260/Configuration.h @@ -74,7 +74,7 @@ // User-specified version info of this build to display in [Pronterface, etc] terminal window during // startup. Implementation of an idea by Prof Braino to inform user that any changes made to this // build by the user have been successfully uploaded into firmware. -#define STRING_CONFIG_H_AUTHOR "(none, example CL-260 config)" // Who made the changes. +#define STRING_CONFIG_H_AUTHOR "(none, CL-260)" // Who made the changes. #define SHOW_BOOTSCREEN #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 diff --git a/Marlin/example_configurations/CL-260/README.txt b/Marlin/example_configurations/AliExpress/CL-260/README.txt similarity index 89% rename from Marlin/example_configurations/CL-260/README.txt rename to Marlin/example_configurations/AliExpress/CL-260/README.txt index 80f82893f..b8d6856a6 100644 --- a/Marlin/example_configurations/CL-260/README.txt +++ b/Marlin/example_configurations/AliExpress/CL-260/README.txt @@ -1,4 +1,4 @@ -This is an example configuration for the CL-260. +This is an example configuration for the CL-260 Ultimaker 2 clone. Change Z_MAX_POS to 300 for the CL-260MAX. (The printer is available on AliExpress; be aware that this is not a beginner's diff --git a/Marlin/example_configurations/Hephestos/Configuration.h b/Marlin/example_configurations/BQ/Hephestos/Configuration.h similarity index 100% rename from Marlin/example_configurations/Hephestos/Configuration.h rename to Marlin/example_configurations/BQ/Hephestos/Configuration.h diff --git a/Marlin/example_configurations/Hephestos/Configuration_adv.h b/Marlin/example_configurations/BQ/Hephestos/Configuration_adv.h similarity index 100% rename from Marlin/example_configurations/Hephestos/Configuration_adv.h rename to Marlin/example_configurations/BQ/Hephestos/Configuration_adv.h diff --git a/Marlin/example_configurations/Hephestos_2/Configuration.h b/Marlin/example_configurations/BQ/Hephestos_2/Configuration.h similarity index 100% rename from Marlin/example_configurations/Hephestos_2/Configuration.h rename to Marlin/example_configurations/BQ/Hephestos_2/Configuration.h diff --git a/Marlin/example_configurations/Hephestos_2/Configuration_adv.h b/Marlin/example_configurations/BQ/Hephestos_2/Configuration_adv.h similarity index 100% rename from Marlin/example_configurations/Hephestos_2/Configuration_adv.h rename to Marlin/example_configurations/BQ/Hephestos_2/Configuration_adv.h diff --git a/Marlin/example_configurations/Hephestos_2/README.md b/Marlin/example_configurations/BQ/Hephestos_2/README.md similarity index 100% rename from Marlin/example_configurations/Hephestos_2/README.md rename to Marlin/example_configurations/BQ/Hephestos_2/README.md diff --git a/Marlin/example_configurations/Hephestos_2/_Bootscreen.h b/Marlin/example_configurations/BQ/Hephestos_2/_Bootscreen.h similarity index 100% rename from Marlin/example_configurations/Hephestos_2/_Bootscreen.h rename to Marlin/example_configurations/BQ/Hephestos_2/_Bootscreen.h diff --git a/Marlin/example_configurations/WITBOX/Configuration.h b/Marlin/example_configurations/BQ/WITBOX/Configuration.h similarity index 100% rename from Marlin/example_configurations/WITBOX/Configuration.h rename to Marlin/example_configurations/BQ/WITBOX/Configuration.h diff --git a/Marlin/example_configurations/WITBOX/Configuration_adv.h b/Marlin/example_configurations/BQ/WITBOX/Configuration_adv.h similarity index 100% rename from Marlin/example_configurations/WITBOX/Configuration_adv.h rename to Marlin/example_configurations/BQ/WITBOX/Configuration_adv.h diff --git a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h b/Marlin/example_configurations/Folger Tech/i3-2020/Configuration.h similarity index 100% rename from Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h rename to Marlin/example_configurations/Folger Tech/i3-2020/Configuration.h diff --git a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h b/Marlin/example_configurations/Folger Tech/i3-2020/Configuration_adv.h similarity index 100% rename from Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h rename to Marlin/example_configurations/Folger Tech/i3-2020/Configuration_adv.h diff --git a/Marlin/example_configurations/Infitary-i3-M508/Configuration.h b/Marlin/example_configurations/Infitary/i3-M508/Configuration.h similarity index 100% rename from Marlin/example_configurations/Infitary-i3-M508/Configuration.h rename to Marlin/example_configurations/Infitary/i3-M508/Configuration.h diff --git a/Marlin/example_configurations/Infitary-i3-M508/Configuration_adv.h b/Marlin/example_configurations/Infitary/i3-M508/Configuration_adv.h similarity index 100% rename from Marlin/example_configurations/Infitary-i3-M508/Configuration_adv.h rename to Marlin/example_configurations/Infitary/i3-M508/Configuration_adv.h diff --git a/Marlin/example_configurations/M150/Configuration.h b/Marlin/example_configurations/Malyan/M150/Configuration.h similarity index 100% rename from Marlin/example_configurations/M150/Configuration.h rename to Marlin/example_configurations/Malyan/M150/Configuration.h diff --git a/Marlin/example_configurations/M150/Configuration_adv.h b/Marlin/example_configurations/Malyan/M150/Configuration_adv.h similarity index 100% rename from Marlin/example_configurations/M150/Configuration_adv.h rename to Marlin/example_configurations/Malyan/M150/Configuration_adv.h diff --git a/Marlin/example_configurations/M150/README.md b/Marlin/example_configurations/Malyan/M150/README.md similarity index 100% rename from Marlin/example_configurations/M150/README.md rename to Marlin/example_configurations/Malyan/M150/README.md diff --git a/Marlin/example_configurations/M150/_Bootscreen.h b/Marlin/example_configurations/Malyan/M150/_Bootscreen.h similarity index 100% rename from Marlin/example_configurations/M150/_Bootscreen.h rename to Marlin/example_configurations/Malyan/M150/_Bootscreen.h diff --git a/Marlin/example_configurations/K8200/Configuration.h b/Marlin/example_configurations/Velleman/K8200/Configuration.h similarity index 100% rename from Marlin/example_configurations/K8200/Configuration.h rename to Marlin/example_configurations/Velleman/K8200/Configuration.h diff --git a/Marlin/example_configurations/K8200/Configuration_adv.h b/Marlin/example_configurations/Velleman/K8200/Configuration_adv.h similarity index 100% rename from Marlin/example_configurations/K8200/Configuration_adv.h rename to Marlin/example_configurations/Velleman/K8200/Configuration_adv.h diff --git a/Marlin/example_configurations/K8200/README.md b/Marlin/example_configurations/Velleman/K8200/README.md similarity index 100% rename from Marlin/example_configurations/K8200/README.md rename to Marlin/example_configurations/Velleman/K8200/README.md diff --git a/Marlin/example_configurations/K8400/Configuration.h b/Marlin/example_configurations/Velleman/K8400/Configuration.h similarity index 100% rename from Marlin/example_configurations/K8400/Configuration.h rename to Marlin/example_configurations/Velleman/K8400/Configuration.h diff --git a/Marlin/example_configurations/K8400/Configuration_adv.h b/Marlin/example_configurations/Velleman/K8400/Configuration_adv.h similarity index 100% rename from Marlin/example_configurations/K8400/Configuration_adv.h rename to Marlin/example_configurations/Velleman/K8400/Configuration_adv.h diff --git a/Marlin/example_configurations/K8400/Dual-head/Configuration.h b/Marlin/example_configurations/Velleman/K8400/Dual-head/Configuration.h similarity index 100% rename from Marlin/example_configurations/K8400/Dual-head/Configuration.h rename to Marlin/example_configurations/Velleman/K8400/Dual-head/Configuration.h diff --git a/Marlin/example_configurations/K8400/README.md b/Marlin/example_configurations/Velleman/K8400/README.md similarity index 100% rename from Marlin/example_configurations/K8400/README.md rename to Marlin/example_configurations/Velleman/K8400/README.md diff --git a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h b/Marlin/example_configurations/gCreate/gMax1.5+/Configuration.h similarity index 100% rename from Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h rename to Marlin/example_configurations/gCreate/gMax1.5+/Configuration.h diff --git a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration_adv.h b/Marlin/example_configurations/gCreate/gMax1.5+/Configuration_adv.h similarity index 100% rename from Marlin/example_configurations/gCreate_gMax1.5+/Configuration_adv.h rename to Marlin/example_configurations/gCreate/gMax1.5+/Configuration_adv.h diff --git a/Marlin/example_configurations/gCreate_gMax1.5+/_Bootscreen.h b/Marlin/example_configurations/gCreate/gMax1.5+/_Bootscreen.h similarity index 100% rename from Marlin/example_configurations/gCreate_gMax1.5+/_Bootscreen.h rename to Marlin/example_configurations/gCreate/gMax1.5+/_Bootscreen.h From 4bc79ec877e4a4c247f5014d594ca8ca99a974c1 Mon Sep 17 00:00:00 2001 From: LVD-AC Date: Fri, 7 Jul 2017 09:43:33 +0200 Subject: [PATCH 013/112] Updates for G33-LCD interface --- Marlin/Marlin_main.cpp | 92 ++++++++++--------- .../FLSUN/auto_calibrate/Configuration.h | 2 + .../delta/FLSUN/kossel_mini/Configuration.h | 2 + .../delta/generic/Configuration.h | 2 + .../delta/kossel_mini/Configuration.h | 2 + .../delta/kossel_pro/Configuration.h | 2 + .../delta/kossel_xl/Configuration.h | 2 + Marlin/language_en.h | 3 + Marlin/ultralcd.cpp | 28 +++++- Marlin/utility.h | 2 +- 10 files changed, 92 insertions(+), 45 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 26775212a..35d739a5a 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -5168,11 +5168,28 @@ void home_all_axes() { gcode_G28(true); } SERIAL_PROTOCOL_F(f, 2); } + inline void print_G33_settings(const bool end_stops, const bool tower_angles){ // TODO echo these to LCD ??? + SERIAL_PROTOCOLPAIR(".Height:", DELTA_HEIGHT + home_offset[Z_AXIS]); + if (end_stops) { + print_signed_float(PSTR(" Ex"), endstop_adj[A_AXIS]); + print_signed_float(PSTR("Ey"), endstop_adj[B_AXIS]); + print_signed_float(PSTR("Ez"), endstop_adj[C_AXIS]); + SERIAL_PROTOCOLPAIR(" Radius:", delta_radius); + } + SERIAL_EOL(); + if (tower_angles) { + SERIAL_PROTOCOLPGM(".Tower angle : "); + print_signed_float(PSTR("Tx"), delta_tower_angle_trim[A_AXIS]); + print_signed_float(PSTR("Ty"), delta_tower_angle_trim[B_AXIS]); + SERIAL_PROTOCOLLNPGM(" Tz:+0.00"); + } + } + inline void gcode_G33() { const int8_t probe_points = parser.intval('P', DELTA_CALIBRATION_DEFAULT_POINTS); if (!WITHIN(probe_points, 1, 7)) { - SERIAL_PROTOCOLLNPGM("?(P)oints is implausible (1 to 7)."); + SERIAL_PROTOCOLLNPGM("?(P)oints is implausible (1-7)."); return; } @@ -5256,26 +5273,13 @@ void home_all_axes() { gcode_G28(true); } // print settings - SERIAL_PROTOCOLPGM("Checking... AC"); + const char *checkingac = PSTR("Checking... AC"); // TODO: Make translatable string + serialprintPGM(checkingac); if (verbose_level == 0) SERIAL_PROTOCOLPGM(" (DRY-RUN)"); SERIAL_EOL(); - LCD_MESSAGEPGM("Checking... AC"); // TODO: Make translatable string + lcd_setstatusPGM(checkingac); - SERIAL_PROTOCOLPAIR(".Height:", DELTA_HEIGHT + home_offset[Z_AXIS]); - if (!_1p_calibration) { - print_signed_float(PSTR(" Ex"), endstop_adj[A_AXIS]); - print_signed_float(PSTR("Ey"), endstop_adj[B_AXIS]); - print_signed_float(PSTR("Ez"), endstop_adj[C_AXIS]); - SERIAL_PROTOCOLPAIR(" Radius:", delta_radius); - } - SERIAL_EOL(); - if (_7p_calibration && towers_set) { - SERIAL_PROTOCOLPGM(".Tower angle : "); - print_signed_float(PSTR("Tx"), delta_tower_angle_trim[A_AXIS]); - print_signed_float(PSTR("Ty"), delta_tower_angle_trim[B_AXIS]); - SERIAL_PROTOCOLPGM(" Tz:+0.00"); - SERIAL_EOL(); - } + print_G33_settings(!_1p_calibration, _7p_calibration && towers_set); #if DISABLED(PROBE_MANUALLY) home_offset[Z_AXIS] -= probe_pt(dx, dy, stow_after_each, 1, false); // 1st probe to set height @@ -5345,7 +5349,6 @@ void home_all_axes() { gcode_G28(true); } N++; } zero_std_dev_old = zero_std_dev; - NOMORE(zero_std_dev_min, zero_std_dev); zero_std_dev = round(sqrt(S2 / N) * 1000.0) / 1000.0 + 0.00001; // Solve matrices @@ -5436,8 +5439,9 @@ void home_all_axes() { gcode_G28(true); } recalc_delta_settings(delta_radius, delta_diagonal_rod); } + NOMORE(zero_std_dev_min, zero_std_dev); - // print report + // print report if (verbose_level != 1) { SERIAL_PROTOCOLPGM(". "); @@ -5470,47 +5474,51 @@ void home_all_axes() { gcode_G28(true); } #endif { SERIAL_PROTOCOLPGM("std dev:"); - SERIAL_PROTOCOL_F(zero_std_dev, 3); + SERIAL_PROTOCOL_F(zero_std_dev_min, 3); } SERIAL_EOL(); - LCD_MESSAGEPGM("Calibration OK"); // TODO: Make translatable string + char mess[21]; + sprintf_P(mess, PSTR("Calibration sd:")); + if (zero_std_dev_min < 1) + sprintf_P(&mess[15], PSTR("0.%03i"), (int)round(zero_std_dev_min * 1000.0)); + else + sprintf_P(&mess[15], PSTR("%03i.x"), (int)round(zero_std_dev_min)); + lcd_setstatus(mess); + print_G33_settings(!_1p_calibration, _7p_calibration && towers_set); + serialprintPGM(save_message); + SERIAL_EOL(); } else { // !end iterations - char mess[15] = "No convergence"; + char mess[15]; if (iterations < 31) sprintf_P(mess, PSTR("Iteration : %02i"), (int)iterations); + else + sprintf_P(mess, PSTR("No convergence")); SERIAL_PROTOCOL(mess); SERIAL_PROTOCOL_SP(36); SERIAL_PROTOCOLPGM("std dev:"); SERIAL_PROTOCOL_F(zero_std_dev, 3); SERIAL_EOL(); lcd_setstatus(mess); + print_G33_settings(!_1p_calibration, _7p_calibration && towers_set); } - SERIAL_PROTOCOLPAIR(".Height:", DELTA_HEIGHT + home_offset[Z_AXIS]); - if (!_1p_calibration) { - print_signed_float(PSTR(" Ex"), endstop_adj[A_AXIS]); - print_signed_float(PSTR("Ey"), endstop_adj[B_AXIS]); - print_signed_float(PSTR("Ez"), endstop_adj[C_AXIS]); - SERIAL_PROTOCOLPAIR(" Radius:", delta_radius); - } - SERIAL_EOL(); - if (_7p_calibration && towers_set) { - SERIAL_PROTOCOLPGM(".Tower angle : "); - print_signed_float(PSTR("Tx"), delta_tower_angle_trim[A_AXIS]); - print_signed_float(PSTR("Ty"), delta_tower_angle_trim[B_AXIS]); - SERIAL_PROTOCOLPGM(" Tz:+0.00"); - SERIAL_EOL(); - } - if ((zero_std_dev >= test_precision || zero_std_dev <= calibration_precision) && iterations > force_iterations) - serialprintPGM(save_message); - SERIAL_EOL(); } else { // dry run - SERIAL_PROTOCOLPGM("End DRY-RUN"); + const char *enddryrun = PSTR("End DRY-RUN"); + serialprintPGM(enddryrun); SERIAL_PROTOCOL_SP(39); SERIAL_PROTOCOLPGM("std dev:"); SERIAL_PROTOCOL_F(zero_std_dev, 3); SERIAL_EOL(); + + char mess[21]; + sprintf_P(mess, enddryrun); + sprintf_P(&mess[11], PSTR(" sd:")); + if (zero_std_dev < 1) + sprintf_P(&mess[15], PSTR("0.%03i"), (int)round(zero_std_dev * 1000.0)); + else + sprintf_P(&mess[15], PSTR("%03i.x"), (int)round(zero_std_dev)); + lcd_setstatus(mess); } endstops.enable(true); diff --git a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h index 52acb8871..729a35f2d 100644 --- a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h +++ b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h @@ -482,6 +482,8 @@ #if ENABLED(DELTA_AUTO_CALIBRATION) || ENABLED(DELTA_CALIBRATION_MENU) // Set the radius for the calibration probe points - max DELTA_PRINTABLE_RADIUS*0.869 for non-eccentric probes #define DELTA_CALIBRATION_RADIUS 73.5 // mm + // Set the steprate for papertest probing + #define PROBE_MANUALLY_STEP 0.025 #endif // Print surface diameter/2 minus unreachable space (avoid collisions with vertical towers). diff --git a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h index ec2e2b313..666a3d7fc 100644 --- a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h +++ b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h @@ -482,6 +482,8 @@ #if ENABLED(DELTA_AUTO_CALIBRATION) || ENABLED(DELTA_CALIBRATION_MENU) // Set the radius for the calibration probe points - max DELTA_PRINTABLE_RADIUS*0.869 for non-eccentric probes #define DELTA_CALIBRATION_RADIUS 73.5 // mm + // Set the steprate for papertest probing + #define PROBE_MANUALLY_STEP 0.025 #endif // Print surface diameter/2 minus unreachable space (avoid collisions with vertical towers). diff --git a/Marlin/example_configurations/delta/generic/Configuration.h b/Marlin/example_configurations/delta/generic/Configuration.h index f69074b61..d38c7d833 100644 --- a/Marlin/example_configurations/delta/generic/Configuration.h +++ b/Marlin/example_configurations/delta/generic/Configuration.h @@ -472,6 +472,8 @@ #if ENABLED(DELTA_AUTO_CALIBRATION) || ENABLED(DELTA_CALIBRATION_MENU) // Set the radius for the calibration probe points - max DELTA_PRINTABLE_RADIUS*0.869 for non-eccentric probes #define DELTA_CALIBRATION_RADIUS 121.5 // mm + // Set the steprate for papertest probing + #define PROBE_MANUALLY_STEP 0.025 #endif // Print surface diameter/2 minus unreachable space (avoid collisions with vertical towers). diff --git a/Marlin/example_configurations/delta/kossel_mini/Configuration.h b/Marlin/example_configurations/delta/kossel_mini/Configuration.h index 5118929cd..ccc082064 100644 --- a/Marlin/example_configurations/delta/kossel_mini/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_mini/Configuration.h @@ -472,6 +472,8 @@ #if ENABLED(DELTA_AUTO_CALIBRATION) || ENABLED(DELTA_CALIBRATION_MENU) // Set the radius for the calibration probe points - max DELTA_PRINTABLE_RADIUS*0.869 for non-eccentric probes #define DELTA_CALIBRATION_RADIUS 78.0 // mm + // Set the steprate for papertest probing + #define PROBE_MANUALLY_STEP 0.025 #endif // Print surface diameter/2 minus unreachable space (avoid collisions with vertical towers). diff --git a/Marlin/example_configurations/delta/kossel_pro/Configuration.h b/Marlin/example_configurations/delta/kossel_pro/Configuration.h index 383413346..14d34acea 100644 --- a/Marlin/example_configurations/delta/kossel_pro/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_pro/Configuration.h @@ -458,6 +458,8 @@ #if ENABLED(DELTA_AUTO_CALIBRATION) || ENABLED(DELTA_CALIBRATION_MENU) // Set the radius for the calibration probe points - max DELTA_PRINTABLE_RADIUS*0.869 for non-eccentric probes #define DELTA_CALIBRATION_RADIUS 110.0 // mm + // Set the steprate for papertest probing + #define PROBE_MANUALLY_STEP 0.025 #endif // Print surface diameter/2 minus unreachable space (avoid collisions with vertical towers). diff --git a/Marlin/example_configurations/delta/kossel_xl/Configuration.h b/Marlin/example_configurations/delta/kossel_xl/Configuration.h index 6dfbf7792..b3a3de811 100644 --- a/Marlin/example_configurations/delta/kossel_xl/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_xl/Configuration.h @@ -476,6 +476,8 @@ #if ENABLED(DELTA_AUTO_CALIBRATION) || ENABLED(DELTA_CALIBRATION_MENU) // Set the radius for the calibration probe points - max DELTA_PRINTABLE_RADIUS*0.869 for non-eccentric probes #define DELTA_CALIBRATION_RADIUS 121.5 // mm + // Set the steprate for papertest probing + #define PROBE_MANUALLY_STEP 0.025 #endif // Print surface diameter/2 minus unreachable space (avoid collisions with vertical towers). diff --git a/Marlin/language_en.h b/Marlin/language_en.h index e18812f7c..c67a1ac9f 100644 --- a/Marlin/language_en.h +++ b/Marlin/language_en.h @@ -713,6 +713,9 @@ #ifndef MSG_DELTA_CALIBRATE_CENTER #define MSG_DELTA_CALIBRATE_CENTER _UxGT("Calibrate Center") #endif +#ifndef MSG_DELTA_SETTINGS + #define MSG_DELTA_SETTINGS _UxGT("Show Delta Settings") +#endif #ifndef MSG_DELTA_AUTO_CALIBRATE #define MSG_DELTA_AUTO_CALIBRATE _UxGT("Auto Calibration") #endif diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index e2f320ecc..95145c3b5 100644 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -2500,16 +2500,19 @@ void kill_screen(const char* lcd_msg) { line_to_z(z_dest); lcd_synchronize(); - move_menu_scale = 0.1; + move_menu_scale = PROBE_MANUALLY_STEP; lcd_goto_screen(lcd_move_z); } float lcd_probe_pt(const float &lx, const float &ly) { _man_probe_pt(lx, ly); KEEPALIVE_STATE(PAUSED_FOR_USER); + defer_return_to_status = true; wait_for_user = true; while (wait_for_user) idle(); KEEPALIVE_STATE(IN_HANDLER); + defer_return_to_status = false; + lcd_goto_previous_menu(); return current_position[Z_AXIS]; } @@ -2518,12 +2521,32 @@ void kill_screen(const char* lcd_msg) { void _goto_tower_z() { _man_probe_pt(cos(RADIANS( 90)) * delta_calibration_radius, sin(RADIANS( 90)) * delta_calibration_radius); } void _goto_center() { _man_probe_pt(0,0); } + void lcd_delta_G33_settings() { + START_MENU(); + MENU_BACK(MSG_DELTA_CALIBRATE); + float delta_height = DELTA_HEIGHT + home_offset[Z_AXIS], Tz = 0.00; + MENU_ITEM_EDIT(float52, "Height", &delta_height, delta_height, delta_height); + MENU_ITEM_EDIT(float43, "Ex", &endstop_adj[A_AXIS], -5.0, 5.0); + MENU_ITEM_EDIT(float43, "Ey", &endstop_adj[B_AXIS], -5.0, 5.0); + MENU_ITEM_EDIT(float43, "Ez", &endstop_adj[C_AXIS], -5.0, 5.0); + MENU_ITEM_EDIT(float52, "Radius", &delta_radius, DELTA_RADIUS - 5.0, DELTA_RADIUS + 5.0); + MENU_ITEM_EDIT(float43, "Tx", &delta_tower_angle_trim[A_AXIS], -5.0, 5.0); + MENU_ITEM_EDIT(float43, "Ty", &delta_tower_angle_trim[B_AXIS], -5.0, 5.0); + MENU_ITEM_EDIT(float43, "Tz", &Tz, -5.0, 5.0); + END_MENU(); + } + void lcd_delta_calibrate_menu() { START_MENU(); MENU_BACK(MSG_MAIN); #if ENABLED(DELTA_AUTO_CALIBRATION) + MENU_ITEM(submenu, MSG_DELTA_SETTINGS, lcd_delta_G33_settings); MENU_ITEM(gcode, MSG_DELTA_AUTO_CALIBRATE, PSTR("G33")); MENU_ITEM(gcode, MSG_DELTA_HEIGHT_CALIBRATE, PSTR("G33 P1")); + #if ENABLED(EEPROM_SETTINGS) + MENU_ITEM(function, MSG_STORE_EEPROM, lcd_store_settings); + MENU_ITEM(function, MSG_LOAD_EEPROM, lcd_load_settings); + #endif #endif MENU_ITEM(submenu, MSG_AUTO_HOME, _lcd_delta_calibrate_home); if (axis_homed[Z_AXIS]) { @@ -2612,7 +2635,8 @@ void kill_screen(const char* lcd_msg) { encoderPosition = 0; lcdDrawUpdate = LCDVIEW_REDRAW_NOW; } - if (lcdDrawUpdate) lcd_implementation_drawedit(name, ftostr41sign(current_position[axis])); + if (lcdDrawUpdate) + lcd_implementation_drawedit(name, move_menu_scale >= 0.1 ? ftostr41sign(current_position[axis]) : ftostr43sign(current_position[axis])); } 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); } diff --git a/Marlin/utility.h b/Marlin/utility.h index f88e6943a..426c5837c 100644 --- a/Marlin/utility.h +++ b/Marlin/utility.h @@ -47,7 +47,7 @@ void safe_delay(millis_t ms); char* ftostr12ns(const float &x); // Convert signed float to fixed-length string with 023.45 / -23.45 format - char *ftostr32(const float &x); + char* ftostr32(const float &x); // Convert float to fixed-length string with +123.4 / -123.4 format char* ftostr41sign(const float &x); From aaacef9441d5e1a2047b1b804c0dd6ea1c2b4e70 Mon Sep 17 00:00:00 2001 From: Tannoo Date: Fri, 7 Jul 2017 10:05:08 -0600 Subject: [PATCH 014/112] Corrections (#7231) 20x4 map integration. Also some minor changes to the UBL Menu layout. Both 20x4 LCD's and Graphical LCD panels should have similar functionality now. --- Marlin/Conditionals_LCD.h | 6 - Marlin/language_en.h | 3 + Marlin/stepper.cpp | 11 +- Marlin/ubl_G29.cpp | 1 - Marlin/ultralcd.cpp | 27 +- Marlin/ultralcd_impl_HD44780.h | 527 ++++++++++++++++++++++++++++----- 6 files changed, 482 insertions(+), 93 deletions(-) diff --git a/Marlin/Conditionals_LCD.h b/Marlin/Conditionals_LCD.h index 4dcda59cd..63be06202 100644 --- a/Marlin/Conditionals_LCD.h +++ b/Marlin/Conditionals_LCD.h @@ -273,12 +273,6 @@ #define LCD_FEEDRATE_CHAR 0x06 #define LCD_CLOCK_CHAR 0x07 #define LCD_STR_ARROW_RIGHT ">" /* from the default character set */ - - #if ENABLED(AUTO_BED_LEVELING_UBL) - #define LCD_UBL_BOXTOP_CHAR 0x01 - #define LCD_UBL_BOXBOT_CHAR 0x02 - #endif - #endif /** diff --git a/Marlin/language_en.h b/Marlin/language_en.h index e18812f7c..c262308c8 100644 --- a/Marlin/language_en.h +++ b/Marlin/language_en.h @@ -208,6 +208,9 @@ #ifndef MSG_UBL_CUSTOM_HOTEND_TEMP #define MSG_UBL_CUSTOM_HOTEND_TEMP MSG_UBL_SET_HOTEND_TEMP #endif +#ifndef MSG_UBL_MESH_EDIT + #define MSG_UBL_MESH_EDIT _UxGT("Mesh Edit") +#endif #ifndef MSG_UBL_EDIT_CUSTOM_MESH #define MSG_UBL_EDIT_CUSTOM_MESH _UxGT("Edit Custom Mesh") #endif diff --git a/Marlin/stepper.cpp b/Marlin/stepper.cpp index 717213c50..14b1ebc7d 100644 --- a/Marlin/stepper.cpp +++ b/Marlin/stepper.cpp @@ -62,6 +62,10 @@ Stepper stepper; // Singleton // public: +#if ENABLED(AUTO_BED_LEVELING_UBL) + extern bool ubl_lcd_map_control; +#endif + block_t* Stepper::current_block = NULL; // A pointer to the block currently being traced #if ENABLED(ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED) @@ -1281,7 +1285,12 @@ void Stepper::finish_and_disable() { } void Stepper::quick_stop() { - cleaning_buffer_counter = 5000; + #if ENABLED(AUTO_BED_LEVELING_UBL) + if (!ubl_lcd_map_control) + cleaning_buffer_counter = 5000; + #else + cleaning_buffer_counter = 5000; + #endif DISABLE_STEPPER_DRIVER_INTERRUPT(); while (planner.blocks_queued()) planner.discard_current_block(); current_block = NULL; diff --git a/Marlin/ubl_G29.cpp b/Marlin/ubl_G29.cpp index 162e27c0f..24ea39445 100644 --- a/Marlin/ubl_G29.cpp +++ b/Marlin/ubl_G29.cpp @@ -1533,7 +1533,6 @@ while (ubl_lcd_clicked()) { // debounce and watch for abort idle(); if (ELAPSED(millis(), nxt)) { - ubl_lcd_map_control = false; lcd_return_to_status(); do_blocking_move_to_z(Z_CLEARANCE_BETWEEN_PROBES); LCD_MESSAGEPGM(MSG_EDITING_STOPPED); diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index e2f320ecc..838162cc8 100644 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -467,6 +467,9 @@ uint16_t max_display_update_time = 0; encoderPosition = encoder; if (screen == lcd_status_screen) { defer_return_to_status = false; + #if ENABLED(AUTO_BED_LEVELING_UBL) + ubl_lcd_map_control = false; + #endif screen_history_depth = 0; } lcd_implementation_clear(); @@ -2149,14 +2152,11 @@ void kill_screen(const char* lcd_msg) { void _lcd_ubl_map_homing() { defer_return_to_status = true; - if (lcdDrawUpdate) lcd_implementation_drawedit(PSTR(MSG_LEVEL_BED_HOMING), NULL); + ubl_lcd_map_control = true; // Return to the map screen + if (lcdDrawUpdate) lcd_implementation_drawmenu_static(LCD_HEIGHT < 3 ? 0 : (LCD_HEIGHT > 4 ? 2 : 1), PSTR(MSG_LEVEL_BED_HOMING)); lcdDrawUpdate = LCDVIEW_CALL_NO_REDRAW; - if (axis_homed[X_AXIS] && axis_homed[Y_AXIS] && axis_homed[Z_AXIS]) { - #if DISABLED(DOGLCD) - lcd_set_ubl_map_plot_chars(); - #endif + if (axis_homed[X_AXIS] && axis_homed[Y_AXIS] && axis_homed[Z_AXIS]) lcd_goto_screen(_lcd_ubl_output_map_lcd); - } } /** @@ -2232,9 +2232,12 @@ void kill_screen(const char* lcd_msg) { ubl_map_move_to_xy(); // Move to current location - if (planner.movesplanned() > 1) { // if the nozzle is moving, cancel the move. There is a new location - quickstop_stepper(); + if (planner.movesplanned() > 1) { // if the nozzle is moving, cancel the move. There is a new location + stepper.quick_stop(); + set_current_from_steppers_for_axis(ALL_AXES); + sync_plan_position(); ubl_map_move_to_xy(); // Move to new location + refresh_cmd_timeout(); } } } @@ -2243,9 +2246,10 @@ void kill_screen(const char* lcd_msg) { * UBL Homing before LCD map */ void _lcd_ubl_output_map_lcd_cmd() { - ubl_lcd_map_control = true; // Return to the map screen (and don't restore the character set) - if (!(axis_known_position[X_AXIS] && axis_known_position[Y_AXIS] && axis_known_position[Z_AXIS])) + if (!(axis_known_position[X_AXIS] && axis_known_position[Y_AXIS] && axis_known_position[Z_AXIS])) { + axis_homed[X_AXIS] = axis_homed[Y_AXIS] = axis_homed[Z_AXIS] = false; enqueue_and_echo_commands_P(PSTR("G28")); + } lcd_goto_screen(_lcd_ubl_map_homing); } @@ -2281,6 +2285,7 @@ void kill_screen(const char* lcd_msg) { START_MENU(); MENU_BACK(MSG_UBL_LEVEL_BED); MENU_ITEM(submenu, MSG_UBL_BUILD_MESH_MENU, _lcd_ubl_build_mesh); + MENU_ITEM(gcode, MSG_UBL_MANUAL_MESH, PSTR("G29 I999\nG29 P2 B T0")); MENU_ITEM(submenu, MSG_UBL_VALIDATE_MESH_MENU, _lcd_ubl_validate_mesh); MENU_ITEM(submenu, MSG_UBL_EDIT_MESH_MENU, _lcd_ubl_edit_mesh); MENU_ITEM(submenu, MSG_UBL_MESH_LEVELING, _lcd_ubl_mesh_leveling); @@ -2329,10 +2334,10 @@ void kill_screen(const char* lcd_msg) { void _lcd_ubl_level_bed() { START_MENU(); MENU_BACK(MSG_PREPARE); - MENU_ITEM(gcode, MSG_UBL_MANUAL_MESH, PSTR("G29 I999\nG29 P2 B T0")); MENU_ITEM(gcode, MSG_UBL_ACTIVATE_MESH, PSTR("G29 A")); MENU_ITEM(gcode, MSG_UBL_DEACTIVATE_MESH, PSTR("G29 D")); MENU_ITEM(submenu, MSG_UBL_STEP_BY_STEP_MENU, _lcd_ubl_step_by_step); + MENU_ITEM(function, MSG_UBL_MESH_EDIT, _lcd_ubl_output_map_lcd_cmd); MENU_ITEM(submenu, MSG_UBL_STORAGE_MESH_MENU, _lcd_ubl_storage_mesh); MENU_ITEM(submenu, MSG_UBL_OUTPUT_MAP, _lcd_ubl_output_map); MENU_ITEM(submenu, MSG_UBL_TOOLS, _lcd_ubl_tools_menu); diff --git a/Marlin/ultralcd_impl_HD44780.h b/Marlin/ultralcd_impl_HD44780.h index c2642b4d7..7c530d445 100644 --- a/Marlin/ultralcd_impl_HD44780.h +++ b/Marlin/ultralcd_impl_HD44780.h @@ -33,6 +33,20 @@ #if ENABLED(AUTO_BED_LEVELING_UBL) #include "ubl.h" + + #if ENABLED(ULTIPANEL) + #define ULTRA_X_PIXELS_PER_CHAR 5 + #define ULTRA_Y_PIXELS_PER_CHAR 8 + #define ULTRA_COLUMNS_FOR_MESH_MAP 7 + #define ULTRA_ROWS_FOR_MESH_MAP 4 + + #define N_USER_CHARS 8 + + #define TOP_LEFT 0x01 + #define TOP_RIGHT 0x02 + #define LOWER_LEFT 0x04 + #define LOWER_RIGHT 0x08 + #endif #endif extern volatile uint8_t buttons; //an extended version of the last checked buttons in a bit array. @@ -1078,68 +1092,68 @@ static void lcd_implementation_status_screen() { lcd.setBacklight(leds); ledsprev = leds; } - } #endif // LCD_HAS_STATUS_INDICATORS #if ENABLED(AUTO_BED_LEVELING_UBL) - /** - * These are just basic data for the 20x4 LCD work that - * is coming up very soon. - * Soon this will morph into a map code. - */ + /** + Possible map screens: - /** - Possible map screens: + 16x2 |X000.00 Y000.00| + |(00,00) Z00.000| - 16x2 |X000.00 Y000.00| - |(00,00) Z00.000| + 20x2 | X:000.00 Y:000.00 | + | (00,00) Z:00.000 | - 20x2 | X:000.00 Y:000.00 | - | (00,00) Z:00.000 | + 16x4 |+-------+(00,00)| + || |X000.00| + || |Y000.00| + |+-------+Z00.000| - 16x4 |+-------+(00,00)| - || |X000.00| - || |Y000.00| - |+-------+Z00.000| + 20x4 | +-------+ (00,00) | + | | | X:000.00| + | | | Y:000.00| + | +-------+ Z:00.000| + */ - 20x4 | +-------+ (00,00) | - | | | X:000.00| - | | | Y:000.00| - | +-------+ Z:00.000| - */ + struct custom_char { + uint8_t custom_char_bits[ULTRA_Y_PIXELS_PER_CHAR]; + }; - void lcd_set_ubl_map_plot_chars() { - #if LCD_HEIGHT > 3 - //#include "_ubl_lcd_map_characters.h" - const static byte _lcd_box_top[8] PROGMEM = { - B11111, - B00000, - B00000, - B00000, - B00000, - B00000, - B00000, - B00000 - }; - const static byte _lcd_box_bottom[8] PROGMEM = { - B00000, - B00000, - B00000, - B00000, - B00000, - B00000, - B00000, - B11111 - }; - createChar_P(LCD_UBL_BOXTOP_CHAR, _lcd_box_top); - createChar_P(LCD_UBL_BOXBOT_CHAR, _lcd_box_bottom); - #endif + struct coordinate pixel_location(uint8_t x, uint8_t y); + + struct coordinate { + uint8_t column; + uint8_t row; + uint8_t y_pixel_offset; + uint8_t x_pixel_offset; + uint8_t x_pixel_mask; + }; + + void add_edges_to_custom_char(struct custom_char *custom, struct coordinate *ul, struct coordinate *lr, struct coordinate *brc, uint8_t cell_location); + extern custom_char user_defined_chars[N_USER_CHARS]; + inline static void CLEAR_CUSTOM_CHAR(struct custom_char *cc) { uint8_t j; for (j = 0; j < ULTRA_Y_PIXELS_PER_CHAR; j++) cc->custom_char_bits[j] = 0; } + + /* + void dump_custom_char(char *title, struct custom_char *c) { // This debug routine should be deleted by anybody that sees it. It doesn't belong here + int i, j; // But I'm leaving it for now until we know the 20x4 Radar Map is working right. + SERIAL_PROTOCOLLN(title); // We will need it again if any funny lines show up on the mesh points. + for(j=0; j<8; j++) { + for(i=7; i>=0; i--) { + if (c->custom_char_bits[j] & (0x01 << i)) + SERIAL_PROTOCOL("1"); + else + SERIAL_PROTOCOL("0"); + } + SERIAL_PROTOCOL("\n"); + } + SERIAL_PROTOCOL("\n"); } + */ - void lcd_implementation_ubl_plot(const uint8_t x_plot, const uint8_t y_plot) { + void lcd_implementation_ubl_plot(uint8_t x, uint8_t inverted_y) { #if LCD_WIDTH >= 20 #define _LCD_W_POS 12 @@ -1165,38 +1179,233 @@ static void lcd_implementation_status_screen() { * Show X and Y positions */ _XLABEL(_PLOT_X, 0); - lcd.print(ftostr32(LOGICAL_X_POSITION(pgm_read_float(&ubl._mesh_index_to_xpos[x_plot])))); + lcd.print(ftostr32(LOGICAL_X_POSITION(pgm_read_float(&ubl._mesh_index_to_xpos[x])))); _YLABEL(_LCD_W_POS, 0); - lcd.print(ftostr32(LOGICAL_Y_POSITION(pgm_read_float(&ubl._mesh_index_to_ypos[y_plot])))); + lcd.print(ftostr32(LOGICAL_Y_POSITION(pgm_read_float(&ubl._mesh_index_to_ypos[inverted_y])))); lcd.setCursor(_PLOT_X, 0); - #else // 16x4 or 20x4 display + #else // 16x4 or 20x4 display - /** - * Draw the Mesh Map Box + struct coordinate upper_left, lower_right, bottom_right_corner; + struct custom_char new_char; + uint8_t i, j, k, l, m, n, n_rows, n_cols, y; + uint8_t bottom_line, right_edge; + uint8_t x_map_pixels, y_map_pixels; + uint8_t pixels_per_X_mesh_pnt, pixels_per_Y_mesh_pnt; + uint8_t suppress_x_offset=0, suppress_y_offset=0; + + // ******************************************************** + // ************ Clear and setup everything ********* + // ******************************************************** + + y = GRID_MAX_POINTS_Y - inverted_y - 1; + + upper_left.column = 0; + upper_left.row = 0; + lower_right.column = 0; + lower_right.row = 0; + + lcd_implementation_clear(); + + x_map_pixels = ULTRA_X_PIXELS_PER_CHAR * ULTRA_COLUMNS_FOR_MESH_MAP - 2; // minus 2 because we are drawing a box around the map + y_map_pixels = ULTRA_Y_PIXELS_PER_CHAR * ULTRA_ROWS_FOR_MESH_MAP - 2; + + pixels_per_X_mesh_pnt = x_map_pixels / GRID_MAX_POINTS_X; + pixels_per_Y_mesh_pnt = y_map_pixels / GRID_MAX_POINTS_Y; + + if (pixels_per_X_mesh_pnt >= ULTRA_X_PIXELS_PER_CHAR) { // There are only 2 custom characters available, so the X + pixels_per_X_mesh_pnt = ULTRA_X_PIXELS_PER_CHAR; // size of the mesh point needs to fit within them independent + suppress_x_offset = 1; // of where the starting pixel is located. + } + + if (pixels_per_Y_mesh_pnt >= ULTRA_Y_PIXELS_PER_CHAR) { // There are only 2 custom characters available, so the Y + pixels_per_Y_mesh_pnt = ULTRA_Y_PIXELS_PER_CHAR; // size of the mesh point needs to fit within them independent + suppress_y_offset = 1; // of where the starting pixel is located. + } + + x_map_pixels = pixels_per_X_mesh_pnt * GRID_MAX_POINTS_X; // now we have the right number of pixels to make both + y_map_pixels = pixels_per_Y_mesh_pnt * GRID_MAX_POINTS_Y; // directions fit nicely + + right_edge = pixels_per_X_mesh_pnt * GRID_MAX_POINTS_X + 1; // find location of right edge within the character cell + bottom_line= pixels_per_Y_mesh_pnt * GRID_MAX_POINTS_Y + 1; // find location of bottome line within the character cell + + n_rows = (bottom_line / ULTRA_Y_PIXELS_PER_CHAR) + 1; + n_cols = (right_edge / ULTRA_X_PIXELS_PER_CHAR) + 1; + + for (i = 0; i < n_cols; i++) { + lcd.setCursor(i, 0); + lcd.print((char) 0x00); // top line of the box + + lcd.setCursor(i, n_rows-1); + lcd.write(0x01); // bottom line of the box + } + + for (j = 0; j < n_rows; j++) { + lcd.setCursor(0, j); + lcd.write(0x02); // Left edge of the box + lcd.setCursor(n_cols-1, j); + lcd.write(0x03); // right edge of the box + } + + // + /* if the entire 4th row is not in use, do not put vertical bars all the way down to the bottom of the display */ + // + + k = pixels_per_Y_mesh_pnt * GRID_MAX_POINTS_Y + 2; + l = ULTRA_Y_PIXELS_PER_CHAR * n_rows; + if ((k != l) && ((l-k)>=ULTRA_Y_PIXELS_PER_CHAR/2)) { + lcd.setCursor(0, n_rows-1); // left edge of the box + lcd.write(' '); + lcd.setCursor(n_cols-1, n_rows-1); // right edge of the box + lcd.write(' '); + } + + CLEAR_CUSTOM_CHAR(&new_char); + new_char.custom_char_bits[0] = (unsigned char) 0B11111; // char #0 is used for the top line of the box + lcd.createChar(0, (uint8_t *) &new_char); + + CLEAR_CUSTOM_CHAR(&new_char); + k = GRID_MAX_POINTS_Y * pixels_per_Y_mesh_pnt + 1; // row of pixels for the bottom box line + l = k % ULTRA_Y_PIXELS_PER_CHAR; // row within relivant character cell + new_char.custom_char_bits[l] = (unsigned char) 0B11111; // char #1 is used for the bottom line of the box + lcd.createChar(1, (uint8_t *) &new_char); + + CLEAR_CUSTOM_CHAR(&new_char); + for (j = 0; j < ULTRA_Y_PIXELS_PER_CHAR; j++) + new_char.custom_char_bits[j] = (unsigned char) 0B10000; // char #2 is used for the left edge of the box + lcd.createChar(2, (uint8_t *) &new_char); + + CLEAR_CUSTOM_CHAR(&new_char); + m = GRID_MAX_POINTS_X * pixels_per_X_mesh_pnt + 1; // column of pixels for the right box line + n = m % ULTRA_X_PIXELS_PER_CHAR; // column within relivant character cell + i = ULTRA_X_PIXELS_PER_CHAR - 1 - n; // column within relivant character cell (0 on the right) + for (j = 0; j < ULTRA_Y_PIXELS_PER_CHAR; j++) + new_char.custom_char_bits[j] = (unsigned char) 0B00001 << i; // char #3 is used for the right edge of the box + lcd.createChar(3, (uint8_t *) &new_char); + + i = x*pixels_per_X_mesh_pnt - suppress_x_offset; + j = y*pixels_per_Y_mesh_pnt - suppress_y_offset; + upper_left = pixel_location(i, j); + + k = (x+1)*pixels_per_X_mesh_pnt-1-suppress_x_offset; + l = (y+1)*pixels_per_Y_mesh_pnt-1-suppress_y_offset; + lower_right = pixel_location(k, l); + + bottom_right_corner = pixel_location(x_map_pixels, y_map_pixels); + + /* + * First, handle the simple case where everything is within a single character cell. + * If part of the Mesh Plot is outside of this character cell, we will follow up + * and deal with that next. */ - uint8_t m; - lcd.setCursor(_MAP_X, 0); for (m = 0; m < 5; m++) lcd.write(LCD_UBL_BOXTOP_CHAR); // Top - lcd.setCursor(_MAP_X, 3); for (m = 0; m < 5; m++) lcd.write(LCD_UBL_BOXBOT_CHAR); // Bottom - for (m = 0; m <= 3; m++) { - lcd.setCursor(2, m); lcd.write('|'); // Left - lcd.setCursor(8, m); lcd.write('|'); // Right + + //dump_custom_char("at entry:", &new_char); + + CLEAR_CUSTOM_CHAR(&new_char); + for(j=upper_left.y_pixel_offset; j= ULTRA_Y_PIXELS_PER_CHAR) + break; + i=upper_left.x_pixel_mask; + for(k=0; k> 1; + } } + //dump_custom_char("after loops:", &new_char); - lcd.setCursor(_LCD_W_POS, 0); + add_edges_to_custom_char(&new_char, &upper_left, &lower_right, &bottom_right_corner, TOP_LEFT); + //dump_custom_char("after add edges", &new_char); + lcd.createChar(4, (uint8_t *) &new_char); + + lcd.setCursor(upper_left.column, upper_left.row); + lcd.write(0x04); + //dump_custom_char("after lcd update:", &new_char); + + /* + * Next, check for two side by side character cells being used to display the Mesh Point + * If found... do the right hand character cell next. + */ + if (upper_left.column+1 == lower_right.column) { + l = upper_left.x_pixel_offset; + CLEAR_CUSTOM_CHAR(&new_char); + for (j = upper_left.y_pixel_offset; j < upper_left.y_pixel_offset + pixels_per_Y_mesh_pnt; j++) { + if (j >= ULTRA_Y_PIXELS_PER_CHAR) + break; + i=0x01 << (ULTRA_X_PIXELS_PER_CHAR-1); // fill in the left side of the right character cell + for(k=0; k> 1; + } + } + add_edges_to_custom_char(&new_char, &upper_left, &lower_right, &bottom_right_corner, TOP_RIGHT); + + lcd.createChar(5, (uint8_t *) &new_char); + + lcd.setCursor(lower_right.column, upper_left.row); + lcd.write(0x05); + } + + /* + * Next, check for two character cells stacked on top of each other being used to display the Mesh Point + */ + if (upper_left.row+1 == lower_right.row) { + l = ULTRA_Y_PIXELS_PER_CHAR - upper_left.y_pixel_offset; // number of pixel rows in top character cell + k = pixels_per_Y_mesh_pnt - l; // number of pixel rows in bottom character cell + CLEAR_CUSTOM_CHAR(&new_char); + for(j=0; j> 1; + if (!i) + break; + } + } + add_edges_to_custom_char(&new_char, &upper_left, &lower_right, &bottom_right_corner, LOWER_LEFT); + lcd.createChar(6, (uint8_t *) &new_char); + + lcd.setCursor(upper_left.column, lower_right.row); + lcd.write(0x06); + } + + /* + * Next, check for four character cells being used to display the Mesh Point. If that is + * what is here, we work to fill in the character cell that is down one and to the right one + * from the upper_left character cell. + */ + + if (upper_left.column+1 == lower_right.column && upper_left.row+1 == lower_right.row) { + l = ULTRA_Y_PIXELS_PER_CHAR - upper_left.y_pixel_offset; // number of pixel rows in top character cell + k = pixels_per_Y_mesh_pnt - l; // number of pixel rows in bottom character cell + CLEAR_CUSTOM_CHAR(&new_char); + for (j = 0; j> 1; + } + } + add_edges_to_custom_char(&new_char, &upper_left, &lower_right, &bottom_right_corner, LOWER_RIGHT); + lcd.createChar(7, (uint8_t *) &new_char); + + lcd.setCursor(lower_right.column, lower_right.row); + lcd.write(0x07); + } #endif - /** - * Print plot position - */ - lcd.write('('); - lcd.print(x_plot); - lcd.write(','); - lcd.print(y_plot); - lcd.write(')'); + /** + * Print plot position + */ + lcd.setCursor(_LCD_W_POS, 0); + lcd.write('('); + lcd.print(x); + lcd.write(','); + lcd.print(inverted_y); + lcd.write(')'); #if LCD_HEIGHT <= 3 // 16x2 or 20x2 display @@ -1204,8 +1413,8 @@ static void lcd_implementation_status_screen() { * Print Z values */ _ZLABEL(_LCD_W_POS, 1); - if (!isnan(ubl.z_values[x_plot][y_plot])) - lcd.print(ftostr43sign(ubl.z_values[x_plot][y_plot])); + if (!isnan(ubl.z_values[x][inverted_y])) + lcd.print(ftostr43sign(ubl.z_values[x][inverted_y])); else lcd_printPGM(PSTR(" -----")); @@ -1215,20 +1424,190 @@ static void lcd_implementation_status_screen() { * Show all values at right of screen */ _XLABEL(_LCD_W_POS, 1); - lcd.print(ftostr32(LOGICAL_X_POSITION(pgm_read_float(&ubl._mesh_index_to_xpos[x_plot])))); + lcd.print(ftostr32(LOGICAL_X_POSITION(pgm_read_float(&ubl._mesh_index_to_xpos[x])))); _YLABEL(_LCD_W_POS, 2); - lcd.print(ftostr32(LOGICAL_Y_POSITION(pgm_read_float(&ubl._mesh_index_to_ypos[y_plot])))); + lcd.print(ftostr32(LOGICAL_Y_POSITION(pgm_read_float(&ubl._mesh_index_to_ypos[inverted_y])))); /** * Show the location value */ _ZLABEL(_LCD_W_POS, 3); - if (!isnan(ubl.z_values[x_plot][y_plot])) - lcd.print(ftostr43sign(ubl.z_values[x_plot][y_plot])); + if (!isnan(ubl.z_values[x][inverted_y])) + lcd.print(ftostr43sign(ubl.z_values[x][inverted_y])); else lcd_printPGM(PSTR(" -----")); #endif // LCD_HEIGHT > 3 + + return; + } +void add_edges_to_custom_char(struct custom_char *custom, struct coordinate *ul, struct coordinate *lr, struct coordinate *brc, unsigned char cell_location) { + unsigned char i, k; + int n_rows, n_cols; + + n_rows = lr->row - ul->row + 1; + n_cols = lr->column - ul->column + 1; + + /* + * Check if Top line of box needs to be filled in + */ + if ((ul->row == 0) && ((cell_location&TOP_LEFT) || (cell_location&TOP_RIGHT))) { // Only fill in the top line for the top character cells + + if (n_cols == 1) { + if (ul->column != brc->column) + custom->custom_char_bits[0] = 0xff; // single column in middle + else { + for (i = brc->x_pixel_offset; icustom_char_bits[0] |= 0x01 << i; + } + } + else { + if (cell_location & TOP_LEFT) + custom->custom_char_bits[0] = 0xff; // multiple column in the middle + else + if (lr->column != brc->column) + custom->custom_char_bits[0] = 0xff; // multiple column with right cell in middle + else { + for (i = brc->x_pixel_offset; icustom_char_bits[0] |= 0x01 << i; + } + } + } + + /* + * Check if left line of box needs to be filled in + */ + if ((cell_location & TOP_LEFT) || (cell_location & LOWER_LEFT)) { + if (ul->column == 0) { // Left column of characters on LCD Display + if (ul->row != brc->row) + k = ULTRA_Y_PIXELS_PER_CHAR; // if it isn't the last row... do the full character cell + else + k = brc->y_pixel_offset; + + for (i = 0; i < k; i++) + custom->custom_char_bits[i] |= 0x01 << (ULTRA_X_PIXELS_PER_CHAR - 1); + } + } + + /* + * Check if bottom line of box needs to be filled in + */ + + // Single row of mesh plot cells + if ((n_rows==1) /* && ((cell_location == TOP_LEFT) || (cell_location==TOP_RIGHT)) */) { + if (ul->row == brc->row) { + if (n_cols == 1) { // single row, single column case + if (ul->column != brc->column) + k = 0x01; + else + k = brc->x_pixel_mask; + } else { + if (cell_location & TOP_RIGHT) { // single row, multiple column case + if(lr->column != brc->column) + k = 0x01; + else + k = brc->x_pixel_mask; + } else // single row, left of multiple columns + k = 0x01; + } + while (k < (0x01 << ULTRA_X_PIXELS_PER_CHAR)) { + custom->custom_char_bits[brc->y_pixel_offset] |= k; + k = k << 1; + } + } + } + + + // Double row of characters on LCD Display + // And this is a bottom custom character + if ((n_rows==2) && ((cell_location == LOWER_LEFT) || (cell_location==LOWER_RIGHT))) { + if (lr->row == brc->row) { + if (n_cols == 1) { // double row, single column case + if (ul->column != brc->column) + k = 0x01; + else + k = brc->x_pixel_mask; + } else { + if (cell_location & LOWER_RIGHT) { // double row, multiple column case + if(lr->column != brc->column) + k = 0x01; + else + k = brc->x_pixel_mask; + } else // double row, left of multiple columns + k = 0x01; + } + while (k < (0x01 << ULTRA_X_PIXELS_PER_CHAR)) { + custom->custom_char_bits[brc->y_pixel_offset] |= k; + k = k << 1; + } + } + } + + /* + * Check if right line of box needs to be filled in + */ + + if (lr->column == brc->column) { // nothing to do if the lower right part of the mesh pnt isn't in the same column as the box line + if ((ul->column == brc->column) || + ((lr->column == brc->column) && (cell_location&TOP_RIGHT)) || + ((lr->column == brc->column) && (cell_location&LOWER_RIGHT))) { // This mesh point is in the same character cell as the right box line + + if (ul->row != brc->row) + k = ULTRA_Y_PIXELS_PER_CHAR; // if it isn't the last row... do the full character cell + else + k = brc->y_pixel_offset; + + for (i = 0; i < k; i++) + custom->custom_char_bits[i] |= brc->x_pixel_mask; + } + } + } + + struct coordinate pixel_location(int x, int y) { + struct coordinate ret_val; + int xp, yp, r, c; + + x++; // +1 because there is a line on the left + y++; // and a line at the top to make the box + + c = x / ULTRA_X_PIXELS_PER_CHAR; + r = y / ULTRA_Y_PIXELS_PER_CHAR; + + ret_val.column = c; + ret_val.row = r; + + xp = x - c * ULTRA_X_PIXELS_PER_CHAR; // get the pixel offsets into the character cell + xp = ULTRA_X_PIXELS_PER_CHAR - 1 - xp; // column within relivant character cell (0 on the right) + yp = y - r * ULTRA_Y_PIXELS_PER_CHAR; + + ret_val.x_pixel_mask = 0x01 << xp; + ret_val.x_pixel_offset = xp; + ret_val.y_pixel_offset = yp; + return ret_val; + } + + struct coordinate pixel_location(uint8_t x, uint8_t y) { + struct coordinate ret_val; + uint8_t xp, yp, r, c; + + x++; // +1 because there is a line on the left + y++; // and a line at the top to make the box + + c = x / ULTRA_X_PIXELS_PER_CHAR; + r = y / ULTRA_Y_PIXELS_PER_CHAR; + + ret_val.column = c; + ret_val.row = r; + + xp = x - c * ULTRA_X_PIXELS_PER_CHAR; // get the pixel offsets into the character cell + xp = ULTRA_X_PIXELS_PER_CHAR - 1 - xp; // column within relivant character cell (0 on the right) + yp = y - r * ULTRA_Y_PIXELS_PER_CHAR; + + ret_val.x_pixel_mask = 0x01 << xp; + ret_val.x_pixel_offset = xp; + ret_val.y_pixel_offset = yp; + + return ret_val; } #endif // AUTO_BED_LEVELING_UBL From e927941c064890cf05e10a5e31c869fcc93084ab Mon Sep 17 00:00:00 2001 From: Tannoo Date: Sat, 8 Jul 2017 08:44:50 -0600 Subject: [PATCH 015/112] Bugfix (#7265) Fix compile error when UBL is enabled but there is no LCD Panel. --- Marlin/stepper.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/stepper.cpp b/Marlin/stepper.cpp index 14b1ebc7d..9493cedf1 100644 --- a/Marlin/stepper.cpp +++ b/Marlin/stepper.cpp @@ -62,7 +62,7 @@ Stepper stepper; // Singleton // public: -#if ENABLED(AUTO_BED_LEVELING_UBL) +#if ENABLED(AUTO_BED_LEVELING_UBL) && ENABLED(ULTIPANEL) extern bool ubl_lcd_map_control; #endif @@ -1285,7 +1285,7 @@ void Stepper::finish_and_disable() { } void Stepper::quick_stop() { - #if ENABLED(AUTO_BED_LEVELING_UBL) + #if ENABLED(AUTO_BED_LEVELING_UBL) && ENABLED(ULTIPANEL) if (!ubl_lcd_map_control) cleaning_buffer_counter = 5000; #else From 00e4ced58e6bba77448369e4baa4aedd2c8bae14 Mon Sep 17 00:00:00 2001 From: Jamie Bainbridge Date: Sat, 8 Jul 2017 13:10:49 +1000 Subject: [PATCH 016/112] Stay in User Menu after command. Add feedback. When a user executes a User Menu command, the LCD returns to the main menu. If the user has multiple menu items they want to run, such as one menu item per bed leveling corner, then it's better to stay in the User Menu rather than return to the main menu. This PR modifies Marlin to stay in the User Menu after a command. --- Marlin/ultralcd.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index c70775c03..d32dd6044 100644 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -834,8 +834,8 @@ void kill_screen(const char* lcd_msg) { #endif void _lcd_user_gcode(const char * const cmd) { - lcd_return_to_status(); enqueue_and_echo_commands_P(cmd); + lcd_completion_feedback(); } #if defined(USER_DESC_1) && defined(USER_GCODE_1) From 76e90b93b78a12e8d3926309f7ef9f6a7aacc451 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 10 Jul 2017 15:38:54 -0500 Subject: [PATCH 017/112] Volatile keyword not needed for parser.seen --- Marlin/gcode.h | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/Marlin/gcode.h b/Marlin/gcode.h index ace84d8de..36549b851 100644 --- a/Marlin/gcode.h +++ b/Marlin/gcode.h @@ -131,8 +131,7 @@ public: // Code seen bit was set. If not found, value_ptr is unchanged. // This allows "if (seen('A')||seen('B'))" to use the last-found value. - // This is volatile because its side-effects are important - static volatile bool seen(const char c) { + static bool seen(const char c) { const uint8_t ind = LETTER_OFF(c); if (ind >= COUNT(param)) return false; // Only A-Z const bool b = TEST(codebits[PARAM_IND(ind)], PARAM_BIT(ind)); @@ -148,8 +147,7 @@ public: // Code is found in the string. If not found, value_ptr is unchanged. // This allows "if (seen('A')||seen('B'))" to use the last-found value. - // This is volatile because its side-effects are important - static volatile bool seen(const char c) { + static bool seen(const char c) { const char *p = strchr(command_args, c); const bool b = !!p; if (b) value_ptr = DECIMAL_SIGNED(p[1]) ? &p[1] : (char*)NULL; From 9af67e2446ae743b9ee1a139de494ff8217a10e1 Mon Sep 17 00:00:00 2001 From: Roxy-3D Date: Mon, 10 Jul 2017 19:05:11 -0500 Subject: [PATCH 018/112] Save 7714 bytes of program memory when doing AUTO_BED_LEVELING_LINEAR (#7276) We can save more and a pile of RAM by eleminating the eqnBVector and EqnAMatrix arrays next. --- Marlin/Marlin_main.cpp | 40 +- Marlin/least_squares_fit.cpp | 4 +- Marlin/least_squares_fit.h | 2 +- Marlin/qr_solve.cpp | 1591 ---------------------------------- Marlin/qr_solve.h | 44 - 5 files changed, 28 insertions(+), 1653 deletions(-) delete mode 100644 Marlin/qr_solve.cpp delete mode 100644 Marlin/qr_solve.h diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 35d739a5a..d244b198d 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -261,7 +261,7 @@ #if HAS_ABL #include "vector_3.h" #if ENABLED(AUTO_BED_LEVELING_LINEAR) - #include "qr_solve.h" + #include "least_squares_fit.h" #endif #elif ENABLED(MESH_BED_LEVELING) #include "mesh_bed_leveling.h" @@ -4336,8 +4336,8 @@ void home_all_axes() { gcode_G28(true); } ABL_VAR int indexIntoAB[GRID_MAX_POINTS_X][GRID_MAX_POINTS_Y]; ABL_VAR float eqnAMatrix[GRID_MAX_POINTS * 3], // "A" matrix of the linear system of equations - eqnBVector[GRID_MAX_POINTS], // "B" vector of Z points - mean; + eqnBVector[GRID_MAX_POINTS], // "B" vector of Z points + mean; #endif #elif ENABLED(AUTO_BED_LEVELING_3POINT) @@ -4353,6 +4353,11 @@ void home_all_axes() { gcode_G28(true); } #endif // AUTO_BED_LEVELING_3POINT + #if ENABLED(AUTO_BED_LEVELING_LINEAR) + struct linear_fit_data lsf_results; + incremental_LSF_reset(&lsf_results); + #endif + /** * On the initial G29 fetch command parameters. */ @@ -4549,11 +4554,7 @@ void home_all_axes() { gcode_G28(true); } abl_should_enable = false; } - #elif ENABLED(AUTO_BED_LEVELING_LINEAR) - - mean = 0.0; - - #endif // AUTO_BED_LEVELING_LINEAR + #endif // AUTO_BED_LEVELING_BILINEAR #if ENABLED(AUTO_BED_LEVELING_3POINT) @@ -4616,11 +4617,11 @@ void home_all_axes() { gcode_G28(true); } #if ENABLED(AUTO_BED_LEVELING_LINEAR) - mean += measured_z; - eqnBVector[abl_probe_index] = measured_z; - eqnAMatrix[abl_probe_index + 0 * abl2] = xProbe; - eqnAMatrix[abl_probe_index + 1 * abl2] = yProbe; - eqnAMatrix[abl_probe_index + 2 * abl2] = 1; +// mean += measured_z; // I believe this is unused code? +// eqnBVector[abl_probe_index] = measured_z; // I believe this is unused code? +// eqnAMatrix[abl_probe_index + 0 * abl2] = xProbe; // I believe this is unused code? +// eqnAMatrix[abl_probe_index + 1 * abl2] = yProbe; // I believe this is unused code? +// eqnAMatrix[abl_probe_index + 2 * abl2] = 1; // I believe this is unused code? #elif ENABLED(AUTO_BED_LEVELING_BILINEAR) @@ -4794,6 +4795,11 @@ void home_all_axes() { gcode_G28(true); } eqnAMatrix[abl_probe_index + 1 * abl2] = yProbe; eqnAMatrix[abl_probe_index + 2 * abl2] = 1; + incremental_LSF(&lsf_results, xProbe, yProbe, measured_z); + + #if ENABLED(AUTO_BED_LEVELING_LINEAR) + indexIntoAB[xCount][yCount] = abl_probe_index; + #endif #elif ENABLED(AUTO_BED_LEVELING_BILINEAR) z_values[xCount][yCount] = measured_z + zoffset; @@ -4894,7 +4900,11 @@ void home_all_axes() { gcode_G28(true); } * so Vx = -a Vy = -b Vz = 1 (we want the vector facing towards positive Z */ float plane_equation_coefficients[3]; - qr_solve(plane_equation_coefficients, abl2, 3, eqnAMatrix, eqnBVector); + + finish_incremental_LSF(&lsf_results); + plane_equation_coefficients[0] = -lsf_results.A; // We should be able to eliminate the '-' on these three lines and down below + plane_equation_coefficients[1] = -lsf_results.B; // but that is not yet tested. + plane_equation_coefficients[2] = -lsf_results.D; mean /= abl2; @@ -4916,7 +4926,7 @@ void home_all_axes() { gcode_G28(true); } // 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) + vector_3(-plane_equation_coefficients[0], -plane_equation_coefficients[1], 1) // We can eleminate the '-' here and up above ); } diff --git a/Marlin/least_squares_fit.cpp b/Marlin/least_squares_fit.cpp index 42adc8fe6..f8c7a0b52 100644 --- a/Marlin/least_squares_fit.cpp +++ b/Marlin/least_squares_fit.cpp @@ -34,7 +34,7 @@ #include "MarlinConfig.h" -#if ENABLED(AUTO_BED_LEVELING_UBL) // Currently only used by UBL, but is applicable to Grid Based (Linear) Bed Leveling +#if ENABLED(AUTO_BED_LEVELING_UBL) || ENABLED(AUTO_BED_LEVELING_LINEAR) #include "macros.h" #include @@ -68,4 +68,4 @@ int finish_incremental_LSF(struct linear_fit_data *lsf) { return 0; } -#endif // AUTO_BED_LEVELING_UBL +#endif // AUTO_BED_LEVELING_UBL || ENABLED(AUTO_BED_LEVELING_LINEAR) diff --git a/Marlin/least_squares_fit.h b/Marlin/least_squares_fit.h index bdb427159..00d7a2419 100644 --- a/Marlin/least_squares_fit.h +++ b/Marlin/least_squares_fit.h @@ -34,7 +34,7 @@ #include "MarlinConfig.h" -#if ENABLED(AUTO_BED_LEVELING_UBL) // Currently only used by UBL, but is applicable to Grid Based (Linear) Bed Leveling +#if ENABLED(AUTO_BED_LEVELING_UBL) || ENABLED(AUTO_BED_LEVELING_LINEAR) #include "Marlin.h" #include "macros.h" diff --git a/Marlin/qr_solve.cpp b/Marlin/qr_solve.cpp deleted file mode 100644 index 7706c6f8c..000000000 --- a/Marlin/qr_solve.cpp +++ /dev/null @@ -1,1591 +0,0 @@ -/** - * 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 . - * - */ - -#include "qr_solve.h" - -#if ENABLED(AUTO_BED_LEVELING_LINEAR) - -#include -#include - -//# include "r8lib.h" - -int i4_min(int i1, int i2) - -/******************************************************************************/ -/** - Purpose: - - I4_MIN returns the smaller of two I4's. - - Licensing: - - This code is distributed under the GNU LGPL license. - - Modified: - - 29 August 2006 - - Author: - - John Burkardt - - Parameters: - - Input, int I1, I2, two integers to be compared. - - Output, int I4_MIN, the smaller of I1 and I2. -*/ -{ - return (i1 < i2) ? i1 : i2; -} - -float r8_epsilon(void) - -/******************************************************************************/ -/** - Purpose: - - R8_EPSILON returns the R8 round off unit. - - Discussion: - - R8_EPSILON is a number R which is a power of 2 with the property that, - to the precision of the computer's arithmetic, - 1 < 1 + R - but - 1 = ( 1 + R / 2 ) - - Licensing: - - This code is distributed under the GNU LGPL license. - - Modified: - - 01 September 2012 - - Author: - - John Burkardt - - Parameters: - - Output, float R8_EPSILON, the R8 round-off unit. -*/ -{ - const float value = 2.220446049250313E-016; - return value; -} - -float r8_max(float x, float y) - -/******************************************************************************/ -/** - Purpose: - - R8_MAX returns the maximum of two R8's. - - Licensing: - - This code is distributed under the GNU LGPL license. - - Modified: - - 07 May 2006 - - Author: - - John Burkardt - - Parameters: - - Input, float X, Y, the quantities to compare. - - Output, float R8_MAX, the maximum of X and Y. -*/ -{ - return (y < x) ? x : y; -} - -float r8_abs(float x) - -/******************************************************************************/ -/** - Purpose: - - R8_ABS returns the absolute value of an R8. - - Licensing: - - This code is distributed under the GNU LGPL license. - - Modified: - - 07 May 2006 - - Author: - - John Burkardt - - Parameters: - - Input, float X, the quantity whose absolute value is desired. - - Output, float R8_ABS, the absolute value of X. -*/ -{ - return (x < 0.0) ? -x : x; -} - -float r8_sign(float x) - -/******************************************************************************/ -/** - Purpose: - - R8_SIGN returns the sign of an R8. - - Licensing: - - This code is distributed under the GNU LGPL license. - - Modified: - - 08 May 2006 - - Author: - - John Burkardt - - Parameters: - - Input, float X, the number whose sign is desired. - - Output, float R8_SIGN, the sign of X. -*/ -{ - return (x < 0.0) ? -1.0 : 1.0; -} - -float r8mat_amax(int m, int n, float a[]) - -/******************************************************************************/ -/** - Purpose: - - R8MAT_AMAX returns the maximum absolute value entry of an R8MAT. - - Discussion: - - An R8MAT is a doubly dimensioned array of R8 values, stored as a vector - in column-major order. - - Licensing: - - This code is distributed under the GNU LGPL license. - - Modified: - - 07 September 2012 - - Author: - - John Burkardt - - Parameters: - - Input, int M, the number of rows in A. - - Input, int N, the number of columns in A. - - Input, float A[M*N], the M by N matrix. - - Output, float R8MAT_AMAX, the maximum absolute value entry of A. -*/ -{ - 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])); - } - } - return value; -} - -void r8mat_copy(float a2[], int m, int n, float a1[]) - -/******************************************************************************/ -/** - Purpose: - - R8MAT_COPY_NEW copies one R8MAT to a "new" R8MAT. - - Discussion: - - An R8MAT is a doubly dimensioned array of R8 values, stored as a vector - in column-major order. - - Licensing: - - This code is distributed under the GNU LGPL license. - - Modified: - - 26 July 2008 - - Author: - - John Burkardt - - Parameters: - - Input, int M, N, the number of rows and columns. - - Input, float A1[M*N], the matrix to be copied. - - Output, float R8MAT_COPY_NEW[M*N], the copy of A1. -*/ -{ - for (int j = 0; j < n; j++) { - for (int i = 0; i < m; i++) - a2[i + j * m] = a1[i + j * m]; - } -} - -/******************************************************************************/ - -void daxpy(int n, float da, float dx[], int incx, float dy[], int incy) - -/******************************************************************************/ -/** - Purpose: - - DAXPY computes constant times a vector plus a vector. - - Discussion: - - This routine uses unrolled loops for increments equal to one. - - Licensing: - - This code is distributed under the GNU LGPL license. - - Modified: - - 30 March 2007 - - Author: - - C version by John Burkardt - - Reference: - - Jack Dongarra, Cleve Moler, Jim Bunch, Pete Stewart, - LINPACK User's Guide, - SIAM, 1979. - - Charles Lawson, Richard Hanson, David Kincaid, Fred Krogh, - Basic Linear Algebra Subprograms for Fortran Usage, - Algorithm 539, - ACM Transactions on Mathematical Software, - Volume 5, Number 3, September 1979, pages 308-323. - - Parameters: - - Input, int N, the number of elements in DX and DY. - - Input, float DA, the multiplier of DX. - - Input, float DX[*], the first vector. - - Input, int INCX, the increment between successive entries of DX. - - 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. -*/ -{ - if (n <= 0 || da == 0.0) return; - - int i, ix, iy, m; - /** - Code for unequal increments or equal increments - not equal to 1. - */ - if (incx != 1 || incy != 1) { - if (0 <= incx) - ix = 0; - else - ix = (- n + 1) * incx; - if (0 <= incy) - iy = 0; - else - iy = (- n + 1) * incy; - for (i = 0; i < n; i++) { - dy[iy] = dy[iy] + da * dx[ix]; - ix = ix + incx; - iy = iy + incy; - } - } - /** - Code for both increments equal to 1. - */ - else { - m = n % 4; - for (i = 0; i < m; i++) - dy[i] = dy[i] + da * dx[i]; - for (i = m; i < n; i = i + 4) { - dy[i ] = dy[i ] + da * dx[i ]; - dy[i + 1] = dy[i + 1] + da * dx[i + 1]; - dy[i + 2] = dy[i + 2] + da * dx[i + 2]; - dy[i + 3] = dy[i + 3] + da * dx[i + 3]; - } - } -} -/******************************************************************************/ - -float ddot(int n, float dx[], int incx, float dy[], int incy) - -/******************************************************************************/ -/** - Purpose: - - DDOT forms the dot product of two vectors. - - Discussion: - - This routine uses unrolled loops for increments equal to one. - - Licensing: - - This code is distributed under the GNU LGPL license. - - Modified: - - 30 March 2007 - - Author: - - C version by John Burkardt - - Reference: - - Jack Dongarra, Cleve Moler, Jim Bunch, Pete Stewart, - LINPACK User's Guide, - SIAM, 1979. - - Charles Lawson, Richard Hanson, David Kincaid, Fred Krogh, - Basic Linear Algebra Subprograms for Fortran Usage, - Algorithm 539, - ACM Transactions on Mathematical Software, - Volume 5, Number 3, September 1979, pages 308-323. - - Parameters: - - Input, int N, the number of entries in the vectors. - - Input, float DX[*], the first vector. - - Input, int INCX, the increment between successive entries in DX. - - Input, float DY[*], the second vector. - - Input, int INCY, the increment between successive entries in DY. - - Output, float DDOT, the sum of the product of the corresponding - entries of DX and DY. -*/ -{ - - if (n <= 0) return 0.0; - - int i, m; - float dtemp = 0.0; - - /** - Code for unequal increments or equal increments - not equal to 1. - */ - if (incx != 1 || incy != 1) { - int ix = (incx >= 0) ? 0 : (-n + 1) * incx, - iy = (incy >= 0) ? 0 : (-n + 1) * incy; - for (i = 0; i < n; i++) { - dtemp += dx[ix] * dy[iy]; - ix = ix + incx; - iy = iy + incy; - } - } - /** - Code for both increments equal to 1. - */ - else { - m = n % 5; - for (i = 0; i < m; i++) - dtemp += dx[i] * dy[i]; - for (i = m; i < n; i = i + 5) { - dtemp += dx[i] * dy[i] - + dx[i + 1] * dy[i + 1] - + dx[i + 2] * dy[i + 2] - + dx[i + 3] * dy[i + 3] - + dx[i + 4] * dy[i + 4]; - } - } - return dtemp; -} -/******************************************************************************/ - -float dnrm2(int n, float x[], int incx) - -/******************************************************************************/ -/** - Purpose: - - DNRM2 returns the euclidean norm of a vector. - - Discussion: - - DNRM2 ( X ) = sqrt ( X' * X ) - - Licensing: - - This code is distributed under the GNU LGPL license. - - Modified: - - 30 March 2007 - - Author: - - C version by John Burkardt - - Reference: - - Jack Dongarra, Cleve Moler, Jim Bunch, Pete Stewart, - LINPACK User's Guide, - SIAM, 1979. - - Charles Lawson, Richard Hanson, David Kincaid, Fred Krogh, - Basic Linear Algebra Subprograms for Fortran Usage, - Algorithm 539, - ACM Transactions on Mathematical Software, - Volume 5, Number 3, September 1979, pages 308-323. - - Parameters: - - Input, int N, the number of entries in the vector. - - Input, float X[*], the vector whose norm is to be computed. - - Input, int INCX, the increment between successive entries of X. - - Output, float DNRM2, the Euclidean norm of X. -*/ -{ - float norm; - if (n < 1 || incx < 1) - norm = 0.0; - else if (n == 1) - norm = r8_abs(x[0]); - else { - float scale = 0.0, ssq = 1.0; - int ix = 0; - for (int i = 0; i < n; i++) { - if (x[ix] != 0.0) { - float absxi = r8_abs(x[ix]); - if (scale < absxi) { - ssq = 1.0 + ssq * (scale / absxi) * (scale / absxi); - scale = absxi; - } - else - ssq = ssq + (absxi / scale) * (absxi / scale); - } - ix += incx; - } - norm = scale * SQRT(ssq); - } - return norm; -} -/******************************************************************************/ - -void dqrank(float a[], int lda, int m, int n, float tol, int* kr, - int jpvt[], float qraux[]) - -/******************************************************************************/ -/** - Purpose: - - DQRANK computes the QR factorization of a rectangular matrix. - - Discussion: - - This routine is used in conjunction with DQRLSS to solve - overdetermined, underdetermined and singular linear systems - in a least squares sense. - - DQRANK uses the LINPACK subroutine DQRDC to compute the QR - factorization, with column pivoting, of an M by N matrix A. - The numerical rank is determined using the tolerance TOL. - - Note that on output, ABS ( A(1,1) ) / ABS ( A(KR,KR) ) is an estimate - of the condition number of the matrix of independent columns, - and of R. This estimate will be <= 1/TOL. - - Licensing: - - This code is distributed under the GNU LGPL license. - - Modified: - - 21 April 2012 - - Author: - - C version by John Burkardt. - - Reference: - - Jack Dongarra, Cleve Moler, Jim Bunch, Pete Stewart, - LINPACK User's Guide, - SIAM, 1979, - ISBN13: 978-0-898711-72-1, - LC: QA214.L56. - - Parameters: - - 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 - matrix Q is stored below the diagonal in A and in the vector QRAUX. - - Input, int LDA, the leading dimension of A, which must - be at least M. - - Input, int M, the number of rows of A. - - Input, int N, the number of columns of A. - - 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 - element. - - Output, int *KR, the numerical rank. - - Output, int JPVT[N], the pivot information from DQRDC. - Columns JPVT(1), ..., JPVT(KR) of the original matrix are linearly - independent to within the tolerance TOL and the remaining columns - are linearly dependent. - - Output, float QRAUX[N], will contain extra information defining - the QR factorization. -*/ -{ - float work[n]; - - for (int i = 0; i < n; i++) - jpvt[i] = 0; - - int job = 1; - - dqrdc(a, lda, m, n, qraux, jpvt, work, job); - - *kr = 0; - int k = i4_min(m, n); - for (int j = 0; j < k; j++) { - if (r8_abs(a[j + j * lda]) <= tol * r8_abs(a[0 + 0 * lda])) - return; - *kr = j + 1; - } -} -/******************************************************************************/ - -void dqrdc(float a[], int lda, int n, int p, float qraux[], int jpvt[], - float work[], int job) - -/******************************************************************************/ -/** - Purpose: - - DQRDC computes the QR factorization of a real rectangular matrix. - - Discussion: - - DQRDC uses Householder transformations. - - Column pivoting based on the 2-norms of the reduced columns may be - performed at the user's option. - - Licensing: - - This code is distributed under the GNU LGPL license. - - Modified: - - 07 June 2005 - - Author: - - C version by John Burkardt. - - Reference: - - Jack Dongarra, Cleve Moler, Jim Bunch and Pete Stewart, - LINPACK User's Guide, - SIAM, (Society for Industrial and Applied Mathematics), - 3600 University City Science Center, - Philadelphia, PA, 19104-2688. - ISBN 0-89871-172-X - - Parameters: - - 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 - which the orthogonal part of the decomposition can be recovered. - Note that if pivoting has been requested, the decomposition is not that - of the original matrix A but that of A with its columns permuted - as described by JPVT. - - Input, int LDA, the leading dimension of the array A. LDA must - be at least N. - - Input, int N, the number of rows of the matrix A. - - Input, int P, the number of columns of the matrix A. - - 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 - control the selection of the pivot columns. The K-th column A(*,K) of A - is placed in one of three classes according to the value of JPVT(K). - > 0, then A(K) is an initial column. - = 0, then A(K) is a free column. - < 0, then A(K) is a final column. - Before the decomposition is computed, initial columns are moved to - the beginning of the array A and final columns to the end. Both - initial and final columns are frozen in place during the computation - and only free columns are moved. At the K-th stage of the - reduction, if A(*,K) is occupied by a free column it is interchanged - with the free column of largest reduced norm. JPVT is not referenced - if JOB == 0. On output, JPVT(K) contains the index of the column of the - original matrix that has been interchanged into the K-th column, if - pivoting was requested. - - Workspace, float WORK[P]. WORK is not referenced if JOB == 0. - - Input, int JOB, initiates column pivoting. - 0, no pivoting is done. - nonzero, pivoting is done. -*/ -{ - int jp; - int j; - int lup; - int maxj; - float maxnrm, nrmxl, t, tt; - - int pl = 1, pu = 0; - /** - If pivoting is requested, rearrange the columns. - */ - if (job != 0) { - for (j = 1; j <= p; j++) { - int swapj = (0 < jpvt[j - 1]); - jpvt[j - 1] = (jpvt[j - 1] < 0) ? -j : j; - if (swapj) { - if (j != pl) - dswap(n, a + 0 + (pl - 1)*lda, 1, a + 0 + (j - 1), 1); - jpvt[j - 1] = jpvt[pl - 1]; - jpvt[pl - 1] = j; - pl++; - } - } - pu = p; - for (j = p; 1 <= j; j--) { - if (jpvt[j - 1] < 0) { - jpvt[j - 1] = -jpvt[j - 1]; - if (j != pu) { - dswap(n, a + 0 + (pu - 1)*lda, 1, a + 0 + (j - 1)*lda, 1); - jp = jpvt[pu - 1]; - jpvt[pu - 1] = jpvt[j - 1]; - jpvt[j - 1] = jp; - } - pu = pu - 1; - } - } - } - /** - Compute the norms of the free columns. - */ - for (j = pl; j <= pu; j++) - qraux[j - 1] = dnrm2(n, a + 0 + (j - 1) * lda, 1); - for (j = pl; j <= pu; j++) - work[j - 1] = qraux[j - 1]; - /** - Perform the Householder reduction of A. - */ - lup = i4_min(n, p); - for (int l = 1; l <= lup; l++) { - /** - Bring the column of largest norm into the pivot position. - */ - if (pl <= l && l < pu) { - maxnrm = 0.0; - maxj = l; - for (j = l; j <= pu; j++) { - if (maxnrm < qraux[j - 1]) { - maxnrm = qraux[j - 1]; - maxj = j; - } - } - if (maxj != l) { - dswap(n, a + 0 + (l - 1)*lda, 1, a + 0 + (maxj - 1)*lda, 1); - qraux[maxj - 1] = qraux[l - 1]; - work[maxj - 1] = work[l - 1]; - jp = jpvt[maxj - 1]; - jpvt[maxj - 1] = jpvt[l - 1]; - jpvt[l - 1] = jp; - } - } - /** - Compute the Householder transformation for column L. - */ - qraux[l - 1] = 0.0; - if (l != n) { - nrmxl = dnrm2(n - l + 1, a + l - 1 + (l - 1) * lda, 1); - if (nrmxl != 0.0) { - if (a[l - 1 + (l - 1)*lda] != 0.0) - nrmxl = nrmxl * r8_sign(a[l - 1 + (l - 1) * lda]); - dscal(n - l + 1, 1.0 / nrmxl, a + l - 1 + (l - 1)*lda, 1); - a[l - 1 + (l - 1)*lda] = 1.0 + a[l - 1 + (l - 1) * lda]; - /** - Apply the transformation to the remaining columns, updating the norms. - */ - for (j = l + 1; j <= p; j++) { - t = -ddot(n - l + 1, a + l - 1 + (l - 1) * lda, 1, a + l - 1 + (j - 1) * lda, 1) - / a[l - 1 + (l - 1) * lda]; - daxpy(n - l + 1, t, a + l - 1 + (l - 1)*lda, 1, a + l - 1 + (j - 1)*lda, 1); - if (pl <= j && j <= pu) { - if (qraux[j - 1] != 0.0) { - tt = 1.0 - POW(r8_abs(a[l - 1 + (j - 1) * lda]) / qraux[j - 1], 2); - tt = r8_max(tt, 0.0); - t = tt; - tt = 1.0 + 0.05 * tt * POW(qraux[j - 1] / work[j - 1], 2); - if (tt != 1.0) - qraux[j - 1] = qraux[j - 1] * SQRT(t); - else { - qraux[j - 1] = dnrm2(n - l, a + l + (j - 1) * lda, 1); - work[j - 1] = qraux[j - 1]; - } - } - } - } - /** - Save the transformation. - */ - qraux[l - 1] = a[l - 1 + (l - 1) * lda]; - a[l - 1 + (l - 1)*lda] = -nrmxl; - } - } - } -} -/******************************************************************************/ - -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) - -/******************************************************************************/ -/** - Purpose: - - DQRLS factors and solves a linear system in the least squares sense. - - Discussion: - - The linear system may be overdetermined, underdetermined or singular. - The solution is obtained using a QR factorization of the - coefficient matrix. - - DQRLS can be efficiently used to solve several least squares - problems with the same matrix A. The first system is solved - with ITASK = 1. The subsequent systems are solved with - ITASK = 2, to avoid the recomputation of the matrix factors. - The parameters KR, JPVT, and QRAUX must not be modified - between calls to DQRLS. - - DQRLS is used to solve in a least squares sense - overdetermined, underdetermined and singular linear systems. - The system is A*X approximates B where A is M by N. - B is a given M-vector, and X is the N-vector to be computed. - A solution X is found which minimimzes the sum of squares (2-norm) - of the residual, A*X - B. - - The numerical rank of A is determined using the tolerance TOL. - - DQRLS uses the LINPACK subroutine DQRDC to compute the QR - factorization, with column pivoting, of an M by N matrix A. - - Licensing: - - This code is distributed under the GNU LGPL license. - - Modified: - - 10 September 2012 - - Author: - - C version by John Burkardt. - - Reference: - - David Kahaner, Cleve Moler, Steven Nash, - Numerical Methods and Software, - Prentice Hall, 1989, - ISBN: 0-13-627258-4, - LC: TA345.K34. - - Parameters: - - 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. - On output, A contains the output from DQRDC. 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 the vector QRAUX. - - Input, int LDA, the leading dimension of A. - - Input, int M, the number of rows of A. - - Input, int N, the number of columns of A. - - 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 - element. - - Output, int *KR, the numerical rank. - - Input, float B[M], the right hand side of the linear system. - - Output, float X[N], a least squares solution to the linear - system. - - Output, float RSD[M], the residual, B - A*X. RSD may - overwrite B. - - Workspace, int JPVT[N], required if ITASK = 1. - Columns JPVT(1), ..., JPVT(KR) of the original matrix are linearly - independent to within the tolerance TOL and the remaining columns - are linearly dependent. ABS ( A(1,1) ) / ABS ( A(KR,KR) ) is an estimate - of the condition number of the matrix of independent columns, - and of R. This estimate will be <= 1/TOL. - - Workspace, float QRAUX[N], required if ITASK = 1. - - Input, int ITASK. - 1, DQRLS factors the matrix A and solves the least squares problem. - 2, DQRLS assumes that the matrix A was factored with an earlier - call to DQRLS, and only solves the least squares problem. - - Output, int DQRLS, error code. - 0: no error - -1: LDA < M (fatal error) - -2: N < 1 (fatal error) - -3: ITASK < 1 (fatal error) -*/ -{ - int ind; - if (lda < m) { - /*fprintf ( stderr, "\n" ); - fprintf ( stderr, "DQRLS - Fatal error!\n" ); - fprintf ( stderr, " LDA < M.\n" );*/ - ind = -1; - return ind; - } - - if (n <= 0) { - /*fprintf ( stderr, "\n" ); - fprintf ( stderr, "DQRLS - Fatal error!\n" ); - fprintf ( stderr, " N <= 0.\n" );*/ - ind = -2; - return ind; - } - - if (itask < 1) { - /*fprintf ( stderr, "\n" ); - fprintf ( stderr, "DQRLS - Fatal error!\n" ); - fprintf ( stderr, " ITASK < 1.\n" );*/ - ind = -3; - return ind; - } - - ind = 0; - /** - Factor the matrix. - */ - if (itask == 1) - dqrank(a, lda, m, n, tol, kr, jpvt, qraux); - /** - Solve the least-squares problem. - */ - dqrlss(a, lda, m, n, *kr, b, x, rsd, jpvt, qraux); - return ind; -} -/******************************************************************************/ - -void dqrlss(float a[], int lda, int m, int n, int kr, float b[], float x[], - float rsd[], int jpvt[], float qraux[]) - -/******************************************************************************/ -/** - Purpose: - - DQRLSS solves a linear system in a least squares sense. - - Discussion: - - DQRLSS must be preceded by a call to DQRANK. - - The system is to be solved is - A * X = B - where - A is an M by N matrix with rank KR, as determined by DQRANK, - B is a given M-vector, - X is the N-vector to be computed. - - A solution X, with at most KR nonzero components, is found which - minimizes the 2-norm of the residual (A*X-B). - - Once the matrix A has been formed, DQRANK should be - called once to decompose it. Then, for each right hand - side B, DQRLSS should be called once to obtain the - solution and residual. - - Licensing: - - This code is distributed under the GNU LGPL license. - - Modified: - - 10 September 2012 - - Author: - - C version by John Burkardt - - Parameters: - - 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 - the vector QRAUX. - - Input, int LDA, the leading dimension of A, which must - be at least M. - - Input, int M, the number of rows of A. - - Input, int N, the number of columns of A. - - Input, int KR, the rank of the matrix, as estimated by DQRANK. - - Input, float B[M], the right hand side of the linear system. - - Output, float X[N], a least squares solution to the - linear system. - - Output, float RSD[M], the residual, B - A*X. RSD may - overwrite B. - - Input, int JPVT[N], the pivot information from DQRANK. - Columns JPVT[0], ..., JPVT[KR-1] of the original matrix are linearly - independent to within the tolerance TOL and the remaining columns - are linearly dependent. - - Input, float QRAUX[N], auxiliary information from DQRANK - defining the QR factorization. -*/ -{ - int i; - int info; - int j; - int job; - int k; - float t; - - if (kr != 0) { - job = 110; - info = dqrsl(a, lda, m, kr, qraux, b, rsd, rsd, x, rsd, rsd, job); UNUSED(info); - } - - for (i = 0; i < n; i++) - jpvt[i] = - jpvt[i]; - - for (i = kr; i < n; i++) - x[i] = 0.0; - - for (j = 1; j <= n; j++) { - if (jpvt[j - 1] <= 0) { - k = - jpvt[j - 1]; - jpvt[j - 1] = k; - - while (k != j) { - t = x[j - 1]; - x[j - 1] = x[k - 1]; - x[k - 1] = t; - jpvt[k - 1] = -jpvt[k - 1]; - k = jpvt[k - 1]; - } - } - } -} -/******************************************************************************/ - -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) - -/******************************************************************************/ -/** - Purpose: - - DQRSL computes transformations, projections, and least squares solutions. - - Discussion: - - DQRSL requires the output of DQRDC. - - For K <= min(N,P), let AK be the matrix - - AK = ( A(JPVT[0]), A(JPVT(2)), ..., A(JPVT(K)) ) - - formed from columns JPVT[0], ..., JPVT(K) of the original - N by P matrix A that was input to DQRDC. If no pivoting was - done, AK consists of the first K columns of A in their - original order. DQRDC produces a factored orthogonal matrix Q - and an upper triangular matrix R such that - - AK = Q * (R) - (0) - - This information is contained in coded form in the arrays - A and QRAUX. - - The parameters QY, QTY, B, RSD, and AB are not referenced - if their computation is not requested and in this case - can be replaced by dummy variables in the calling program. - To save storage, the user may in some cases use the same - array for different parameters in the calling sequence. A - frequently occurring example is when one wishes to compute - any of B, RSD, or AB and does not need Y or QTY. In this - case one may identify Y, QTY, and one of B, RSD, or AB, while - providing separate arrays for anything else that is to be - computed. - - Thus the calling sequence - - dqrsl ( a, lda, n, k, qraux, y, dum, y, b, y, dum, 110, info ) - - will result in the computation of B and RSD, with RSD - overwriting Y. More generally, each item in the following - list contains groups of permissible identifications for - a single calling sequence. - - 1. (Y,QTY,B) (RSD) (AB) (QY) - - 2. (Y,QTY,RSD) (B) (AB) (QY) - - 3. (Y,QTY,AB) (B) (RSD) (QY) - - 4. (Y,QY) (QTY,B) (RSD) (AB) - - 5. (Y,QY) (QTY,RSD) (B) (AB) - - 6. (Y,QY) (QTY,AB) (B) (RSD) - - In any group the value returned in the array allocated to - the group corresponds to the last member of the group. - - Licensing: - - This code is distributed under the GNU LGPL license. - - Modified: - - 07 June 2005 - - Author: - - C version by John Burkardt. - - Reference: - - Jack Dongarra, Cleve Moler, Jim Bunch and Pete Stewart, - LINPACK User's Guide, - SIAM, (Society for Industrial and Applied Mathematics), - 3600 University City Science Center, - Philadelphia, PA, 19104-2688. - ISBN 0-89871-172-X - - Parameters: - - Input, float A[LDA*P], contains the output of DQRDC. - - Input, int LDA, the leading dimension of the array A. - - Input, int N, the number of rows of the matrix AK. It must - have the same value as N in DQRDC. - - Input, int K, the number of columns of the matrix AK. K - must not be greater than min(N,P), where P is the same as in the - calling sequence to DQRDC. - - Input, float QRAUX[P], the auxiliary output from DQRDC. - - Input, float Y[N], a vector to be manipulated by DQRSL. - - Output, float QY[N], contains Q * Y, if requested. - - Output, float QTY[N], contains Q' * Y, if requested. - - 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, 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, 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. - - Input, integer JOB, specifies what is to be computed. JOB has - the decimal expansion ABCDE, with the following meaning: - - if A != 0, compute QY. - if B != 0, compute QTY. - if C != 0, compute QTY and B. - if D != 0, compute QTY and RSD. - if E != 0, compute QTY and AB. - - Note that a request to compute B, RSD, or AB automatically triggers - the computation of QTY, for which an array must be provided in the - calling sequence. - - Output, int DQRSL, is zero unless the computation of B has - been requested and R is exactly singular. In this case, INFO is the - index of the first zero diagonal element of R, and B is left unaltered. -*/ -{ - int cab; - int cb; - int cqty; - int cqy; - int cr; - int i; - int info; - int j; - int jj; - int ju; - float t; - float temp; - /** - Set INFO flag. - */ - info = 0; - - /** - Determine what is to be computed. - */ - cqy = ( job / 10000 != 0); - cqty = ((job % 10000) != 0); - cb = ((job % 1000) / 100 != 0); - cr = ((job % 100) / 10 != 0); - cab = ((job % 10) != 0); - ju = i4_min(k, n - 1); - - /** - Special action when N = 1. - */ - if (ju == 0) { - if (cqy) - qy[0] = y[0]; - if (cqty) - qty[0] = y[0]; - if (cab) - ab[0] = y[0]; - if (cb) { - if (a[0 + 0 * lda] == 0.0) - info = 1; - else - b[0] = y[0] / a[0 + 0 * lda]; - } - if (cr) - rsd[0] = 0.0; - return info; - } - /** - Set up to compute QY or QTY. - */ - if (cqy) { - for (i = 1; i <= n; i++) - qy[i - 1] = y[i - 1]; - } - if (cqty) { - for (i = 1; i <= n; i++) - qty[i - 1] = y[i - 1]; - } - /** - Compute QY. - */ - if (cqy) { - for (jj = 1; jj <= ju; jj++) { - j = ju - jj + 1; - if (qraux[j - 1] != 0.0) { - temp = a[j - 1 + (j - 1) * lda]; - a[j - 1 + (j - 1)*lda] = qraux[j - 1]; - t = -ddot(n - j + 1, a + j - 1 + (j - 1) * lda, 1, qy + j - 1, 1) / a[j - 1 + (j - 1) * lda]; - daxpy(n - j + 1, t, a + j - 1 + (j - 1)*lda, 1, qy + j - 1, 1); - a[j - 1 + (j - 1)*lda] = temp; - } - } - } - /** - Compute Q'*Y. - */ - if (cqty) { - for (j = 1; j <= ju; j++) { - if (qraux[j - 1] != 0.0) { - temp = a[j - 1 + (j - 1) * lda]; - a[j - 1 + (j - 1)*lda] = qraux[j - 1]; - t = -ddot(n - j + 1, a + j - 1 + (j - 1) * lda, 1, qty + j - 1, 1) / a[j - 1 + (j - 1) * lda]; - daxpy(n - j + 1, t, a + j - 1 + (j - 1)*lda, 1, qty + j - 1, 1); - a[j - 1 + (j - 1)*lda] = temp; - } - } - } - /** - Set up to compute B, RSD, or AB. - */ - if (cb) { - for (i = 1; i <= k; i++) - b[i - 1] = qty[i - 1]; - } - if (cab) { - for (i = 1; i <= k; i++) - ab[i - 1] = qty[i - 1]; - } - if (cr && k < n) { - for (i = k + 1; i <= n; i++) - rsd[i - 1] = qty[i - 1]; - } - if (cab && k + 1 <= n) { - for (i = k + 1; i <= n; i++) - ab[i - 1] = 0.0; - } - if (cr) { - for (i = 1; i <= k; i++) - rsd[i - 1] = 0.0; - } - /** - Compute B. - */ - if (cb) { - for (jj = 1; jj <= k; jj++) { - j = k - jj + 1; - if (a[j - 1 + (j - 1)*lda] == 0.0) { - info = j; - break; - } - b[j - 1] = b[j - 1] / a[j - 1 + (j - 1) * lda]; - if (j != 1) { - t = -b[j - 1]; - daxpy(j - 1, t, a + 0 + (j - 1)*lda, 1, b, 1); - } - } - } - /** - Compute RSD or AB as required. - */ - if (cr || cab) { - for (jj = 1; jj <= ju; jj++) { - j = ju - jj + 1; - if (qraux[j - 1] != 0.0) { - temp = a[j - 1 + (j - 1) * lda]; - a[j - 1 + (j - 1)*lda] = qraux[j - 1]; - if (cr) { - t = -ddot(n - j + 1, a + j - 1 + (j - 1) * lda, 1, rsd + j - 1, 1) - / a[j - 1 + (j - 1) * lda]; - daxpy(n - j + 1, t, a + j - 1 + (j - 1)*lda, 1, rsd + j - 1, 1); - } - if (cab) { - t = -ddot(n - j + 1, a + j - 1 + (j - 1) * lda, 1, ab + j - 1, 1) - / a[j - 1 + (j - 1) * lda]; - daxpy(n - j + 1, t, a + j - 1 + (j - 1)*lda, 1, ab + j - 1, 1); - } - a[j - 1 + (j - 1)*lda] = temp; - } - } - } - return info; -} -/******************************************************************************/ - -/******************************************************************************/ - -void dscal(int n, float sa, float x[], int incx) - -/******************************************************************************/ -/** - Purpose: - - DSCAL scales a vector by a constant. - - Licensing: - - This code is distributed under the GNU LGPL license. - - Modified: - - 30 March 2007 - - Author: - - C version by John Burkardt - - Reference: - - Jack Dongarra, Cleve Moler, Jim Bunch, Pete Stewart, - LINPACK User's Guide, - SIAM, 1979. - - Charles Lawson, Richard Hanson, David Kincaid, Fred Krogh, - Basic Linear Algebra Subprograms for Fortran Usage, - Algorithm 539, - ACM Transactions on Mathematical Software, - Volume 5, Number 3, September 1979, pages 308-323. - - Parameters: - - Input, int N, the number of entries in the vector. - - Input, float SA, the multiplier. - - Input/output, float X[*], the vector to be scaled. - - Input, int INCX, the increment between successive entries of X. -*/ -{ - int i; - int ix; - int m; - - if (n <= 0) return; - - if (incx == 1) { - m = n % 5; - for (i = 0; i < m; i++) - x[i] = sa * x[i]; - for (i = m; i < n; i = i + 5) { - x[i] = sa * x[i]; - x[i + 1] = sa * x[i + 1]; - x[i + 2] = sa * x[i + 2]; - x[i + 3] = sa * x[i + 3]; - x[i + 4] = sa * x[i + 4]; - } - } - else { - if (0 <= incx) - ix = 0; - else - ix = (- n + 1) * incx; - for (i = 0; i < n; i++) { - x[ix] = sa * x[ix]; - ix = ix + incx; - } - } -} -/******************************************************************************/ - - -void dswap(int n, float x[], int incx, float y[], int incy) - -/******************************************************************************/ -/** - Purpose: - - DSWAP interchanges two vectors. - - Licensing: - - This code is distributed under the GNU LGPL license. - - Modified: - - 30 March 2007 - - Author: - - C version by John Burkardt - - Reference: - - Jack Dongarra, Cleve Moler, Jim Bunch, Pete Stewart, - LINPACK User's Guide, - SIAM, 1979. - - Charles Lawson, Richard Hanson, David Kincaid, Fred Krogh, - Basic Linear Algebra Subprograms for Fortran Usage, - Algorithm 539, - ACM Transactions on Mathematical Software, - Volume 5, Number 3, September 1979, pages 308-323. - - Parameters: - - Input, int N, the number of entries in the vectors. - - Input/output, float X[*], one of the vectors to swap. - - Input, int INCX, the increment between successive entries of X. - - Input/output, float Y[*], one of the vectors to swap. - - Input, int INCY, the increment between successive elements of Y. -*/ -{ - if (n <= 0) return; - - int i, ix, iy, m; - float temp; - - if (incx == 1 && incy == 1) { - m = n % 3; - for (i = 0; i < m; i++) { - temp = x[i]; - x[i] = y[i]; - y[i] = temp; - } - for (i = m; i < n; i = i + 3) { - temp = x[i]; - x[i] = y[i]; - y[i] = temp; - temp = x[i + 1]; - x[i + 1] = y[i + 1]; - y[i + 1] = temp; - temp = x[i + 2]; - x[i + 2] = y[i + 2]; - y[i + 2] = temp; - } - } - else { - ix = (incx >= 0) ? 0 : (-n + 1) * incx; - iy = (incy >= 0) ? 0 : (-n + 1) * incy; - for (i = 0; i < n; i++) { - temp = x[ix]; - x[ix] = y[iy]; - y[iy] = temp; - ix = ix + incx; - iy = iy + incy; - } - } -} -/******************************************************************************/ - -/******************************************************************************/ - -void qr_solve(float x[], int m, int n, float a[], float b[]) - -/******************************************************************************/ -/** - Purpose: - - QR_SOLVE solves a linear system in the least squares sense. - - Discussion: - - If the matrix A has full column rank, then the solution X should be the - unique vector that minimizes the Euclidean norm of the residual. - - If the matrix A does not have full column rank, then the solution is - not unique; the vector X will minimize the residual norm, but so will - various other vectors. - - Licensing: - - This code is distributed under the GNU LGPL license. - - Modified: - - 11 September 2012 - - Author: - - John Burkardt - - Reference: - - David Kahaner, Cleve Moler, Steven Nash, - Numerical Methods and Software, - Prentice Hall, 1989, - ISBN: 0-13-627258-4, - LC: TA345.K34. - - Parameters: - - Input, int M, the number of rows of A. - - Input, int N, the number of columns of A. - - Input, float A[M*N], the matrix. - - Input, float B[M], the right hand side. - - Output, float QR_SOLVE[N], the least squares solution. -*/ -{ - float a_qr[n * m], qraux[n], r[m], tol; - int ind, itask, jpvt[n], kr, lda; - - r8mat_copy(a_qr, m, n, a); - lda = m; - tol = r8_epsilon() / r8mat_amax(m, n, a_qr); - itask = 1; - - ind = dqrls(a_qr, lda, m, n, tol, &kr, b, x, r, jpvt, qraux, itask); UNUSED(ind); -} -/******************************************************************************/ - -#endif diff --git a/Marlin/qr_solve.h b/Marlin/qr_solve.h deleted file mode 100644 index c409220d3..000000000 --- a/Marlin/qr_solve.h +++ /dev/null @@ -1,44 +0,0 @@ -/** - * 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 . - * - */ - -#include "MarlinConfig.h" - -#if ENABLED(AUTO_BED_LEVELING_LINEAR) - -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 From 8c2907d10fedb7d32870f113ac1b9aee54fe989c Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 12 Jul 2017 22:47:23 -0500 Subject: [PATCH 019/112] Fix ABL broken by recent change --- Marlin/Marlin_main.cpp | 18 +++++++----------- 1 file changed, 7 insertions(+), 11 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index d244b198d..10a316b74 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -4617,11 +4617,11 @@ void home_all_axes() { gcode_G28(true); } #if ENABLED(AUTO_BED_LEVELING_LINEAR) -// mean += measured_z; // I believe this is unused code? -// eqnBVector[abl_probe_index] = measured_z; // I believe this is unused code? -// eqnAMatrix[abl_probe_index + 0 * abl2] = xProbe; // I believe this is unused code? -// eqnAMatrix[abl_probe_index + 1 * abl2] = yProbe; // I believe this is unused code? -// eqnAMatrix[abl_probe_index + 2 * abl2] = 1; // I believe this is unused code? + mean += measured_z; + eqnBVector[abl_probe_index] = measured_z; + eqnAMatrix[abl_probe_index + 0 * abl2] = xProbe; + eqnAMatrix[abl_probe_index + 1 * abl2] = yProbe; + eqnAMatrix[abl_probe_index + 2 * abl2] = 1; #elif ENABLED(AUTO_BED_LEVELING_BILINEAR) @@ -4797,9 +4797,6 @@ void home_all_axes() { gcode_G28(true); } incremental_LSF(&lsf_results, xProbe, yProbe, measured_z); - #if ENABLED(AUTO_BED_LEVELING_LINEAR) - indexIntoAB[xCount][yCount] = abl_probe_index; - #endif #elif ENABLED(AUTO_BED_LEVELING_BILINEAR) z_values[xCount][yCount] = measured_z + zoffset; @@ -4924,11 +4921,10 @@ void home_all_axes() { gcode_G28(true); } } // Create the matrix but don't correct the position yet - if (!dryrun) { + if (!dryrun) planner.bed_level_matrix = matrix_3x3::create_look_at( - vector_3(-plane_equation_coefficients[0], -plane_equation_coefficients[1], 1) // We can eleminate the '-' here and up above + vector_3(-plane_equation_coefficients[0], -plane_equation_coefficients[1], 1) // We can eliminate the '-' here and up above ); - } // Show the Topography map if enabled if (do_topography_map) { From 0873c667fa39320800eefd0c5fa9c2b4e726f968 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 12 Jul 2017 21:39:37 -0500 Subject: [PATCH 020/112] Apply coding standards to recent merges --- Marlin/G26_Mesh_Validation_Tool.cpp | 72 +-- Marlin/Marlin_main.cpp | 2 +- Marlin/least_squares_fit.cpp | 2 +- Marlin/least_squares_fit.h | 2 +- Marlin/ultralcd_impl_DOGM.h | 20 +- Marlin/ultralcd_impl_HD44780.h | 858 +++++++++++++--------------- 6 files changed, 438 insertions(+), 518 deletions(-) diff --git a/Marlin/G26_Mesh_Validation_Tool.cpp b/Marlin/G26_Mesh_Validation_Tool.cpp index 80f6782aa..a0e17fe76 100644 --- a/Marlin/G26_Mesh_Validation_Tool.cpp +++ b/Marlin/G26_Mesh_Validation_Tool.cpp @@ -58,67 +58,67 @@ * * G26 is a Mesh Validation Tool intended to provide support for the Marlin Unified Bed Leveling System. * In order to fully utilize and benefit from the Marlin Unified Bed Leveling System an accurate Mesh must - * be defined. G29 is designed to allow the user to quickly validate the correctness of her Mesh. It will + * be defined. G29 is designed to allow the user to quickly validate the correctness of her Mesh. It will * first heat the bed and nozzle. It will then print lines and circles along the Mesh Cell boundaries and * the intersections of those lines (respectively). * * This action allows the user to immediately see where the Mesh is properly defined and where it needs to - * be edited. The command will generate the Mesh lines closest to the nozzle's starting position. Alternatively - * the user can specify the X and Y position of interest with command parameters. This allows the user to + * be edited. The command will generate the Mesh lines closest to the nozzle's starting position. Alternatively + * the user can specify the X and Y position of interest with command parameters. This allows the user to * focus on a particular area of the Mesh where attention is needed. * - * B # Bed Set the Bed Temperature. If not specified, a default of 60 C. will be assumed. + * B # Bed Set the Bed Temperature. If not specified, a default of 60 C. will be assumed. * * C Current When searching for Mesh Intersection points to draw, use the current nozzle location * as the base for any distance comparison. * - * D Disable Disable the Unified Bed Leveling System. In the normal case the user is invoking this - * command to see how well a Mesh as been adjusted to match a print surface. In order to do - * this the Unified Bed Leveling System is turned on by the G26 command. The D parameter + * D Disable Disable the Unified Bed Leveling System. In the normal case the user is invoking this + * command to see how well a Mesh as been adjusted to match a print surface. In order to do + * this the Unified Bed Leveling System is turned on by the G26 command. The D parameter * alters the command's normal behaviour and disables the Unified Bed Leveling System even if * it is on. * - * H # Hotend Set the Nozzle Temperature. If not specified, a default of 205 C. will be assumed. + * H # Hotend Set the Nozzle Temperature. If not specified, a default of 205 C. will be assumed. * - * F # Filament Used to specify the diameter of the filament being used. If not specified - * 1.75mm filament is assumed. If you are not getting acceptable results by using the + * F # Filament Used to specify the diameter of the filament being used. If not specified + * 1.75mm filament is assumed. If you are not getting acceptable results by using the * 'correct' numbers, you can scale this number up or down a little bit to change the amount * of filament that is being extruded during the printing of the various lines on the bed. * * K Keep-On Keep the heaters turned on at the end of the command. * - * L # Layer Layer height. (Height of nozzle above bed) If not specified .20mm will be used. + * L # Layer Layer height. (Height of nozzle above bed) If not specified .20mm will be used. * - * O # Ooooze How much your nozzle will Ooooze filament while getting in position to print. This + * O # Ooooze How much your nozzle will Ooooze filament while getting in position to print. This * is over kill, but using this parameter will let you get the very first 'circle' perfect * so you have a trophy to peel off of the bed and hang up to show how perfectly you have your - * Mesh calibrated. If not specified, a filament length of .3mm is assumed. + * Mesh calibrated. If not specified, a filament length of .3mm is assumed. * - * P # Prime Prime the nozzle with specified length of filament. If this parameter is not - * given, no prime action will take place. If the parameter specifies an amount, that much - * will be purged before continuing. If no amount is specified the command will start + * P # Prime Prime the nozzle with specified length of filament. If this parameter is not + * given, no prime action will take place. If the parameter specifies an amount, that much + * will be purged before continuing. If no amount is specified the command will start * purging filament until the user provides an LCD Click and then it will continue with - * printing the Mesh. You can carefully remove the spent filament with a needle nose - * pliers while holding the LCD Click wheel in a depressed state. If you do not have + * printing the Mesh. You can carefully remove the spent filament with a needle nose + * pliers while holding the LCD Click wheel in a depressed state. If you do not have * an LCD, you must specify a value if you use P. * - * Q # Multiplier Retraction Multiplier. Normally not needed. Retraction defaults to 1.0mm and + * Q # Multiplier Retraction Multiplier. Normally not needed. Retraction defaults to 1.0mm and * un-retraction is at 1.2mm These numbers will be scaled by the specified amount * * R # Repeat Prints the number of patterns given as a parameter, starting at the current location. * If a parameter isn't given, every point will be printed unless G26 is interrupted. * This works the same way that the UBL G29 P4 R parameter works. * - * NOTE: If you do not have an LCD, you -must- specify R. This is to ensure that you are + * NOTE: If you do not have an LCD, you -must- specify R. This is to ensure that you are * aware that there's some risk associated with printing without the ability to abort in - * cases where mesh point Z value may be inaccurate. As above, if you do not include a + * cases where mesh point Z value may be inaccurate. As above, if you do not include a * parameter, every point will be printed. * - * S # Nozzle Used to control the size of nozzle diameter. If not specified, a .4mm nozzle is assumed. + * S # Nozzle Used to control the size of nozzle diameter. If not specified, a .4mm nozzle is assumed. * - * U # Random Randomize the order that the circles are drawn on the bed. The search for the closest - * undrawn cicle is still done. But the distance to the location for each circle has a - * random number of the size specified added to it. Specifying S50 will give an interesting + * U # Random Randomize the order that the circles are drawn on the bed. The search for the closest + * undrawn cicle is still done. But the distance to the location for each circle has a + * random number of the size specified added to it. Specifying S50 will give an interesting * deviation from the normal behaviour on a 10 x 10 Mesh. * * X # X Coord. Specify the starting location of the drawing activity. @@ -218,7 +218,7 @@ * nozzle in a problem area and doing a G29 P4 R command. */ void unified_bed_leveling::G26() { - SERIAL_ECHOLNPGM("G26 command started. Waiting for heater(s)."); + SERIAL_ECHOLNPGM("G26 command started. Waiting for heater(s)."); float tmp, start_angle, end_angle; int i, xi, yi; mesh_index_pair location; @@ -264,7 +264,7 @@ //debug_current_and_destination(PSTR("Starting G26 Mesh Validation Pattern.")); /** - * Declare and generate a sin() & cos() table to be used during the circle drawing. This will lighten + * Declare and generate a sin() & cos() table to be used during the circle drawing. This will lighten * the CPU load and make the arc drawing faster and more smooth */ float sin_table[360 / 30 + 1], cos_table[360 / 30 + 1]; @@ -575,17 +575,17 @@ /** * print_line_from_here_to_there() takes two cartesian coordinates and draws a line from one - * to the other. But there are really three sets of coordinates involved. The first coordinate - * is the present location of the nozzle. We don't necessarily want to print from this location. - * We first need to move the nozzle to the start of line segment where we want to print. Once + * to the other. But there are really three sets of coordinates involved. The first coordinate + * is the present location of the nozzle. We don't necessarily want to print from this location. + * We first need to move the nozzle to the start of line segment where we want to print. Once * there, we can use the two coordinates supplied to draw the line. * * Note: Although we assume the first set of coordinates is the start of the line and the second - * set of coordinates is the end of the line, it does not always work out that way. This function - * optimizes the movement to minimize the travel distance before it can start printing. This saves - * a lot of time and eleminates a lot of non-sensical movement of the nozzle. However, it does + * set of coordinates is the end of the line, it does not always work out that way. This function + * optimizes the movement to minimize the travel distance before it can start printing. This saves + * a lot of time and eliminates a lot of nonsensical movement of the nozzle. However, it does * cause a lot of very little short retracement of th nozzle when it draws the very first line - * segment of a 'circle'. The time this requires is very short and is easily saved by the other + * segment of a 'circle'. The time this requires is very short and is easily saved by the other * cases where the optimization comes into play. */ void unified_bed_leveling::print_line_from_here_to_there(const float &sx, const float &sy, const float &sz, const float &ex, const float &ey, const float &ez) { @@ -850,7 +850,7 @@ stepper.synchronize(); // Without this synchronize, the purge is more consistent, // but because the planner has a buffer, we won't be able - // to stop as quickly. So we put up with the less smooth + // to stop as quickly. So we put up with the less smooth // action to give the user a more responsive 'Stop'. set_destination_to_current(); idle(); @@ -860,7 +860,7 @@ #if ENABLED(ULTRA_LCD) strcpy_P(lcd_status_message, PSTR("Done Priming")); // We can't do lcd_setstatusPGM() without having it continue; - // So... We cheat to get a message up. + // So... We cheat to get a message up. lcd_setstatusPGM(PSTR("Done Priming"), 99); lcd_quick_feedback(); #endif diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 10a316b74..cbd33480a 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -3242,7 +3242,7 @@ inline void gcode_G0_G1( if (autoretract_enabled && !(parser.seen('X') || parser.seen('Y') || parser.seen('Z')) && parser.seen('E')) { const float echange = destination[E_AXIS] - current_position[E_AXIS]; // Is this move an attempt to retract or recover? - if ((echange < -MIN_RETRACT && !retracted[active_extruder]) || (echange > MIN_RETRACT && retracted[active_extruder])) { + if ((echange < -(MIN_RETRACT) && !retracted[active_extruder]) || (echange > MIN_RETRACT && retracted[active_extruder])) { current_position[E_AXIS] = destination[E_AXIS]; // hide the slicer-generated retract/recover from calculations sync_plan_position_e(); // AND from the planner retract(!retracted[active_extruder]); diff --git a/Marlin/least_squares_fit.cpp b/Marlin/least_squares_fit.cpp index f8c7a0b52..66821ce58 100644 --- a/Marlin/least_squares_fit.cpp +++ b/Marlin/least_squares_fit.cpp @@ -68,4 +68,4 @@ int finish_incremental_LSF(struct linear_fit_data *lsf) { return 0; } -#endif // AUTO_BED_LEVELING_UBL || ENABLED(AUTO_BED_LEVELING_LINEAR) +#endif // AUTO_BED_LEVELING_UBL || ENABLED(AUTO_BED_LEVELING_LINEAR) diff --git a/Marlin/least_squares_fit.h b/Marlin/least_squares_fit.h index 00d7a2419..9ed923ab4 100644 --- a/Marlin/least_squares_fit.h +++ b/Marlin/least_squares_fit.h @@ -34,7 +34,7 @@ #include "MarlinConfig.h" -#if ENABLED(AUTO_BED_LEVELING_UBL) || ENABLED(AUTO_BED_LEVELING_LINEAR) +#if ENABLED(AUTO_BED_LEVELING_UBL) || ENABLED(AUTO_BED_LEVELING_LINEAR) #include "Marlin.h" #include "macros.h" diff --git a/Marlin/ultralcd_impl_DOGM.h b/Marlin/ultralcd_impl_DOGM.h index 28848cdeb..5d075124d 100644 --- a/Marlin/ultralcd_impl_DOGM.h +++ b/Marlin/ultralcd_impl_DOGM.h @@ -976,8 +976,8 @@ static void lcd_implementation_status_screen() { uint8_t x_map_pixels = ((MAP_MAX_PIXELS_X - 4) / (GRID_MAX_POINTS_X)) * (GRID_MAX_POINTS_X), y_map_pixels = ((MAP_MAX_PIXELS_Y - 4) / (GRID_MAX_POINTS_Y)) * (GRID_MAX_POINTS_Y), - pixels_per_X_mesh_pnt = x_map_pixels / (GRID_MAX_POINTS_X), - pixels_per_Y_mesh_pnt = y_map_pixels / (GRID_MAX_POINTS_Y), + pixels_per_x_mesh_pnt = x_map_pixels / (GRID_MAX_POINTS_X), + pixels_per_y_mesh_pnt = y_map_pixels / (GRID_MAX_POINTS_Y), x_offset = MAP_UPPER_LEFT_CORNER_X + 1 + (MAP_MAX_PIXELS_X - x_map_pixels - 2) / 2, y_offset = MAP_UPPER_LEFT_CORNER_Y + 1 + (MAP_MAX_PIXELS_Y - y_map_pixels - 2) / 2; @@ -996,11 +996,11 @@ static void lcd_implementation_status_screen() { // Display Mesh Point Locations u8g.setColorIndex(1); - const uint8_t sx = x_offset + pixels_per_X_mesh_pnt / 2; - uint8_t y = y_offset + pixels_per_Y_mesh_pnt / 2; - for (uint8_t j = 0; j < GRID_MAX_POINTS_Y; j++, y += pixels_per_Y_mesh_pnt) + const uint8_t sx = x_offset + pixels_per_x_mesh_pnt / 2; + uint8_t y = y_offset + pixels_per_y_mesh_pnt / 2; + for (uint8_t j = 0; j < GRID_MAX_POINTS_Y; j++, y += pixels_per_y_mesh_pnt) if (PAGE_CONTAINS(y, y)) - for (uint8_t i = 0, x = sx; i < GRID_MAX_POINTS_X; i++, x += pixels_per_X_mesh_pnt) + for (uint8_t i = 0, x = sx; i < GRID_MAX_POINTS_X; i++, x += pixels_per_x_mesh_pnt) u8g.drawBox(sx, y, 1, 1); // Fill in the Specified Mesh Point @@ -1008,11 +1008,11 @@ static void lcd_implementation_status_screen() { uint8_t inverted_y = GRID_MAX_POINTS_Y - y_plot - 1; // The origin is typically in the lower right corner. We need to // invert the Y to get it to plot in the right location. - const uint8_t by = y_offset + inverted_y * pixels_per_Y_mesh_pnt; - if (PAGE_CONTAINS(by, by + pixels_per_Y_mesh_pnt)) + const uint8_t by = y_offset + inverted_y * pixels_per_y_mesh_pnt; + if (PAGE_CONTAINS(by, by + pixels_per_y_mesh_pnt)) u8g.drawBox( - x_offset + x_plot * pixels_per_X_mesh_pnt, by, - pixels_per_X_mesh_pnt, pixels_per_Y_mesh_pnt + x_offset + x_plot * pixels_per_x_mesh_pnt, by, + pixels_per_x_mesh_pnt, pixels_per_y_mesh_pnt ); // Put Relevant Text on Display diff --git a/Marlin/ultralcd_impl_HD44780.h b/Marlin/ultralcd_impl_HD44780.h index 7c530d445..e8ecd9cf4 100644 --- a/Marlin/ultralcd_impl_HD44780.h +++ b/Marlin/ultralcd_impl_HD44780.h @@ -42,10 +42,10 @@ #define N_USER_CHARS 8 - #define TOP_LEFT 0x01 - #define TOP_RIGHT 0x02 - #define LOWER_LEFT 0x04 - #define LOWER_RIGHT 0x08 + #define TOP_LEFT _BV(0) + #define TOP_RIGHT _BV(1) + #define LOWER_LEFT _BV(2) + #define LOWER_RIGHT _BV(3) #endif #endif @@ -1057,345 +1057,351 @@ static void lcd_implementation_status_screen() { #endif // LCD_HAS_SLOW_BUTTONS -#endif // ULTIPANEL - -#if ENABLED(LCD_HAS_STATUS_INDICATORS) + #if ENABLED(LCD_HAS_STATUS_INDICATORS) - static void lcd_implementation_update_indicators() { - // Set the LEDS - referred to as backlights by the LiquidTWI2 library - static uint8_t ledsprev = 0; - uint8_t leds = 0; + static void lcd_implementation_update_indicators() { + // Set the LEDS - referred to as backlights by the LiquidTWI2 library + static uint8_t ledsprev = 0; + uint8_t leds = 0; - if (thermalManager.degTargetBed() > 0) leds |= LED_A; + if (thermalManager.degTargetBed() > 0) leds |= LED_A; - if (thermalManager.degTargetHotend(0) > 0) leds |= LED_B; + if (thermalManager.degTargetHotend(0) > 0) leds |= LED_B; - #if FAN_COUNT > 0 - if (0 - #if HAS_FAN0 - || fanSpeeds[0] - #endif - #if HAS_FAN1 - || fanSpeeds[1] - #endif - #if HAS_FAN2 - || fanSpeeds[2] - #endif - ) leds |= LED_C; - #endif // FAN_COUNT > 0 + #if FAN_COUNT > 0 + if (0 + #if HAS_FAN0 + || fanSpeeds[0] + #endif + #if HAS_FAN1 + || fanSpeeds[1] + #endif + #if HAS_FAN2 + || fanSpeeds[2] + #endif + ) leds |= LED_C; + #endif // FAN_COUNT > 0 - #if HOTENDS > 1 - if (thermalManager.degTargetHotend(1) > 0) leds |= LED_C; - #endif + #if HOTENDS > 1 + if (thermalManager.degTargetHotend(1) > 0) leds |= LED_C; + #endif - if (leds != ledsprev) { - lcd.setBacklight(leds); - ledsprev = leds; + if (leds != ledsprev) { + lcd.setBacklight(leds); + ledsprev = leds; + } } - } -#endif // LCD_HAS_STATUS_INDICATORS + #endif // LCD_HAS_STATUS_INDICATORS -#if ENABLED(AUTO_BED_LEVELING_UBL) + #if ENABLED(AUTO_BED_LEVELING_UBL) - /** - Possible map screens: + /** + Possible map screens: - 16x2 |X000.00 Y000.00| - |(00,00) Z00.000| + 16x2 |X000.00 Y000.00| + |(00,00) Z00.000| - 20x2 | X:000.00 Y:000.00 | - | (00,00) Z:00.000 | + 20x2 | X:000.00 Y:000.00 | + | (00,00) Z:00.000 | - 16x4 |+-------+(00,00)| - || |X000.00| - || |Y000.00| - |+-------+Z00.000| + 16x4 |+-------+(00,00)| + || |X000.00| + || |Y000.00| + |+-------+Z00.000| - 20x4 | +-------+ (00,00) | - | | | X:000.00| - | | | Y:000.00| - | +-------+ Z:00.000| + 20x4 | +-------+ (00,00) | + | | | X:000.00| + | | | Y:000.00| + | +-------+ Z:00.000| */ - struct custom_char { - uint8_t custom_char_bits[ULTRA_Y_PIXELS_PER_CHAR]; - }; + typedef struct { + uint8_t custom_char_bits[ULTRA_Y_PIXELS_PER_CHAR]; + } custom_char; + + typedef struct { + uint8_t column, row; + uint8_t y_pixel_offset, x_pixel_offset; + uint8_t x_pixel_mask; + } coordinate; + + void add_edges_to_custom_char(custom_char * const custom, coordinate * const ul, coordinate * const lr, coordinate * const brc, const uint8_t cell_location); + FORCE_INLINE static void clear_custom_char(custom_char * const cc) { ZERO(cc->custom_char_bits); } + + /* + // This debug routine should be deleted by anybody that sees it. It doesn't belong here + // But I'm leaving it for now until we know the 20x4 Radar Map is working right. + // We may need it again if any funny lines show up on the mesh points. + void dump_custom_char(char *title, custom_char *c) { + SERIAL_PROTOCOLLN(title); + for (uint8_t j = 0; j < 8; j++) { + for (uint8_t i = 7; i >= 0; i--) + SERIAL_PROTOCOLCHAR(TEST(c->custom_char_bits[j], i) ? '1' : '0'); + SERIAL_EOL(); + } + SERIAL_EOL(); + } + //*/ - struct coordinate pixel_location(uint8_t x, uint8_t y); + coordinate pixel_location(int16_t x, int16_t y) { + coordinate ret_val; + int16_t xp, yp, r, c; - struct coordinate { - uint8_t column; - uint8_t row; - uint8_t y_pixel_offset; - uint8_t x_pixel_offset; - uint8_t x_pixel_mask; - }; + x++; y++; // +1 because lines on the left and top - void add_edges_to_custom_char(struct custom_char *custom, struct coordinate *ul, struct coordinate *lr, struct coordinate *brc, uint8_t cell_location); - extern custom_char user_defined_chars[N_USER_CHARS]; - inline static void CLEAR_CUSTOM_CHAR(struct custom_char *cc) { uint8_t j; for (j = 0; j < ULTRA_Y_PIXELS_PER_CHAR; j++) cc->custom_char_bits[j] = 0; } - - /* - void dump_custom_char(char *title, struct custom_char *c) { // This debug routine should be deleted by anybody that sees it. It doesn't belong here - int i, j; // But I'm leaving it for now until we know the 20x4 Radar Map is working right. - SERIAL_PROTOCOLLN(title); // We will need it again if any funny lines show up on the mesh points. - for(j=0; j<8; j++) { - for(i=7; i>=0; i--) { - if (c->custom_char_bits[j] & (0x01 << i)) - SERIAL_PROTOCOL("1"); - else - SERIAL_PROTOCOL("0"); - } - SERIAL_PROTOCOL("\n"); - } - SERIAL_PROTOCOL("\n"); - } - */ - - void lcd_implementation_ubl_plot(uint8_t x, uint8_t inverted_y) { - - #if LCD_WIDTH >= 20 - #define _LCD_W_POS 12 - #define _PLOT_X 1 - #define _MAP_X 3 - #define _LABEL(C,X,Y) lcd.setCursor(X, Y); lcd.print(C) - #define _XLABEL(X,Y) _LABEL("X:",X,Y) - #define _YLABEL(X,Y) _LABEL("Y:",X,Y) - #define _ZLABEL(X,Y) _LABEL("Z:",X,Y) - #else - #define _LCD_W_POS 8 - #define _PLOT_X 0 - #define _MAP_X 1 - #define _LABEL(X,Y,C) lcd.setCursor(X, Y); lcd.write(C) - #define _XLABEL(X,Y) _LABEL('X',X,Y) - #define _YLABEL(X,Y) _LABEL('Y',X,Y) - #define _ZLABEL(X,Y) _LABEL('Z',X,Y) - #endif + c = x / (ULTRA_X_PIXELS_PER_CHAR); + r = y / (ULTRA_Y_PIXELS_PER_CHAR); - #if LCD_HEIGHT <= 3 // 16x2 or 20x2 display + ret_val.column = c; + ret_val.row = r; - /** - * Show X and Y positions - */ - _XLABEL(_PLOT_X, 0); - lcd.print(ftostr32(LOGICAL_X_POSITION(pgm_read_float(&ubl._mesh_index_to_xpos[x])))); + xp = x - c * (ULTRA_X_PIXELS_PER_CHAR); // get the pixel offsets into the character cell + xp = ULTRA_X_PIXELS_PER_CHAR - 1 - xp; // column within relevant character cell (0 on the right) + yp = y - r * (ULTRA_Y_PIXELS_PER_CHAR); - _YLABEL(_LCD_W_POS, 0); - lcd.print(ftostr32(LOGICAL_Y_POSITION(pgm_read_float(&ubl._mesh_index_to_ypos[inverted_y])))); + ret_val.x_pixel_mask = _BV(xp); + ret_val.x_pixel_offset = xp; + ret_val.y_pixel_offset = yp; + return ret_val; + } - lcd.setCursor(_PLOT_X, 0); + coordinate pixel_location(uint8_t x, uint8_t y) { return pixel_location((int16_t)x, (int16_t)y); } - #else // 16x4 or 20x4 display + void lcd_implementation_ubl_plot(uint8_t x, uint8_t inverted_y) { - struct coordinate upper_left, lower_right, bottom_right_corner; - struct custom_char new_char; - uint8_t i, j, k, l, m, n, n_rows, n_cols, y; - uint8_t bottom_line, right_edge; - uint8_t x_map_pixels, y_map_pixels; - uint8_t pixels_per_X_mesh_pnt, pixels_per_Y_mesh_pnt; - uint8_t suppress_x_offset=0, suppress_y_offset=0; + #if LCD_WIDTH >= 20 + #define _LCD_W_POS 12 + #define _PLOT_X 1 + #define _MAP_X 3 + #define _LABEL(C,X,Y) lcd.setCursor(X, Y); lcd.print(C) + #define _XLABEL(X,Y) _LABEL("X:",X,Y) + #define _YLABEL(X,Y) _LABEL("Y:",X,Y) + #define _ZLABEL(X,Y) _LABEL("Z:",X,Y) + #else + #define _LCD_W_POS 8 + #define _PLOT_X 0 + #define _MAP_X 1 + #define _LABEL(X,Y,C) lcd.setCursor(X, Y); lcd.write(C) + #define _XLABEL(X,Y) _LABEL('X',X,Y) + #define _YLABEL(X,Y) _LABEL('Y',X,Y) + #define _ZLABEL(X,Y) _LABEL('Z',X,Y) + #endif - // ******************************************************** - // ************ Clear and setup everything ********* - // ******************************************************** + #if LCD_HEIGHT <= 3 // 16x2 or 20x2 display - y = GRID_MAX_POINTS_Y - inverted_y - 1; + /** + * Show X and Y positions + */ + _XLABEL(_PLOT_X, 0); + lcd.print(ftostr32(LOGICAL_X_POSITION(pgm_read_float(&ubl._mesh_index_to_xpos[x])))); - upper_left.column = 0; - upper_left.row = 0; - lower_right.column = 0; - lower_right.row = 0; + _YLABEL(_LCD_W_POS, 0); + lcd.print(ftostr32(LOGICAL_Y_POSITION(pgm_read_float(&ubl._mesh_index_to_ypos[inverted_y])))); - lcd_implementation_clear(); + lcd.setCursor(_PLOT_X, 0); - x_map_pixels = ULTRA_X_PIXELS_PER_CHAR * ULTRA_COLUMNS_FOR_MESH_MAP - 2; // minus 2 because we are drawing a box around the map - y_map_pixels = ULTRA_Y_PIXELS_PER_CHAR * ULTRA_ROWS_FOR_MESH_MAP - 2; + #else // 16x4 or 20x4 display - pixels_per_X_mesh_pnt = x_map_pixels / GRID_MAX_POINTS_X; - pixels_per_Y_mesh_pnt = y_map_pixels / GRID_MAX_POINTS_Y; + coordinate upper_left, lower_right, bottom_right_corner; + custom_char new_char; + uint8_t i, j, k, l, m, n, n_rows, n_cols, y, + bottom_line, right_edge, + x_map_pixels, y_map_pixels, + pixels_per_x_mesh_pnt, pixels_per_y_mesh_pnt, + suppress_x_offset = 0, suppress_y_offset = 0; - if (pixels_per_X_mesh_pnt >= ULTRA_X_PIXELS_PER_CHAR) { // There are only 2 custom characters available, so the X - pixels_per_X_mesh_pnt = ULTRA_X_PIXELS_PER_CHAR; // size of the mesh point needs to fit within them independent - suppress_x_offset = 1; // of where the starting pixel is located. - } + y = GRID_MAX_POINTS_Y - inverted_y - 1; - if (pixels_per_Y_mesh_pnt >= ULTRA_Y_PIXELS_PER_CHAR) { // There are only 2 custom characters available, so the Y - pixels_per_Y_mesh_pnt = ULTRA_Y_PIXELS_PER_CHAR; // size of the mesh point needs to fit within them independent - suppress_y_offset = 1; // of where the starting pixel is located. - } + upper_left.column = 0; + upper_left.row = 0; + lower_right.column = 0; + lower_right.row = 0; - x_map_pixels = pixels_per_X_mesh_pnt * GRID_MAX_POINTS_X; // now we have the right number of pixels to make both - y_map_pixels = pixels_per_Y_mesh_pnt * GRID_MAX_POINTS_Y; // directions fit nicely + lcd_implementation_clear(); - right_edge = pixels_per_X_mesh_pnt * GRID_MAX_POINTS_X + 1; // find location of right edge within the character cell - bottom_line= pixels_per_Y_mesh_pnt * GRID_MAX_POINTS_Y + 1; // find location of bottome line within the character cell + x_map_pixels = (ULTRA_X_PIXELS_PER_CHAR) * (ULTRA_COLUMNS_FOR_MESH_MAP) - 2; // minus 2 because we are drawing a box around the map + y_map_pixels = (ULTRA_Y_PIXELS_PER_CHAR) * (ULTRA_ROWS_FOR_MESH_MAP) - 2; - n_rows = (bottom_line / ULTRA_Y_PIXELS_PER_CHAR) + 1; - n_cols = (right_edge / ULTRA_X_PIXELS_PER_CHAR) + 1; + pixels_per_x_mesh_pnt = x_map_pixels / (GRID_MAX_POINTS_X); + pixels_per_y_mesh_pnt = y_map_pixels / (GRID_MAX_POINTS_Y); - for (i = 0; i < n_cols; i++) { - lcd.setCursor(i, 0); - lcd.print((char) 0x00); // top line of the box + if (pixels_per_x_mesh_pnt >= ULTRA_X_PIXELS_PER_CHAR) { // There are only 2 custom characters available, so the X + pixels_per_x_mesh_pnt = ULTRA_X_PIXELS_PER_CHAR; // size of the mesh point needs to fit within them independent + suppress_x_offset = 1; // of where the starting pixel is located. + } - lcd.setCursor(i, n_rows-1); - lcd.write(0x01); // bottom line of the box - } + if (pixels_per_y_mesh_pnt >= ULTRA_Y_PIXELS_PER_CHAR) { // There are only 2 custom characters available, so the Y + pixels_per_y_mesh_pnt = ULTRA_Y_PIXELS_PER_CHAR; // size of the mesh point needs to fit within them independent + suppress_y_offset = 1; // of where the starting pixel is located. + } - for (j = 0; j < n_rows; j++) { - lcd.setCursor(0, j); - lcd.write(0x02); // Left edge of the box - lcd.setCursor(n_cols-1, j); - lcd.write(0x03); // right edge of the box - } + x_map_pixels = pixels_per_x_mesh_pnt * (GRID_MAX_POINTS_X); // now we have the right number of pixels to make both + y_map_pixels = pixels_per_y_mesh_pnt * (GRID_MAX_POINTS_Y); // directions fit nicely - // - /* if the entire 4th row is not in use, do not put vertical bars all the way down to the bottom of the display */ - // + right_edge = pixels_per_x_mesh_pnt * (GRID_MAX_POINTS_X) + 1; // find location of right edge within the character cell + bottom_line= pixels_per_y_mesh_pnt * (GRID_MAX_POINTS_Y) + 1; // find location of bottome line within the character cell - k = pixels_per_Y_mesh_pnt * GRID_MAX_POINTS_Y + 2; - l = ULTRA_Y_PIXELS_PER_CHAR * n_rows; - if ((k != l) && ((l-k)>=ULTRA_Y_PIXELS_PER_CHAR/2)) { - lcd.setCursor(0, n_rows-1); // left edge of the box - lcd.write(' '); - lcd.setCursor(n_cols-1, n_rows-1); // right edge of the box - lcd.write(' '); - } + n_rows = bottom_line / (ULTRA_Y_PIXELS_PER_CHAR) + 1; + n_cols = right_edge / (ULTRA_X_PIXELS_PER_CHAR) + 1; - CLEAR_CUSTOM_CHAR(&new_char); - new_char.custom_char_bits[0] = (unsigned char) 0B11111; // char #0 is used for the top line of the box - lcd.createChar(0, (uint8_t *) &new_char); - - CLEAR_CUSTOM_CHAR(&new_char); - k = GRID_MAX_POINTS_Y * pixels_per_Y_mesh_pnt + 1; // row of pixels for the bottom box line - l = k % ULTRA_Y_PIXELS_PER_CHAR; // row within relivant character cell - new_char.custom_char_bits[l] = (unsigned char) 0B11111; // char #1 is used for the bottom line of the box - lcd.createChar(1, (uint8_t *) &new_char); - - CLEAR_CUSTOM_CHAR(&new_char); - for (j = 0; j < ULTRA_Y_PIXELS_PER_CHAR; j++) - new_char.custom_char_bits[j] = (unsigned char) 0B10000; // char #2 is used for the left edge of the box - lcd.createChar(2, (uint8_t *) &new_char); - - CLEAR_CUSTOM_CHAR(&new_char); - m = GRID_MAX_POINTS_X * pixels_per_X_mesh_pnt + 1; // column of pixels for the right box line - n = m % ULTRA_X_PIXELS_PER_CHAR; // column within relivant character cell - i = ULTRA_X_PIXELS_PER_CHAR - 1 - n; // column within relivant character cell (0 on the right) - for (j = 0; j < ULTRA_Y_PIXELS_PER_CHAR; j++) - new_char.custom_char_bits[j] = (unsigned char) 0B00001 << i; // char #3 is used for the right edge of the box - lcd.createChar(3, (uint8_t *) &new_char); - - i = x*pixels_per_X_mesh_pnt - suppress_x_offset; - j = y*pixels_per_Y_mesh_pnt - suppress_y_offset; - upper_left = pixel_location(i, j); - - k = (x+1)*pixels_per_X_mesh_pnt-1-suppress_x_offset; - l = (y+1)*pixels_per_Y_mesh_pnt-1-suppress_y_offset; - lower_right = pixel_location(k, l); - - bottom_right_corner = pixel_location(x_map_pixels, y_map_pixels); - - /* - * First, handle the simple case where everything is within a single character cell. - * If part of the Mesh Plot is outside of this character cell, we will follow up - * and deal with that next. - */ + for (i = 0; i < n_cols; i++) { + lcd.setCursor(i, 0); + lcd.print((char)0x00); // top line of the box - //dump_custom_char("at entry:", &new_char); + lcd.setCursor(i, n_rows - 1); + lcd.write(0x01); // bottom line of the box + } - CLEAR_CUSTOM_CHAR(&new_char); - for(j=upper_left.y_pixel_offset; j= ULTRA_Y_PIXELS_PER_CHAR) - break; - i=upper_left.x_pixel_mask; - for(k=0; k> 1; + for (j = 0; j < n_rows; j++) { + lcd.setCursor(0, j); + lcd.write(0x02); // Left edge of the box + lcd.setCursor(n_cols - 1, j); + lcd.write(0x03); // right edge of the box } - } - //dump_custom_char("after loops:", &new_char); - add_edges_to_custom_char(&new_char, &upper_left, &lower_right, &bottom_right_corner, TOP_LEFT); - //dump_custom_char("after add edges", &new_char); - lcd.createChar(4, (uint8_t *) &new_char); + /** + * If the entire 4th row is not in use, do not put vertical bars all the way down to the bottom of the display + */ - lcd.setCursor(upper_left.column, upper_left.row); - lcd.write(0x04); - //dump_custom_char("after lcd update:", &new_char); + k = pixels_per_y_mesh_pnt * (GRID_MAX_POINTS_Y) + 2; + l = (ULTRA_Y_PIXELS_PER_CHAR) * n_rows; + if (l > k && l - k >= (ULTRA_Y_PIXELS_PER_CHAR) / 2) { + lcd.setCursor(0, n_rows - 1); // left edge of the box + lcd.write(' '); + lcd.setCursor(n_cols - 1, n_rows - 1); // right edge of the box + lcd.write(' '); + } - /* - * Next, check for two side by side character cells being used to display the Mesh Point - * If found... do the right hand character cell next. - */ - if (upper_left.column+1 == lower_right.column) { - l = upper_left.x_pixel_offset; - CLEAR_CUSTOM_CHAR(&new_char); - for (j = upper_left.y_pixel_offset; j < upper_left.y_pixel_offset + pixels_per_Y_mesh_pnt; j++) { - if (j >= ULTRA_Y_PIXELS_PER_CHAR) - break; - i=0x01 << (ULTRA_X_PIXELS_PER_CHAR-1); // fill in the left side of the right character cell - for(k=0; k> 1; + i >>= 1; } } - add_edges_to_custom_char(&new_char, &upper_left, &lower_right, &bottom_right_corner, TOP_RIGHT); + //dump_custom_char("after loops:", &new_char); - lcd.createChar(5, (uint8_t *) &new_char); + add_edges_to_custom_char(&new_char, &upper_left, &lower_right, &bottom_right_corner, TOP_LEFT); + //dump_custom_char("after add edges", &new_char); + lcd.createChar(4, (uint8_t*)&new_char); - lcd.setCursor(lower_right.column, upper_left.row); - lcd.write(0x05); - } + lcd.setCursor(upper_left.column, upper_left.row); + lcd.write(0x04); + //dump_custom_char("after lcd update:", &new_char); - /* - * Next, check for two character cells stacked on top of each other being used to display the Mesh Point - */ - if (upper_left.row+1 == lower_right.row) { - l = ULTRA_Y_PIXELS_PER_CHAR - upper_left.y_pixel_offset; // number of pixel rows in top character cell - k = pixels_per_Y_mesh_pnt - l; // number of pixel rows in bottom character cell - CLEAR_CUSTOM_CHAR(&new_char); - for(j=0; j> 1; - if (!i) - break; + /** + * Next, check for two side by side character cells being used to display the Mesh Point + * If found... do the right hand character cell next. + */ + if (upper_left.column == lower_right.column - 1) { + l = upper_left.x_pixel_offset; + clear_custom_char(&new_char); + for (j = upper_left.y_pixel_offset; j < ypix; j++) { + i = _BV(ULTRA_X_PIXELS_PER_CHAR - 1); // Fill in the left side of the right character cell + for (k = 0; k < pixels_per_x_mesh_pnt - 1 - l; k++) { + new_char.custom_char_bits[j] |= i; + i >>= 1; + } } - } - add_edges_to_custom_char(&new_char, &upper_left, &lower_right, &bottom_right_corner, LOWER_LEFT); - lcd.createChar(6, (uint8_t *) &new_char); + add_edges_to_custom_char(&new_char, &upper_left, &lower_right, &bottom_right_corner, TOP_RIGHT); - lcd.setCursor(upper_left.column, lower_right.row); - lcd.write(0x06); - } + lcd.createChar(5, (uint8_t *) &new_char); - /* - * Next, check for four character cells being used to display the Mesh Point. If that is - * what is here, we work to fill in the character cell that is down one and to the right one - * from the upper_left character cell. - */ + lcd.setCursor(lower_right.column, upper_left.row); + lcd.write(0x05); + } - if (upper_left.column+1 == lower_right.column && upper_left.row+1 == lower_right.row) { - l = ULTRA_Y_PIXELS_PER_CHAR - upper_left.y_pixel_offset; // number of pixel rows in top character cell - k = pixels_per_Y_mesh_pnt - l; // number of pixel rows in bottom character cell - CLEAR_CUSTOM_CHAR(&new_char); - for (j = 0; j> 1; + /** + * Next, check for two character cells stacked on top of each other being used to display the Mesh Point + */ + if (upper_left.row == lower_right.row - 1) { + l = ULTRA_Y_PIXELS_PER_CHAR - upper_left.y_pixel_offset; // Number of pixel rows in top character cell + k = pixels_per_y_mesh_pnt - l; // Number of pixel rows in bottom character cell + clear_custom_char(&new_char); + for (j = 0; j < k; j++) { + i = upper_left.x_pixel_mask; + for (m = 0; m < pixels_per_x_mesh_pnt; m++) { // Fill in the top side of the bottom character cell + new_char.custom_char_bits[j] |= i; + if (!(i >>= 1)) break; + } } + add_edges_to_custom_char(&new_char, &upper_left, &lower_right, &bottom_right_corner, LOWER_LEFT); + lcd.createChar(6, (uint8_t *) &new_char); + + lcd.setCursor(upper_left.column, lower_right.row); + lcd.write(0x06); } - add_edges_to_custom_char(&new_char, &upper_left, &lower_right, &bottom_right_corner, LOWER_RIGHT); - lcd.createChar(7, (uint8_t *) &new_char); - lcd.setCursor(lower_right.column, lower_right.row); - lcd.write(0x07); - } + /** + * Next, check for four character cells being used to display the Mesh Point. If that is + * what is here, we work to fill in the character cell that is down one and to the right one + * from the upper_left character cell. + */ + + if (upper_left.column == lower_right.column - 1 && upper_left.row == lower_right.row - 1) { + l = ULTRA_Y_PIXELS_PER_CHAR - upper_left.y_pixel_offset; // Number of pixel rows in top character cell + k = pixels_per_y_mesh_pnt - l; // Number of pixel rows in bottom character cell + clear_custom_char(&new_char); + for (j = 0; j < k; j++) { + l = upper_left.x_pixel_offset; + i = _BV(ULTRA_X_PIXELS_PER_CHAR - 1); // Fill in the left side of the right character cell + for (m = 0; m < pixels_per_x_mesh_pnt - 1 - l; m++) { // Fill in the top side of the bottom character cell + new_char.custom_char_bits[j] |= i; + i >>= 1; + } + } + add_edges_to_custom_char(&new_char, &upper_left, &lower_right, &bottom_right_corner, LOWER_RIGHT); + lcd.createChar(7, (uint8_t*)&new_char); - #endif + lcd.setCursor(lower_right.column, lower_right.row); + lcd.write(0x07); + } + + #endif /** * Print plot position @@ -1407,209 +1413,123 @@ static void lcd_implementation_status_screen() { lcd.print(inverted_y); lcd.write(')'); - #if LCD_HEIGHT <= 3 // 16x2 or 20x2 display + #if LCD_HEIGHT <= 3 // 16x2 or 20x2 display - /** - * Print Z values - */ - _ZLABEL(_LCD_W_POS, 1); - if (!isnan(ubl.z_values[x][inverted_y])) - lcd.print(ftostr43sign(ubl.z_values[x][inverted_y])); - else - lcd_printPGM(PSTR(" -----")); + /** + * Print Z values + */ + _ZLABEL(_LCD_W_POS, 1); + if (!isnan(ubl.z_values[x][inverted_y])) + lcd.print(ftostr43sign(ubl.z_values[x][inverted_y])); + else + lcd_printPGM(PSTR(" -----")); + + #else // 16x4 or 20x4 display + + /** + * Show all values at right of screen + */ + _XLABEL(_LCD_W_POS, 1); + lcd.print(ftostr32(LOGICAL_X_POSITION(pgm_read_float(&ubl._mesh_index_to_xpos[x])))); + _YLABEL(_LCD_W_POS, 2); + lcd.print(ftostr32(LOGICAL_Y_POSITION(pgm_read_float(&ubl._mesh_index_to_ypos[inverted_y])))); + + /** + * Show the location value + */ + _ZLABEL(_LCD_W_POS, 3); + if (!isnan(ubl.z_values[x][inverted_y])) + lcd.print(ftostr43sign(ubl.z_values[x][inverted_y])); + else + lcd_printPGM(PSTR(" -----")); + + #endif // LCD_HEIGHT > 3 + } - #else // 16x4 or 20x4 display + void add_edges_to_custom_char(custom_char * const custom, coordinate * const ul, coordinate * const lr, coordinate * const brc, uint8_t cell_location) { + uint8_t i, k; + int16_t n_rows = lr->row - ul->row + 1, + n_cols = lr->column - ul->column + 1; /** - * Show all values at right of screen + * Check if Top line of box needs to be filled in */ - _XLABEL(_LCD_W_POS, 1); - lcd.print(ftostr32(LOGICAL_X_POSITION(pgm_read_float(&ubl._mesh_index_to_xpos[x])))); - _YLABEL(_LCD_W_POS, 2); - lcd.print(ftostr32(LOGICAL_Y_POSITION(pgm_read_float(&ubl._mesh_index_to_ypos[inverted_y])))); + if (ul->row == 0 && ((cell_location & TOP_LEFT) || (cell_location & TOP_RIGHT))) { // Only fill in the top line for the top character cells + + if (n_cols == 1) { + if (ul->column != brc->column) + custom->custom_char_bits[0] = 0xFF; // Single column in middle + else + for (i = brc->x_pixel_offset; i < ULTRA_X_PIXELS_PER_CHAR; i++) // Single column on right side + SBI(custom->custom_char_bits[0], i); + } + else if ((cell_location & TOP_LEFT) || lr->column != brc->column) // Multiple column in the middle or with right cell in middle + custom->custom_char_bits[0] = 0xFF; + else + for (i = brc->x_pixel_offset; i < ULTRA_X_PIXELS_PER_CHAR; i++) + SBI(custom->custom_char_bits[0], i); + } /** - * Show the location value + * Check if left line of box needs to be filled in */ - _ZLABEL(_LCD_W_POS, 3); - if (!isnan(ubl.z_values[x][inverted_y])) - lcd.print(ftostr43sign(ubl.z_values[x][inverted_y])); - else - lcd_printPGM(PSTR(" -----")); - - #endif // LCD_HEIGHT > 3 - - return; - } -void add_edges_to_custom_char(struct custom_char *custom, struct coordinate *ul, struct coordinate *lr, struct coordinate *brc, unsigned char cell_location) { - unsigned char i, k; - int n_rows, n_cols; - - n_rows = lr->row - ul->row + 1; - n_cols = lr->column - ul->column + 1; + if ((cell_location & TOP_LEFT) || (cell_location & LOWER_LEFT)) { + if (ul->column == 0) { // Left column of characters on LCD Display + k = ul->row == brc->row ? brc->y_pixel_offset : ULTRA_Y_PIXELS_PER_CHAR; // If it isn't the last row... do the full character cell + for (i = 0; i < k; i++) + SBI(custom->custom_char_bits[i], ULTRA_X_PIXELS_PER_CHAR - 1); + } + } - /* - * Check if Top line of box needs to be filled in - */ - if ((ul->row == 0) && ((cell_location&TOP_LEFT) || (cell_location&TOP_RIGHT))) { // Only fill in the top line for the top character cells + /** + * Check if bottom line of box needs to be filled in + */ - if (n_cols == 1) { - if (ul->column != brc->column) - custom->custom_char_bits[0] = 0xff; // single column in middle - else { - for (i = brc->x_pixel_offset; icustom_char_bits[0] |= 0x01 << i; - } - } - else { - if (cell_location & TOP_LEFT) - custom->custom_char_bits[0] = 0xff; // multiple column in the middle - else - if (lr->column != brc->column) - custom->custom_char_bits[0] = 0xff; // multiple column with right cell in middle - else { - for (i = brc->x_pixel_offset; icustom_char_bits[0] |= 0x01 << i; + // Single row of mesh plot cells + if (n_rows == 1 /* && (cell_location == TOP_LEFT || cell_location == TOP_RIGHT) */ && ul->row == brc->row) { + if (n_cols == 1) // Single row, single column case + k = ul->column == brc->column ? brc->x_pixel_mask : 0x01; + else if (cell_location & TOP_RIGHT) // Single row, multiple column case + k = lr->column == brc->column ? brc->x_pixel_mask : 0x01; + else // Single row, left of multiple columns + k = 0x01; + while (k < _BV(ULTRA_X_PIXELS_PER_CHAR)) { + custom->custom_char_bits[brc->y_pixel_offset] |= k; + k <<= 1; } - } - } + } - /* - * Check if left line of box needs to be filled in - */ - if ((cell_location & TOP_LEFT) || (cell_location & LOWER_LEFT)) { - if (ul->column == 0) { // Left column of characters on LCD Display - if (ul->row != brc->row) - k = ULTRA_Y_PIXELS_PER_CHAR; // if it isn't the last row... do the full character cell - else - k = brc->y_pixel_offset; + // Double row of characters on LCD Display + // And this is a bottom custom character + if (n_rows == 2 && (cell_location == LOWER_LEFT || cell_location == LOWER_RIGHT) && lr->row == brc->row) { + if (n_cols == 1) // Double row, single column case + k = ul->column == brc->column ? brc->x_pixel_mask : 0x01; + else if (cell_location & LOWER_RIGHT) // Double row, multiple column case + k = lr->column == brc->column ? brc->x_pixel_mask : 0x01; + else // Double row, left of multiple columns + k = 0x01; + while (k < _BV(ULTRA_X_PIXELS_PER_CHAR)) { + custom->custom_char_bits[brc->y_pixel_offset] |= k; + k <<= 1; + } + } - for (i = 0; i < k; i++) - custom->custom_char_bits[i] |= 0x01 << (ULTRA_X_PIXELS_PER_CHAR - 1); + /** + * Check if right line of box needs to be filled in + */ + // Nothing to do if the lower right part of the mesh pnt isn't in the same column as the box line + if (lr->column == brc->column) { + // This mesh point is in the same character cell as the right box line + if (ul->column == brc->column || (cell_location & TOP_RIGHT) || (cell_location & LOWER_RIGHT)) { + // If not the last row... do the full character cell + k = ul->row == brc->row ? brc->y_pixel_offset : ULTRA_Y_PIXELS_PER_CHAR; + for (i = 0; i < k; i++) custom->custom_char_bits[i] |= brc->x_pixel_mask; + } + } } - } - - /* - * Check if bottom line of box needs to be filled in - */ - - // Single row of mesh plot cells - if ((n_rows==1) /* && ((cell_location == TOP_LEFT) || (cell_location==TOP_RIGHT)) */) { - if (ul->row == brc->row) { - if (n_cols == 1) { // single row, single column case - if (ul->column != brc->column) - k = 0x01; - else - k = brc->x_pixel_mask; - } else { - if (cell_location & TOP_RIGHT) { // single row, multiple column case - if(lr->column != brc->column) - k = 0x01; - else - k = brc->x_pixel_mask; - } else // single row, left of multiple columns - k = 0x01; - } - while (k < (0x01 << ULTRA_X_PIXELS_PER_CHAR)) { - custom->custom_char_bits[brc->y_pixel_offset] |= k; - k = k << 1; - } - } - } - - - // Double row of characters on LCD Display - // And this is a bottom custom character - if ((n_rows==2) && ((cell_location == LOWER_LEFT) || (cell_location==LOWER_RIGHT))) { - if (lr->row == brc->row) { - if (n_cols == 1) { // double row, single column case - if (ul->column != brc->column) - k = 0x01; - else - k = brc->x_pixel_mask; - } else { - if (cell_location & LOWER_RIGHT) { // double row, multiple column case - if(lr->column != brc->column) - k = 0x01; - else - k = brc->x_pixel_mask; - } else // double row, left of multiple columns - k = 0x01; - } - while (k < (0x01 << ULTRA_X_PIXELS_PER_CHAR)) { - custom->custom_char_bits[brc->y_pixel_offset] |= k; - k = k << 1; - } - } - } - - /* - * Check if right line of box needs to be filled in - */ - - if (lr->column == brc->column) { // nothing to do if the lower right part of the mesh pnt isn't in the same column as the box line - if ((ul->column == brc->column) || - ((lr->column == brc->column) && (cell_location&TOP_RIGHT)) || - ((lr->column == brc->column) && (cell_location&LOWER_RIGHT))) { // This mesh point is in the same character cell as the right box line - - if (ul->row != brc->row) - k = ULTRA_Y_PIXELS_PER_CHAR; // if it isn't the last row... do the full character cell - else - k = brc->y_pixel_offset; - - for (i = 0; i < k; i++) - custom->custom_char_bits[i] |= brc->x_pixel_mask; - } - } - } - - struct coordinate pixel_location(int x, int y) { - struct coordinate ret_val; - int xp, yp, r, c; - x++; // +1 because there is a line on the left - y++; // and a line at the top to make the box + #endif // AUTO_BED_LEVELING_UBL - c = x / ULTRA_X_PIXELS_PER_CHAR; - r = y / ULTRA_Y_PIXELS_PER_CHAR; - - ret_val.column = c; - ret_val.row = r; - - xp = x - c * ULTRA_X_PIXELS_PER_CHAR; // get the pixel offsets into the character cell - xp = ULTRA_X_PIXELS_PER_CHAR - 1 - xp; // column within relivant character cell (0 on the right) - yp = y - r * ULTRA_Y_PIXELS_PER_CHAR; - - ret_val.x_pixel_mask = 0x01 << xp; - ret_val.x_pixel_offset = xp; - ret_val.y_pixel_offset = yp; - return ret_val; - } - - struct coordinate pixel_location(uint8_t x, uint8_t y) { - struct coordinate ret_val; - uint8_t xp, yp, r, c; - - x++; // +1 because there is a line on the left - y++; // and a line at the top to make the box - - c = x / ULTRA_X_PIXELS_PER_CHAR; - r = y / ULTRA_Y_PIXELS_PER_CHAR; - - ret_val.column = c; - ret_val.row = r; - - xp = x - c * ULTRA_X_PIXELS_PER_CHAR; // get the pixel offsets into the character cell - xp = ULTRA_X_PIXELS_PER_CHAR - 1 - xp; // column within relivant character cell (0 on the right) - yp = y - r * ULTRA_Y_PIXELS_PER_CHAR; - - ret_val.x_pixel_mask = 0x01 << xp; - ret_val.x_pixel_offset = xp; - ret_val.y_pixel_offset = yp; - - return ret_val; - } - -#endif // AUTO_BED_LEVELING_UBL +#endif // ULTIPANEL #endif // ULTRALCD_IMPL_HD44780_H From a519b093b97b5d0318f436221ae789acb0614d7a Mon Sep 17 00:00:00 2001 From: "C. Scott Ananian" Date: Thu, 13 Jul 2017 13:02:15 -0400 Subject: [PATCH 021/112] Fix build by replacing qr_solve by least_squares_fit. (#7285) This was broken by 9af67e2446ae743b9ee1a139de494ff8217a10e1. --- Marlin/Makefile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/Makefile b/Marlin/Makefile index d366f4ae5..cabcf3000 100644 --- a/Marlin/Makefile +++ b/Marlin/Makefile @@ -295,7 +295,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 endstops.cpp stopwatch.cpp utility.cpp \ + dac_mcp4728.cpp vector_3.cpp least_squares_fit.cpp endstops.cpp stopwatch.cpp utility.cpp \ printcounter.cpp nozzle.cpp serial.cpp ifeq ($(LIQUID_TWI2), 0) CXXSRC += LiquidCrystal.cpp From 37a6833d7e9bf5f0f9525251a7905ebdd89d92a8 Mon Sep 17 00:00:00 2001 From: Roxy-3D Date: Thu, 13 Jul 2017 16:33:02 -0500 Subject: [PATCH 022/112] Allow the sampled point to be added into the Least Squares Best Fit (#7289) Without this... The LSF won't work because none of the sampled points in this code block get added. --- Marlin/Marlin_main.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index cbd33480a..26b7df639 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -4623,6 +4623,8 @@ void home_all_axes() { gcode_G28(true); } eqnAMatrix[abl_probe_index + 1 * abl2] = yProbe; eqnAMatrix[abl_probe_index + 2 * abl2] = 1; + incremental_LSF(&lsf_results, xProbe, yProbe, measured_z); + #elif ENABLED(AUTO_BED_LEVELING_BILINEAR) z_values[xCount][yCount] = measured_z + zoffset; From 2ad3ca5d8a31e6b10243259bf7039654bf045db6 Mon Sep 17 00:00:00 2001 From: Tannoo Date: Tue, 18 Jul 2017 21:55:14 -0600 Subject: [PATCH 023/112] Bugfix (#7310) --- Marlin/ultralcd_impl_DOGM.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/ultralcd_impl_DOGM.h b/Marlin/ultralcd_impl_DOGM.h index 5d075124d..991183c2d 100644 --- a/Marlin/ultralcd_impl_DOGM.h +++ b/Marlin/ultralcd_impl_DOGM.h @@ -1001,7 +1001,7 @@ static void lcd_implementation_status_screen() { for (uint8_t j = 0; j < GRID_MAX_POINTS_Y; j++, y += pixels_per_y_mesh_pnt) if (PAGE_CONTAINS(y, y)) for (uint8_t i = 0, x = sx; i < GRID_MAX_POINTS_X; i++, x += pixels_per_x_mesh_pnt) - u8g.drawBox(sx, y, 1, 1); + u8g.drawBox(x, y, 1, 1); // Fill in the Specified Mesh Point From e530c6734938aee8bf688fa258d07fb19f699b1c Mon Sep 17 00:00:00 2001 From: fixoid Date: Wed, 19 Jul 2017 21:01:07 +0300 Subject: [PATCH 024/112] Fixing SWITCHING_EXTRUDER feature --- Marlin/Marlin_main.cpp | 14 ++++++-------- 1 file changed, 6 insertions(+), 8 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 26b7df639..baf42cc06 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -10350,22 +10350,20 @@ void tool_change(const uint8_t tmp_extruder, const float fr_mm_s/*=0.0*/, bool n UNUSED(fr_mm_s); UNUSED(no_move); - #if ENABLED(SWITCHING_EXTRUDER) && !DONT_SWITCH - - stepper.synchronize(); - move_extruder_servo(tmp_extruder); - - #elif ENABLED(MK2_MULTIPLEXER) - + #if ENABLED(MK2_MULTIPLEXER) if (tmp_extruder >= E_STEPPERS) return invalid_extruder_error(tmp_extruder); select_multiplexed_stepper(tmp_extruder); - #endif #endif // HOTENDS <= 1 + #if ENABLED(SWITCHING_EXTRUDER) && !DONT_SWITCH + stepper.synchronize(); + move_extruder_servo(tmp_extruder); + #endif + active_extruder = tmp_extruder; SERIAL_ECHO_START(); From 4d98e3f0a7a38dfc8bb73a0d308d92e402f50b84 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 18 Jul 2017 03:18:05 -0500 Subject: [PATCH 025/112] General cleanup --- Marlin/Marlin_main.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 26b7df639..cec1293a1 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -12511,7 +12511,7 @@ void prepare_move_to_destination() { #endif // FAST_PWM_FAN -float calculate_volumetric_multiplier(float diameter) { +float calculate_volumetric_multiplier(const float diameter) { if (!volumetric_enabled || diameter == 0) return 1.0; return 1.0 / (M_PI * sq(diameter * 0.5)); } From 72de280c1e4581534f47df8cd1fe062589c983ad Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 17 Jul 2017 22:01:20 -0500 Subject: [PATCH 026/112] BARICUDA valve pressure consistently uint8_t --- Marlin/Marlin.h | 3 +-- Marlin/Marlin_main.cpp | 4 ++-- Marlin/planner.cpp | 4 ++-- Marlin/planner.h | 2 +- 4 files changed, 6 insertions(+), 7 deletions(-) diff --git a/Marlin/Marlin.h b/Marlin/Marlin.h index 307dd370d..543fbcc5e 100644 --- a/Marlin/Marlin.h +++ b/Marlin/Marlin.h @@ -362,8 +362,7 @@ extern float soft_endstop_min[XYZ], soft_endstop_max[XYZ]; #endif #if ENABLED(BARICUDA) - extern int baricuda_valve_pressure; - extern int baricuda_e_to_p_pressure; + extern uint8_t baricuda_valve_pressure, baricuda_e_to_p_pressure; #endif #if ENABLED(FILAMENT_WIDTH_SENSOR) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index cec1293a1..5f46090b9 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -561,8 +561,8 @@ static uint8_t target_extruder; #endif #if ENABLED(BARICUDA) - int baricuda_valve_pressure = 0; - int baricuda_e_to_p_pressure = 0; + uint8_t baricuda_valve_pressure = 0, + baricuda_e_to_p_pressure = 0; #endif #if ENABLED(FWRETRACT) diff --git a/Marlin/planner.cpp b/Marlin/planner.cpp index 1e84ae208..c84ce9bae 100644 --- a/Marlin/planner.cpp +++ b/Marlin/planner.cpp @@ -409,10 +409,10 @@ void Planner::check_axes_activity() { #if ENABLED(BARICUDA) #if HAS_HEATER_1 - unsigned char tail_valve_pressure = baricuda_valve_pressure; + uint8_t tail_valve_pressure = baricuda_valve_pressure; #endif #if HAS_HEATER_2 - unsigned char tail_e_to_p_pressure = baricuda_e_to_p_pressure; + uint8_t tail_e_to_p_pressure = baricuda_e_to_p_pressure; #endif #endif diff --git a/Marlin/planner.h b/Marlin/planner.h index 90593816e..9abcf10b2 100644 --- a/Marlin/planner.h +++ b/Marlin/planner.h @@ -121,7 +121,7 @@ typedef struct { #endif #if ENABLED(BARICUDA) - uint32_t valve_pressure, e_to_p_pressure; + uint8_t valve_pressure, e_to_p_pressure; #endif uint32_t segment_time; From c45798694f16266f73639d6b787fe4610ccca352 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 17 Jul 2017 22:02:12 -0500 Subject: [PATCH 027/112] Add some more requirements to the G-code list --- Marlin/Marlin_main.cpp | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 5f46090b9..d6856ac8c 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -51,23 +51,23 @@ * 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 + * G10 - Retract filament according to settings of M207 (Requires FWRETRACT) + * G11 - Retract recover filament according to settings of M208 (Requires FWRETRACT) + * G12 - Clean tool (Requires NOZZLE_CLEAN_FEATURE) * G17 - Select Plane XY (Requires CNC_WORKSPACE_PLANES) * G18 - Select Plane ZX (Requires CNC_WORKSPACE_PLANES) * G19 - Select Plane YZ (Requires CNC_WORKSPACE_PLANES) - * G20 - Set input units to inches - * G21 - Set input units to millimeters + * G20 - Set input units to inches (Requires INCH_MODE_SUPPORT) + * G21 - Set input units to millimeters (Requires INCH_MODE_SUPPORT) * G26 - Mesh Validation Pattern (Requires UBL_G26_MESH_VALIDATION) * G27 - Park Nozzle (Requires NOZZLE_PARK_FEATURE) * 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. + * G29 - Start or continue the bed leveling probe procedure (Requires bed leveling) * 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) * G33 - Delta Auto-Calibration (Requires DELTA_AUTO_CALIBRATION) - * G38 - Probe target - similar to G28 except it uses the Z_MIN_PROBE for all three axes + * G38 - Probe in any direction using the Z_MIN_PROBE (Requires G38_PROBE_TARGET) * G42 - Coordinated move to a mesh point (Requires AUTO_BED_LEVELING_UBL) * G90 - Use Absolute Coordinates * G91 - Use Relative Coordinates From 7afafb05b866cad4dcce1ff08c9f13f84319a8e9 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 18 Jul 2017 01:37:54 -0500 Subject: [PATCH 028/112] Split G10/G11 into separate functions --- Marlin/Marlin_main.cpp | 31 ++++++++++++++++++------------- 1 file changed, 18 insertions(+), 13 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index d6856ac8c..c9f2583cc 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -3403,20 +3403,24 @@ inline void gcode_G4() { /** * G10 - Retract filament according to settings of M207 - * G11 - Recover filament according to settings of M208 */ - inline void gcode_G10_G11(bool doRetract=false) { + inline void gcode_G10() { #if EXTRUDERS > 1 - if (doRetract) - retracted_swap[active_extruder] = parser.boolval('S'); // checks for swap retract argument + const bool rs = parser.boolval('S'); + retracted_swap[active_extruder] = rs; // Use 'S' for swap, default to false #endif - retract(doRetract - #if EXTRUDERS > 1 - , retracted_swap[active_extruder] - #endif + retract(true + #if EXTRUDERS > 1 + , rs + #endif ); } + /** + * G11 - Recover filament according to settings of M208 + */ + inline void gcode_G11() { retract(false); } + #endif // FWRETRACT #if ENABLED(NOZZLE_CLEAN_FEATURE) @@ -10450,8 +10454,8 @@ void process_next_command() { // G2, G3 #if ENABLED(ARC_SUPPORT) && DISABLED(SCARA) - case 2: // G2 - CW ARC - case 3: // G3 - CCW ARC + case 2: // G2: CW ARC + case 3: // G3: CCW ARC gcode_G2_G3(parser.codenum == 2); break; #endif @@ -10462,16 +10466,17 @@ void process_next_command() { break; #if ENABLED(BEZIER_CURVE_SUPPORT) - // G5 - case 5: // G5 - Cubic B_spline + case 5: // G5: Cubic B_spline gcode_G5(); break; #endif // BEZIER_CURVE_SUPPORT #if ENABLED(FWRETRACT) case 10: // G10: retract + gcode_G10(); + break; case 11: // G11: retract_recover - gcode_G10_G11(parser.codenum == 10); + gcode_G11(); break; #endif // FWRETRACT From b0173ccdb9022877388e34aea08eae48cb8e240c Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 18 Jul 2017 03:17:50 -0500 Subject: [PATCH 029/112] Drop extra initializers for vars initialized by EEPROM code --- Marlin/Marlin_main.cpp | 27 +++++++-------------------- Marlin/endstops.cpp | 9 +-------- Marlin/planner.cpp | 8 +++++--- Marlin/stepper.cpp | 2 +- Marlin/temperature.cpp | 18 +++++++----------- Marlin/ultralcd.cpp | 1 + Marlin/ultralcd_impl_DOGM.h | 2 +- 7 files changed, 23 insertions(+), 44 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index c9f2583cc..75eb63e3a 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -427,16 +427,10 @@ static float saved_feedrate_mm_s; int16_t feedrate_percentage = 100, saved_feedrate_percentage, flow_percentage[EXTRUDERS] = ARRAY_BY_EXTRUDERS1(100); +// Initialized by settings.load() bool axis_relative_modes[] = AXIS_RELATIVE_MODES, - volumetric_enabled = - #if ENABLED(VOLUMETRIC_DEFAULT_ON) - true - #else - false - #endif - ; -float filament_size[EXTRUDERS] = ARRAY_BY_EXTRUDERS1(DEFAULT_NOMINAL_FILAMENT_DIA), - volumetric_multiplier[EXTRUDERS] = ARRAY_BY_EXTRUDERS1(1.0); + volumetric_enabled; +float filament_size[EXTRUDERS], volumetric_multiplier[EXTRUDERS]; #if HAS_WORKSPACE_OFFSET #if HAS_POSITION_SHIFT @@ -513,7 +507,7 @@ static millis_t stepper_inactive_time = (DEFAULT_STEPPER_DEACTIVE_TIME) * 1000UL static uint8_t target_extruder; #if HAS_BED_PROBE - float zprobe_zoffset = Z_PROBE_OFFSET_FROM_EXTRUDER; + float zprobe_zoffset; // Initialized by settings.load() #endif #if HAS_ABL @@ -542,18 +536,12 @@ static uint8_t target_extruder; #endif #if ENABLED(Z_DUAL_ENDSTOPS) - float z_endstop_adj = - #ifdef Z_DUAL_ENDSTOPS_ADJUSTMENT - Z_DUAL_ENDSTOPS_ADJUSTMENT - #else - 0 - #endif - ; + float z_endstop_adj; #endif // Extruder offsets #if HOTENDS > 1 - float hotend_offset[XYZ][HOTENDS]; + float hotend_offset[XYZ][HOTENDS]; // Initialized by settings.load() #endif #if HAS_Z_SERVO_ENDSTOP @@ -596,8 +584,7 @@ static uint8_t target_extruder; float delta[ABC], endstop_adj[ABC] = { 0 }; - // These values are loaded or reset at boot time when setup() calls - // settings.load(), which calls recalc_delta_settings(). + // Initialized by settings.load() float delta_radius, delta_tower_angle_trim[2], delta_tower[ABC][2], diff --git a/Marlin/endstops.cpp b/Marlin/endstops.cpp index 1d98ec9d4..32541b675 100644 --- a/Marlin/endstops.cpp +++ b/Marlin/endstops.cpp @@ -38,14 +38,7 @@ Endstops endstops; // public: -bool Endstops::enabled = true, - Endstops::enabled_globally = - #if ENABLED(ENDSTOPS_ALWAYS_ON_DEFAULT) - (true) - #else - (false) - #endif - ; +bool Endstops::enabled, Endstops::enabled_globally; // Initialized by settings.load() volatile char Endstops::endstop_hit_bits; // use X_MIN, Y_MIN, Z_MIN and Z_MIN_PROBE as BIT value #if ENABLED(Z_DUAL_ENDSTOPS) diff --git a/Marlin/planner.cpp b/Marlin/planner.cpp index c84ce9bae..349e8affd 100644 --- a/Marlin/planner.cpp +++ b/Marlin/planner.cpp @@ -95,6 +95,8 @@ 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; + +// Initialized by settings.load() 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 @@ -111,7 +113,7 @@ float Planner::min_feedrate_mm_s, #endif #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) - float Planner::z_fade_height, + float Planner::z_fade_height, // Initialized by settings.load() Planner::inverse_z_fade_height; #endif @@ -143,8 +145,8 @@ float Planner::previous_speed[NUM_AXIS], #endif #if ENABLED(LIN_ADVANCE) - float Planner::extruder_advance_k = LIN_ADVANCE_K, - Planner::advance_ed_ratio = LIN_ADVANCE_E_D_RATIO, + float Planner::extruder_advance_k, // Initialized by settings.load() + Planner::advance_ed_ratio, // Initialized by settings.load() Planner::position_float[NUM_AXIS] = { 0 }; #endif diff --git a/Marlin/stepper.cpp b/Marlin/stepper.cpp index 9493cedf1..600bc3925 100644 --- a/Marlin/stepper.cpp +++ b/Marlin/stepper.cpp @@ -77,7 +77,7 @@ block_t* Stepper::current_block = NULL; // A pointer to the block currently bei #endif #if HAS_MOTOR_CURRENT_PWM - uint32_t Stepper::motor_current_setting[3] = PWM_MOTOR_CURRENT; + uint32_t Stepper::motor_current_setting[3]; // Initialized by settings.load() #endif // private: diff --git a/Marlin/temperature.cpp b/Marlin/temperature.cpp index deaa79ce8..bf757cef6 100644 --- a/Marlin/temperature.cpp +++ b/Marlin/temperature.cpp @@ -73,28 +73,24 @@ int16_t Temperature::current_temperature_raw[HOTENDS] = { 0 }, int16_t Temperature::target_temperature_bed = 0; #endif +// Initialized by settings.load() #if ENABLED(PIDTEMP) #if ENABLED(PID_PARAMS_PER_HOTEND) && HOTENDS > 1 - float Temperature::Kp[HOTENDS] = ARRAY_BY_HOTENDS1(DEFAULT_Kp), - Temperature::Ki[HOTENDS] = ARRAY_BY_HOTENDS1((DEFAULT_Ki) * (PID_dT)), - Temperature::Kd[HOTENDS] = ARRAY_BY_HOTENDS1((DEFAULT_Kd) / (PID_dT)); + float Temperature::Kp[HOTENDS], Temperature::Ki[HOTENDS], Temperature::Kd[HOTENDS]; #if ENABLED(PID_EXTRUSION_SCALING) - float Temperature::Kc[HOTENDS] = ARRAY_BY_HOTENDS1(DEFAULT_Kc); + float Temperature::Kc[HOTENDS]; #endif #else - float Temperature::Kp = DEFAULT_Kp, - Temperature::Ki = (DEFAULT_Ki) * (PID_dT), - Temperature::Kd = (DEFAULT_Kd) / (PID_dT); + float Temperature::Kp, Temperature::Ki, Temperature::Kd; #if ENABLED(PID_EXTRUSION_SCALING) - float Temperature::Kc = DEFAULT_Kc; + float Temperature::Kc; #endif #endif #endif +// Initialized by settings.load() #if ENABLED(PIDTEMPBED) - float Temperature::bedKp = DEFAULT_bedKp, - Temperature::bedKi = ((DEFAULT_bedKi) * PID_dT), - Temperature::bedKd = ((DEFAULT_bedKd) / PID_dT); + float Temperature::bedKp, Temperature::bedKi, Temperature::bedKd; #endif #if ENABLED(BABYSTEPPING) diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index d32dd6044..2acfd3d33 100644 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -49,6 +49,7 @@ bool ubl_lcd_map_control = false; #endif +// Initialized by settings.load() int16_t lcd_preheat_hotend_temp[2], lcd_preheat_bed_temp[2], lcd_preheat_fan_speed[2]; #if ENABLED(FILAMENT_LCD_DISPLAY) && ENABLED(SDSUPPORT) diff --git a/Marlin/ultralcd_impl_DOGM.h b/Marlin/ultralcd_impl_DOGM.h index 991183c2d..3cbced445 100644 --- a/Marlin/ultralcd_impl_DOGM.h +++ b/Marlin/ultralcd_impl_DOGM.h @@ -202,7 +202,7 @@ #include "utf_mapper.h" -uint16_t lcd_contrast; +uint16_t lcd_contrast; // Initialized by settings.load() static char currentfont = 0; // The current graphical page being rendered From 8a3bc6be4de6dca2664f6e977315693a6f842a4c Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 17 Jul 2017 15:37:36 -0500 Subject: [PATCH 030/112] Improve FWRETRACT config options and commentary Add more details as requested in #7198 --- Marlin/Configuration_adv.h | 40 ++++++++++++------- .../AlephObjects/TAZ4/Configuration_adv.h | 40 ++++++++++++------- .../Anet/A6/Configuration_adv.h | 40 ++++++++++++------- .../Anet/A8/Configuration_adv.h | 40 ++++++++++++------- .../BQ/Hephestos/Configuration_adv.h | 40 ++++++++++++------- .../BQ/Hephestos_2/Configuration_adv.h | 40 ++++++++++++------- .../BQ/WITBOX/Configuration_adv.h | 40 ++++++++++++------- .../Cartesio/Configuration_adv.h | 40 ++++++++++++------- .../Felix/Configuration_adv.h | 40 ++++++++++++------- .../Folger Tech/i3-2020/Configuration_adv.h | 40 ++++++++++++------- .../Infitary/i3-M508/Configuration_adv.h | 40 ++++++++++++------- .../Malyan/M150/Configuration_adv.h | 40 ++++++++++++------- .../RigidBot/Configuration_adv.h | 40 ++++++++++++------- .../SCARA/Configuration_adv.h | 40 ++++++++++++------- .../TinyBoy2/Configuration_adv.h | 40 ++++++++++++------- .../Velleman/K8200/Configuration_adv.h | 40 ++++++++++++------- .../Velleman/K8400/Configuration_adv.h | 40 ++++++++++++------- .../FLSUN/auto_calibrate/Configuration_adv.h | 40 ++++++++++++------- .../FLSUN/kossel_mini/Configuration_adv.h | 40 ++++++++++++------- .../delta/generic/Configuration_adv.h | 40 ++++++++++++------- .../delta/kossel_mini/Configuration_adv.h | 40 ++++++++++++------- .../delta/kossel_pro/Configuration_adv.h | 40 ++++++++++++------- .../delta/kossel_xl/Configuration_adv.h | 40 ++++++++++++------- .../gCreate/gMax1.5+/Configuration_adv.h | 40 ++++++++++++------- .../makibox/Configuration_adv.h | 40 ++++++++++++------- .../tvrrug/Round2/Configuration_adv.h | 40 ++++++++++++------- .../wt150/Configuration_adv.h | 40 ++++++++++++------- 27 files changed, 675 insertions(+), 405 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 57c371613..95a690d1f 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -757,22 +757,32 @@ // @section fwretract -// Firmware based and LCD controlled retract -// M207 and M208 can be used to define parameters for the retraction. -// The retraction can be called by the slicer using G10 and G11 -// until then, intended retractions can be detected by moves that only extrude and the direction. -// the moves are than replaced by the firmware controlled ones. - -//#define FWRETRACT //ONLY PARTIALLY TESTED +/** + * Firmware-based and LCD-controlled retract + * + * Add G10 / G11 commands for automatic firmware-based retract / recover. + * Use M207 and M208 to define parameters for retract / recover. + * + * Use M209 to enable or disable auto-retract. + * With auto-retract enabled, all G1 E moves over the MIN_RETRACT length + * will be converted to firmware-based retract/recover moves. + * + * Be sure to turn off auto-retract during filament change. + * + * Note that M207 / M208 / M209 settings are saved to EEPROM. + * + */ +//#define FWRETRACT // ONLY PARTIALLY TESTED #if ENABLED(FWRETRACT) - #define MIN_RETRACT 0.1 //minimum extruded mm to accept a automatic gcode retraction attempt - #define RETRACT_LENGTH 3 //default retract length (positive mm) - #define RETRACT_LENGTH_SWAP 13 //default swap retract length (positive mm), for extruder change - #define RETRACT_FEEDRATE 45 //default feedrate for retracting (mm/s) - #define RETRACT_ZLIFT 0 //default retract Z-lift - #define RETRACT_RECOVER_LENGTH 0 //default additional recover length (mm, added to retract length when recovering) - #define RETRACT_RECOVER_LENGTH_SWAP 0 //default additional swap recover length (mm, added to retract length when recovering from extruder change) - #define RETRACT_RECOVER_FEEDRATE 8 //default feedrate for recovering from retraction (mm/s) + #define MIN_RETRACT 0.1 // A retract/recover of this length or longer can be converted to auto-retract + #define RETRACT_LENGTH 3 // Default retract length (positive mm) + #define RETRACT_LENGTH_SWAP 13 // Default swap retract length (positive mm), for extruder change + #define RETRACT_FEEDRATE 45 // Default feedrate for retracting (mm/s) + #define RETRACT_ZLIFT 0 // Default retract Z-lift + #define RETRACT_RECOVER_LENGTH 0 // Default additional recover length (mm, added to retract length when recovering) + #define RETRACT_RECOVER_LENGTH_SWAP 0 // Default additional swap recover length (mm, added to retract length when recovering from extruder change) + #define RETRACT_RECOVER_FEEDRATE 8 // Default feedrate for recovering from retraction (mm/s) + #define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s) #endif /** diff --git a/Marlin/example_configurations/AlephObjects/TAZ4/Configuration_adv.h b/Marlin/example_configurations/AlephObjects/TAZ4/Configuration_adv.h index 6800a96bc..98f833393 100644 --- a/Marlin/example_configurations/AlephObjects/TAZ4/Configuration_adv.h +++ b/Marlin/example_configurations/AlephObjects/TAZ4/Configuration_adv.h @@ -750,22 +750,32 @@ // @section fwretract -// Firmware based and LCD controlled retract -// M207 and M208 can be used to define parameters for the retraction. -// The retraction can be called by the slicer using G10 and G11 -// until then, intended retractions can be detected by moves that only extrude and the direction. -// the moves are than replaced by the firmware controlled ones. - -//#define FWRETRACT //ONLY PARTIALLY TESTED +/** + * Firmware-based and LCD-controlled retract + * + * Add G10 / G11 commands for automatic firmware-based retract / recover. + * Use M207 and M208 to define parameters for retract / recover. + * + * Use M209 to enable or disable auto-retract. + * With auto-retract enabled, all G1 E moves over the MIN_RETRACT length + * will be converted to firmware-based retract/recover moves. + * + * Be sure to turn off auto-retract during filament change. + * + * Note that M207 / M208 / M209 settings are saved to EEPROM. + * + */ +//#define FWRETRACT // ONLY PARTIALLY TESTED #if ENABLED(FWRETRACT) - #define MIN_RETRACT 0.1 //minimum extruded mm to accept a automatic gcode retraction attempt - #define RETRACT_LENGTH 3 //default retract length (positive mm) - #define RETRACT_LENGTH_SWAP 13 //default swap retract length (positive mm), for extruder change - #define RETRACT_FEEDRATE 45 //default feedrate for retracting (mm/s) - #define RETRACT_ZLIFT 0 //default retract Z-lift - #define RETRACT_RECOVER_LENGTH 0 //default additional recover length (mm, added to retract length when recovering) - #define RETRACT_RECOVER_LENGTH_SWAP 0 //default additional swap recover length (mm, added to retract length when recovering from extruder change) - #define RETRACT_RECOVER_FEEDRATE 8 //default feedrate for recovering from retraction (mm/s) + #define MIN_RETRACT 0.1 // A retract/recover of this length or longer can be converted to auto-retract + #define RETRACT_LENGTH 3 // Default retract length (positive mm) + #define RETRACT_LENGTH_SWAP 13 // Default swap retract length (positive mm), for extruder change + #define RETRACT_FEEDRATE 45 // Default feedrate for retracting (mm/s) + #define RETRACT_ZLIFT 0 // Default retract Z-lift + #define RETRACT_RECOVER_LENGTH 0 // Default additional recover length (mm, added to retract length when recovering) + #define RETRACT_RECOVER_LENGTH_SWAP 0 // Default additional swap recover length (mm, added to retract length when recovering from extruder change) + #define RETRACT_RECOVER_FEEDRATE 8 // Default feedrate for recovering from retraction (mm/s) + #define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s) #endif /** diff --git a/Marlin/example_configurations/Anet/A6/Configuration_adv.h b/Marlin/example_configurations/Anet/A6/Configuration_adv.h index ea27f9331..e233b6ba1 100644 --- a/Marlin/example_configurations/Anet/A6/Configuration_adv.h +++ b/Marlin/example_configurations/Anet/A6/Configuration_adv.h @@ -757,22 +757,32 @@ // @section fwretract -// Firmware based and LCD controlled retract -// M207 and M208 can be used to define parameters for the retraction. -// The retraction can be called by the slicer using G10 and G11 -// until then, intended retractions can be detected by moves that only extrude and the direction. -// the moves are than replaced by the firmware controlled ones. - -//#define FWRETRACT //ONLY PARTIALLY TESTED +/** + * Firmware-based and LCD-controlled retract + * + * Add G10 / G11 commands for automatic firmware-based retract / recover. + * Use M207 and M208 to define parameters for retract / recover. + * + * Use M209 to enable or disable auto-retract. + * With auto-retract enabled, all G1 E moves over the MIN_RETRACT length + * will be converted to firmware-based retract/recover moves. + * + * Be sure to turn off auto-retract during filament change. + * + * Note that M207 / M208 / M209 settings are saved to EEPROM. + * + */ +//#define FWRETRACT // ONLY PARTIALLY TESTED #if ENABLED(FWRETRACT) - #define MIN_RETRACT 0.1 //minimum extruded mm to accept a automatic gcode retraction attempt - #define RETRACT_LENGTH 3 //default retract length (positive mm) - #define RETRACT_LENGTH_SWAP 13 //default swap retract length (positive mm), for extruder change - #define RETRACT_FEEDRATE 45 //default feedrate for retracting (mm/s) - #define RETRACT_ZLIFT 0 //default retract Z-lift - #define RETRACT_RECOVER_LENGTH 0 //default additional recover length (mm, added to retract length when recovering) - #define RETRACT_RECOVER_LENGTH_SWAP 0 //default additional swap recover length (mm, added to retract length when recovering from extruder change) - #define RETRACT_RECOVER_FEEDRATE 8 //default feedrate for recovering from retraction (mm/s) + #define MIN_RETRACT 0.1 // A retract/recover of this length or longer can be converted to auto-retract + #define RETRACT_LENGTH 3 // Default retract length (positive mm) + #define RETRACT_LENGTH_SWAP 13 // Default swap retract length (positive mm), for extruder change + #define RETRACT_FEEDRATE 45 // Default feedrate for retracting (mm/s) + #define RETRACT_ZLIFT 0 // Default retract Z-lift + #define RETRACT_RECOVER_LENGTH 0 // Default additional recover length (mm, added to retract length when recovering) + #define RETRACT_RECOVER_LENGTH_SWAP 0 // Default additional swap recover length (mm, added to retract length when recovering from extruder change) + #define RETRACT_RECOVER_FEEDRATE 8 // Default feedrate for recovering from retraction (mm/s) + #define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s) #endif /** diff --git a/Marlin/example_configurations/Anet/A8/Configuration_adv.h b/Marlin/example_configurations/Anet/A8/Configuration_adv.h index c264b17be..eac7964ae 100644 --- a/Marlin/example_configurations/Anet/A8/Configuration_adv.h +++ b/Marlin/example_configurations/Anet/A8/Configuration_adv.h @@ -757,22 +757,32 @@ // @section fwretract -// Firmware based and LCD controlled retract -// M207 and M208 can be used to define parameters for the retraction. -// The retraction can be called by the slicer using G10 and G11 -// until then, intended retractions can be detected by moves that only extrude and the direction. -// the moves are than replaced by the firmware controlled ones. - -//#define FWRETRACT //ONLY PARTIALLY TESTED +/** + * Firmware-based and LCD-controlled retract + * + * Add G10 / G11 commands for automatic firmware-based retract / recover. + * Use M207 and M208 to define parameters for retract / recover. + * + * Use M209 to enable or disable auto-retract. + * With auto-retract enabled, all G1 E moves over the MIN_RETRACT length + * will be converted to firmware-based retract/recover moves. + * + * Be sure to turn off auto-retract during filament change. + * + * Note that M207 / M208 / M209 settings are saved to EEPROM. + * + */ +//#define FWRETRACT // ONLY PARTIALLY TESTED #if ENABLED(FWRETRACT) - #define MIN_RETRACT 0.1 //minimum extruded mm to accept a automatic gcode retraction attempt - #define RETRACT_LENGTH 3 //default retract length (positive mm) - #define RETRACT_LENGTH_SWAP 13 //default swap retract length (positive mm), for extruder change - #define RETRACT_FEEDRATE 45 //default feedrate for retracting (mm/s) - #define RETRACT_ZLIFT 0 //default retract Z-lift - #define RETRACT_RECOVER_LENGTH 0 //default additional recover length (mm, added to retract length when recovering) - #define RETRACT_RECOVER_LENGTH_SWAP 0 //default additional swap recover length (mm, added to retract length when recovering from extruder change) - #define RETRACT_RECOVER_FEEDRATE 8 //default feedrate for recovering from retraction (mm/s) + #define MIN_RETRACT 0.1 // A retract/recover of this length or longer can be converted to auto-retract + #define RETRACT_LENGTH 3 // Default retract length (positive mm) + #define RETRACT_LENGTH_SWAP 13 // Default swap retract length (positive mm), for extruder change + #define RETRACT_FEEDRATE 45 // Default feedrate for retracting (mm/s) + #define RETRACT_ZLIFT 0 // Default retract Z-lift + #define RETRACT_RECOVER_LENGTH 0 // Default additional recover length (mm, added to retract length when recovering) + #define RETRACT_RECOVER_LENGTH_SWAP 0 // Default additional swap recover length (mm, added to retract length when recovering from extruder change) + #define RETRACT_RECOVER_FEEDRATE 8 // Default feedrate for recovering from retraction (mm/s) + #define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s) #endif /** diff --git a/Marlin/example_configurations/BQ/Hephestos/Configuration_adv.h b/Marlin/example_configurations/BQ/Hephestos/Configuration_adv.h index 89f30b1fe..a9d32e272 100644 --- a/Marlin/example_configurations/BQ/Hephestos/Configuration_adv.h +++ b/Marlin/example_configurations/BQ/Hephestos/Configuration_adv.h @@ -750,22 +750,32 @@ // @section fwretract -// Firmware based and LCD controlled retract -// M207 and M208 can be used to define parameters for the retraction. -// The retraction can be called by the slicer using G10 and G11 -// until then, intended retractions can be detected by moves that only extrude and the direction. -// the moves are than replaced by the firmware controlled ones. - -//#define FWRETRACT //ONLY PARTIALLY TESTED +/** + * Firmware-based and LCD-controlled retract + * + * Add G10 / G11 commands for automatic firmware-based retract / recover. + * Use M207 and M208 to define parameters for retract / recover. + * + * Use M209 to enable or disable auto-retract. + * With auto-retract enabled, all G1 E moves over the MIN_RETRACT length + * will be converted to firmware-based retract/recover moves. + * + * Be sure to turn off auto-retract during filament change. + * + * Note that M207 / M208 / M209 settings are saved to EEPROM. + * + */ +//#define FWRETRACT // ONLY PARTIALLY TESTED #if ENABLED(FWRETRACT) - #define MIN_RETRACT 0.1 //minimum extruded mm to accept a automatic gcode retraction attempt - #define RETRACT_LENGTH 3 //default retract length (positive mm) - #define RETRACT_LENGTH_SWAP 13 //default swap retract length (positive mm), for extruder change - #define RETRACT_FEEDRATE 80 //default feedrate for retracting (mm/s) - #define RETRACT_ZLIFT 0 //default retract Z-lift - #define RETRACT_RECOVER_LENGTH 0 //default additional recover length (mm, added to retract length when recovering) - //#define RETRACT_RECOVER_LENGTH_SWAP 0 //default additional swap recover length (mm, added to retract length when recovering from extruder change) - #define RETRACT_RECOVER_FEEDRATE 8 //default feedrate for recovering from retraction (mm/s) + #define MIN_RETRACT 0.1 // A retract/recover of this length or longer can be converted to auto-retract + #define RETRACT_LENGTH 3 // Default retract length (positive mm) + #define RETRACT_LENGTH_SWAP 13 // Default swap retract length (positive mm), for extruder change + #define RETRACT_FEEDRATE 45 // Default feedrate for retracting (mm/s) + #define RETRACT_ZLIFT 0 // Default retract Z-lift + #define RETRACT_RECOVER_LENGTH 0 // Default additional recover length (mm, added to retract length when recovering) + #define RETRACT_RECOVER_LENGTH_SWAP 0 // Default additional swap recover length (mm, added to retract length when recovering from extruder change) + #define RETRACT_RECOVER_FEEDRATE 8 // Default feedrate for recovering from retraction (mm/s) + #define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s) #endif /** diff --git a/Marlin/example_configurations/BQ/Hephestos_2/Configuration_adv.h b/Marlin/example_configurations/BQ/Hephestos_2/Configuration_adv.h index 7748bbf3c..63a738603 100644 --- a/Marlin/example_configurations/BQ/Hephestos_2/Configuration_adv.h +++ b/Marlin/example_configurations/BQ/Hephestos_2/Configuration_adv.h @@ -733,22 +733,32 @@ // @section fwretract -// Firmware based and LCD controlled retract -// M207 and M208 can be used to define parameters for the retraction. -// The retraction can be called by the slicer using G10 and G11 -// until then, intended retractions can be detected by moves that only extrude and the direction. -// the moves are than replaced by the firmware controlled ones. - -//#define FWRETRACT //ONLY PARTIALLY TESTED +/** + * Firmware-based and LCD-controlled retract + * + * Add G10 / G11 commands for automatic firmware-based retract / recover. + * Use M207 and M208 to define parameters for retract / recover. + * + * Use M209 to enable or disable auto-retract. + * With auto-retract enabled, all G1 E moves over the MIN_RETRACT length + * will be converted to firmware-based retract/recover moves. + * + * Be sure to turn off auto-retract during filament change. + * + * Note that M207 / M208 / M209 settings are saved to EEPROM. + * + */ +//#define FWRETRACT // ONLY PARTIALLY TESTED #if ENABLED(FWRETRACT) - #define MIN_RETRACT 0.1 //minimum extruded mm to accept a automatic gcode retraction attempt - #define RETRACT_LENGTH 3 //default retract length (positive mm) - #define RETRACT_LENGTH_SWAP 13 //default swap retract length (positive mm), for extruder change - #define RETRACT_FEEDRATE 45 //default feedrate for retracting (mm/s) - #define RETRACT_ZLIFT 0 //default retract Z-lift - #define RETRACT_RECOVER_LENGTH 0 //default additional recover length (mm, added to retract length when recovering) - #define RETRACT_RECOVER_LENGTH_SWAP 0 //default additional swap recover length (mm, added to retract length when recovering from extruder change) - #define RETRACT_RECOVER_FEEDRATE 8 //default feedrate for recovering from retraction (mm/s) + #define MIN_RETRACT 0.1 // A retract/recover of this length or longer can be converted to auto-retract + #define RETRACT_LENGTH 3 // Default retract length (positive mm) + #define RETRACT_LENGTH_SWAP 13 // Default swap retract length (positive mm), for extruder change + #define RETRACT_FEEDRATE 45 // Default feedrate for retracting (mm/s) + #define RETRACT_ZLIFT 0 // Default retract Z-lift + #define RETRACT_RECOVER_LENGTH 0 // Default additional recover length (mm, added to retract length when recovering) + #define RETRACT_RECOVER_LENGTH_SWAP 0 // Default additional swap recover length (mm, added to retract length when recovering from extruder change) + #define RETRACT_RECOVER_FEEDRATE 8 // Default feedrate for recovering from retraction (mm/s) + #define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s) #endif /** diff --git a/Marlin/example_configurations/BQ/WITBOX/Configuration_adv.h b/Marlin/example_configurations/BQ/WITBOX/Configuration_adv.h index 89f30b1fe..a9d32e272 100644 --- a/Marlin/example_configurations/BQ/WITBOX/Configuration_adv.h +++ b/Marlin/example_configurations/BQ/WITBOX/Configuration_adv.h @@ -750,22 +750,32 @@ // @section fwretract -// Firmware based and LCD controlled retract -// M207 and M208 can be used to define parameters for the retraction. -// The retraction can be called by the slicer using G10 and G11 -// until then, intended retractions can be detected by moves that only extrude and the direction. -// the moves are than replaced by the firmware controlled ones. - -//#define FWRETRACT //ONLY PARTIALLY TESTED +/** + * Firmware-based and LCD-controlled retract + * + * Add G10 / G11 commands for automatic firmware-based retract / recover. + * Use M207 and M208 to define parameters for retract / recover. + * + * Use M209 to enable or disable auto-retract. + * With auto-retract enabled, all G1 E moves over the MIN_RETRACT length + * will be converted to firmware-based retract/recover moves. + * + * Be sure to turn off auto-retract during filament change. + * + * Note that M207 / M208 / M209 settings are saved to EEPROM. + * + */ +//#define FWRETRACT // ONLY PARTIALLY TESTED #if ENABLED(FWRETRACT) - #define MIN_RETRACT 0.1 //minimum extruded mm to accept a automatic gcode retraction attempt - #define RETRACT_LENGTH 3 //default retract length (positive mm) - #define RETRACT_LENGTH_SWAP 13 //default swap retract length (positive mm), for extruder change - #define RETRACT_FEEDRATE 80 //default feedrate for retracting (mm/s) - #define RETRACT_ZLIFT 0 //default retract Z-lift - #define RETRACT_RECOVER_LENGTH 0 //default additional recover length (mm, added to retract length when recovering) - //#define RETRACT_RECOVER_LENGTH_SWAP 0 //default additional swap recover length (mm, added to retract length when recovering from extruder change) - #define RETRACT_RECOVER_FEEDRATE 8 //default feedrate for recovering from retraction (mm/s) + #define MIN_RETRACT 0.1 // A retract/recover of this length or longer can be converted to auto-retract + #define RETRACT_LENGTH 3 // Default retract length (positive mm) + #define RETRACT_LENGTH_SWAP 13 // Default swap retract length (positive mm), for extruder change + #define RETRACT_FEEDRATE 45 // Default feedrate for retracting (mm/s) + #define RETRACT_ZLIFT 0 // Default retract Z-lift + #define RETRACT_RECOVER_LENGTH 0 // Default additional recover length (mm, added to retract length when recovering) + #define RETRACT_RECOVER_LENGTH_SWAP 0 // Default additional swap recover length (mm, added to retract length when recovering from extruder change) + #define RETRACT_RECOVER_FEEDRATE 8 // Default feedrate for recovering from retraction (mm/s) + #define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s) #endif /** diff --git a/Marlin/example_configurations/Cartesio/Configuration_adv.h b/Marlin/example_configurations/Cartesio/Configuration_adv.h index f71292cbd..0da151cb3 100644 --- a/Marlin/example_configurations/Cartesio/Configuration_adv.h +++ b/Marlin/example_configurations/Cartesio/Configuration_adv.h @@ -750,22 +750,32 @@ // @section fwretract -// Firmware based and LCD controlled retract -// M207 and M208 can be used to define parameters for the retraction. -// The retraction can be called by the slicer using G10 and G11 -// until then, intended retractions can be detected by moves that only extrude and the direction. -// the moves are than replaced by the firmware controlled ones. - -//#define FWRETRACT //ONLY PARTIALLY TESTED +/** + * Firmware-based and LCD-controlled retract + * + * Add G10 / G11 commands for automatic firmware-based retract / recover. + * Use M207 and M208 to define parameters for retract / recover. + * + * Use M209 to enable or disable auto-retract. + * With auto-retract enabled, all G1 E moves over the MIN_RETRACT length + * will be converted to firmware-based retract/recover moves. + * + * Be sure to turn off auto-retract during filament change. + * + * Note that M207 / M208 / M209 settings are saved to EEPROM. + * + */ +//#define FWRETRACT // ONLY PARTIALLY TESTED #if ENABLED(FWRETRACT) - #define MIN_RETRACT 0.1 //minimum extruded mm to accept a automatic gcode retraction attempt - #define RETRACT_LENGTH 3 //default retract length (positive mm) - #define RETRACT_LENGTH_SWAP 13 //default swap retract length (positive mm), for extruder change - #define RETRACT_FEEDRATE 45 //default feedrate for retracting (mm/s) - #define RETRACT_ZLIFT 0 //default retract Z-lift - #define RETRACT_RECOVER_LENGTH 0 //default additional recover length (mm, added to retract length when recovering) - #define RETRACT_RECOVER_LENGTH_SWAP 0 //default additional swap recover length (mm, added to retract length when recovering from extruder change) - #define RETRACT_RECOVER_FEEDRATE 8 //default feedrate for recovering from retraction (mm/s) + #define MIN_RETRACT 0.1 // A retract/recover of this length or longer can be converted to auto-retract + #define RETRACT_LENGTH 3 // Default retract length (positive mm) + #define RETRACT_LENGTH_SWAP 13 // Default swap retract length (positive mm), for extruder change + #define RETRACT_FEEDRATE 45 // Default feedrate for retracting (mm/s) + #define RETRACT_ZLIFT 0 // Default retract Z-lift + #define RETRACT_RECOVER_LENGTH 0 // Default additional recover length (mm, added to retract length when recovering) + #define RETRACT_RECOVER_LENGTH_SWAP 0 // Default additional swap recover length (mm, added to retract length when recovering from extruder change) + #define RETRACT_RECOVER_FEEDRATE 8 // Default feedrate for recovering from retraction (mm/s) + #define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s) #endif /** diff --git a/Marlin/example_configurations/Felix/Configuration_adv.h b/Marlin/example_configurations/Felix/Configuration_adv.h index 94fcbf30b..c72719ec0 100644 --- a/Marlin/example_configurations/Felix/Configuration_adv.h +++ b/Marlin/example_configurations/Felix/Configuration_adv.h @@ -750,22 +750,32 @@ // @section fwretract -// Firmware based and LCD controlled retract -// M207 and M208 can be used to define parameters for the retraction. -// The retraction can be called by the slicer using G10 and G11 -// until then, intended retractions can be detected by moves that only extrude and the direction. -// the moves are than replaced by the firmware controlled ones. - -//#define FWRETRACT //ONLY PARTIALLY TESTED +/** + * Firmware-based and LCD-controlled retract + * + * Add G10 / G11 commands for automatic firmware-based retract / recover. + * Use M207 and M208 to define parameters for retract / recover. + * + * Use M209 to enable or disable auto-retract. + * With auto-retract enabled, all G1 E moves over the MIN_RETRACT length + * will be converted to firmware-based retract/recover moves. + * + * Be sure to turn off auto-retract during filament change. + * + * Note that M207 / M208 / M209 settings are saved to EEPROM. + * + */ +//#define FWRETRACT // ONLY PARTIALLY TESTED #if ENABLED(FWRETRACT) - #define MIN_RETRACT 0.1 //minimum extruded mm to accept a automatic gcode retraction attempt - #define RETRACT_LENGTH 3 //default retract length (positive mm) - #define RETRACT_LENGTH_SWAP 13 //default swap retract length (positive mm), for extruder change - #define RETRACT_FEEDRATE 45 //default feedrate for retracting (mm/s) - #define RETRACT_ZLIFT 0 //default retract Z-lift - #define RETRACT_RECOVER_LENGTH 0 //default additional recover length (mm, added to retract length when recovering) - #define RETRACT_RECOVER_LENGTH_SWAP 0 //default additional swap recover length (mm, added to retract length when recovering from extruder change) - #define RETRACT_RECOVER_FEEDRATE 8 //default feedrate for recovering from retraction (mm/s) + #define MIN_RETRACT 0.1 // A retract/recover of this length or longer can be converted to auto-retract + #define RETRACT_LENGTH 3 // Default retract length (positive mm) + #define RETRACT_LENGTH_SWAP 13 // Default swap retract length (positive mm), for extruder change + #define RETRACT_FEEDRATE 45 // Default feedrate for retracting (mm/s) + #define RETRACT_ZLIFT 0 // Default retract Z-lift + #define RETRACT_RECOVER_LENGTH 0 // Default additional recover length (mm, added to retract length when recovering) + #define RETRACT_RECOVER_LENGTH_SWAP 0 // Default additional swap recover length (mm, added to retract length when recovering from extruder change) + #define RETRACT_RECOVER_FEEDRATE 8 // Default feedrate for recovering from retraction (mm/s) + #define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s) #endif /** diff --git a/Marlin/example_configurations/Folger Tech/i3-2020/Configuration_adv.h b/Marlin/example_configurations/Folger Tech/i3-2020/Configuration_adv.h index 4b3fb3568..f7408a373 100644 --- a/Marlin/example_configurations/Folger Tech/i3-2020/Configuration_adv.h +++ b/Marlin/example_configurations/Folger Tech/i3-2020/Configuration_adv.h @@ -757,22 +757,32 @@ // @section fwretract -// Firmware based and LCD controlled retract -// M207 and M208 can be used to define parameters for the retraction. -// The retraction can be called by the slicer using G10 and G11 -// until then, intended retractions can be detected by moves that only extrude and the direction. -// the moves are than replaced by the firmware controlled ones. - -//#define FWRETRACT //ONLY PARTIALLY TESTED +/** + * Firmware-based and LCD-controlled retract + * + * Add G10 / G11 commands for automatic firmware-based retract / recover. + * Use M207 and M208 to define parameters for retract / recover. + * + * Use M209 to enable or disable auto-retract. + * With auto-retract enabled, all G1 E moves over the MIN_RETRACT length + * will be converted to firmware-based retract/recover moves. + * + * Be sure to turn off auto-retract during filament change. + * + * Note that M207 / M208 / M209 settings are saved to EEPROM. + * + */ +//#define FWRETRACT // ONLY PARTIALLY TESTED #if ENABLED(FWRETRACT) - #define MIN_RETRACT 0.1 //minimum extruded mm to accept a automatic gcode retraction attempt - #define RETRACT_LENGTH 3 //default retract length (positive mm) - #define RETRACT_LENGTH_SWAP 13 //default swap retract length (positive mm), for extruder change - #define RETRACT_FEEDRATE 45 //default feedrate for retracting (mm/s) - #define RETRACT_ZLIFT 0 //default retract Z-lift - #define RETRACT_RECOVER_LENGTH 0 //default additional recover length (mm, added to retract length when recovering) - #define RETRACT_RECOVER_LENGTH_SWAP 0 //default additional swap recover length (mm, added to retract length when recovering from extruder change) - #define RETRACT_RECOVER_FEEDRATE 8 //default feedrate for recovering from retraction (mm/s) + #define MIN_RETRACT 0.1 // A retract/recover of this length or longer can be converted to auto-retract + #define RETRACT_LENGTH 3 // Default retract length (positive mm) + #define RETRACT_LENGTH_SWAP 13 // Default swap retract length (positive mm), for extruder change + #define RETRACT_FEEDRATE 45 // Default feedrate for retracting (mm/s) + #define RETRACT_ZLIFT 0 // Default retract Z-lift + #define RETRACT_RECOVER_LENGTH 0 // Default additional recover length (mm, added to retract length when recovering) + #define RETRACT_RECOVER_LENGTH_SWAP 0 // Default additional swap recover length (mm, added to retract length when recovering from extruder change) + #define RETRACT_RECOVER_FEEDRATE 8 // Default feedrate for recovering from retraction (mm/s) + #define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s) #endif /** diff --git a/Marlin/example_configurations/Infitary/i3-M508/Configuration_adv.h b/Marlin/example_configurations/Infitary/i3-M508/Configuration_adv.h index 373783338..92a1eb1b5 100644 --- a/Marlin/example_configurations/Infitary/i3-M508/Configuration_adv.h +++ b/Marlin/example_configurations/Infitary/i3-M508/Configuration_adv.h @@ -747,22 +747,32 @@ // @section fwretract -// Firmware based and LCD controlled retract -// M207 and M208 can be used to define parameters for the retraction. -// The retraction can be called by the slicer using G10 and G11 -// until then, intended retractions can be detected by moves that only extrude and the direction. -// the moves are than replaced by the firmware controlled ones. - -//#define FWRETRACT //ONLY PARTIALLY TESTED +/** + * Firmware-based and LCD-controlled retract + * + * Add G10 / G11 commands for automatic firmware-based retract / recover. + * Use M207 and M208 to define parameters for retract / recover. + * + * Use M209 to enable or disable auto-retract. + * With auto-retract enabled, all G1 E moves over the MIN_RETRACT length + * will be converted to firmware-based retract/recover moves. + * + * Be sure to turn off auto-retract during filament change. + * + * Note that M207 / M208 / M209 settings are saved to EEPROM. + * + */ +//#define FWRETRACT // ONLY PARTIALLY TESTED #if ENABLED(FWRETRACT) - #define MIN_RETRACT 0.1 //minimum extruded mm to accept a automatic gcode retraction attempt - #define RETRACT_LENGTH 3 //default retract length (positive mm) - #define RETRACT_LENGTH_SWAP 13 //default swap retract length (positive mm), for extruder change - #define RETRACT_FEEDRATE 45 //default feedrate for retracting (mm/s) - #define RETRACT_ZLIFT 0 //default retract Z-lift - #define RETRACT_RECOVER_LENGTH 0 //default additional recover length (mm, added to retract length when recovering) - #define RETRACT_RECOVER_LENGTH_SWAP 0 //default additional swap recover length (mm, added to retract length when recovering from extruder change) - #define RETRACT_RECOVER_FEEDRATE 8 //default feedrate for recovering from retraction (mm/s) + #define MIN_RETRACT 0.1 // A retract/recover of this length or longer can be converted to auto-retract + #define RETRACT_LENGTH 3 // Default retract length (positive mm) + #define RETRACT_LENGTH_SWAP 13 // Default swap retract length (positive mm), for extruder change + #define RETRACT_FEEDRATE 45 // Default feedrate for retracting (mm/s) + #define RETRACT_ZLIFT 0 // Default retract Z-lift + #define RETRACT_RECOVER_LENGTH 0 // Default additional recover length (mm, added to retract length when recovering) + #define RETRACT_RECOVER_LENGTH_SWAP 0 // Default additional swap recover length (mm, added to retract length when recovering from extruder change) + #define RETRACT_RECOVER_FEEDRATE 8 // Default feedrate for recovering from retraction (mm/s) + #define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s) #endif /** diff --git a/Marlin/example_configurations/Malyan/M150/Configuration_adv.h b/Marlin/example_configurations/Malyan/M150/Configuration_adv.h index d31f0320a..53481c208 100644 --- a/Marlin/example_configurations/Malyan/M150/Configuration_adv.h +++ b/Marlin/example_configurations/Malyan/M150/Configuration_adv.h @@ -757,22 +757,32 @@ // @section fwretract -// Firmware based and LCD controlled retract -// M207 and M208 can be used to define parameters for the retraction. -// The retraction can be called by the slicer using G10 and G11 -// until then, intended retractions can be detected by moves that only extrude and the direction. -// the moves are than replaced by the firmware controlled ones. - -//#define FWRETRACT //ONLY PARTIALLY TESTED +/** + * Firmware-based and LCD-controlled retract + * + * Add G10 / G11 commands for automatic firmware-based retract / recover. + * Use M207 and M208 to define parameters for retract / recover. + * + * Use M209 to enable or disable auto-retract. + * With auto-retract enabled, all G1 E moves over the MIN_RETRACT length + * will be converted to firmware-based retract/recover moves. + * + * Be sure to turn off auto-retract during filament change. + * + * Note that M207 / M208 / M209 settings are saved to EEPROM. + * + */ +//#define FWRETRACT // ONLY PARTIALLY TESTED #if ENABLED(FWRETRACT) - #define MIN_RETRACT 0.1 //minimum extruded mm to accept a automatic gcode retraction attempt - #define RETRACT_LENGTH 3 //default retract length (positive mm) - #define RETRACT_LENGTH_SWAP 13 //default swap retract length (positive mm), for extruder change - #define RETRACT_FEEDRATE 45 //default feedrate for retracting (mm/s) - #define RETRACT_ZLIFT 0 //default retract Z-lift - #define RETRACT_RECOVER_LENGTH 0 //default additional recover length (mm, added to retract length when recovering) - #define RETRACT_RECOVER_LENGTH_SWAP 0 //default additional swap recover length (mm, added to retract length when recovering from extruder change) - #define RETRACT_RECOVER_FEEDRATE 8 //default feedrate for recovering from retraction (mm/s) + #define MIN_RETRACT 0.1 // A retract/recover of this length or longer can be converted to auto-retract + #define RETRACT_LENGTH 3 // Default retract length (positive mm) + #define RETRACT_LENGTH_SWAP 13 // Default swap retract length (positive mm), for extruder change + #define RETRACT_FEEDRATE 45 // Default feedrate for retracting (mm/s) + #define RETRACT_ZLIFT 0 // Default retract Z-lift + #define RETRACT_RECOVER_LENGTH 0 // Default additional recover length (mm, added to retract length when recovering) + #define RETRACT_RECOVER_LENGTH_SWAP 0 // Default additional swap recover length (mm, added to retract length when recovering from extruder change) + #define RETRACT_RECOVER_FEEDRATE 8 // Default feedrate for recovering from retraction (mm/s) + #define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s) #endif /** diff --git a/Marlin/example_configurations/RigidBot/Configuration_adv.h b/Marlin/example_configurations/RigidBot/Configuration_adv.h index ac15cd356..f2abeda02 100644 --- a/Marlin/example_configurations/RigidBot/Configuration_adv.h +++ b/Marlin/example_configurations/RigidBot/Configuration_adv.h @@ -750,22 +750,32 @@ // @section fwretract -// Firmware based and LCD controlled retract -// M207 and M208 can be used to define parameters for the retraction. -// The retraction can be called by the slicer using G10 and G11 -// until then, intended retractions can be detected by moves that only extrude and the direction. -// the moves are than replaced by the firmware controlled ones. - -//#define FWRETRACT //ONLY PARTIALLY TESTED +/** + * Firmware-based and LCD-controlled retract + * + * Add G10 / G11 commands for automatic firmware-based retract / recover. + * Use M207 and M208 to define parameters for retract / recover. + * + * Use M209 to enable or disable auto-retract. + * With auto-retract enabled, all G1 E moves over the MIN_RETRACT length + * will be converted to firmware-based retract/recover moves. + * + * Be sure to turn off auto-retract during filament change. + * + * Note that M207 / M208 / M209 settings are saved to EEPROM. + * + */ +//#define FWRETRACT // ONLY PARTIALLY TESTED #if ENABLED(FWRETRACT) - #define MIN_RETRACT 0.1 //minimum extruded mm to accept a automatic gcode retraction attempt - #define RETRACT_LENGTH 3 //default retract length (positive mm) - #define RETRACT_LENGTH_SWAP 13 //default swap retract length (positive mm), for extruder change - #define RETRACT_FEEDRATE 45 //default feedrate for retracting (mm/s) - #define RETRACT_ZLIFT 0 //default retract Z-lift - #define RETRACT_RECOVER_LENGTH 0 //default additional recover length (mm, added to retract length when recovering) - #define RETRACT_RECOVER_LENGTH_SWAP 0 //default additional swap recover length (mm, added to retract length when recovering from extruder change) - #define RETRACT_RECOVER_FEEDRATE 8 //default feedrate for recovering from retraction (mm/s) + #define MIN_RETRACT 0.1 // A retract/recover of this length or longer can be converted to auto-retract + #define RETRACT_LENGTH 3 // Default retract length (positive mm) + #define RETRACT_LENGTH_SWAP 13 // Default swap retract length (positive mm), for extruder change + #define RETRACT_FEEDRATE 45 // Default feedrate for retracting (mm/s) + #define RETRACT_ZLIFT 0 // Default retract Z-lift + #define RETRACT_RECOVER_LENGTH 0 // Default additional recover length (mm, added to retract length when recovering) + #define RETRACT_RECOVER_LENGTH_SWAP 0 // Default additional swap recover length (mm, added to retract length when recovering from extruder change) + #define RETRACT_RECOVER_FEEDRATE 8 // Default feedrate for recovering from retraction (mm/s) + #define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s) #endif /** diff --git a/Marlin/example_configurations/SCARA/Configuration_adv.h b/Marlin/example_configurations/SCARA/Configuration_adv.h index d820ed78b..47a5d070b 100644 --- a/Marlin/example_configurations/SCARA/Configuration_adv.h +++ b/Marlin/example_configurations/SCARA/Configuration_adv.h @@ -750,22 +750,32 @@ // @section fwretract -// Firmware based and LCD controlled retract -// M207 and M208 can be used to define parameters for the retraction. -// The retraction can be called by the slicer using G10 and G11 -// until then, intended retractions can be detected by moves that only extrude and the direction. -// the moves are than replaced by the firmware controlled ones. - -//#define FWRETRACT //ONLY PARTIALLY TESTED +/** + * Firmware-based and LCD-controlled retract + * + * Add G10 / G11 commands for automatic firmware-based retract / recover. + * Use M207 and M208 to define parameters for retract / recover. + * + * Use M209 to enable or disable auto-retract. + * With auto-retract enabled, all G1 E moves over the MIN_RETRACT length + * will be converted to firmware-based retract/recover moves. + * + * Be sure to turn off auto-retract during filament change. + * + * Note that M207 / M208 / M209 settings are saved to EEPROM. + * + */ +//#define FWRETRACT // ONLY PARTIALLY TESTED #if ENABLED(FWRETRACT) - #define MIN_RETRACT 0.1 //minimum extruded mm to accept a automatic gcode retraction attempt - #define RETRACT_LENGTH 3 //default retract length (positive mm) - #define RETRACT_LENGTH_SWAP 13 //default swap retract length (positive mm), for extruder change - #define RETRACT_FEEDRATE 35 //default feedrate for retracting (mm/s) - #define RETRACT_ZLIFT 0 //default retract Z-lift - #define RETRACT_RECOVER_LENGTH 0 //default additional recover length (mm, added to retract length when recovering) - #define RETRACT_RECOVER_LENGTH_SWAP 0 //default additional swap recover length (mm, added to retract length when recovering from extruder change) - #define RETRACT_RECOVER_FEEDRATE 8 //default feedrate for recovering from retraction (mm/s) + #define MIN_RETRACT 0.1 // A retract/recover of this length or longer can be converted to auto-retract + #define RETRACT_LENGTH 3 // Default retract length (positive mm) + #define RETRACT_LENGTH_SWAP 13 // Default swap retract length (positive mm), for extruder change + #define RETRACT_FEEDRATE 35 // Default feedrate for retracting (mm/s) + #define RETRACT_ZLIFT 0 // Default retract Z-lift + #define RETRACT_RECOVER_LENGTH 0 // Default additional recover length (mm, added to retract length when recovering) + #define RETRACT_RECOVER_LENGTH_SWAP 0 // Default additional swap recover length (mm, added to retract length when recovering from extruder change) + #define RETRACT_RECOVER_FEEDRATE 8 // Default feedrate for recovering from retraction (mm/s) + #define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s) #endif /** diff --git a/Marlin/example_configurations/TinyBoy2/Configuration_adv.h b/Marlin/example_configurations/TinyBoy2/Configuration_adv.h index 5f332f31a..3b637bd91 100644 --- a/Marlin/example_configurations/TinyBoy2/Configuration_adv.h +++ b/Marlin/example_configurations/TinyBoy2/Configuration_adv.h @@ -753,22 +753,32 @@ // @section fwretract -// Firmware based and LCD controlled retract -// M207 and M208 can be used to define parameters for the retraction. -// The retraction can be called by the slicer using G10 and G11 -// until then, intended retractions can be detected by moves that only extrude and the direction. -// the moves are than replaced by the firmware controlled ones. - -//#define FWRETRACT //ONLY PARTIALLY TESTED +/** + * Firmware-based and LCD-controlled retract + * + * Add G10 / G11 commands for automatic firmware-based retract / recover. + * Use M207 and M208 to define parameters for retract / recover. + * + * Use M209 to enable or disable auto-retract. + * With auto-retract enabled, all G1 E moves over the MIN_RETRACT length + * will be converted to firmware-based retract/recover moves. + * + * Be sure to turn off auto-retract during filament change. + * + * Note that M207 / M208 / M209 settings are saved to EEPROM. + * + */ +//#define FWRETRACT // ONLY PARTIALLY TESTED #if ENABLED(FWRETRACT) - #define MIN_RETRACT 0.1 //minimum extruded mm to accept a automatic gcode retraction attempt - #define RETRACT_LENGTH 3 //default retract length (positive mm) - #define RETRACT_LENGTH_SWAP 13 //default swap retract length (positive mm), for extruder change - #define RETRACT_FEEDRATE 45 //default feedrate for retracting (mm/s) - #define RETRACT_ZLIFT 0 //default retract Z-lift - #define RETRACT_RECOVER_LENGTH 0 //default additional recover length (mm, added to retract length when recovering) - #define RETRACT_RECOVER_LENGTH_SWAP 0 //default additional swap recover length (mm, added to retract length when recovering from extruder change) - #define RETRACT_RECOVER_FEEDRATE 8 //default feedrate for recovering from retraction (mm/s) + #define MIN_RETRACT 0.1 // A retract/recover of this length or longer can be converted to auto-retract + #define RETRACT_LENGTH 3 // Default retract length (positive mm) + #define RETRACT_LENGTH_SWAP 13 // Default swap retract length (positive mm), for extruder change + #define RETRACT_FEEDRATE 45 // Default feedrate for retracting (mm/s) + #define RETRACT_ZLIFT 0 // Default retract Z-lift + #define RETRACT_RECOVER_LENGTH 0 // Default additional recover length (mm, added to retract length when recovering) + #define RETRACT_RECOVER_LENGTH_SWAP 0 // Default additional swap recover length (mm, added to retract length when recovering from extruder change) + #define RETRACT_RECOVER_FEEDRATE 8 // Default feedrate for recovering from retraction (mm/s) + #define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s) #endif /** diff --git a/Marlin/example_configurations/Velleman/K8200/Configuration_adv.h b/Marlin/example_configurations/Velleman/K8200/Configuration_adv.h index 5adbc19d8..5baa75858 100644 --- a/Marlin/example_configurations/Velleman/K8200/Configuration_adv.h +++ b/Marlin/example_configurations/Velleman/K8200/Configuration_adv.h @@ -763,22 +763,32 @@ // @section fwretract -// Firmware based and LCD controlled retract -// M207 and M208 can be used to define parameters for the retraction. -// The retraction can be called by the slicer using G10 and G11 -// until then, intended retractions can be detected by moves that only extrude and the direction. -// the moves are than replaced by the firmware controlled ones. - -//#define FWRETRACT //ONLY PARTIALLY TESTED +/** + * Firmware-based and LCD-controlled retract + * + * Add G10 / G11 commands for automatic firmware-based retract / recover. + * Use M207 and M208 to define parameters for retract / recover. + * + * Use M209 to enable or disable auto-retract. + * With auto-retract enabled, all G1 E moves over the MIN_RETRACT length + * will be converted to firmware-based retract/recover moves. + * + * Be sure to turn off auto-retract during filament change. + * + * Note that M207 / M208 / M209 settings are saved to EEPROM. + * + */ +//#define FWRETRACT // ONLY PARTIALLY TESTED #if ENABLED(FWRETRACT) - #define MIN_RETRACT 0.1 //minimum extruded mm to accept a automatic gcode retraction attempt - #define RETRACT_LENGTH 3 //default retract length (positive mm) - #define RETRACT_LENGTH_SWAP 13 //default swap retract length (positive mm), for extruder change - #define RETRACT_FEEDRATE 45 //default feedrate for retracting (mm/s) - #define RETRACT_ZLIFT 0 //default retract Z-lift - #define RETRACT_RECOVER_LENGTH 0 //default additional recover length (mm, added to retract length when recovering) - #define RETRACT_RECOVER_LENGTH_SWAP 0 //default additional swap recover length (mm, added to retract length when recovering from extruder change) - #define RETRACT_RECOVER_FEEDRATE 8 //default feedrate for recovering from retraction (mm/s) + #define MIN_RETRACT 0.1 // A retract/recover of this length or longer can be converted to auto-retract + #define RETRACT_LENGTH 3 // Default retract length (positive mm) + #define RETRACT_LENGTH_SWAP 13 // Default swap retract length (positive mm), for extruder change + #define RETRACT_FEEDRATE 45 // Default feedrate for retracting (mm/s) + #define RETRACT_ZLIFT 0 // Default retract Z-lift + #define RETRACT_RECOVER_LENGTH 0 // Default additional recover length (mm, added to retract length when recovering) + #define RETRACT_RECOVER_LENGTH_SWAP 0 // Default additional swap recover length (mm, added to retract length when recovering from extruder change) + #define RETRACT_RECOVER_FEEDRATE 8 // Default feedrate for recovering from retraction (mm/s) + #define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s) #endif /** diff --git a/Marlin/example_configurations/Velleman/K8400/Configuration_adv.h b/Marlin/example_configurations/Velleman/K8400/Configuration_adv.h index 04ed926e1..88c88cffe 100644 --- a/Marlin/example_configurations/Velleman/K8400/Configuration_adv.h +++ b/Marlin/example_configurations/Velleman/K8400/Configuration_adv.h @@ -750,22 +750,32 @@ // @section fwretract -// Firmware based and LCD controlled retract -// M207 and M208 can be used to define parameters for the retraction. -// The retraction can be called by the slicer using G10 and G11 -// until then, intended retractions can be detected by moves that only extrude and the direction. -// the moves are than replaced by the firmware controlled ones. - -//#define FWRETRACT //ONLY PARTIALLY TESTED +/** + * Firmware-based and LCD-controlled retract + * + * Add G10 / G11 commands for automatic firmware-based retract / recover. + * Use M207 and M208 to define parameters for retract / recover. + * + * Use M209 to enable or disable auto-retract. + * With auto-retract enabled, all G1 E moves over the MIN_RETRACT length + * will be converted to firmware-based retract/recover moves. + * + * Be sure to turn off auto-retract during filament change. + * + * Note that M207 / M208 / M209 settings are saved to EEPROM. + * + */ +//#define FWRETRACT // ONLY PARTIALLY TESTED #if ENABLED(FWRETRACT) - #define MIN_RETRACT 0.1 //minimum extruded mm to accept a automatic gcode retraction attempt - #define RETRACT_LENGTH 3 //default retract length (positive mm) - #define RETRACT_LENGTH_SWAP 13 //default swap retract length (positive mm), for extruder change - #define RETRACT_FEEDRATE 45 //default feedrate for retracting (mm/s) - #define RETRACT_ZLIFT 0 //default retract Z-lift - #define RETRACT_RECOVER_LENGTH 0 //default additional recover length (mm, added to retract length when recovering) - #define RETRACT_RECOVER_LENGTH_SWAP 0 //default additional swap recover length (mm, added to retract length when recovering from extruder change) - #define RETRACT_RECOVER_FEEDRATE 8 //default feedrate for recovering from retraction (mm/s) + #define MIN_RETRACT 0.1 // A retract/recover of this length or longer can be converted to auto-retract + #define RETRACT_LENGTH 3 // Default retract length (positive mm) + #define RETRACT_LENGTH_SWAP 13 // Default swap retract length (positive mm), for extruder change + #define RETRACT_FEEDRATE 45 // Default feedrate for retracting (mm/s) + #define RETRACT_ZLIFT 0 // Default retract Z-lift + #define RETRACT_RECOVER_LENGTH 0 // Default additional recover length (mm, added to retract length when recovering) + #define RETRACT_RECOVER_LENGTH_SWAP 0 // Default additional swap recover length (mm, added to retract length when recovering from extruder change) + #define RETRACT_RECOVER_FEEDRATE 8 // Default feedrate for recovering from retraction (mm/s) + #define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s) #endif /** diff --git a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h index 66b681d17..e02fd97a6 100644 --- a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h +++ b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h @@ -755,22 +755,32 @@ // @section fwretract -// Firmware based and LCD controlled retract -// M207 and M208 can be used to define parameters for the retraction. -// The retraction can be called by the slicer using G10 and G11 -// until then, intended retractions can be detected by moves that only extrude and the direction. -// the moves are than replaced by the firmware controlled ones. - -//#define FWRETRACT //ONLY PARTIALLY TESTED +/** + * Firmware-based and LCD-controlled retract + * + * Add G10 / G11 commands for automatic firmware-based retract / recover. + * Use M207 and M208 to define parameters for retract / recover. + * + * Use M209 to enable or disable auto-retract. + * With auto-retract enabled, all G1 E moves over the MIN_RETRACT length + * will be converted to firmware-based retract/recover moves. + * + * Be sure to turn off auto-retract during filament change. + * + * Note that M207 / M208 / M209 settings are saved to EEPROM. + * + */ +//#define FWRETRACT // ONLY PARTIALLY TESTED #if ENABLED(FWRETRACT) - #define MIN_RETRACT 0.1 //minimum extruded mm to accept a automatic gcode retraction attempt - #define RETRACT_LENGTH 3 //default retract length (positive mm) - #define RETRACT_LENGTH_SWAP 13 //default swap retract length (positive mm), for extruder change - #define RETRACT_FEEDRATE 45 //default feedrate for retracting (mm/s) - #define RETRACT_ZLIFT 0 //default retract Z-lift - #define RETRACT_RECOVER_LENGTH 0 //default additional recover length (mm, added to retract length when recovering) - #define RETRACT_RECOVER_LENGTH_SWAP 0 //default additional swap recover length (mm, added to retract length when recovering from extruder change) - #define RETRACT_RECOVER_FEEDRATE 8 //default feedrate for recovering from retraction (mm/s) + #define MIN_RETRACT 0.1 // A retract/recover of this length or longer can be converted to auto-retract + #define RETRACT_LENGTH 3 // Default retract length (positive mm) + #define RETRACT_LENGTH_SWAP 13 // Default swap retract length (positive mm), for extruder change + #define RETRACT_FEEDRATE 45 // Default feedrate for retracting (mm/s) + #define RETRACT_ZLIFT 0 // Default retract Z-lift + #define RETRACT_RECOVER_LENGTH 0 // Default additional recover length (mm, added to retract length when recovering) + #define RETRACT_RECOVER_LENGTH_SWAP 0 // Default additional swap recover length (mm, added to retract length when recovering from extruder change) + #define RETRACT_RECOVER_FEEDRATE 8 // Default feedrate for recovering from retraction (mm/s) + #define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s) #endif /** diff --git a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h index 8de3b0bdf..3f763b8bb 100644 --- a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h +++ b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h @@ -754,22 +754,32 @@ // @section fwretract -// Firmware based and LCD controlled retract -// M207 and M208 can be used to define parameters for the retraction. -// The retraction can be called by the slicer using G10 and G11 -// until then, intended retractions can be detected by moves that only extrude and the direction. -// the moves are than replaced by the firmware controlled ones. - -//#define FWRETRACT //ONLY PARTIALLY TESTED +/** + * Firmware-based and LCD-controlled retract + * + * Add G10 / G11 commands for automatic firmware-based retract / recover. + * Use M207 and M208 to define parameters for retract / recover. + * + * Use M209 to enable or disable auto-retract. + * With auto-retract enabled, all G1 E moves over the MIN_RETRACT length + * will be converted to firmware-based retract/recover moves. + * + * Be sure to turn off auto-retract during filament change. + * + * Note that M207 / M208 / M209 settings are saved to EEPROM. + * + */ +//#define FWRETRACT // ONLY PARTIALLY TESTED #if ENABLED(FWRETRACT) - #define MIN_RETRACT 0.1 //minimum extruded mm to accept a automatic gcode retraction attempt - #define RETRACT_LENGTH 3 //default retract length (positive mm) - #define RETRACT_LENGTH_SWAP 13 //default swap retract length (positive mm), for extruder change - #define RETRACT_FEEDRATE 45 //default feedrate for retracting (mm/s) - #define RETRACT_ZLIFT 0 //default retract Z-lift - #define RETRACT_RECOVER_LENGTH 0 //default additional recover length (mm, added to retract length when recovering) - #define RETRACT_RECOVER_LENGTH_SWAP 0 //default additional swap recover length (mm, added to retract length when recovering from extruder change) - #define RETRACT_RECOVER_FEEDRATE 8 //default feedrate for recovering from retraction (mm/s) + #define MIN_RETRACT 0.1 // A retract/recover of this length or longer can be converted to auto-retract + #define RETRACT_LENGTH 3 // Default retract length (positive mm) + #define RETRACT_LENGTH_SWAP 13 // Default swap retract length (positive mm), for extruder change + #define RETRACT_FEEDRATE 45 // Default feedrate for retracting (mm/s) + #define RETRACT_ZLIFT 0 // Default retract Z-lift + #define RETRACT_RECOVER_LENGTH 0 // Default additional recover length (mm, added to retract length when recovering) + #define RETRACT_RECOVER_LENGTH_SWAP 0 // Default additional swap recover length (mm, added to retract length when recovering from extruder change) + #define RETRACT_RECOVER_FEEDRATE 8 // Default feedrate for recovering from retraction (mm/s) + #define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s) #endif /** diff --git a/Marlin/example_configurations/delta/generic/Configuration_adv.h b/Marlin/example_configurations/delta/generic/Configuration_adv.h index fd2bdf30f..035539149 100644 --- a/Marlin/example_configurations/delta/generic/Configuration_adv.h +++ b/Marlin/example_configurations/delta/generic/Configuration_adv.h @@ -752,22 +752,32 @@ // @section fwretract -// Firmware based and LCD controlled retract -// M207 and M208 can be used to define parameters for the retraction. -// The retraction can be called by the slicer using G10 and G11 -// until then, intended retractions can be detected by moves that only extrude and the direction. -// the moves are than replaced by the firmware controlled ones. - -//#define FWRETRACT //ONLY PARTIALLY TESTED +/** + * Firmware-based and LCD-controlled retract + * + * Add G10 / G11 commands for automatic firmware-based retract / recover. + * Use M207 and M208 to define parameters for retract / recover. + * + * Use M209 to enable or disable auto-retract. + * With auto-retract enabled, all G1 E moves over the MIN_RETRACT length + * will be converted to firmware-based retract/recover moves. + * + * Be sure to turn off auto-retract during filament change. + * + * Note that M207 / M208 / M209 settings are saved to EEPROM. + * + */ +//#define FWRETRACT // ONLY PARTIALLY TESTED #if ENABLED(FWRETRACT) - #define MIN_RETRACT 0.1 //minimum extruded mm to accept a automatic gcode retraction attempt - #define RETRACT_LENGTH 3 //default retract length (positive mm) - #define RETRACT_LENGTH_SWAP 13 //default swap retract length (positive mm), for extruder change - #define RETRACT_FEEDRATE 45 //default feedrate for retracting (mm/s) - #define RETRACT_ZLIFT 0 //default retract Z-lift - #define RETRACT_RECOVER_LENGTH 0 //default additional recover length (mm, added to retract length when recovering) - #define RETRACT_RECOVER_LENGTH_SWAP 0 //default additional swap recover length (mm, added to retract length when recovering from extruder change) - #define RETRACT_RECOVER_FEEDRATE 8 //default feedrate for recovering from retraction (mm/s) + #define MIN_RETRACT 0.1 // A retract/recover of this length or longer can be converted to auto-retract + #define RETRACT_LENGTH 3 // Default retract length (positive mm) + #define RETRACT_LENGTH_SWAP 13 // Default swap retract length (positive mm), for extruder change + #define RETRACT_FEEDRATE 45 // Default feedrate for retracting (mm/s) + #define RETRACT_ZLIFT 0 // Default retract Z-lift + #define RETRACT_RECOVER_LENGTH 0 // Default additional recover length (mm, added to retract length when recovering) + #define RETRACT_RECOVER_LENGTH_SWAP 0 // Default additional swap recover length (mm, added to retract length when recovering from extruder change) + #define RETRACT_RECOVER_FEEDRATE 8 // Default feedrate for recovering from retraction (mm/s) + #define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s) #endif /** diff --git a/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h index fd2bdf30f..035539149 100644 --- a/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h @@ -752,22 +752,32 @@ // @section fwretract -// Firmware based and LCD controlled retract -// M207 and M208 can be used to define parameters for the retraction. -// The retraction can be called by the slicer using G10 and G11 -// until then, intended retractions can be detected by moves that only extrude and the direction. -// the moves are than replaced by the firmware controlled ones. - -//#define FWRETRACT //ONLY PARTIALLY TESTED +/** + * Firmware-based and LCD-controlled retract + * + * Add G10 / G11 commands for automatic firmware-based retract / recover. + * Use M207 and M208 to define parameters for retract / recover. + * + * Use M209 to enable or disable auto-retract. + * With auto-retract enabled, all G1 E moves over the MIN_RETRACT length + * will be converted to firmware-based retract/recover moves. + * + * Be sure to turn off auto-retract during filament change. + * + * Note that M207 / M208 / M209 settings are saved to EEPROM. + * + */ +//#define FWRETRACT // ONLY PARTIALLY TESTED #if ENABLED(FWRETRACT) - #define MIN_RETRACT 0.1 //minimum extruded mm to accept a automatic gcode retraction attempt - #define RETRACT_LENGTH 3 //default retract length (positive mm) - #define RETRACT_LENGTH_SWAP 13 //default swap retract length (positive mm), for extruder change - #define RETRACT_FEEDRATE 45 //default feedrate for retracting (mm/s) - #define RETRACT_ZLIFT 0 //default retract Z-lift - #define RETRACT_RECOVER_LENGTH 0 //default additional recover length (mm, added to retract length when recovering) - #define RETRACT_RECOVER_LENGTH_SWAP 0 //default additional swap recover length (mm, added to retract length when recovering from extruder change) - #define RETRACT_RECOVER_FEEDRATE 8 //default feedrate for recovering from retraction (mm/s) + #define MIN_RETRACT 0.1 // A retract/recover of this length or longer can be converted to auto-retract + #define RETRACT_LENGTH 3 // Default retract length (positive mm) + #define RETRACT_LENGTH_SWAP 13 // Default swap retract length (positive mm), for extruder change + #define RETRACT_FEEDRATE 45 // Default feedrate for retracting (mm/s) + #define RETRACT_ZLIFT 0 // Default retract Z-lift + #define RETRACT_RECOVER_LENGTH 0 // Default additional recover length (mm, added to retract length when recovering) + #define RETRACT_RECOVER_LENGTH_SWAP 0 // Default additional swap recover length (mm, added to retract length when recovering from extruder change) + #define RETRACT_RECOVER_FEEDRATE 8 // Default feedrate for recovering from retraction (mm/s) + #define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s) #endif /** diff --git a/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h index f7ae11b99..4b676e425 100644 --- a/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h @@ -757,22 +757,32 @@ // @section fwretract -// Firmware based and LCD controlled retract -// M207 and M208 can be used to define parameters for the retraction. -// The retraction can be called by the slicer using G10 and G11 -// until then, intended retractions can be detected by moves that only extrude and the direction. -// the moves are than replaced by the firmware controlled ones. - -//#define FWRETRACT //ONLY PARTIALLY TESTED +/** + * Firmware-based and LCD-controlled retract + * + * Add G10 / G11 commands for automatic firmware-based retract / recover. + * Use M207 and M208 to define parameters for retract / recover. + * + * Use M209 to enable or disable auto-retract. + * With auto-retract enabled, all G1 E moves over the MIN_RETRACT length + * will be converted to firmware-based retract/recover moves. + * + * Be sure to turn off auto-retract during filament change. + * + * Note that M207 / M208 / M209 settings are saved to EEPROM. + * + */ +//#define FWRETRACT // ONLY PARTIALLY TESTED #if ENABLED(FWRETRACT) - #define MIN_RETRACT 0.1 //minimum extruded mm to accept a automatic gcode retraction attempt - #define RETRACT_LENGTH 3 //default retract length (positive mm) - #define RETRACT_LENGTH_SWAP 13 //default swap retract length (positive mm), for extruder change - #define RETRACT_FEEDRATE 45 //default feedrate for retracting (mm/s) - #define RETRACT_ZLIFT 0 //default retract Z-lift - #define RETRACT_RECOVER_LENGTH 0 //default additional recover length (mm, added to retract length when recovering) - #define RETRACT_RECOVER_LENGTH_SWAP 0 //default additional swap recover length (mm, added to retract length when recovering from extruder change) - #define RETRACT_RECOVER_FEEDRATE 8 //default feedrate for recovering from retraction (mm/s) + #define MIN_RETRACT 0.1 // A retract/recover of this length or longer can be converted to auto-retract + #define RETRACT_LENGTH 3 // Default retract length (positive mm) + #define RETRACT_LENGTH_SWAP 13 // Default swap retract length (positive mm), for extruder change + #define RETRACT_FEEDRATE 45 // Default feedrate for retracting (mm/s) + #define RETRACT_ZLIFT 0 // Default retract Z-lift + #define RETRACT_RECOVER_LENGTH 0 // Default additional recover length (mm, added to retract length when recovering) + #define RETRACT_RECOVER_LENGTH_SWAP 0 // Default additional swap recover length (mm, added to retract length when recovering from extruder change) + #define RETRACT_RECOVER_FEEDRATE 8 // Default feedrate for recovering from retraction (mm/s) + #define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s) #endif /** diff --git a/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h index ef02e7559..a3994d5ec 100644 --- a/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h @@ -752,22 +752,32 @@ // @section fwretract -// Firmware based and LCD controlled retract -// M207 and M208 can be used to define parameters for the retraction. -// The retraction can be called by the slicer using G10 and G11 -// until then, intended retractions can be detected by moves that only extrude and the direction. -// the moves are than replaced by the firmware controlled ones. - -//#define FWRETRACT //ONLY PARTIALLY TESTED +/** + * Firmware-based and LCD-controlled retract + * + * Add G10 / G11 commands for automatic firmware-based retract / recover. + * Use M207 and M208 to define parameters for retract / recover. + * + * Use M209 to enable or disable auto-retract. + * With auto-retract enabled, all G1 E moves over the MIN_RETRACT length + * will be converted to firmware-based retract/recover moves. + * + * Be sure to turn off auto-retract during filament change. + * + * Note that M207 / M208 / M209 settings are saved to EEPROM. + * + */ +//#define FWRETRACT // ONLY PARTIALLY TESTED #if ENABLED(FWRETRACT) - #define MIN_RETRACT 0.1 //minimum extruded mm to accept a automatic gcode retraction attempt - #define RETRACT_LENGTH 3 //default retract length (positive mm) - #define RETRACT_LENGTH_SWAP 13 //default swap retract length (positive mm), for extruder change - #define RETRACT_FEEDRATE 45 //default feedrate for retracting (mm/s) - #define RETRACT_ZLIFT 0 //default retract Z-lift - #define RETRACT_RECOVER_LENGTH 0 //default additional recover length (mm, added to retract length when recovering) - #define RETRACT_RECOVER_LENGTH_SWAP 0 //default additional swap recover length (mm, added to retract length when recovering from extruder change) - #define RETRACT_RECOVER_FEEDRATE 8 //default feedrate for recovering from retraction (mm/s) + #define MIN_RETRACT 0.1 // A retract/recover of this length or longer can be converted to auto-retract + #define RETRACT_LENGTH 3 // Default retract length (positive mm) + #define RETRACT_LENGTH_SWAP 13 // Default swap retract length (positive mm), for extruder change + #define RETRACT_FEEDRATE 45 // Default feedrate for retracting (mm/s) + #define RETRACT_ZLIFT 0 // Default retract Z-lift + #define RETRACT_RECOVER_LENGTH 0 // Default additional recover length (mm, added to retract length when recovering) + #define RETRACT_RECOVER_LENGTH_SWAP 0 // Default additional swap recover length (mm, added to retract length when recovering from extruder change) + #define RETRACT_RECOVER_FEEDRATE 8 // Default feedrate for recovering from retraction (mm/s) + #define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s) #endif /** diff --git a/Marlin/example_configurations/gCreate/gMax1.5+/Configuration_adv.h b/Marlin/example_configurations/gCreate/gMax1.5+/Configuration_adv.h index 784624954..d1c31153b 100644 --- a/Marlin/example_configurations/gCreate/gMax1.5+/Configuration_adv.h +++ b/Marlin/example_configurations/gCreate/gMax1.5+/Configuration_adv.h @@ -757,22 +757,32 @@ // @section fwretract -// Firmware based and LCD controlled retract -// M207 and M208 can be used to define parameters for the retraction. -// The retraction can be called by the slicer using G10 and G11 -// until then, intended retractions can be detected by moves that only extrude and the direction. -// the moves are than replaced by the firmware controlled ones. - -//#define FWRETRACT //ONLY PARTIALLY TESTED +/** + * Firmware-based and LCD-controlled retract + * + * Add G10 / G11 commands for automatic firmware-based retract / recover. + * Use M207 and M208 to define parameters for retract / recover. + * + * Use M209 to enable or disable auto-retract. + * With auto-retract enabled, all G1 E moves over the MIN_RETRACT length + * will be converted to firmware-based retract/recover moves. + * + * Be sure to turn off auto-retract during filament change. + * + * Note that M207 / M208 / M209 settings are saved to EEPROM. + * + */ +//#define FWRETRACT // ONLY PARTIALLY TESTED #if ENABLED(FWRETRACT) - #define MIN_RETRACT 0.1 //minimum extruded mm to accept a automatic gcode retraction attempt - #define RETRACT_LENGTH 3 //default retract length (positive mm) - #define RETRACT_LENGTH_SWAP 13 //default swap retract length (positive mm), for extruder change - #define RETRACT_FEEDRATE 45 //default feedrate for retracting (mm/s) - #define RETRACT_ZLIFT 0 //default retract Z-lift - #define RETRACT_RECOVER_LENGTH 0 //default additional recover length (mm, added to retract length when recovering) - #define RETRACT_RECOVER_LENGTH_SWAP 0 //default additional swap recover length (mm, added to retract length when recovering from extruder change) - #define RETRACT_RECOVER_FEEDRATE 8 //default feedrate for recovering from retraction (mm/s) + #define MIN_RETRACT 0.1 // A retract/recover of this length or longer can be converted to auto-retract + #define RETRACT_LENGTH 3 // Default retract length (positive mm) + #define RETRACT_LENGTH_SWAP 13 // Default swap retract length (positive mm), for extruder change + #define RETRACT_FEEDRATE 45 // Default feedrate for retracting (mm/s) + #define RETRACT_ZLIFT 0 // Default retract Z-lift + #define RETRACT_RECOVER_LENGTH 0 // Default additional recover length (mm, added to retract length when recovering) + #define RETRACT_RECOVER_LENGTH_SWAP 0 // Default additional swap recover length (mm, added to retract length when recovering from extruder change) + #define RETRACT_RECOVER_FEEDRATE 8 // Default feedrate for recovering from retraction (mm/s) + #define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s) #endif /** diff --git a/Marlin/example_configurations/makibox/Configuration_adv.h b/Marlin/example_configurations/makibox/Configuration_adv.h index 58b2a842d..52649f494 100644 --- a/Marlin/example_configurations/makibox/Configuration_adv.h +++ b/Marlin/example_configurations/makibox/Configuration_adv.h @@ -750,22 +750,32 @@ // @section fwretract -// Firmware based and LCD controlled retract -// M207 and M208 can be used to define parameters for the retraction. -// The retraction can be called by the slicer using G10 and G11 -// until then, intended retractions can be detected by moves that only extrude and the direction. -// the moves are than replaced by the firmware controlled ones. - -//#define FWRETRACT //ONLY PARTIALLY TESTED +/** + * Firmware-based and LCD-controlled retract + * + * Add G10 / G11 commands for automatic firmware-based retract / recover. + * Use M207 and M208 to define parameters for retract / recover. + * + * Use M209 to enable or disable auto-retract. + * With auto-retract enabled, all G1 E moves over the MIN_RETRACT length + * will be converted to firmware-based retract/recover moves. + * + * Be sure to turn off auto-retract during filament change. + * + * Note that M207 / M208 / M209 settings are saved to EEPROM. + * + */ +//#define FWRETRACT // ONLY PARTIALLY TESTED #if ENABLED(FWRETRACT) - #define MIN_RETRACT 0.1 //minimum extruded mm to accept a automatic gcode retraction attempt - #define RETRACT_LENGTH 3 //default retract length (positive mm) - #define RETRACT_LENGTH_SWAP 13 //default swap retract length (positive mm), for extruder change - #define RETRACT_FEEDRATE 45 //default feedrate for retracting (mm/s) - #define RETRACT_ZLIFT 0 //default retract Z-lift - #define RETRACT_RECOVER_LENGTH 0 //default additional recover length (mm, added to retract length when recovering) - #define RETRACT_RECOVER_LENGTH_SWAP 0 //default additional swap recover length (mm, added to retract length when recovering from extruder change) - #define RETRACT_RECOVER_FEEDRATE 8 //default feedrate for recovering from retraction (mm/s) + #define MIN_RETRACT 0.1 // A retract/recover of this length or longer can be converted to auto-retract + #define RETRACT_LENGTH 3 // Default retract length (positive mm) + #define RETRACT_LENGTH_SWAP 13 // Default swap retract length (positive mm), for extruder change + #define RETRACT_FEEDRATE 45 // Default feedrate for retracting (mm/s) + #define RETRACT_ZLIFT 0 // Default retract Z-lift + #define RETRACT_RECOVER_LENGTH 0 // Default additional recover length (mm, added to retract length when recovering) + #define RETRACT_RECOVER_LENGTH_SWAP 0 // Default additional swap recover length (mm, added to retract length when recovering from extruder change) + #define RETRACT_RECOVER_FEEDRATE 8 // Default feedrate for recovering from retraction (mm/s) + #define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s) #endif /** diff --git a/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h b/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h index de5a967b7..431e14383 100644 --- a/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h +++ b/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h @@ -750,22 +750,32 @@ // @section fwretract -// Firmware based and LCD controlled retract -// M207 and M208 can be used to define parameters for the retraction. -// The retraction can be called by the slicer using G10 and G11 -// until then, intended retractions can be detected by moves that only extrude and the direction. -// the moves are than replaced by the firmware controlled ones. - -//#define FWRETRACT //ONLY PARTIALLY TESTED +/** + * Firmware-based and LCD-controlled retract + * + * Add G10 / G11 commands for automatic firmware-based retract / recover. + * Use M207 and M208 to define parameters for retract / recover. + * + * Use M209 to enable or disable auto-retract. + * With auto-retract enabled, all G1 E moves over the MIN_RETRACT length + * will be converted to firmware-based retract/recover moves. + * + * Be sure to turn off auto-retract during filament change. + * + * Note that M207 / M208 / M209 settings are saved to EEPROM. + * + */ +//#define FWRETRACT // ONLY PARTIALLY TESTED #if ENABLED(FWRETRACT) - #define MIN_RETRACT 0.1 //minimum extruded mm to accept a automatic gcode retraction attempt - #define RETRACT_LENGTH 3 //default retract length (positive mm) - #define RETRACT_LENGTH_SWAP 13 //default swap retract length (positive mm), for extruder change - #define RETRACT_FEEDRATE 45 //default feedrate for retracting (mm/s) - #define RETRACT_ZLIFT 0 //default retract Z-lift - #define RETRACT_RECOVER_LENGTH 0 //default additional recover length (mm, added to retract length when recovering) - #define RETRACT_RECOVER_LENGTH_SWAP 0 //default additional swap recover length (mm, added to retract length when recovering from extruder change) - #define RETRACT_RECOVER_FEEDRATE 8 //default feedrate for recovering from retraction (mm/s) + #define MIN_RETRACT 0.1 // A retract/recover of this length or longer can be converted to auto-retract + #define RETRACT_LENGTH 3 // Default retract length (positive mm) + #define RETRACT_LENGTH_SWAP 13 // Default swap retract length (positive mm), for extruder change + #define RETRACT_FEEDRATE 45 // Default feedrate for retracting (mm/s) + #define RETRACT_ZLIFT 0 // Default retract Z-lift + #define RETRACT_RECOVER_LENGTH 0 // Default additional recover length (mm, added to retract length when recovering) + #define RETRACT_RECOVER_LENGTH_SWAP 0 // Default additional swap recover length (mm, added to retract length when recovering from extruder change) + #define RETRACT_RECOVER_FEEDRATE 8 // Default feedrate for recovering from retraction (mm/s) + #define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s) #endif /** diff --git a/Marlin/example_configurations/wt150/Configuration_adv.h b/Marlin/example_configurations/wt150/Configuration_adv.h index bf612de94..efac0c4b2 100644 --- a/Marlin/example_configurations/wt150/Configuration_adv.h +++ b/Marlin/example_configurations/wt150/Configuration_adv.h @@ -757,22 +757,32 @@ // @section fwretract -// Firmware based and LCD controlled retract -// M207 and M208 can be used to define parameters for the retraction. -// The retraction can be called by the slicer using G10 and G11 -// until then, intended retractions can be detected by moves that only extrude and the direction. -// the moves are than replaced by the firmware controlled ones. - -//#define FWRETRACT //ONLY PARTIALLY TESTED +/** + * Firmware-based and LCD-controlled retract + * + * Add G10 / G11 commands for automatic firmware-based retract / recover. + * Use M207 and M208 to define parameters for retract / recover. + * + * Use M209 to enable or disable auto-retract. + * With auto-retract enabled, all G1 E moves over the MIN_RETRACT length + * will be converted to firmware-based retract/recover moves. + * + * Be sure to turn off auto-retract during filament change. + * + * Note that M207 / M208 / M209 settings are saved to EEPROM. + * + */ +//#define FWRETRACT // ONLY PARTIALLY TESTED #if ENABLED(FWRETRACT) - #define MIN_RETRACT 0.1 //minimum extruded mm to accept a automatic gcode retraction attempt - #define RETRACT_LENGTH 3 //default retract length (positive mm) - #define RETRACT_LENGTH_SWAP 13 //default swap retract length (positive mm), for extruder change - #define RETRACT_FEEDRATE 45 //default feedrate for retracting (mm/s) - #define RETRACT_ZLIFT 0 //default retract Z-lift - #define RETRACT_RECOVER_LENGTH 0 //default additional recover length (mm, added to retract length when recovering) - #define RETRACT_RECOVER_LENGTH_SWAP 0 //default additional swap recover length (mm, added to retract length when recovering from extruder change) - #define RETRACT_RECOVER_FEEDRATE 8 //default feedrate for recovering from retraction (mm/s) + #define MIN_RETRACT 0.1 // A retract/recover of this length or longer can be converted to auto-retract + #define RETRACT_LENGTH 3 // Default retract length (positive mm) + #define RETRACT_LENGTH_SWAP 13 // Default swap retract length (positive mm), for extruder change + #define RETRACT_FEEDRATE 45 // Default feedrate for retracting (mm/s) + #define RETRACT_ZLIFT 0 // Default retract Z-lift + #define RETRACT_RECOVER_LENGTH 0 // Default additional recover length (mm, added to retract length when recovering) + #define RETRACT_RECOVER_LENGTH_SWAP 0 // Default additional swap recover length (mm, added to retract length when recovering from extruder change) + #define RETRACT_RECOVER_FEEDRATE 8 // Default feedrate for recovering from retraction (mm/s) + #define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s) #endif /** From f38b8c5bf87858abd4bc8d96a2f0ae4fadcdbf2e Mon Sep 17 00:00:00 2001 From: Alexey Shvetsov Date: Wed, 5 Jul 2017 19:54:26 +0300 Subject: [PATCH 031/112] MKS 1.3+: Add pin mapping for PS_ON This allows the use of D4 as PS_ON since MKS Gen doesn't have a PS_ON pin. However this effectively allows only 3 servos (instead of 4). Signed-off-by: Alexey Shvetsov --- Marlin/pins_MKS_13.h | 10 ++++++++++ Marlin/pins_RAMPS.h | 8 ++++++-- 2 files changed, 16 insertions(+), 2 deletions(-) diff --git a/Marlin/pins_MKS_13.h b/Marlin/pins_MKS_13.h index 8b466c652..07aa65811 100644 --- a/Marlin/pins_MKS_13.h +++ b/Marlin/pins_MKS_13.h @@ -41,6 +41,16 @@ // Power outputs EFBF or EFBE #define MOSFET_D_PIN 7 +// +// PSU / SERVO +// +// If POWER_SUPPLY is specified, always hijack Servo 3 +// +#if POWER_SUPPLY > 0 + #define SERVO3_PIN -1 + #define PS_ON_PIN 4 +#endif + #include "pins_RAMPS.h" // diff --git a/Marlin/pins_RAMPS.h b/Marlin/pins_RAMPS.h index 91d435afb..9b1846113 100644 --- a/Marlin/pins_RAMPS.h +++ b/Marlin/pins_RAMPS.h @@ -64,7 +64,9 @@ #endif #define SERVO1_PIN 6 #define SERVO2_PIN 5 -#define SERVO3_PIN 4 +#ifndef SERVO3_PIN + #define SERVO3_PIN 4 +#endif // // Limit Switches @@ -203,7 +205,9 @@ // 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 +#ifndef PS_ON_PIN + #define PS_ON_PIN 12 +#endif #if ENABLED(CASE_LIGHT_ENABLE) && !PIN_EXISTS(CASE_LIGHT) && !defined(SPINDLE_LASER_ENABLE_PIN) #if !defined(NUM_SERVOS) || NUM_SERVOS == 0 // try to use servo connector first From 851f9f5399d8255f9f585452383970a65ac8e7dd Mon Sep 17 00:00:00 2001 From: Alexey Shvetsov Date: Fri, 21 Jul 2017 00:50:15 +0300 Subject: [PATCH 032/112] Update Russian translation - Part 1 Signed-off-by: Alexey Shvetsov --- Marlin/language_ru.h | 151 ++++++++++++++++++++++++++++++++++++++----- 1 file changed, 136 insertions(+), 15 deletions(-) diff --git a/Marlin/language_ru.h b/Marlin/language_ru.h index 1c82986cb..0ed8ff1d8 100644 --- a/Marlin/language_ru.h +++ b/Marlin/language_ru.h @@ -34,30 +34,37 @@ #define DISPLAY_CHARSET_ISO10646_5 #define WELCOME_MSG MACHINE_NAME _UxGT(" Готов.") +#define MSG_BACK _UxGT("Назад") #define MSG_SD_INSERTED _UxGT("Карта вставлена") #define MSG_SD_REMOVED _UxGT("Карта извлечена") +#define MSG_LCD_ENDSTOPS _UxGT("Концевики") #define MSG_MAIN _UxGT("Меню") -#define MSG_LCD_ENDSTOPS _UxGT("концевик") #define MSG_AUTOSTART _UxGT("Автостарт") #define MSG_DISABLE_STEPPERS _UxGT("Выкл. двигатели") -#define MSG_AUTO_HOME _UxGT("Парковка") +#define MSG_DEBUG_MENU _UxGT("Меню отладки") +#define MSG_PROGRESS_BAR_TEST _UxGT("Тест индикатора") +#define MSG_AUTO_HOME _UxGT("Авто Парковка") +#define MSG_AUTO_HOME_X _UxGT("Парковка X") +#define MSG_AUTO_HOME_Y _UxGT("Парковка Y") +#define MSG_AUTO_HOME_Z _UxGT("Парковка Z") #define MSG_LEVEL_BED_HOMING _UxGT("Нулевое полож") #define MSG_LEVEL_BED_WAITING _UxGT("Нажмите начать") #define MSG_LEVEL_BED_NEXT_POINT _UxGT("Следующая точка") -#define MSG_LEVEL_BED_DONE _UxGT("Уровень!") +#define MSG_LEVEL_BED_DONE _UxGT("Выравнинваие готово!") +#define MSG_Z_FADE_HEIGHT _UxGT("Высота спада") #define MSG_SET_HOME_OFFSETS _UxGT("Запомнить парковку") #define MSG_HOME_OFFSETS_APPLIED _UxGT("Коррекции примен") #define MSG_SET_ORIGIN _UxGT("Запомнить ноль") #define MSG_PREHEAT_1 _UxGT("Преднагрев PLA") -#define MSG_PREHEAT_1_N _UxGT("Греть PLA Сопло ") -#define MSG_PREHEAT_1_ALL _UxGT("Греть PLA Все") -#define MSG_PREHEAT_1_BEDONLY _UxGT("Греть PLA Стол") -#define MSG_PREHEAT_1_SETTINGS _UxGT("Настройки PLA") +#define MSG_PREHEAT_1_N MSG_PREHEAT_1 _UxGT(" ") +#define MSG_PREHEAT_1_ALL MSG_PREHEAT_1 _UxGT(" Всё") +#define MSG_PREHEAT_1_END MSG_PREHEAT_1 _UxGT(" Сопло") +#define MSG_PREHEAT_1_BEDONLY MSG_PREHEAT_1 _UxGT(" Стол") #define MSG_PREHEAT_2 _UxGT("Преднагрев ABS") -#define MSG_PREHEAT_2_N _UxGT("Греть ABS Сопло ") -#define MSG_PREHEAT_2_ALL _UxGT("Греть ABS Все") -#define MSG_PREHEAT_2_BEDONLY _UxGT("Греть ABS Стол") -#define MSG_PREHEAT_2_SETTINGS _UxGT("Настройки ABS") +#define MSG_PREHEAT_2_N MSG_PREHEAT_2 _UxGT(" ") +#define MSG_PREHEAT_2_ALL MSG_PREHEAT_2 _UxGT(" Всё") +#define MSG_PREHEAT_2_END MSG_PREHEAT_2 _UxGT(" Сопло") +#define MSG_PREHEAT_2_BEDONLY MSG_PREHEAT_2 _UxGT(" Стол") #define MSG_COOLDOWN _UxGT("Охлаждение") #define MSG_SWITCH_PS_ON _UxGT("Включить Питание") #define MSG_SWITCH_PS_OFF _UxGT("Отключить Питание") @@ -66,6 +73,46 @@ #define MSG_MOVE_AXIS _UxGT("Движение по осям") #define MSG_BED_LEVELING _UxGT("Калибровать стол") #define MSG_LEVEL_BED _UxGT("Калибровать стол") +#define MSG_UBL_DOING_G29 _UxGT("Выполняем G29") +#define MSG_UBL_UNHOMED _UxGT("Паркуем сначала XYZ") +#define MSG_UBL_TOOLS _UxGT("Утилиты UBL") +#define MSG_UBL_BC_INSERT2 _UxGT("Измерение") +#define MSG_UBL_MOVING_TO_NEXT _UxGT("Двигаемся дальше") +#define MSG_UBL_ACTIVATE_MESH _UxGT("Активировать UBL") +#define MSG_UBL_DEACTIVATE_MESH _UxGT("Выключить UBL") +#define MSG_UBL_SET_BED_TEMP _UxGT("Температура стола") +#define MSG_UBL_CUSTOM_BED_TEMP MSG_UBL_SET_BED_TEMP +#define MSG_UBL_SET_HOTEND_TEMP _UxGT("Температура сопла") +#define MSG_UBL_CUSTOM_HOTEND_TEMP MSG_UBL_SET_HOTEND_TEMP +#define MSG_UBL_MESH_EDIT _UxGT("Редактор сеток") +#define MSG_UBL_BUILD_CUSTOM_MESH _UxGT("Построить свою сетку") +#define MSG_UBL_BUILD_MESH_MENU _UxGT("Построить сетку") +#define MSG_UBL_BUILD_PLA_MESH _UxGT("Построить сетку PLA") +#define MSG_UBL_BUILD_ABS_MESH _UxGT("Построить сетку ABS") +#define MSG_UBL_MESH_HEIGHT_AMOUNT _UxGT("Высота") +#define MSG_UBL_VALIDATE_MESH_MENU _UxGT("Проверить сетку") +#define MSG_UBL_VALIDATE_PLA_MESH _UxGT("Проверить сетку PLA") +#define MSG_UBL_VALIDATE_ABS_MESH _UxGT("Проверить сетку ABS") +#define MSG_UBL_VALIDATE_CUSTOM_MESH _UxGT("Проверить свою сетку") +#define MSG_UBL_MESH_LEVEL _UxGT("Выровнять сетку") +#define MSG_UBL_SIDE_POINTS _UxGT("Крайние точки") +#define MSG_UBL_MAP_TYPE _UxGT("Типа карты") +#define MSG_UBL_OUTPUT_MAP _UxGT("Вывести карту сетки") +#define MSG_UBL_OUTPUT_MAP_HOST _UxGT("Вывести на хост") +#define MSG_UBL_OUTPUT_MAP_CSV _UxGT("Вывести в CSV") +#define MSG_UBL_OUTPUT_MAP_BACKUP _UxGT("Забекапить сетку") +#define MSG_UBL_EDIT_MESH_MENU _UxGT("Редактировать сетку") +#define MSG_UBL_FILLIN_AMOUNT _UxGT("Заполнить значения") +#define MSG_UBL_MANUAL_FILLIN _UxGT("Ручное заполнение") +#define MSG_UBL_SMART_FILLIN _UxGT("Уменое заполнение") +#define MSG_UBL_FILLIN_MESH _UxGT("Заполнить сетку") +#define MSG_UBL_INVALIDATE_ALL _UxGT("Аннулировать всё") +#define MSG_UBL_STORAGE_MESH_MENU _UxGT("Хранилище сетей") +#define MSG_UBL_STORAGE_SLOT _UxGT("Слот памяти") +#define MSG_UBL_RESTORE_ERROR _UxGT("Ошибка: Загрузки UBL") +#define MSG_UBL_STEP_BY_STEP_MENU _UxGT("Пошаговый UBL") +#define MSG_MOVING _UxGT("Движемся...") +#define MSG_FREE_XY _UxGT("Освобождаем XY") #define MSG_MOVE_X _UxGT("Движение по X") #define MSG_MOVE_Y _UxGT("Движение по Y") #define MSG_MOVE_Z _UxGT("Движение по Z") @@ -90,15 +137,18 @@ #define MSG_PID_I _UxGT("PID-I") #define MSG_PID_D _UxGT("PID-D") #define MSG_PID_C _UxGT("PID-C") -#define MSG_ACC _UxGT("Acc") +#define MSG_SELECT _UxGT("Выбор") +#define MSG_ACC _UxGT("Ускорение") #define MSG_JERK _UxGT("Рывок") #define MSG_VX_JERK _UxGT("Vx-рывок") #define MSG_VY_JERK _UxGT("Vy-рывок") #define MSG_VZ_JERK _UxGT("Vz-рывок") #define MSG_VE_JERK _UxGT("Ve-рывок") +#define MSG_VELOCITY _UxGT("Скорость") #define MSG_VMAX _UxGT("Vмакс ") #define MSG_VMIN _UxGT("Vмин") #define MSG_VTRAV_MIN _UxGT("Vпутеш. мин") +#define MSG_ACCELERATION _UxGT("Ускорение") #define MSG_AMAX _UxGT("Aмакс") #define MSG_A_RETRACT _UxGT("A-втягивание") #define MSG_A_TRAVEL _UxGT("A-путеш.") @@ -111,11 +161,13 @@ #define MSG_E2STEPS _UxGT("E2 шаг/мм") #define MSG_E3STEPS _UxGT("E3 шаг/мм") #define MSG_E4STEPS _UxGT("E4 шаг/мм") +#define MSG_E5STEPS _UxGT("E5 шаг/мм") #define MSG_TEMPERATURE _UxGT("Температура") #define MSG_MOTION _UxGT("Механика") #define MSG_FILAMENT _UxGT("Пруток") #define MSG_VOLUMETRIC_ENABLED _UxGT("E в mm3") #define MSG_FILAMENT_DIAM _UxGT("Диаметр прутка") +#define MSG_ADVANCE_K _UxGT("K продвижения") #define MSG_CONTRAST _UxGT("Контраст LCD") #define MSG_STORE_EEPROM _UxGT("Сохранить в EEPROM") #define MSG_LOAD_EEPROM _UxGT("Считать из EEPROM") @@ -130,7 +182,7 @@ #define MSG_CARD_MENU _UxGT("Обзор карты") #define MSG_NO_CARD _UxGT("Нет карты") #define MSG_DWELL _UxGT("Сон...") -#define MSG_USERWAIT _UxGT("Ожиданиие") +#define MSG_PRINT_PAUSED _UxGT("Печать остановлена") #define MSG_RESUMING _UxGT("Возобновление...") #define MSG_PRINT_ABORTED _UxGT("Отмена печати") #define MSG_NO_MOVE _UxGT("Нет движения.") @@ -148,7 +200,12 @@ #define MSG_INIT_SDCARD _UxGT("Иниц. карту") #define MSG_CNG_SDCARD _UxGT("Сменить карту") #define MSG_ZPROBE_OUT _UxGT("Z датчик вне стола") -#define MSG_HOME _UxGT("Паркуй X/Y перед Z") +#define MSG_BLTOUCH _UxGT("BLTouch") +#define MSG_BLTOUCH_SELFTEST _UxGT("Тестирование BLTouch") +#define MSG_BLTOUCH_RESET _UxGT("Сброс BLTouch") +#define MSG_BLTOUCH_DEPLOY _UxGT("Установка BLTouch") +#define MSG_BLTOUCH_STOW _UxGT("Набивка BLTouch") +#define MSG_HOME _UxGT("Паркуй") #define MSG_FIRST _UxGT("первый") #define MSG_ZPROBE_ZOFFSET _UxGT("Смещение Z") #define MSG_BABYSTEP_X _UxGT("Микрошаг X") @@ -156,12 +213,17 @@ #define MSG_BABYSTEP_Z _UxGT("Микрошаг Z") #define MSG_ENDSTOP_ABORT _UxGT("Сработал концевик") #define MSG_HEATING_FAILED_LCD _UxGT("Разогрев не удался") -#define MSG_ERR_REDUNDANT_TEMP _UxGT("Ошибка:Слишком горячо") #define MSG_THERMAL_RUNAWAY _UxGT("ТЕПЛО УБЕГАНИЯ!") #define MSG_ERR_MAXTEMP _UxGT("Ошибка: Т макс.") #define MSG_ERR_MINTEMP _UxGT("Ошибка: Т мин.") #define MSG_ERR_MAXTEMP_BED _UxGT("Ошибка:Т макс.стол") #define MSG_ERR_MINTEMP_BED _UxGT("Ошибка:Т мин.стол") +#define MSG_ERR_Z_HOMING _UxGT("G28 Z Запрещено") +#define MSG_HALTED _UxGT("ПРИНТЕР ОСТАНОВЛЕН") +#define MSG_PLEASE_RESET _UxGT("Нажмите ресет") +#define MSG_SHORT_DAY _UxGT("д") // One character only +#define MSG_SHORT_HOUR _UxGT("ч") // One character only +#define MSG_SHORT_MINUTE _UxGT("м") // One character only #define MSG_HEATING _UxGT("Нагреваю сопло...") #define MSG_HEATING_COMPLETE _UxGT("Нагрев выполнен") #define MSG_BED_HEATING _UxGT("Нагреваю стол") @@ -171,5 +233,64 @@ #define MSG_DELTA_CALIBRATE_Y _UxGT("Калибровать Y") #define MSG_DELTA_CALIBRATE_Z _UxGT("Калибровать Z") #define MSG_DELTA_CALIBRATE_CENTER _UxGT("Калибровать центр") +#define MSG_DELTA_AUTO_CALIBRATE _UxGT("Авто калибровка") +#define MSG_DELTA_HEIGHT_CALIBRATE _UxGT("Задать высоту Delta") +#define MSG_INFO_MENU _UxGT("О принтере") +#define MSG_INFO_STATS_MENU _UxGT("Статистика принтера") +#define MSG_INFO_THERMISTOR_MENU _UxGT("Термисторы") +#define MSG_INFO_EXTRUDERS _UxGT("Экструдеры") +#define MSG_INFO_BAUDRATE _UxGT("Бод") +#define MSG_INFO_PROTOCOL _UxGT("Протокол") +#define MSG_CASE_LIGHT _UxGT("Корпусное освещение") +#define MSG_CASE_LIGHT_BRIGHTNESS _UxGT("Яркость освещения") +#if LCD_WIDTH >= 20 + #define MSG_INFO_COMPLETED_PRINTS _UxGT("Закончено") + #define MSG_INFO_PRINT_TIME _UxGT("Полное время печати") + #define MSG_INFO_PRINT_FILAMENT _UxGT("Длинна филамента") +#else + #define MSG_INFO_PRINT_COUNT _UxGT("Отпечатков") + #define MSG_INFO_COMPLETED_PRINTS _UxGT("Закончено") + #define MSG_INFO_PRINT_TIME _UxGT("Всего") + #define MSG_INFO_PRINT_LONGEST _UxGT("Наибольшее") + #define MSG_INFO_PRINT_FILAMENT _UxGT("Выдавлено") +#endif +#define MSG_INFO_PSU _UxGT("Блок питания") +#define MSG_DRIVE_STRENGTH _UxGT("Сила привода") +#define MSG_DAC_PERCENT _UxGT("Привод %") +#define MSG_DAC_EEPROM_WRITE _UxGT("Записи DAC EEPROM") +#define MSG_FILAMENT_CHANGE_HEADER _UxGT("ПЕЧАТЬ ОСТАНОВЛЕНА") +#define MSG_FILAMENT_CHANGE_OPTION_EXTRUDE _UxGT("Выдавить ещё") +#define MSG_FILAMENT_CHANGE_OPTION_RESUME _UxGT("Возобновить печать") +#define MSG_FILAMENT_CHANGE_NOZZLE _UxGT(" Сопла: ") +// +// Filament Change screens show up to 3 lines on a 4-line display +// ...or up to 2 lines on a 3-line display +// +#if LCD_HEIGHT >= 4 + #define MSG_FILAMENT_CHANGE_INIT_1 _UxGT("Ожидайте") + #define MSG_FILAMENT_CHANGE_INIT_2 _UxGT("начала смены") + #define MSG_FILAMENT_CHANGE_INIT_3 _UxGT("филамента") + #define MSG_FILAMENT_CHANGE_UNLOAD_1 _UxGT("Ожидайте") + #define MSG_FILAMENT_CHANGE_UNLOAD_2 _UxGT("выгрузки филамента") + #define MSG_FILAMENT_CHANGE_INSERT_1 _UxGT("Вставьте филамент") + #define MSG_FILAMENT_CHANGE_INSERT_2 _UxGT("и нажмите кнопку") + #define MSG_FILAMENT_CHANGE_INSERT_3 _UxGT("для продолжения...") + #define MSG_FILAMENT_CHANGE_HEAT_1 _UxGT("Нажмите кнопку для") + #define MSG_FILAMENT_CHANGE_HEAT_2 _UxGT("нагрева сопла...") + #define MSG_FILAMENT_CHANGE_HEATING_1 _UxGT("Нагрев сопла") + #define MSG_FILAMENT_CHANGE_HEATING_2 _UxGT("Ждите...") + #define MSG_FILAMENT_CHANGE_LOAD_1 _UxGT("Ожидайте") + #define MSG_FILAMENT_CHANGE_LOAD_2 _UxGT("загрузки филамента") + #define MSG_FILAMENT_CHANGE_RESUME_1 _UxGT("Ожидайте") + #define MSG_FILAMENT_CHANGE_RESUME_2 _UxGT("возобновления") +#else // LCD_HEIGHT < 4 + #define MSG_FILAMENT_CHANGE_INIT_1 _UxGT("Ожидайте...") + #define MSG_FILAMENT_CHANGE_UNLOAD_1 _UxGT("Выгрузка...") + #define MSG_FILAMENT_CHANGE_INSERT_1 _UxGT("Вставь и нажми") + #define MSG_FILAMENT_CHANGE_HEATING_1 _UxGT("Нагрев...") + #define MSG_FILAMENT_CHANGE_LOAD_1 _UxGT("Загрузка...") + #define MSG_FILAMENT_CHANGE_EXTRUDE_1 _UxGT("Выдавливание...") + #define MSG_FILAMENT_CHANGE_RESUME_1 _UxGT("Возобновление...") +#endif // LCD_HEIGHT < 4 #endif // LANGUAGE_RU_H From a059e95463b4a3b232572eb5f0a3772b36a59b1b Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 21 Jul 2017 20:43:10 -0500 Subject: [PATCH 033/112] Bring Infitary i3 config up to date --- .../Infitary/i3-M508/Configuration.h | 76 ++++++++++++++----- 1 file changed, 57 insertions(+), 19 deletions(-) diff --git a/Marlin/example_configurations/Infitary/i3-M508/Configuration.h b/Marlin/example_configurations/Infitary/i3-M508/Configuration.h index 10bf51ee9..eadfa6a4d 100644 --- a/Marlin/example_configurations/Infitary/i3-M508/Configuration.h +++ b/Marlin/example_configurations/Infitary/i3-M508/Configuration.h @@ -58,15 +58,15 @@ //=========================================================================== //============================= DELTA Printer =============================== //=========================================================================== -// For a Delta printer replace the configuration files with the files in the -// example_configurations/delta directory. +// For a Delta printer start with one of the configuration files in the +// example_configurations/delta directory and customize for your machine. // //=========================================================================== //============================= SCARA Printer =============================== //=========================================================================== -// For a Scara printer replace the configuration files with the files in the -// example_configurations/SCARA directory. +// For a SCARA printer start with the configuration files in +// example_configurations/SCARA and customize for your machine. // // @section info @@ -138,11 +138,33 @@ // For Cyclops or any "multi-extruder" that shares a single nozzle. //#define SINGLENOZZLE +/** + * Průša MK2 Single Nozzle Multi-Material Multiplexer, and variants. + * + * This device allows one stepper driver on a control board to drive + * two to eight stepper motors, one at a time, in a manner suitable + * for extruders. + * + * This option only allows the multiplexer to switch on tool-change. + * Additional options to configure custom E moves are pending. + */ +//#define MK2_MULTIPLEXER +#if ENABLED(MK2_MULTIPLEXER) + // Override the default DIO selector pins here, if needed. + // Some pins files may provide defaults for these pins. + //#define E_MUX0_PIN 40 // Always Required + //#define E_MUX1_PIN 42 // Needed for 3 to 8 steppers + //#define E_MUX2_PIN 44 // Needed for 5 to 8 steppers +#endif + // A dual extruder that uses a single stepper motor //#define SWITCHING_EXTRUDER #if ENABLED(SWITCHING_EXTRUDER) #define SWITCHING_EXTRUDER_SERVO_NR 0 - #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 + #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1[, E2, E3] + #if EXTRUDERS > 3 + #define SWITCHING_EXTRUDER_E23_SERVO_NR 1 + #endif #endif // A dual-nozzle that uses a servomotor to raise/lower one of the nozzles @@ -312,6 +334,7 @@ #define K1 0.95 //smoothing factor within the PID // If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it + // Ultimaker //#define DEFAULT_Kp 22.2 //#define DEFAULT_Ki 1.08 @@ -569,7 +592,6 @@ * */ //#define Z_MIN_PROBE_ENDSTOP -//#define Z_MIN_PROBE_PIN Z_MAX_PIN /** * Probe Type @@ -884,12 +906,14 @@ #define UBL_MESH_INSET 1 // Mesh inset margin on print area #define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited. #define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X - #define UBL_PROBE_PT_1_X 39 // These set the probe locations for when UBL does a 3-Point leveling - #define UBL_PROBE_PT_1_Y 180 // of the mesh. + + #define UBL_PROBE_PT_1_X 39 // Probing points for 3-Point leveling of the mesh + #define UBL_PROBE_PT_1_Y 180 #define UBL_PROBE_PT_2_X 39 #define UBL_PROBE_PT_2_Y 20 #define UBL_PROBE_PT_3_X 180 #define UBL_PROBE_PT_3_Y 20 + #define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation #define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle @@ -971,11 +995,8 @@ // M502 - reverts to the default "factory settings". You still need to store them in EEPROM afterwards if you want to. // //#define EEPROM_SETTINGS // Enable for M500 and M501 commands - -#if ENABLED(EEPROM_SETTINGS) - // To disable EEPROM Serial responses and decrease program space by ~1700 byte: comment this out: - #define EEPROM_CHITCHAT // Please keep turned on if you can. -#endif +//#define DISABLE_M503 // Saves ~2700 bytes of PROGMEM. Disable for release! +#define EEPROM_CHITCHAT // Give feedback on EEPROM commands. Disable to save PROGMEM. // // Host Keepalive @@ -1135,10 +1156,11 @@ * * Select the language to display on the LCD. These 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, tr, uk, test + * en, an, bg, ca, cn, cz, cz_utf8, 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, tr, uk, + * zh_CN, zh_TW, 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' } + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } */ #define LCD_LANGUAGE en @@ -1160,7 +1182,7 @@ * - Click the controller to view the LCD menu * - The LCD will display Japanese, Western, or Cyrillic text * - * See https: *github.com/MarlinFirmware/Marlin/wiki/LCD-Language + * See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language * * :['JAPANESE', 'WESTERN', 'CYRILLIC'] */ @@ -1374,6 +1396,16 @@ // //#define BQ_LCD_SMART_CONTROLLER +// +// ANET_10 Controller supported displays. +// +//#define ANET_KEYPAD_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin. + // This LCD is known to be susceptible to electrical interference + // which scrambles the display. Pressing any button clears it up. +//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6 + // A clone of the RepRapDiscount full graphics display but with + // different pins/wiring (see pins_ANET_10.h). + // // LCD for Melzi Card with Graphical LCD // @@ -1395,6 +1427,9 @@ // // Sainsmart YW Robot (LCM1602) LCD Display // +// Note: This controller requires F.Malpartida's LiquidCrystal_I2C library +// https://bitbucket.org/fmalpartida/new-liquidcrystal/wiki/Home +// //#define LCD_I2C_SAINSMART_YWROBOT // @@ -1485,12 +1520,15 @@ // SkeinForge sends the wrong arc g-codes when using Arc Point as fillet procedure //#define SF_ARC_FIX -// Support for the BariCUDA Paste Extruder. +// Support for the BariCUDA Paste Extruder //#define BARICUDA -//define BlinkM/CyzRgb Support +// Support for BlinkM/CyzRgb //#define BLINKM +// Support for PCA9632 PWM LED driver +//#define PCA9632 + /** * RGB LED / LED Strip Control * From 890e7a16a93241fae148e2647edf5e2c1e15017a Mon Sep 17 00:00:00 2001 From: "C. Scott Ananian" Date: Thu, 13 Jul 2017 11:01:21 -0400 Subject: [PATCH 034/112] Add support for Printrbot Neopixel RGBW strip. Connected as described at http://printrbot.com/shop/led-strip/ Based on patch by Kelly Anderson at http://www.xilka.com/printrbot/marlin/1.1.4/20170707/ --- .travis.yml | 5 ++ Marlin/Conditionals_LCD.h | 2 +- Marlin/Configuration.h | 10 ++- Marlin/Makefile | 6 ++ Marlin/Marlin_main.cpp | 83 +++++++++++++++++-- Marlin/SanityCheck.h | 8 +- .../AlephObjects/TAZ4/Configuration.h | 10 ++- .../AliExpress/CL-260/Configuration.h | 10 ++- .../Anet/A6/Configuration.h | 10 ++- .../Anet/A8/Configuration.h | 10 ++- .../BQ/Hephestos/Configuration.h | 10 ++- .../BQ/Hephestos_2/Configuration.h | 10 ++- .../BQ/WITBOX/Configuration.h | 10 ++- .../Cartesio/Configuration.h | 10 ++- .../Creality/CR-10/Configuration.h | 10 ++- .../Felix/Configuration.h | 10 ++- .../Felix/DUAL/Configuration.h | 10 ++- .../Folger Tech/i3-2020/Configuration.h | 10 ++- .../Infitary/i3-M508/Configuration.h | 10 ++- .../Malyan/M150/Configuration.h | 10 ++- .../RepRapWorld/Megatronics/Configuration.h | 10 ++- .../RigidBot/Configuration.h | 10 ++- .../SCARA/Configuration.h | 10 ++- .../TinyBoy2/Configuration.h | 10 ++- .../Velleman/K8200/Configuration.h | 10 ++- .../Velleman/K8400/Configuration.h | 10 ++- .../Velleman/K8400/Dual-head/Configuration.h | 10 ++- .../adafruit/ST7565/Configuration.h | 10 ++- .../FLSUN/auto_calibrate/Configuration.h | 10 ++- .../delta/FLSUN/kossel_mini/Configuration.h | 10 ++- .../delta/generic/Configuration.h | 10 ++- .../delta/kossel_mini/Configuration.h | 10 ++- .../delta/kossel_pro/Configuration.h | 10 ++- .../delta/kossel_xl/Configuration.h | 10 ++- .../gCreate/gMax1.5+/Configuration.h | 10 ++- .../makibox/Configuration.h | 10 ++- .../tvrrug/Round2/Configuration.h | 10 ++- .../wt150/Configuration.h | 10 ++- 38 files changed, 392 insertions(+), 42 deletions(-) diff --git a/.travis.yml b/.travis.yml index f3ccc3247..370b4ea26 100644 --- a/.travis.yml +++ b/.travis.yml @@ -50,6 +50,10 @@ install: - git clone https://github.com/teemuatlut/TMC2130Stepper.git - sudo mv TMC2130Stepper /usr/local/share/arduino/libraries/TMC2130Stepper # + # Install: Adafruit Neopixel library + - git clone https://github.com/adafruit/Adafruit_NeoPixel.git + - sudo mv Adafruit_NeoPixel /usr/local/share/arduino/libraries/Adafruit_NeoPixel + # before_script: # # Change current working directory to the build dir @@ -80,6 +84,7 @@ script: - opt_set TEMP_SENSOR_1 1 - opt_set TEMP_SENSOR_BED 1 - opt_enable PIDTEMPBED FIX_MOUNTED_PROBE Z_SAFE_HOMING ARC_P_CIRCLES CNC_WORKSPACE_PLANES + - opt_enable BLINKM PCA9632 RGB_LED NEOPIXEL_RGBW_LED - build_marlin # # ...with AUTO_BED_LEVELING_LINEAR, Z_MIN_PROBE_REPEATABILITY_TEST, and DEBUG_LEVELING_FEATURE diff --git a/Marlin/Conditionals_LCD.h b/Marlin/Conditionals_LCD.h index 63be06202..914ef51a6 100644 --- a/Marlin/Conditionals_LCD.h +++ b/Marlin/Conditionals_LCD.h @@ -430,6 +430,6 @@ #define HAS_SOFTWARE_ENDSTOPS (ENABLED(MIN_SOFTWARE_ENDSTOPS) || ENABLED(MAX_SOFTWARE_ENDSTOPS)) #define HAS_RESUME_CONTINUE (ENABLED(NEWPANEL) || ENABLED(EMERGENCY_PARSER)) - #define HAS_COLOR_LEDS (ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632)) + #define HAS_COLOR_LEDS (ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_RGBW_LED)) #endif // CONDITIONALS_LCD_H diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 08e495e96..b62f5827f 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -1551,6 +1551,14 @@ #define RGB_LED_W_PIN -1 #endif +// Support for Adafruit Neopixel LED driver +//#define NEOPIXEL_RGBW_LED +#if ENABLED(NEOPIXEL_RGBW_LED) + #define NEOPIXEL_PIN 4 // D4 (EXP2-5 on Printrboard) + #define NEOPIXEL_PIXELS 3 + //#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup +#endif + /** * Printer Event LEDs * @@ -1562,7 +1570,7 @@ * - Change to green once print has finished * - Turn off after the print has finished and the user has pushed a button */ -#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) +#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_RGBW_LED) #define PRINTER_EVENT_LEDS #endif diff --git a/Marlin/Makefile b/Marlin/Makefile index cabcf3000..eb6ea73b1 100644 --- a/Marlin/Makefile +++ b/Marlin/Makefile @@ -270,6 +270,9 @@ ifeq ($(WIRE), 1) VPATH += $(ARDUINO_INSTALL_DIR)/libraries/Wire VPATH += $(ARDUINO_INSTALL_DIR)/libraries/Wire/utility endif +ifeq ($(NEOPIXEL), 1) +VPATH += $(ARDUINO_INSTALL_DIR)/libraries/Adafruit_NeoPixel +endif ifeq ($(HARDWARE_VARIANT), arduino) HARDWARE_SUB_VARIANT ?= mega @@ -297,6 +300,9 @@ CXXSRC = WMath.cpp WString.cpp Print.cpp Marlin_main.cpp \ watchdog.cpp SPI.cpp servo.cpp Tone.cpp ultralcd.cpp digipot_mcp4451.cpp \ dac_mcp4728.cpp vector_3.cpp least_squares_fit.cpp endstops.cpp stopwatch.cpp utility.cpp \ printcounter.cpp nozzle.cpp serial.cpp +ifeq ($(NEOPIXEL), 1) +CXXSRC += Adafruit_NeoPixel.cpp +endif ifeq ($(LIQUID_TWI2), 0) CXXSRC += LiquidCrystal.cpp else diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 6fa2f144a..5af9537d1 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -279,6 +279,10 @@ #include "watchdog.h" #endif +#if ENABLED(NEOPIXEL_RGBW_LED) + #include +#endif + #if ENABLED(BLINKM) #include "blinkm.h" #include "Wire.h" @@ -968,13 +972,61 @@ void servo_init() { #if HAS_COLOR_LEDS + #if ENABLED(NEOPIXEL_RGBW_LED) + + Adafruit_NeoPixel pixels(NEOPIXEL_PIXELS, NEOPIXEL_PIN, NEO_GRBW + NEO_KHZ800); + + void set_neopixel_color(const uint32_t color) { + for (uint16_t i = 0; i < pixels.numPixels(); ++i) + pixels.setPixelColor(i, color); + pixels.show(); + } + + void setup_neopixel() { + pixels.setBrightness(255); // 0 - 255 range + pixels.begin(); + pixels.show(); // initialize to all off + + #if ENABLED(NEOPIXEL_STARTUP_TEST) + delay(2000); + set_neopixel_color(pixels.Color(255, 0, 0, 0)); // red + delay(2000); + set_neopixel_color(pixels.Color(0, 255, 0, 0)); // green + delay(2000); + set_neopixel_color(pixels.Color(0, 0, 255, 0)); // blue + delay(2000); + #endif + set_neopixel_color(pixels.Color(0, 0, 0, 255)); // white + } + + #endif // NEOPIXEL_RGBW_LED + void set_led_color( const uint8_t r, const uint8_t g, const uint8_t b - #if ENABLED(RGBW_LED) - , const uint8_t w=0 + #if ENABLED(RGBW_LED) || ENABLED(NEOPIXEL_RGBW_LED) + , const uint8_t w = 0 + #if ENABLED(NEOPIXEL_RGBW_LED) + , bool isSequence = false + #endif #endif ) { + #if ENABLED(NEOPIXEL_RGBW_LED) + + const uint32_t color = pixels.Color(r, g, b, w); + static int nextLed = 0; + + if (!isSequence) + set_neopixel_color(color); + else { + pixels.setPixelColor(nextLed, color); + pixels.show(); + if (++nextLed >= pixels.numPixels()) nextLed = 0; + return; + } + + #endif + #if ENABLED(BLINKM) // This variant uses i2c to send the RGB components to the device. @@ -7355,7 +7407,14 @@ inline void gcode_M109() { // Gradually change LED strip from violet to red as nozzle heats up if (!wants_to_cool) { const uint8_t blue = map(constrain(temp, start_temp, target_temp), start_temp, target_temp, 255, 0); - if (blue != old_blue) set_led_color(255, 0, (old_blue = blue)); + if (blue != old_blue) { + old_blue = blue; + set_led_color(255, 0, blue + #if ENABLED(NEOPIXEL_RGBW_LED) + , 0, true + #endif + ); + } } #endif @@ -7390,7 +7449,7 @@ inline void gcode_M109() { if (wait_for_heatup) { LCD_MESSAGEPGM(MSG_HEATING_COMPLETE); #if ENABLED(PRINTER_EVENT_LEDS) - #if ENABLED(RGBW_LED) + #if ENABLED(RGBW_LED) || ENABLED(NEOPIXEL_RGBW_LED) set_led_color(0, 0, 0, 255); // Turn on the WHITE LED #else set_led_color(255, 255, 255); // Set LEDs All On @@ -7488,7 +7547,14 @@ inline void gcode_M109() { // Gradually change LED strip from blue to violet as bed heats up if (!wants_to_cool) { const uint8_t red = map(constrain(temp, start_temp, target_temp), start_temp, target_temp, 0, 255); - if (red != old_red) set_led_color((old_red = red), 0, 255); + if (red != old_red) { + old_red = red; + set_led_color(red, 0, 255 + #if ENABLED(NEOPIXEL_RGBW_LED) + , 0, true + #endif + ); + } } #endif @@ -8146,7 +8212,7 @@ inline void gcode_M121() { endstops.enable_globally(false); } parser.seen('R') ? (parser.has_value() ? parser.value_byte() : 255) : 0, parser.seen('U') ? (parser.has_value() ? parser.value_byte() : 255) : 0, parser.seen('B') ? (parser.has_value() ? parser.value_byte() : 255) : 0 - #if ENABLED(RGBW_LED) + #if ENABLED(RGBW_LED) || ENABLED(NEOPIXEL_RGBW_LED) , parser.seen('W') ? (parser.has_value() ? parser.value_byte() : 255) : 0 #endif ); @@ -13072,6 +13138,11 @@ void setup() { OUT_WRITE(STAT_LED_BLUE_PIN, LOW); // turn it off #endif + #if ENABLED(NEOPIXEL_RGBW_LED) + SET_OUTPUT(NEOPIXEL_PIN); + setup_neopixel(); + #endif + #if ENABLED(RGB_LED) || ENABLED(RGBW_LED) SET_OUTPUT(RGB_LED_R_PIN); SET_OUTPUT(RGB_LED_G_PIN); diff --git a/Marlin/SanityCheck.h b/Marlin/SanityCheck.h index df8bdea5f..dcd6ba1d5 100644 --- a/Marlin/SanityCheck.h +++ b/Marlin/SanityCheck.h @@ -1056,8 +1056,12 @@ static_assert(1 >= 0 #if !(_RGB_TEST && PIN_EXISTS(RGB_LED_W)) #error "RGBW_LED requires RGB_LED_R_PIN, RGB_LED_G_PIN, RGB_LED_B_PIN, and RGB_LED_W_PIN." #endif -#elif ENABLED(PRINTER_EVENT_LEDS) && DISABLED(BLINKM) && DISABLED(PCA9632) - #error "PRINTER_EVENT_LEDS requires BLINKM, PCA9632, RGB_LED, or RGBW_LED." +#elif ENABLED(NEOPIXEL_RGBW_LED) + #if !(PIN_EXISTS(NEOPIXEL) && NEOPIXEL_PIXELS > 0) + #error "NEOPIXEL_RGBW_LED requires NEOPIXEL_PIN and NEOPIXEL_PIXELS." + #endif +#elif ENABLED(PRINTER_EVENT_LEDS) && DISABLED(BLINKM) && DISABLED(PCA9632) && DISABLED(NEOPIXEL_RGBW_LED) + #error "PRINTER_EVENT_LEDS requires BLINKM, PCA9632, RGB_LED, RGBW_LED or NEOPIXEL_RGBW_LED." #endif /** diff --git a/Marlin/example_configurations/AlephObjects/TAZ4/Configuration.h b/Marlin/example_configurations/AlephObjects/TAZ4/Configuration.h index 43b52cdb6..e32b57c58 100644 --- a/Marlin/example_configurations/AlephObjects/TAZ4/Configuration.h +++ b/Marlin/example_configurations/AlephObjects/TAZ4/Configuration.h @@ -1566,6 +1566,14 @@ #define RGB_LED_W_PIN -1 #endif +// Support for Adafruit Neopixel LED driver +//#define NEOPIXEL_RGBW_LED +#if ENABLED(NEOPIXEL_RGBW_LED) + #define NEOPIXEL_PIN 4 // D4 (EXP2-5 on Printrboard) + #define NEOPIXEL_PIXELS 3 + //#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup +#endif + /** * Printer Event LEDs * @@ -1577,7 +1585,7 @@ * - Change to green once print has finished * - Turn off after the print has finished and the user has pushed a button */ -#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) +#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_RGBW_LED) #define PRINTER_EVENT_LEDS #endif diff --git a/Marlin/example_configurations/AliExpress/CL-260/Configuration.h b/Marlin/example_configurations/AliExpress/CL-260/Configuration.h index e72d15b5a..769de81ee 100644 --- a/Marlin/example_configurations/AliExpress/CL-260/Configuration.h +++ b/Marlin/example_configurations/AliExpress/CL-260/Configuration.h @@ -1548,6 +1548,14 @@ #define RGB_LED_W_PIN -1 #endif +// Support for Adafruit Neopixel LED driver +//#define NEOPIXEL_RGBW_LED +#if ENABLED(NEOPIXEL_RGBW_LED) + #define NEOPIXEL_PIN 4 // D4 (EXP2-5 on Printrboard) + #define NEOPIXEL_PIXELS 3 + //#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup +#endif + /** * Printer Event LEDs * @@ -1559,7 +1567,7 @@ * - Change to green once print has finished * - Turn off after the print has finished and the user has pushed a button */ -#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) +#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_RGBW_LED) #define PRINTER_EVENT_LEDS #endif diff --git a/Marlin/example_configurations/Anet/A6/Configuration.h b/Marlin/example_configurations/Anet/A6/Configuration.h index 93a0ba564..550fd9953 100644 --- a/Marlin/example_configurations/Anet/A6/Configuration.h +++ b/Marlin/example_configurations/Anet/A6/Configuration.h @@ -1709,6 +1709,14 @@ #define RGB_LED_W_PIN -1 #endif +// Support for Adafruit Neopixel LED driver +//#define NEOPIXEL_RGBW_LED +#if ENABLED(NEOPIXEL_RGBW_LED) + #define NEOPIXEL_PIN 4 // D4 (EXP2-5 on Printrboard) + #define NEOPIXEL_PIXELS 3 + //#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup +#endif + /** * Printer Event LEDs * @@ -1720,7 +1728,7 @@ * - Change to green once print has finished * - Turn off after the print has finished and the user has pushed a button */ -#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) +#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_RGBW_LED) #define PRINTER_EVENT_LEDS #endif diff --git a/Marlin/example_configurations/Anet/A8/Configuration.h b/Marlin/example_configurations/Anet/A8/Configuration.h index cf307c20a..d5aadbf2a 100644 --- a/Marlin/example_configurations/Anet/A8/Configuration.h +++ b/Marlin/example_configurations/Anet/A8/Configuration.h @@ -1558,6 +1558,14 @@ #define RGB_LED_W_PIN -1 #endif +// Support for Adafruit Neopixel LED driver +//#define NEOPIXEL_RGBW_LED +#if ENABLED(NEOPIXEL_RGBW_LED) + #define NEOPIXEL_PIN 4 // D4 (EXP2-5 on Printrboard) + #define NEOPIXEL_PIXELS 3 + //#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup +#endif + /** * Printer Event LEDs * @@ -1569,7 +1577,7 @@ * - Change to green once print has finished * - Turn off after the print has finished and the user has pushed a button */ -#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) +#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_RGBW_LED) #define PRINTER_EVENT_LEDS #endif diff --git a/Marlin/example_configurations/BQ/Hephestos/Configuration.h b/Marlin/example_configurations/BQ/Hephestos/Configuration.h index c1501dbc2..e55858200 100644 --- a/Marlin/example_configurations/BQ/Hephestos/Configuration.h +++ b/Marlin/example_configurations/BQ/Hephestos/Configuration.h @@ -1537,6 +1537,14 @@ #define RGB_LED_W_PIN -1 #endif +// Support for Adafruit Neopixel LED driver +//#define NEOPIXEL_RGBW_LED +#if ENABLED(NEOPIXEL_RGBW_LED) + #define NEOPIXEL_PIN 4 // D4 (EXP2-5 on Printrboard) + #define NEOPIXEL_PIXELS 3 + //#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup +#endif + /** * Printer Event LEDs * @@ -1548,7 +1556,7 @@ * - Change to green once print has finished * - Turn off after the print has finished and the user has pushed a button */ -#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) +#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_RGBW_LED) #define PRINTER_EVENT_LEDS #endif diff --git a/Marlin/example_configurations/BQ/Hephestos_2/Configuration.h b/Marlin/example_configurations/BQ/Hephestos_2/Configuration.h index 33d609654..39af4832d 100644 --- a/Marlin/example_configurations/BQ/Hephestos_2/Configuration.h +++ b/Marlin/example_configurations/BQ/Hephestos_2/Configuration.h @@ -1548,6 +1548,14 @@ #define RGB_LED_W_PIN -1 #endif +// Support for Adafruit Neopixel LED driver +//#define NEOPIXEL_RGBW_LED +#if ENABLED(NEOPIXEL_RGBW_LED) + #define NEOPIXEL_PIN 4 // D4 (EXP2-5 on Printrboard) + #define NEOPIXEL_PIXELS 3 + //#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup +#endif + /** * Printer Event LEDs * @@ -1559,7 +1567,7 @@ * - Change to green once print has finished * - Turn off after the print has finished and the user has pushed a button */ -#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) +#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_RGBW_LED) #define PRINTER_EVENT_LEDS #endif diff --git a/Marlin/example_configurations/BQ/WITBOX/Configuration.h b/Marlin/example_configurations/BQ/WITBOX/Configuration.h index 97b628a5f..6984a9be1 100644 --- a/Marlin/example_configurations/BQ/WITBOX/Configuration.h +++ b/Marlin/example_configurations/BQ/WITBOX/Configuration.h @@ -1537,6 +1537,14 @@ #define RGB_LED_W_PIN -1 #endif +// Support for Adafruit Neopixel LED driver +//#define NEOPIXEL_RGBW_LED +#if ENABLED(NEOPIXEL_RGBW_LED) + #define NEOPIXEL_PIN 4 // D4 (EXP2-5 on Printrboard) + #define NEOPIXEL_PIXELS 3 + //#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup +#endif + /** * Printer Event LEDs * @@ -1548,7 +1556,7 @@ * - Change to green once print has finished * - Turn off after the print has finished and the user has pushed a button */ -#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) +#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_RGBW_LED) #define PRINTER_EVENT_LEDS #endif diff --git a/Marlin/example_configurations/Cartesio/Configuration.h b/Marlin/example_configurations/Cartesio/Configuration.h index e086f3c96..91c8d6bf7 100644 --- a/Marlin/example_configurations/Cartesio/Configuration.h +++ b/Marlin/example_configurations/Cartesio/Configuration.h @@ -1545,6 +1545,14 @@ #define RGB_LED_W_PIN -1 #endif +// Support for Adafruit Neopixel LED driver +//#define NEOPIXEL_RGBW_LED +#if ENABLED(NEOPIXEL_RGBW_LED) + #define NEOPIXEL_PIN 4 // D4 (EXP2-5 on Printrboard) + #define NEOPIXEL_PIXELS 3 + //#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup +#endif + /** * Printer Event LEDs * @@ -1556,7 +1564,7 @@ * - Change to green once print has finished * - Turn off after the print has finished and the user has pushed a button */ -#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) +#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_RGBW_LED) #define PRINTER_EVENT_LEDS #endif diff --git a/Marlin/example_configurations/Creality/CR-10/Configuration.h b/Marlin/example_configurations/Creality/CR-10/Configuration.h index caec496f9..535eec326 100644 --- a/Marlin/example_configurations/Creality/CR-10/Configuration.h +++ b/Marlin/example_configurations/Creality/CR-10/Configuration.h @@ -1562,6 +1562,14 @@ #define RGB_LED_W_PIN -1 #endif +// Support for Adafruit Neopixel LED driver +//#define NEOPIXEL_RGBW_LED +#if ENABLED(NEOPIXEL_RGBW_LED) + #define NEOPIXEL_PIN 4 // D4 (EXP2-5 on Printrboard) + #define NEOPIXEL_PIXELS 3 + //#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup +#endif + /** * Printer Event LEDs * @@ -1573,7 +1581,7 @@ * - Change to green once print has finished * - Turn off after the print has finished and the user has pushed a button */ -#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) +#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_RGBW_LED) #define PRINTER_EVENT_LEDS #endif diff --git a/Marlin/example_configurations/Felix/Configuration.h b/Marlin/example_configurations/Felix/Configuration.h index 3c83423fd..fd80205a7 100644 --- a/Marlin/example_configurations/Felix/Configuration.h +++ b/Marlin/example_configurations/Felix/Configuration.h @@ -1529,6 +1529,14 @@ #define RGB_LED_W_PIN -1 #endif +// Support for Adafruit Neopixel LED driver +//#define NEOPIXEL_RGBW_LED +#if ENABLED(NEOPIXEL_RGBW_LED) + #define NEOPIXEL_PIN 4 // D4 (EXP2-5 on Printrboard) + #define NEOPIXEL_PIXELS 3 + //#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup +#endif + /** * Printer Event LEDs * @@ -1540,7 +1548,7 @@ * - Change to green once print has finished * - Turn off after the print has finished and the user has pushed a button */ -#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) +#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_RGBW_LED) #define PRINTER_EVENT_LEDS #endif diff --git a/Marlin/example_configurations/Felix/DUAL/Configuration.h b/Marlin/example_configurations/Felix/DUAL/Configuration.h index 015398267..f1e5be4c3 100644 --- a/Marlin/example_configurations/Felix/DUAL/Configuration.h +++ b/Marlin/example_configurations/Felix/DUAL/Configuration.h @@ -1529,6 +1529,14 @@ #define RGB_LED_W_PIN -1 #endif +// Support for Adafruit Neopixel LED driver +//#define NEOPIXEL_RGBW_LED +#if ENABLED(NEOPIXEL_RGBW_LED) + #define NEOPIXEL_PIN 4 // D4 (EXP2-5 on Printrboard) + #define NEOPIXEL_PIXELS 3 + //#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup +#endif + /** * Printer Event LEDs * @@ -1540,7 +1548,7 @@ * - Change to green once print has finished * - Turn off after the print has finished and the user has pushed a button */ -#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) +#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_RGBW_LED) #define PRINTER_EVENT_LEDS #endif diff --git a/Marlin/example_configurations/Folger Tech/i3-2020/Configuration.h b/Marlin/example_configurations/Folger Tech/i3-2020/Configuration.h index 9efdf996f..151f76271 100644 --- a/Marlin/example_configurations/Folger Tech/i3-2020/Configuration.h +++ b/Marlin/example_configurations/Folger Tech/i3-2020/Configuration.h @@ -1551,6 +1551,14 @@ #define RGB_LED_W_PIN -1 #endif +// Support for Adafruit Neopixel LED driver +//#define NEOPIXEL_RGBW_LED +#if ENABLED(NEOPIXEL_RGBW_LED) + #define NEOPIXEL_PIN 4 // D4 (EXP2-5 on Printrboard) + #define NEOPIXEL_PIXELS 3 + //#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup +#endif + /** * Printer Event LEDs * @@ -1562,7 +1570,7 @@ * - Change to green once print has finished * - Turn off after the print has finished and the user has pushed a button */ -#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) +#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_RGBW_LED) #define PRINTER_EVENT_LEDS #endif diff --git a/Marlin/example_configurations/Infitary/i3-M508/Configuration.h b/Marlin/example_configurations/Infitary/i3-M508/Configuration.h index eadfa6a4d..f29594e42 100644 --- a/Marlin/example_configurations/Infitary/i3-M508/Configuration.h +++ b/Marlin/example_configurations/Infitary/i3-M508/Configuration.h @@ -1555,6 +1555,14 @@ #define RGB_LED_W_PIN -1 #endif +// Support for Adafruit Neopixel LED driver +//#define NEOPIXEL_RGBW_LED +#if ENABLED(NEOPIXEL_RGBW_LED) + #define NEOPIXEL_PIN 4 // D4 (EXP2-5 on Printrboard) + #define NEOPIXEL_PIXELS 3 + //#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup +#endif + /** * Printer Event LEDs * @@ -1566,7 +1574,7 @@ * - Change to green once print has finished * - Turn off after the print has finished and the user has pushed a button */ -#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) +#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_RGBW_LED) #define PRINTER_EVENT_LEDS #endif diff --git a/Marlin/example_configurations/Malyan/M150/Configuration.h b/Marlin/example_configurations/Malyan/M150/Configuration.h index d3d496eaa..ac3dcbaf9 100644 --- a/Marlin/example_configurations/Malyan/M150/Configuration.h +++ b/Marlin/example_configurations/Malyan/M150/Configuration.h @@ -1574,6 +1574,14 @@ #define RGB_LED_W_PIN -1 #endif +// Support for Adafruit Neopixel LED driver +//#define NEOPIXEL_RGBW_LED +#if ENABLED(NEOPIXEL_RGBW_LED) + #define NEOPIXEL_PIN 4 // D4 (EXP2-5 on Printrboard) + #define NEOPIXEL_PIXELS 3 + //#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup +#endif + /** * Printer Event LEDs * @@ -1585,7 +1593,7 @@ * - Change to green once print has finished * - Turn off after the print has finished and the user has pushed a button */ -#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) +#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_RGBW_LED) #define PRINTER_EVENT_LEDS #endif diff --git a/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h b/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h index c6234d659..f5f6eba19 100644 --- a/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h +++ b/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h @@ -1547,6 +1547,14 @@ #define RGB_LED_W_PIN -1 #endif +// Support for Adafruit Neopixel LED driver +//#define NEOPIXEL_RGBW_LED +#if ENABLED(NEOPIXEL_RGBW_LED) + #define NEOPIXEL_PIN 4 // D4 (EXP2-5 on Printrboard) + #define NEOPIXEL_PIXELS 3 + //#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup +#endif + /** * Printer Event LEDs * @@ -1558,7 +1566,7 @@ * - Change to green once print has finished * - Turn off after the print has finished and the user has pushed a button */ -#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) +#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_RGBW_LED) #define PRINTER_EVENT_LEDS #endif diff --git a/Marlin/example_configurations/RigidBot/Configuration.h b/Marlin/example_configurations/RigidBot/Configuration.h index f8c6e921b..6c3cb72d1 100644 --- a/Marlin/example_configurations/RigidBot/Configuration.h +++ b/Marlin/example_configurations/RigidBot/Configuration.h @@ -1547,6 +1547,14 @@ #define RGB_LED_W_PIN -1 #endif +// Support for Adafruit Neopixel LED driver +//#define NEOPIXEL_RGBW_LED +#if ENABLED(NEOPIXEL_RGBW_LED) + #define NEOPIXEL_PIN 4 // D4 (EXP2-5 on Printrboard) + #define NEOPIXEL_PIXELS 3 + //#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup +#endif + /** * Printer Event LEDs * @@ -1558,7 +1566,7 @@ * - Change to green once print has finished * - Turn off after the print has finished and the user has pushed a button */ -#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) +#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_RGBW_LED) #define PRINTER_EVENT_LEDS #endif diff --git a/Marlin/example_configurations/SCARA/Configuration.h b/Marlin/example_configurations/SCARA/Configuration.h index a12b3393f..71ab77c01 100644 --- a/Marlin/example_configurations/SCARA/Configuration.h +++ b/Marlin/example_configurations/SCARA/Configuration.h @@ -1559,6 +1559,14 @@ #define RGB_LED_W_PIN -1 #endif +// Support for Adafruit Neopixel LED driver +//#define NEOPIXEL_RGBW_LED +#if ENABLED(NEOPIXEL_RGBW_LED) + #define NEOPIXEL_PIN 4 // D4 (EXP2-5 on Printrboard) + #define NEOPIXEL_PIXELS 3 + //#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup +#endif + /** * Printer Event LEDs * @@ -1570,7 +1578,7 @@ * - Change to green once print has finished * - Turn off after the print has finished and the user has pushed a button */ -#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) +#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_RGBW_LED) #define PRINTER_EVENT_LEDS #endif diff --git a/Marlin/example_configurations/TinyBoy2/Configuration.h b/Marlin/example_configurations/TinyBoy2/Configuration.h index cbcd267b0..f41e8a87b 100644 --- a/Marlin/example_configurations/TinyBoy2/Configuration.h +++ b/Marlin/example_configurations/TinyBoy2/Configuration.h @@ -1608,6 +1608,14 @@ #define RGB_LED_W_PIN -1 #endif +// Support for Adafruit Neopixel LED driver +//#define NEOPIXEL_RGBW_LED +#if ENABLED(NEOPIXEL_RGBW_LED) + #define NEOPIXEL_PIN 4 // D4 (EXP2-5 on Printrboard) + #define NEOPIXEL_PIXELS 3 + //#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup +#endif + /** * Printer Event LEDs * @@ -1619,7 +1627,7 @@ * - Change to green once print has finished * - Turn off after the print has finished and the user has pushed a button */ -#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) +#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_RGBW_LED) #define PRINTER_EVENT_LEDS #endif diff --git a/Marlin/example_configurations/Velleman/K8200/Configuration.h b/Marlin/example_configurations/Velleman/K8200/Configuration.h index dfc27e976..0683fcbed 100644 --- a/Marlin/example_configurations/Velleman/K8200/Configuration.h +++ b/Marlin/example_configurations/Velleman/K8200/Configuration.h @@ -1586,6 +1586,14 @@ #define RGB_LED_W_PIN -1 #endif +// Support for Adafruit Neopixel LED driver +//#define NEOPIXEL_RGBW_LED +#if ENABLED(NEOPIXEL_RGBW_LED) + #define NEOPIXEL_PIN 4 // D4 (EXP2-5 on Printrboard) + #define NEOPIXEL_PIXELS 3 + //#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup +#endif + /** * Printer Event LEDs * @@ -1597,7 +1605,7 @@ * - Change to green once print has finished * - Turn off after the print has finished and the user has pushed a button */ -#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) +#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_RGBW_LED) #define PRINTER_EVENT_LEDS #endif diff --git a/Marlin/example_configurations/Velleman/K8400/Configuration.h b/Marlin/example_configurations/Velleman/K8400/Configuration.h index 65633a769..fa595b9a7 100644 --- a/Marlin/example_configurations/Velleman/K8400/Configuration.h +++ b/Marlin/example_configurations/Velleman/K8400/Configuration.h @@ -1547,6 +1547,14 @@ #define RGB_LED_W_PIN -1 #endif +// Support for Adafruit Neopixel LED driver +//#define NEOPIXEL_RGBW_LED +#if ENABLED(NEOPIXEL_RGBW_LED) + #define NEOPIXEL_PIN 4 // D4 (EXP2-5 on Printrboard) + #define NEOPIXEL_PIXELS 3 + //#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup +#endif + /** * Printer Event LEDs * @@ -1558,7 +1566,7 @@ * - Change to green once print has finished * - Turn off after the print has finished and the user has pushed a button */ -#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) +#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_RGBW_LED) #define PRINTER_EVENT_LEDS #endif diff --git a/Marlin/example_configurations/Velleman/K8400/Dual-head/Configuration.h b/Marlin/example_configurations/Velleman/K8400/Dual-head/Configuration.h index 16ee469ad..b7ecf8ad3 100644 --- a/Marlin/example_configurations/Velleman/K8400/Dual-head/Configuration.h +++ b/Marlin/example_configurations/Velleman/K8400/Dual-head/Configuration.h @@ -1547,6 +1547,14 @@ #define RGB_LED_W_PIN -1 #endif +// Support for Adafruit Neopixel LED driver +//#define NEOPIXEL_RGBW_LED +#if ENABLED(NEOPIXEL_RGBW_LED) + #define NEOPIXEL_PIN 4 // D4 (EXP2-5 on Printrboard) + #define NEOPIXEL_PIXELS 3 + //#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup +#endif + /** * Printer Event LEDs * @@ -1558,7 +1566,7 @@ * - Change to green once print has finished * - Turn off after the print has finished and the user has pushed a button */ -#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) +#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_RGBW_LED) #define PRINTER_EVENT_LEDS #endif diff --git a/Marlin/example_configurations/adafruit/ST7565/Configuration.h b/Marlin/example_configurations/adafruit/ST7565/Configuration.h index 990b09543..cef34701f 100644 --- a/Marlin/example_configurations/adafruit/ST7565/Configuration.h +++ b/Marlin/example_configurations/adafruit/ST7565/Configuration.h @@ -1547,6 +1547,14 @@ #define RGB_LED_W_PIN -1 #endif +// Support for Adafruit Neopixel LED driver +//#define NEOPIXEL_RGBW_LED +#if ENABLED(NEOPIXEL_RGBW_LED) + #define NEOPIXEL_PIN 4 // D4 (EXP2-5 on Printrboard) + #define NEOPIXEL_PIXELS 3 + //#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup +#endif + /** * Printer Event LEDs * @@ -1558,7 +1566,7 @@ * - Change to green once print has finished * - Turn off after the print has finished and the user has pushed a button */ -#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) +#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_RGBW_LED) #define PRINTER_EVENT_LEDS #endif diff --git a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h index 729a35f2d..c76ed5bf4 100644 --- a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h +++ b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h @@ -1674,6 +1674,14 @@ #define RGB_LED_W_PIN -1 #endif +// Support for Adafruit Neopixel LED driver +//#define NEOPIXEL_RGBW_LED +#if ENABLED(NEOPIXEL_RGBW_LED) + #define NEOPIXEL_PIN 4 // D4 (EXP2-5 on Printrboard) + #define NEOPIXEL_PIXELS 3 + //#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup +#endif + /** * Printer Event LEDs * @@ -1685,7 +1693,7 @@ * - Change to green once print has finished * - Turn off after the print has finished and the user has pushed a button */ -#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) +#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_RGBW_LED) #define PRINTER_EVENT_LEDS #endif diff --git a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h index 666a3d7fc..dd685ced0 100644 --- a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h +++ b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h @@ -1668,6 +1668,14 @@ #define RGB_LED_W_PIN -1 #endif +// Support for Adafruit Neopixel LED driver +//#define NEOPIXEL_RGBW_LED +#if ENABLED(NEOPIXEL_RGBW_LED) + #define NEOPIXEL_PIN 4 // D4 (EXP2-5 on Printrboard) + #define NEOPIXEL_PIXELS 3 + //#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup +#endif + /** * Printer Event LEDs * @@ -1679,7 +1687,7 @@ * - Change to green once print has finished * - Turn off after the print has finished and the user has pushed a button */ -#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) +#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_RGBW_LED) #define PRINTER_EVENT_LEDS #endif diff --git a/Marlin/example_configurations/delta/generic/Configuration.h b/Marlin/example_configurations/delta/generic/Configuration.h index d38c7d833..7919ff832 100644 --- a/Marlin/example_configurations/delta/generic/Configuration.h +++ b/Marlin/example_configurations/delta/generic/Configuration.h @@ -1658,6 +1658,14 @@ #define RGB_LED_W_PIN -1 #endif +// Support for Adafruit Neopixel LED driver +//#define NEOPIXEL_RGBW_LED +#if ENABLED(NEOPIXEL_RGBW_LED) + #define NEOPIXEL_PIN 4 // D4 (EXP2-5 on Printrboard) + #define NEOPIXEL_PIXELS 3 + //#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup +#endif + /** * Printer Event LEDs * @@ -1669,7 +1677,7 @@ * - Change to green once print has finished * - Turn off after the print has finished and the user has pushed a button */ -#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) +#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_RGBW_LED) #define PRINTER_EVENT_LEDS #endif diff --git a/Marlin/example_configurations/delta/kossel_mini/Configuration.h b/Marlin/example_configurations/delta/kossel_mini/Configuration.h index ccc082064..0e6504820 100644 --- a/Marlin/example_configurations/delta/kossel_mini/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_mini/Configuration.h @@ -1661,6 +1661,14 @@ #define RGB_LED_W_PIN -1 #endif +// Support for Adafruit Neopixel LED driver +//#define NEOPIXEL_RGBW_LED +#if ENABLED(NEOPIXEL_RGBW_LED) + #define NEOPIXEL_PIN 4 // D4 (EXP2-5 on Printrboard) + #define NEOPIXEL_PIXELS 3 + //#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup +#endif + /** * Printer Event LEDs * @@ -1672,7 +1680,7 @@ * - Change to green once print has finished * - Turn off after the print has finished and the user has pushed a button */ -#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) +#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_RGBW_LED) #define PRINTER_EVENT_LEDS #endif diff --git a/Marlin/example_configurations/delta/kossel_pro/Configuration.h b/Marlin/example_configurations/delta/kossel_pro/Configuration.h index 14d34acea..5ed569fd2 100644 --- a/Marlin/example_configurations/delta/kossel_pro/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_pro/Configuration.h @@ -1666,6 +1666,14 @@ #define RGB_LED_W_PIN -1 #endif +// Support for Adafruit Neopixel LED driver +//#define NEOPIXEL_RGBW_LED +#if ENABLED(NEOPIXEL_RGBW_LED) + #define NEOPIXEL_PIN 4 // D4 (EXP2-5 on Printrboard) + #define NEOPIXEL_PIXELS 3 + //#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup +#endif + /** * Printer Event LEDs * @@ -1677,7 +1685,7 @@ * - Change to green once print has finished * - Turn off after the print has finished and the user has pushed a button */ -#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) +#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_RGBW_LED) #define PRINTER_EVENT_LEDS #endif diff --git a/Marlin/example_configurations/delta/kossel_xl/Configuration.h b/Marlin/example_configurations/delta/kossel_xl/Configuration.h index b3a3de811..bca02a2d8 100644 --- a/Marlin/example_configurations/delta/kossel_xl/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_xl/Configuration.h @@ -1724,6 +1724,14 @@ #define RGB_LED_W_PIN -1 #endif +// Support for Adafruit Neopixel LED driver +//#define NEOPIXEL_RGBW_LED +#if ENABLED(NEOPIXEL_RGBW_LED) + #define NEOPIXEL_PIN 4 // D4 (EXP2-5 on Printrboard) + #define NEOPIXEL_PIXELS 3 + //#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup +#endif + /** * Printer Event LEDs * @@ -1735,7 +1743,7 @@ * - Change to green once print has finished * - Turn off after the print has finished and the user has pushed a button */ -#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) +#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_RGBW_LED) #define PRINTER_EVENT_LEDS #endif diff --git a/Marlin/example_configurations/gCreate/gMax1.5+/Configuration.h b/Marlin/example_configurations/gCreate/gMax1.5+/Configuration.h index d7404f478..ec55d2aaa 100644 --- a/Marlin/example_configurations/gCreate/gMax1.5+/Configuration.h +++ b/Marlin/example_configurations/gCreate/gMax1.5+/Configuration.h @@ -1563,6 +1563,14 @@ #define RGB_LED_W_PIN -1 #endif +// Support for Adafruit Neopixel LED driver +//#define NEOPIXEL_RGBW_LED +#if ENABLED(NEOPIXEL_RGBW_LED) + #define NEOPIXEL_PIN 4 // D4 (EXP2-5 on Printrboard) + #define NEOPIXEL_PIXELS 3 + //#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup +#endif + /** * Printer Event LEDs * @@ -1574,7 +1582,7 @@ * - Change to green once print has finished * - Turn off after the print has finished and the user has pushed a button */ -#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) +#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_RGBW_LED) #define PRINTER_EVENT_LEDS #endif diff --git a/Marlin/example_configurations/makibox/Configuration.h b/Marlin/example_configurations/makibox/Configuration.h index 0c317fc51..37b080d3b 100644 --- a/Marlin/example_configurations/makibox/Configuration.h +++ b/Marlin/example_configurations/makibox/Configuration.h @@ -1550,6 +1550,14 @@ #define RGB_LED_W_PIN -1 #endif +// Support for Adafruit Neopixel LED driver +//#define NEOPIXEL_RGBW_LED +#if ENABLED(NEOPIXEL_RGBW_LED) + #define NEOPIXEL_PIN 4 // D4 (EXP2-5 on Printrboard) + #define NEOPIXEL_PIXELS 3 + //#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup +#endif + /** * Printer Event LEDs * @@ -1561,7 +1569,7 @@ * - Change to green once print has finished * - Turn off after the print has finished and the user has pushed a button */ -#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) +#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_RGBW_LED) #define PRINTER_EVENT_LEDS #endif diff --git a/Marlin/example_configurations/tvrrug/Round2/Configuration.h b/Marlin/example_configurations/tvrrug/Round2/Configuration.h index ea2aed618..54c274207 100644 --- a/Marlin/example_configurations/tvrrug/Round2/Configuration.h +++ b/Marlin/example_configurations/tvrrug/Round2/Configuration.h @@ -1542,6 +1542,14 @@ #define RGB_LED_W_PIN -1 #endif +// Support for Adafruit Neopixel LED driver +//#define NEOPIXEL_RGBW_LED +#if ENABLED(NEOPIXEL_RGBW_LED) + #define NEOPIXEL_PIN 4 // D4 (EXP2-5 on Printrboard) + #define NEOPIXEL_PIXELS 3 + //#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup +#endif + /** * Printer Event LEDs * @@ -1553,7 +1561,7 @@ * - Change to green once print has finished * - Turn off after the print has finished and the user has pushed a button */ -#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) +#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_RGBW_LED) #define PRINTER_EVENT_LEDS #endif diff --git a/Marlin/example_configurations/wt150/Configuration.h b/Marlin/example_configurations/wt150/Configuration.h index e26923620..8cdde10c2 100644 --- a/Marlin/example_configurations/wt150/Configuration.h +++ b/Marlin/example_configurations/wt150/Configuration.h @@ -1553,6 +1553,14 @@ #define RGB_LED_W_PIN -1 #endif +// Support for Adafruit Neopixel LED driver +//#define NEOPIXEL_RGBW_LED +#if ENABLED(NEOPIXEL_RGBW_LED) + #define NEOPIXEL_PIN 4 // D4 (EXP2-5 on Printrboard) + #define NEOPIXEL_PIXELS 3 + //#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup +#endif + /** * Printer Event LEDs * @@ -1564,7 +1572,7 @@ * - Change to green once print has finished * - Turn off after the print has finished and the user has pushed a button */ -#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) +#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_RGBW_LED) #define PRINTER_EVENT_LEDS #endif From 4718c09c480ed0e9c6f4275747727a3d7e639b4b Mon Sep 17 00:00:00 2001 From: Dave Johnson Date: Sun, 23 Jul 2017 16:38:40 -0700 Subject: [PATCH 035/112] Remove extraneous USBCON defines for AT90USB boards USBCON is definied by serial.h pullikng in MarlinConfig.h which in turn pulls in Arduino.h. Defining in later includes has shown to cause compile issues so removing all extraneous calls for and potentially easier future linker troubleshooting. more USBCON unification --- Marlin/pins_5DPRINT.h | 1 - Marlin/pins_BRAINWAVE.h | 2 -- Marlin/pins_BRAINWAVE_PRO.h | 1 - Marlin/pins_PRINTRBOARD.h | 1 - Marlin/pins_SAV_MKI.h | 1 - Marlin/pins_TEENSY2.h | 1 - Marlin/pins_TEENSYLU.h | 1 - 7 files changed, 8 deletions(-) diff --git a/Marlin/pins_5DPRINT.h b/Marlin/pins_5DPRINT.h index f56ec0b67..e99047f66 100755 --- a/Marlin/pins_5DPRINT.h +++ b/Marlin/pins_5DPRINT.h @@ -74,7 +74,6 @@ #define DEFAULT_MACHINE_NAME "Makibox" #define BOARD_NAME "5DPrint D8" -#define USBCON 1286 // Disable MarlinSerial etc. #define LARGE_FLASH true // diff --git a/Marlin/pins_BRAINWAVE.h b/Marlin/pins_BRAINWAVE.h index 2776c5006..932619769 100755 --- a/Marlin/pins_BRAINWAVE.h +++ b/Marlin/pins_BRAINWAVE.h @@ -73,8 +73,6 @@ #define BOARD_NAME "Brainwave" -#define USBCON 646 // Disable MarlinSerial etc. - // // Limit Switches // diff --git a/Marlin/pins_BRAINWAVE_PRO.h b/Marlin/pins_BRAINWAVE_PRO.h index ef780d579..acf8642e0 100755 --- a/Marlin/pins_BRAINWAVE_PRO.h +++ b/Marlin/pins_BRAINWAVE_PRO.h @@ -80,7 +80,6 @@ #define BOARD_NAME "Brainwave Pro" -#define USBCON 1286 // Disable MarlinSerial etc. #define LARGE_FLASH true // diff --git a/Marlin/pins_PRINTRBOARD.h b/Marlin/pins_PRINTRBOARD.h index 7dec695d5..9681e0959 100755 --- a/Marlin/pins_PRINTRBOARD.h +++ b/Marlin/pins_PRINTRBOARD.h @@ -67,7 +67,6 @@ #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 diff --git a/Marlin/pins_SAV_MKI.h b/Marlin/pins_SAV_MKI.h index 84646cc4c..aecd58afd 100755 --- a/Marlin/pins_SAV_MKI.h +++ b/Marlin/pins_SAV_MKI.h @@ -69,7 +69,6 @@ #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 // diff --git a/Marlin/pins_TEENSY2.h b/Marlin/pins_TEENSY2.h index fa4280fc1..d5eb893ae 100755 --- a/Marlin/pins_TEENSY2.h +++ b/Marlin/pins_TEENSY2.h @@ -112,7 +112,6 @@ #define BOARD_NAME "Teensy++2.0" -#define USBCON 1286 // Disable MarlinSerial etc. #define LARGE_FLASH true // diff --git a/Marlin/pins_TEENSYLU.h b/Marlin/pins_TEENSYLU.h index 3fb7f5c3e..0c2ded63e 100755 --- a/Marlin/pins_TEENSYLU.h +++ b/Marlin/pins_TEENSYLU.h @@ -79,7 +79,6 @@ #define BOARD_NAME "Teensylu" -#define USBCON 1286 // Disable MarlinSerial etc. #define LARGE_FLASH true From 42aa10d2637ee9cdbd1766e8abbf32593f4e8030 Mon Sep 17 00:00:00 2001 From: Unknown Date: Tue, 25 Jul 2017 19:09:08 -0700 Subject: [PATCH 036/112] Add PIO entry for PRINTRBOARD_REVF fix from PIO corruption --- platformio.ini | 7 +++++++ 1 file changed, 7 insertions(+) diff --git a/platformio.ini b/platformio.ini index c5ef19140..50137628e 100644 --- a/platformio.ini +++ b/platformio.ini @@ -46,6 +46,13 @@ build_flags = -I $BUILDSRC_DIR -D MOTHERBOARD=BOARD_PRINTRBOARD #board_f_cpu = 20000000L lib_deps = ${common.lib_deps} +[env:printrboard_revf] +platform = teensy +framework = arduino +board = teensy20pp +build_flags = -I $BUILDSRC_DIR -D MOTHERBOARD=BOARD_PRINTRBOARD_REVF +lib_deps = ${common.lib_deps} + [env:brainwavepro] platform = teensy framework = arduino From dc7c95e07b7ad1ba67c475706480ce1a80b7a6dd Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 21 Jul 2017 22:43:18 -0500 Subject: [PATCH 037/112] Remove `@ section fwretract` --- Marlin/Configuration_adv.h | 2 +- .../AlephObjects/TAZ4/Configuration_adv.h | 2 +- Marlin/example_configurations/Anet/A6/Configuration_adv.h | 2 +- Marlin/example_configurations/Anet/A8/Configuration_adv.h | 2 +- Marlin/example_configurations/BQ/Hephestos/Configuration_adv.h | 2 +- .../example_configurations/BQ/Hephestos_2/Configuration_adv.h | 2 +- Marlin/example_configurations/BQ/WITBOX/Configuration_adv.h | 2 +- Marlin/example_configurations/Cartesio/Configuration_adv.h | 2 +- Marlin/example_configurations/Felix/Configuration_adv.h | 2 +- .../Folger Tech/i3-2020/Configuration_adv.h | 2 +- .../example_configurations/Infitary/i3-M508/Configuration_adv.h | 2 +- Marlin/example_configurations/Malyan/M150/Configuration_adv.h | 2 +- Marlin/example_configurations/RigidBot/Configuration_adv.h | 2 +- Marlin/example_configurations/SCARA/Configuration_adv.h | 2 +- Marlin/example_configurations/TinyBoy2/Configuration_adv.h | 2 +- .../example_configurations/Velleman/K8200/Configuration_adv.h | 2 +- .../example_configurations/Velleman/K8400/Configuration_adv.h | 2 +- .../delta/FLSUN/auto_calibrate/Configuration_adv.h | 2 +- .../delta/FLSUN/kossel_mini/Configuration_adv.h | 2 +- Marlin/example_configurations/delta/generic/Configuration_adv.h | 2 +- .../delta/kossel_mini/Configuration_adv.h | 2 +- .../example_configurations/delta/kossel_pro/Configuration_adv.h | 2 +- .../example_configurations/delta/kossel_xl/Configuration_adv.h | 2 +- .../example_configurations/gCreate/gMax1.5+/Configuration_adv.h | 2 +- Marlin/example_configurations/makibox/Configuration_adv.h | 2 +- Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h | 2 +- Marlin/example_configurations/wt150/Configuration_adv.h | 2 +- 27 files changed, 27 insertions(+), 27 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 95a690d1f..18276639c 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -755,7 +755,7 @@ // Some clients will have this feature soon. This could make the NO_TIMEOUTS unnecessary. //#define ADVANCED_OK -// @section fwretract +// @section extras /** * Firmware-based and LCD-controlled retract diff --git a/Marlin/example_configurations/AlephObjects/TAZ4/Configuration_adv.h b/Marlin/example_configurations/AlephObjects/TAZ4/Configuration_adv.h index 98f833393..0fbb97caa 100644 --- a/Marlin/example_configurations/AlephObjects/TAZ4/Configuration_adv.h +++ b/Marlin/example_configurations/AlephObjects/TAZ4/Configuration_adv.h @@ -748,7 +748,7 @@ // Some clients will have this feature soon. This could make the NO_TIMEOUTS unnecessary. //#define ADVANCED_OK -// @section fwretract +// @section extras /** * Firmware-based and LCD-controlled retract diff --git a/Marlin/example_configurations/Anet/A6/Configuration_adv.h b/Marlin/example_configurations/Anet/A6/Configuration_adv.h index e233b6ba1..5e0ce3bc6 100644 --- a/Marlin/example_configurations/Anet/A6/Configuration_adv.h +++ b/Marlin/example_configurations/Anet/A6/Configuration_adv.h @@ -755,7 +755,7 @@ // Some clients will have this feature soon. This could make the NO_TIMEOUTS unnecessary. //#define ADVANCED_OK -// @section fwretract +// @section extras /** * Firmware-based and LCD-controlled retract diff --git a/Marlin/example_configurations/Anet/A8/Configuration_adv.h b/Marlin/example_configurations/Anet/A8/Configuration_adv.h index eac7964ae..84ae70044 100644 --- a/Marlin/example_configurations/Anet/A8/Configuration_adv.h +++ b/Marlin/example_configurations/Anet/A8/Configuration_adv.h @@ -755,7 +755,7 @@ // Some clients will have this feature soon. This could make the NO_TIMEOUTS unnecessary. //#define ADVANCED_OK -// @section fwretract +// @section extras /** * Firmware-based and LCD-controlled retract diff --git a/Marlin/example_configurations/BQ/Hephestos/Configuration_adv.h b/Marlin/example_configurations/BQ/Hephestos/Configuration_adv.h index a9d32e272..599709549 100644 --- a/Marlin/example_configurations/BQ/Hephestos/Configuration_adv.h +++ b/Marlin/example_configurations/BQ/Hephestos/Configuration_adv.h @@ -748,7 +748,7 @@ // Some clients will have this feature soon. This could make the NO_TIMEOUTS unnecessary. //#define ADVANCED_OK -// @section fwretract +// @section extras /** * Firmware-based and LCD-controlled retract diff --git a/Marlin/example_configurations/BQ/Hephestos_2/Configuration_adv.h b/Marlin/example_configurations/BQ/Hephestos_2/Configuration_adv.h index 63a738603..9a01afa9b 100644 --- a/Marlin/example_configurations/BQ/Hephestos_2/Configuration_adv.h +++ b/Marlin/example_configurations/BQ/Hephestos_2/Configuration_adv.h @@ -731,7 +731,7 @@ // Some clients will have this feature soon. This could make the NO_TIMEOUTS unnecessary. #define ADVANCED_OK -// @section fwretract +// @section extras /** * Firmware-based and LCD-controlled retract diff --git a/Marlin/example_configurations/BQ/WITBOX/Configuration_adv.h b/Marlin/example_configurations/BQ/WITBOX/Configuration_adv.h index a9d32e272..599709549 100644 --- a/Marlin/example_configurations/BQ/WITBOX/Configuration_adv.h +++ b/Marlin/example_configurations/BQ/WITBOX/Configuration_adv.h @@ -748,7 +748,7 @@ // Some clients will have this feature soon. This could make the NO_TIMEOUTS unnecessary. //#define ADVANCED_OK -// @section fwretract +// @section extras /** * Firmware-based and LCD-controlled retract diff --git a/Marlin/example_configurations/Cartesio/Configuration_adv.h b/Marlin/example_configurations/Cartesio/Configuration_adv.h index 0da151cb3..ddcbf5dca 100644 --- a/Marlin/example_configurations/Cartesio/Configuration_adv.h +++ b/Marlin/example_configurations/Cartesio/Configuration_adv.h @@ -748,7 +748,7 @@ // Some clients will have this feature soon. This could make the NO_TIMEOUTS unnecessary. //#define ADVANCED_OK -// @section fwretract +// @section extras /** * Firmware-based and LCD-controlled retract diff --git a/Marlin/example_configurations/Felix/Configuration_adv.h b/Marlin/example_configurations/Felix/Configuration_adv.h index c72719ec0..c86bbb5d9 100644 --- a/Marlin/example_configurations/Felix/Configuration_adv.h +++ b/Marlin/example_configurations/Felix/Configuration_adv.h @@ -748,7 +748,7 @@ // Some clients will have this feature soon. This could make the NO_TIMEOUTS unnecessary. //#define ADVANCED_OK -// @section fwretract +// @section extras /** * Firmware-based and LCD-controlled retract diff --git a/Marlin/example_configurations/Folger Tech/i3-2020/Configuration_adv.h b/Marlin/example_configurations/Folger Tech/i3-2020/Configuration_adv.h index f7408a373..bb45cf54d 100644 --- a/Marlin/example_configurations/Folger Tech/i3-2020/Configuration_adv.h +++ b/Marlin/example_configurations/Folger Tech/i3-2020/Configuration_adv.h @@ -755,7 +755,7 @@ // Some clients will have this feature soon. This could make the NO_TIMEOUTS unnecessary. //#define ADVANCED_OK -// @section fwretract +// @section extras /** * Firmware-based and LCD-controlled retract diff --git a/Marlin/example_configurations/Infitary/i3-M508/Configuration_adv.h b/Marlin/example_configurations/Infitary/i3-M508/Configuration_adv.h index 92a1eb1b5..289d2a226 100644 --- a/Marlin/example_configurations/Infitary/i3-M508/Configuration_adv.h +++ b/Marlin/example_configurations/Infitary/i3-M508/Configuration_adv.h @@ -745,7 +745,7 @@ // Some clients will have this feature soon. This could make the NO_TIMEOUTS unnecessary. //#define ADVANCED_OK -// @section fwretract +// @section extras /** * Firmware-based and LCD-controlled retract diff --git a/Marlin/example_configurations/Malyan/M150/Configuration_adv.h b/Marlin/example_configurations/Malyan/M150/Configuration_adv.h index 53481c208..744a52b5b 100644 --- a/Marlin/example_configurations/Malyan/M150/Configuration_adv.h +++ b/Marlin/example_configurations/Malyan/M150/Configuration_adv.h @@ -755,7 +755,7 @@ // Some clients will have this feature soon. This could make the NO_TIMEOUTS unnecessary. //#define ADVANCED_OK -// @section fwretract +// @section extras /** * Firmware-based and LCD-controlled retract diff --git a/Marlin/example_configurations/RigidBot/Configuration_adv.h b/Marlin/example_configurations/RigidBot/Configuration_adv.h index f2abeda02..11d859273 100644 --- a/Marlin/example_configurations/RigidBot/Configuration_adv.h +++ b/Marlin/example_configurations/RigidBot/Configuration_adv.h @@ -748,7 +748,7 @@ // Some clients will have this feature soon. This could make the NO_TIMEOUTS unnecessary. //#define ADVANCED_OK -// @section fwretract +// @section extras /** * Firmware-based and LCD-controlled retract diff --git a/Marlin/example_configurations/SCARA/Configuration_adv.h b/Marlin/example_configurations/SCARA/Configuration_adv.h index 47a5d070b..ec2f78530 100644 --- a/Marlin/example_configurations/SCARA/Configuration_adv.h +++ b/Marlin/example_configurations/SCARA/Configuration_adv.h @@ -748,7 +748,7 @@ // Some clients will have this feature soon. This could make the NO_TIMEOUTS unnecessary. //#define ADVANCED_OK -// @section fwretract +// @section extras /** * Firmware-based and LCD-controlled retract diff --git a/Marlin/example_configurations/TinyBoy2/Configuration_adv.h b/Marlin/example_configurations/TinyBoy2/Configuration_adv.h index 3b637bd91..ed8194cfe 100644 --- a/Marlin/example_configurations/TinyBoy2/Configuration_adv.h +++ b/Marlin/example_configurations/TinyBoy2/Configuration_adv.h @@ -751,7 +751,7 @@ // Some clients will have this feature soon. This could make the NO_TIMEOUTS unnecessary. //#define ADVANCED_OK -// @section fwretract +// @section extras /** * Firmware-based and LCD-controlled retract diff --git a/Marlin/example_configurations/Velleman/K8200/Configuration_adv.h b/Marlin/example_configurations/Velleman/K8200/Configuration_adv.h index 5baa75858..3b3a74d53 100644 --- a/Marlin/example_configurations/Velleman/K8200/Configuration_adv.h +++ b/Marlin/example_configurations/Velleman/K8200/Configuration_adv.h @@ -761,7 +761,7 @@ // Some clients will have this feature soon. This could make the NO_TIMEOUTS unnecessary. //#define ADVANCED_OK -// @section fwretract +// @section extras /** * Firmware-based and LCD-controlled retract diff --git a/Marlin/example_configurations/Velleman/K8400/Configuration_adv.h b/Marlin/example_configurations/Velleman/K8400/Configuration_adv.h index 88c88cffe..ae067b567 100644 --- a/Marlin/example_configurations/Velleman/K8400/Configuration_adv.h +++ b/Marlin/example_configurations/Velleman/K8400/Configuration_adv.h @@ -748,7 +748,7 @@ // Some clients will have this feature soon. This could make the NO_TIMEOUTS unnecessary. //#define ADVANCED_OK -// @section fwretract +// @section extras /** * Firmware-based and LCD-controlled retract diff --git a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h index e02fd97a6..e6b328383 100644 --- a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h +++ b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h @@ -753,7 +753,7 @@ // Some clients will have this feature soon. This could make the NO_TIMEOUTS unnecessary. //#define ADVANCED_OK -// @section fwretract +// @section extras /** * Firmware-based and LCD-controlled retract diff --git a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h index 3f763b8bb..b25b49b1a 100644 --- a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h +++ b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h @@ -752,7 +752,7 @@ // Some clients will have this feature soon. This could make the NO_TIMEOUTS unnecessary. //#define ADVANCED_OK -// @section fwretract +// @section extras /** * Firmware-based and LCD-controlled retract diff --git a/Marlin/example_configurations/delta/generic/Configuration_adv.h b/Marlin/example_configurations/delta/generic/Configuration_adv.h index 035539149..739d2d640 100644 --- a/Marlin/example_configurations/delta/generic/Configuration_adv.h +++ b/Marlin/example_configurations/delta/generic/Configuration_adv.h @@ -750,7 +750,7 @@ // Some clients will have this feature soon. This could make the NO_TIMEOUTS unnecessary. //#define ADVANCED_OK -// @section fwretract +// @section extras /** * Firmware-based and LCD-controlled retract diff --git a/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h index 035539149..739d2d640 100644 --- a/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h @@ -750,7 +750,7 @@ // Some clients will have this feature soon. This could make the NO_TIMEOUTS unnecessary. //#define ADVANCED_OK -// @section fwretract +// @section extras /** * Firmware-based and LCD-controlled retract diff --git a/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h index 4b676e425..e08ff0b48 100644 --- a/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h @@ -755,7 +755,7 @@ // Some clients will have this feature soon. This could make the NO_TIMEOUTS unnecessary. //#define ADVANCED_OK -// @section fwretract +// @section extras /** * Firmware-based and LCD-controlled retract diff --git a/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h index a3994d5ec..3b9b4ddcd 100644 --- a/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h @@ -750,7 +750,7 @@ // Some clients will have this feature soon. This could make the NO_TIMEOUTS unnecessary. //#define ADVANCED_OK -// @section fwretract +// @section extras /** * Firmware-based and LCD-controlled retract diff --git a/Marlin/example_configurations/gCreate/gMax1.5+/Configuration_adv.h b/Marlin/example_configurations/gCreate/gMax1.5+/Configuration_adv.h index d1c31153b..7f003a4b8 100644 --- a/Marlin/example_configurations/gCreate/gMax1.5+/Configuration_adv.h +++ b/Marlin/example_configurations/gCreate/gMax1.5+/Configuration_adv.h @@ -755,7 +755,7 @@ // Some clients will have this feature soon. This could make the NO_TIMEOUTS unnecessary. //#define ADVANCED_OK -// @section fwretract +// @section extras /** * Firmware-based and LCD-controlled retract diff --git a/Marlin/example_configurations/makibox/Configuration_adv.h b/Marlin/example_configurations/makibox/Configuration_adv.h index 52649f494..1f616b5b0 100644 --- a/Marlin/example_configurations/makibox/Configuration_adv.h +++ b/Marlin/example_configurations/makibox/Configuration_adv.h @@ -748,7 +748,7 @@ // Some clients will have this feature soon. This could make the NO_TIMEOUTS unnecessary. //#define ADVANCED_OK -// @section fwretract +// @section extras /** * Firmware-based and LCD-controlled retract diff --git a/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h b/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h index 431e14383..b1cafd031 100644 --- a/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h +++ b/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h @@ -748,7 +748,7 @@ // Some clients will have this feature soon. This could make the NO_TIMEOUTS unnecessary. //#define ADVANCED_OK -// @section fwretract +// @section extras /** * Firmware-based and LCD-controlled retract diff --git a/Marlin/example_configurations/wt150/Configuration_adv.h b/Marlin/example_configurations/wt150/Configuration_adv.h index efac0c4b2..afbeb5701 100644 --- a/Marlin/example_configurations/wt150/Configuration_adv.h +++ b/Marlin/example_configurations/wt150/Configuration_adv.h @@ -755,7 +755,7 @@ // Some clients will have this feature soon. This could make the NO_TIMEOUTS unnecessary. //#define ADVANCED_OK -// @section fwretract +// @section extras /** * Firmware-based and LCD-controlled retract From 51864fd365969337b34f2522fb59ead806674e94 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 21 Jul 2017 22:54:39 -0500 Subject: [PATCH 038/112] Add bed size as a configuration option --- Marlin/Conditionals_post.h | 87 +++++++++++++------ Marlin/Configuration.h | 14 +-- Marlin/Marlin_main.cpp | 23 ++--- Marlin/SanityCheck.h | 4 +- .../AlephObjects/TAZ4/Configuration.h | 14 +-- .../AliExpress/CL-260/Configuration.h | 14 +-- .../Anet/A6/Configuration.h | 65 +++++++------- .../Anet/A8/Configuration.h | 14 +-- .../BQ/Hephestos/Configuration.h | 14 +-- .../BQ/Hephestos_2/Configuration.h | 14 +-- .../BQ/WITBOX/Configuration.h | 14 +-- .../Cartesio/Configuration.h | 14 +-- .../Creality/CR-10/Configuration.h | 14 +-- .../Felix/Configuration.h | 14 +-- .../Felix/DUAL/Configuration.h | 14 +-- .../Folger Tech/i3-2020/Configuration.h | 15 ++-- .../Infitary/i3-M508/Configuration.h | 14 +-- .../Malyan/M150/Configuration.h | 14 +-- .../RepRapWorld/Megatronics/Configuration.h | 14 +-- .../RigidBot/Configuration.h | 14 +-- .../SCARA/Configuration.h | 14 +-- .../TinyBoy2/Configuration.h | 16 ++-- .../Velleman/K8200/Configuration.h | 14 +-- .../Velleman/K8400/Configuration.h | 14 +-- .../Velleman/K8400/Dual-head/Configuration.h | 14 +-- .../adafruit/ST7565/Configuration.h | 14 +-- .../FLSUN/auto_calibrate/Configuration.h | 6 +- .../delta/FLSUN/kossel_mini/Configuration.h | 6 +- .../delta/generic/Configuration.h | 6 +- .../delta/kossel_mini/Configuration.h | 6 +- .../delta/kossel_pro/Configuration.h | 6 +- .../delta/kossel_xl/Configuration.h | 6 +- .../gCreate/gMax1.5+/Configuration.h | 12 ++- .../makibox/Configuration.h | 14 +-- .../tvrrug/Round2/Configuration.h | 14 +-- .../wt150/Configuration.h | 14 +-- Marlin/ubl_G29.cpp | 8 +- 37 files changed, 378 insertions(+), 210 deletions(-) diff --git a/Marlin/Conditionals_post.h b/Marlin/Conditionals_post.h index ba7a862ea..c8dacd335 100644 --- a/Marlin/Conditionals_post.h +++ b/Marlin/Conditionals_post.h @@ -34,9 +34,28 @@ #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) + + // Defined only if the sanity-check is bypassed + #ifndef X_BED_SIZE + #define X_BED_SIZE X_MAX_LENGTH + #endif + #ifndef Y_BED_SIZE + #define Y_BED_SIZE Y_MAX_LENGTH + #endif + + #if ENABLED(BED_CENTER_AT_0_0) + #define X_CENTER 0 + #define Y_CENTER 0 + #else + #define X_CENTER ((X_BED_SIZE) / 2) + #define Y_CENTER ((Y_BED_SIZE) / 2) + #endif + #define Z_CENTER ((Z_MIN_POS + Z_MAX_POS) / 2) + + #define X_MIN_BED (X_CENTER - (X_BED_SIZE) / 2) + #define X_MAX_BED (X_CENTER + (X_BED_SIZE) / 2) + #define Y_MIN_BED (Y_CENTER - (Y_BED_SIZE) / 2) + #define Y_MAX_BED (Y_CENTER + (Y_BED_SIZE) / 2) /** * CoreXY, CoreXZ, and CoreYZ - and their reverse @@ -87,11 +106,11 @@ #if ENABLED(DELTA) #define X_HOME_POS 0 #else - #define X_HOME_POS ((X_MAX_LENGTH) * (X_HOME_DIR) * 0.5) + #define X_HOME_POS ((X_BED_SIZE) * (X_HOME_DIR) * 0.5) #endif #else #if ENABLED(DELTA) - #define X_HOME_POS (X_MIN_POS + (X_MAX_LENGTH) * 0.5) + #define X_HOME_POS (X_MIN_POS + (X_BED_SIZE) * 0.5) #else #define X_HOME_POS (X_HOME_DIR < 0 ? X_MIN_POS : X_MAX_POS) #endif @@ -103,11 +122,11 @@ #if ENABLED(DELTA) #define Y_HOME_POS 0 #else - #define Y_HOME_POS ((Y_MAX_LENGTH) * (Y_HOME_DIR) * 0.5) + #define Y_HOME_POS ((Y_BED_SIZE) * (Y_HOME_DIR) * 0.5) #endif #else #if ENABLED(DELTA) - #define Y_HOME_POS (Y_MIN_POS + (Y_MAX_LENGTH) * 0.5) + #define Y_HOME_POS (Y_MIN_POS + (Y_BED_SIZE) * 0.5) #else #define Y_HOME_POS (Y_HOME_DIR < 0 ? Y_MIN_POS : Y_MAX_POS) #endif @@ -151,10 +170,10 @@ */ #if ENABLED(Z_SAFE_HOMING) #ifndef Z_SAFE_HOMING_X_POINT - #define Z_SAFE_HOMING_X_POINT ((X_MIN_POS + X_MAX_POS) / 2) + #define Z_SAFE_HOMING_X_POINT X_CENTER #endif #ifndef Z_SAFE_HOMING_Y_POINT - #define Z_SAFE_HOMING_Y_POINT ((Y_MIN_POS + Y_MAX_POS) / 2) + #define Z_SAFE_HOMING_Y_POINT Y_CENTER #endif #define X_TILT_FULCRUM Z_SAFE_HOMING_X_POINT #define Y_TILT_FULCRUM Z_SAFE_HOMING_Y_POINT @@ -792,25 +811,40 @@ #define MANUAL_PROBE_HEIGHT Z_HOMING_HEIGHT #endif + /** + * Bed Probing rectangular bounds + * These can be further constrained in code for Delta and SCARA + */ #if ENABLED(DELTA) - // These will be further constrained in code, but UBL_PROBE_PT values - // cannot be compile-time verified within the radius. - #define MIN_PROBE_X (-DELTA_PRINTABLE_RADIUS) - #define MAX_PROBE_X ( DELTA_PRINTABLE_RADIUS) - #define MIN_PROBE_Y (-DELTA_PRINTABLE_RADIUS) - #define MAX_PROBE_Y ( DELTA_PRINTABLE_RADIUS) + #ifndef DELTA_PROBEABLE_RADIUS + #define DELTA_PROBEABLE_RADIUS DELTA_PRINTABLE_RADIUS + #endif + // Probing points may be verified at compile time within the radius + // using static_assert(HYPOT2(X2-X1,Y2-Y1)<=sq(DELTA_PRINTABLE_RADIUS),"bad probe point!") + // so that may be added to SanityCheck.h in the future. + #define MIN_PROBE_X (X_CENTER - (DELTA_PROBEABLE_RADIUS)) + #define MIN_PROBE_Y (Y_CENTER - (DELTA_PROBEABLE_RADIUS)) + #define MAX_PROBE_X (X_CENTER + DELTA_PROBEABLE_RADIUS) + #define MAX_PROBE_Y (Y_CENTER + DELTA_PROBEABLE_RADIUS) #elif IS_SCARA #define SCARA_PRINTABLE_RADIUS (SCARA_LINKAGE_1 + SCARA_LINKAGE_2) - #define MIN_PROBE_X (-SCARA_PRINTABLE_RADIUS) - #define MAX_PROBE_X ( SCARA_PRINTABLE_RADIUS) - #define MIN_PROBE_Y (-SCARA_PRINTABLE_RADIUS) - #define MAX_PROBE_Y ( SCARA_PRINTABLE_RADIUS) + #define MIN_PROBE_X (X_CENTER - (SCARA_PRINTABLE_RADIUS)) + #define MIN_PROBE_Y (Y_CENTER - (SCARA_PRINTABLE_RADIUS)) + #define MAX_PROBE_X (X_CENTER + SCARA_PRINTABLE_RADIUS) + #define MAX_PROBE_Y (Y_CENTER + SCARA_PRINTABLE_RADIUS) #else - // Boundaries for 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)) + // Boundaries for Cartesian probing based on set limits + #if ENABLED(BED_CENTER_AT_0_0) + #define MIN_PROBE_X (max(X_PROBE_OFFSET_FROM_EXTRUDER, 0) - (X_BED_SIZE) / 2) + #define MIN_PROBE_Y (max(Y_PROBE_OFFSET_FROM_EXTRUDER, 0) - (Y_BED_SIZE) / 2) + #define MAX_PROBE_X (min(X_BED_SIZE + X_PROBE_OFFSET_FROM_EXTRUDER, X_BED_SIZE) - (X_BED_SIZE) / 2) + #define MAX_PROBE_Y (min(Y_BED_SIZE + Y_PROBE_OFFSET_FROM_EXTRUDER, Y_BED_SIZE) - (Y_BED_SIZE) / 2) + #else + #define MIN_PROBE_X (max(X_MIN_POS + X_PROBE_OFFSET_FROM_EXTRUDER, 0)) + #define MIN_PROBE_Y (max(Y_MIN_POS + Y_PROBE_OFFSET_FROM_EXTRUDER, 0)) + #define MAX_PROBE_X (min(X_MAX_POS + X_PROBE_OFFSET_FROM_EXTRUDER, X_BED_SIZE)) + #define MAX_PROBE_Y (min(Y_MAX_POS + Y_PROBE_OFFSET_FROM_EXTRUDER, Y_BED_SIZE)) + #endif #endif // Stepper pulse duration, in cycles @@ -835,7 +869,7 @@ #endif /** - * DELTA_SEGMENT_MIN_LENGTH and DELTA_PROBEABLE_RADIUS for UBL_DELTA + * DELTA_SEGMENT_MIN_LENGTH for UBL_DELTA */ #if UBL_DELTA #ifndef DELTA_SEGMENT_MIN_LENGTH @@ -847,9 +881,6 @@ #define DELTA_SEGMENT_MIN_LENGTH 1.00 // mm (similar to G2/G3 arc segmentation) #endif #endif - #ifndef DELTA_PROBEABLE_RADIUS - #define DELTA_PROBEABLE_RADIUS DELTA_PRINTABLE_RADIUS - #endif #endif // Shorthand diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index b62f5827f..35a6aaabb 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -755,12 +755,16 @@ // @section machine -// Travel limits after homing (units are in mm) +// The size of the print bed +#define X_BED_SIZE 200 +#define Y_BED_SIZE 200 + +// Travel limits (mm) after homing, corresponding to endstop positions. #define X_MIN_POS 0 #define Y_MIN_POS 0 #define Z_MIN_POS 0 -#define X_MAX_POS 200 -#define Y_MAX_POS 200 +#define X_MAX_POS X_BED_SIZE +#define Y_MAX_POS Y_BED_SIZE #define Z_MAX_POS 200 // If enabled, axes won't move below MIN_POS in response to movement commands. @@ -968,8 +972,8 @@ //#define Z_SAFE_HOMING #if ENABLED(Z_SAFE_HOMING) - #define Z_SAFE_HOMING_X_POINT ((X_MIN_POS + X_MAX_POS) / 2) // X point for Z homing when homing all axis (G28). - #define Z_SAFE_HOMING_Y_POINT ((Y_MIN_POS + Y_MAX_POS) / 2) // Y point for Z homing when homing all axis (G28). + #define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axis (G28). + #define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axis (G28). #endif // Homing speeds (mm/m) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 5af9537d1..21daeae79 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -456,8 +456,8 @@ float filament_size[EXTRUDERS], volumetric_multiplier[EXTRUDERS]; #if HAS_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 }; +float soft_endstop_min[XYZ] = { X_MIN_BED, Y_MIN_BED, Z_MIN_POS }, + soft_endstop_max[XYZ] = { X_MAX_BED, Y_MAX_BED, Z_MAX_POS }; #if FAN_COUNT > 0 int16_t fanSpeeds[FAN_COUNT] = { 0 }; @@ -6905,15 +6905,16 @@ inline void gcode_M42() { 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 - float angle = random(0.0, 360.0), - radius = random( - #if ENABLED(DELTA) - DELTA_PROBEABLE_RADIUS / 8, DELTA_PROBEABLE_RADIUS / 3 - #else - 5, X_MAX_LENGTH / 8 - #endif - ); + const int dir = (random(0, 10) > 5.0) ? -1 : 1; // clockwise or counter clockwise + float angle = random(0.0, 360.0); + const float radius = random( + #if ENABLED(DELTA) + 0.1250000000 * (DELTA_PROBEABLE_RADIUS), + 0.3333333333 * (DELTA_PROBEABLE_RADIUS) + #else + 5.0, 0.125 * min(X_BED_SIZE, Y_BED_SIZE) + #endif + ); if (verbose_level > 3) { SERIAL_ECHOPAIR("Starting radius: ", radius); diff --git a/Marlin/SanityCheck.h b/Marlin/SanityCheck.h index dcd6ba1d5..448be0f04 100644 --- a/Marlin/SanityCheck.h +++ b/Marlin/SanityCheck.h @@ -50,7 +50,9 @@ /** * Warnings for old configurations */ -#if WATCH_TEMP_PERIOD > 500 +#if !defined(X_BED_SIZE) || !defined(Y_BED_SIZE) + #error "X_BED_SIZE and BED_Y_SIZE are now required! Please update your configuration." +#elif 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." diff --git a/Marlin/example_configurations/AlephObjects/TAZ4/Configuration.h b/Marlin/example_configurations/AlephObjects/TAZ4/Configuration.h index e32b57c58..3ed5c5474 100644 --- a/Marlin/example_configurations/AlephObjects/TAZ4/Configuration.h +++ b/Marlin/example_configurations/AlephObjects/TAZ4/Configuration.h @@ -770,12 +770,16 @@ // @section machine -// Travel limits after homing (units are in mm) +// The size of the print bed +#define X_BED_SIZE 298 +#define Y_BED_SIZE 275 + +// Travel limits (mm) after homing, corresponding to endstop positions. #define X_MIN_POS 0 #define Y_MIN_POS 0 #define Z_MIN_POS 0 -#define X_MAX_POS 298 -#define Y_MAX_POS 275 +#define X_MAX_POS X_BED_SIZE +#define Y_MAX_POS Y_BED_SIZE #define Z_MAX_POS 250 // If enabled, axes won't move below MIN_POS in response to movement commands. @@ -983,8 +987,8 @@ //#define Z_SAFE_HOMING #if ENABLED(Z_SAFE_HOMING) - #define Z_SAFE_HOMING_X_POINT ((X_MIN_POS + X_MAX_POS) / 2) // X point for Z homing when homing all axis (G28). - #define Z_SAFE_HOMING_Y_POINT ((Y_MIN_POS + Y_MAX_POS) / 2) // Y point for Z homing when homing all axis (G28). + #define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axis (G28). + #define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axis (G28). #endif // Homing speeds (mm/m) diff --git a/Marlin/example_configurations/AliExpress/CL-260/Configuration.h b/Marlin/example_configurations/AliExpress/CL-260/Configuration.h index 769de81ee..a1e1630d3 100644 --- a/Marlin/example_configurations/AliExpress/CL-260/Configuration.h +++ b/Marlin/example_configurations/AliExpress/CL-260/Configuration.h @@ -752,12 +752,16 @@ // @section machine -// Travel limits after homing (units are in mm) +// The size of the print bed +#define X_BED_SIZE 220 +#define Y_BED_SIZE 220 + +// Travel limits (mm) after homing, corresponding to endstop positions. #define X_MIN_POS 0 #define Y_MIN_POS 0 #define Z_MIN_POS 0 -#define X_MAX_POS 220 -#define Y_MAX_POS 220 +#define X_MAX_POS X_BED_SIZE +#define Y_MAX_POS Y_BED_SIZE #define Z_MAX_POS 260 // If enabled, axes won't move below MIN_POS in response to movement commands. @@ -965,8 +969,8 @@ //#define Z_SAFE_HOMING #if ENABLED(Z_SAFE_HOMING) - #define Z_SAFE_HOMING_X_POINT ((X_MIN_POS + X_MAX_POS) / 2) // X point for Z homing when homing all axis (G28). - #define Z_SAFE_HOMING_Y_POINT ((Y_MIN_POS + Y_MAX_POS) / 2) // Y point for Z homing when homing all axis (G28). + #define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axis (G28). + #define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axis (G28). #endif // Homing speeds (mm/m) diff --git a/Marlin/example_configurations/Anet/A6/Configuration.h b/Marlin/example_configurations/Anet/A6/Configuration.h index 550fd9953..766bde1a7 100644 --- a/Marlin/example_configurations/Anet/A6/Configuration.h +++ b/Marlin/example_configurations/Anet/A6/Configuration.h @@ -839,47 +839,52 @@ // @section machine -// Travel limits after homing (units are in mm) +// The size of the print bed +//#define X_BED_SIZE 200 +//#define Y_BED_SIZE 200 + +// Travel limits (mm) after homing, corresponding to endstop positions. //#define X_MIN_POS 0 //#define Y_MIN_POS 0 +//#define X_MAX_POS X_BED_SIZE +//#define Y_MAX_POS Y_BED_SIZE //#define Z_MIN_POS 0 -//#define X_MAX_POS 200 -//#define Y_MAX_POS 200 //#define Z_MAX_POS 200 // ANET A6 Firmware V2.0 defaults: -//#define X_MIN_POS 0 -//#define Y_MIN_POS 0 -//#define Z_MIN_POS 0 -//#define X_MAX_POS 220 -//#define Y_MAX_POS 220 -//#define Z_MAX_POS 250 +//#define X_BED_SIZE 220 +//#define Y_BED_SIZE 220 +//#define X_MIN_POS 0 +//#define Y_MIN_POS 0 +//#define Z_MIN_POS 0 +//#define Z_MAX_POS 250 // ANET A6, X0/Y0 0 front left bed edge : -#define X_MIN_POS -3 -#define Y_MIN_POS -5 -#define Z_MIN_POS 0 -#define X_MAX_POS 222 -#define Y_MAX_POS 222 -#define Z_MAX_POS 230 +#define X_BED_SIZE 222 +#define Y_BED_SIZE 222 +#define X_MIN_POS -3 +#define Y_MIN_POS -5 +#define Z_MIN_POS 0 +#define Z_MAX_POS 230 // ANET A6 with new X-Axis / modded Y-Axis: -//#define X_MIN_POS 0 -//#define Y_MIN_POS 0 -//#define Z_MIN_POS 0 -//#define X_MAX_POS 235 -//#define Y_MAX_POS 230 -//#define Z_MAX_POS 230 +//#define X_BED_SIZE 235 +//#define Y_BED_SIZE 230 +//#define X_MIN_POS 0 +//#define Y_MIN_POS 0 +//#define Z_MIN_POS 0 +//#define Z_MAX_POS 230 // ANET A6 with new X-Axis / modded Y-Axis, X0/Y0 0 front left bed edge : -//#define X_MIN_POS -8 -//#define Y_MIN_POS -6 -//#define Z_MIN_POS 0 -//#define X_MAX_POS 227 -//#define Y_MAX_POS 224 -//#define Z_MAX_POS 230 - +//#define X_BED_SIZE 227 +//#define Y_BED_SIZE 224 +//#define X_MIN_POS -8 +//#define Y_MIN_POS -6 +//#define Z_MIN_POS 0 +//#define Z_MAX_POS 230 +#define X_MAX_POS X_BED_SIZE +#define Y_MAX_POS Y_BED_SIZE // If enabled, axes won't move below MIN_POS in response to movement commands. #define MIN_SOFTWARE_ENDSTOPS @@ -1115,8 +1120,8 @@ #define Z_SAFE_HOMING #if ENABLED(Z_SAFE_HOMING) - #define Z_SAFE_HOMING_X_POINT ((X_MIN_POS + X_MAX_POS) / 2) // X point for Z homing when homing all axis (G28). - #define Z_SAFE_HOMING_Y_POINT ((Y_MIN_POS + Y_MAX_POS) / 2) // Y point for Z homing when homing all axis (G28). + #define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axis (G28). + #define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axis (G28). //Anet A6 with new X-Axis //#define Z_SAFE_HOMING_X_POINT 113 // X point for Z homing when homing all axis (G28). diff --git a/Marlin/example_configurations/Anet/A8/Configuration.h b/Marlin/example_configurations/Anet/A8/Configuration.h index d5aadbf2a..d02cdb921 100644 --- a/Marlin/example_configurations/Anet/A8/Configuration.h +++ b/Marlin/example_configurations/Anet/A8/Configuration.h @@ -761,12 +761,16 @@ // @section machine -// Travel limits after homing (units are in mm) +// The size of the print bed +#define X_BED_SIZE 220 +#define Y_BED_SIZE 220 + +// Travel limits (mm) after homing, corresponding to endstop positions. #define X_MIN_POS -33 #define Y_MIN_POS -10 #define Z_MIN_POS 0 -#define X_MAX_POS 220 -#define Y_MAX_POS 220 +#define X_MAX_POS X_BED_SIZE +#define Y_MAX_POS Y_BED_SIZE #define Z_MAX_POS 240 // If enabled, axes won't move below MIN_POS in response to movement commands. @@ -974,8 +978,8 @@ //#define Z_SAFE_HOMING #if ENABLED(Z_SAFE_HOMING) - #define Z_SAFE_HOMING_X_POINT ((X_MIN_POS + X_MAX_POS) / 2) // X point for Z homing when homing all axis (G28). - #define Z_SAFE_HOMING_Y_POINT ((Y_MIN_POS + Y_MAX_POS) / 2) // Y point for Z homing when homing all axis (G28). + #define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axis (G28). + #define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axis (G28). #endif // Homing speeds (mm/m) diff --git a/Marlin/example_configurations/BQ/Hephestos/Configuration.h b/Marlin/example_configurations/BQ/Hephestos/Configuration.h index e55858200..4d2da2cbb 100644 --- a/Marlin/example_configurations/BQ/Hephestos/Configuration.h +++ b/Marlin/example_configurations/BQ/Hephestos/Configuration.h @@ -741,12 +741,16 @@ // @section machine -// Travel limits after homing (units are in mm) +// The size of the print bed +#define X_BED_SIZE 215 +#define Y_BED_SIZE 210 + +// Travel limits (mm) after homing, corresponding to endstop positions. #define X_MIN_POS 0 #define Y_MIN_POS 0 #define Z_MIN_POS 0 -#define X_MAX_POS 215 -#define Y_MAX_POS 210 +#define X_MAX_POS X_BED_SIZE +#define Y_MAX_POS Y_BED_SIZE #define Z_MAX_POS 180 // If enabled, axes won't move below MIN_POS in response to movement commands. @@ -954,8 +958,8 @@ //#define Z_SAFE_HOMING #if ENABLED(Z_SAFE_HOMING) - #define Z_SAFE_HOMING_X_POINT ((X_MIN_POS + X_MAX_POS) / 2) // X point for Z homing when homing all axis (G28). - #define Z_SAFE_HOMING_Y_POINT ((Y_MIN_POS + Y_MAX_POS) / 2) // Y point for Z homing when homing all axis (G28). + #define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axis (G28). + #define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axis (G28). #endif // Homing speeds (mm/m) diff --git a/Marlin/example_configurations/BQ/Hephestos_2/Configuration.h b/Marlin/example_configurations/BQ/Hephestos_2/Configuration.h index 39af4832d..f4bff19f7 100644 --- a/Marlin/example_configurations/BQ/Hephestos_2/Configuration.h +++ b/Marlin/example_configurations/BQ/Hephestos_2/Configuration.h @@ -752,12 +752,16 @@ // @section machine -// Travel limits after homing (units are in mm) +// The size of the print bed +#define X_BED_SIZE 210 +#define Y_BED_SIZE 297 + +// Travel limits (mm) after homing, corresponding to endstop positions. #define X_MIN_POS 0 #define Y_MIN_POS 0 #define Z_MIN_POS 0 -#define X_MAX_POS 210 -#define Y_MAX_POS 297 +#define X_MAX_POS X_BED_SIZE +#define Y_MAX_POS Y_BED_SIZE #define Z_MAX_POS 210 // If enabled, axes won't move below MIN_POS in response to movement commands. @@ -965,8 +969,8 @@ #define Z_SAFE_HOMING #if ENABLED(Z_SAFE_HOMING) - #define Z_SAFE_HOMING_X_POINT ((X_MIN_POS + X_MAX_POS) / 2) // X point for Z homing when homing all axis (G28). - #define Z_SAFE_HOMING_Y_POINT ((Y_MIN_POS + Y_MAX_POS) / 2) // Y point for Z homing when homing all axis (G28). + #define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axis (G28). + #define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axis (G28). #endif // Homing speeds (mm/m) diff --git a/Marlin/example_configurations/BQ/WITBOX/Configuration.h b/Marlin/example_configurations/BQ/WITBOX/Configuration.h index 6984a9be1..870f6057d 100644 --- a/Marlin/example_configurations/BQ/WITBOX/Configuration.h +++ b/Marlin/example_configurations/BQ/WITBOX/Configuration.h @@ -741,12 +741,16 @@ // @section machine -// Travel limits after homing (units are in mm) +// The size of the print bed +#define X_BED_SIZE 297 +#define Y_BED_SIZE 210 + +// Travel limits (mm) after homing, corresponding to endstop positions. #define X_MIN_POS 0 #define Y_MIN_POS 0 #define Z_MIN_POS 0 -#define X_MAX_POS 297 -#define Y_MAX_POS 210 +#define X_MAX_POS X_BED_SIZE +#define Y_MAX_POS Y_BED_SIZE #define Z_MAX_POS 200 // If enabled, axes won't move below MIN_POS in response to movement commands. @@ -954,8 +958,8 @@ //#define Z_SAFE_HOMING #if ENABLED(Z_SAFE_HOMING) - #define Z_SAFE_HOMING_X_POINT ((X_MIN_POS + X_MAX_POS) / 2) // X point for Z homing when homing all axis (G28). - #define Z_SAFE_HOMING_Y_POINT ((Y_MIN_POS + Y_MAX_POS) / 2) // Y point for Z homing when homing all axis (G28). + #define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axis (G28). + #define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axis (G28). #endif // Homing speeds (mm/m) diff --git a/Marlin/example_configurations/Cartesio/Configuration.h b/Marlin/example_configurations/Cartesio/Configuration.h index 91c8d6bf7..7e8672468 100644 --- a/Marlin/example_configurations/Cartesio/Configuration.h +++ b/Marlin/example_configurations/Cartesio/Configuration.h @@ -749,12 +749,16 @@ // @section machine -// Travel limits after homing (units are in mm) +// The size of the print bed +#define X_BED_SIZE 435 +#define Y_BED_SIZE 270 + +// Travel limits (mm) after homing, corresponding to endstop positions. #define X_MIN_POS 0 #define Y_MIN_POS 0 #define Z_MIN_POS 0 -#define X_MAX_POS 435 -#define Y_MAX_POS 270 +#define X_MAX_POS X_BED_SIZE +#define Y_MAX_POS Y_BED_SIZE #define Z_MAX_POS 400 // If enabled, axes won't move below MIN_POS in response to movement commands. @@ -962,8 +966,8 @@ //#define Z_SAFE_HOMING #if ENABLED(Z_SAFE_HOMING) - #define Z_SAFE_HOMING_X_POINT ((X_MIN_POS + X_MAX_POS) / 2) // X point for Z homing when homing all axis (G28). - #define Z_SAFE_HOMING_Y_POINT ((Y_MIN_POS + Y_MAX_POS) / 2) // Y point for Z homing when homing all axis (G28). + #define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axis (G28). + #define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axis (G28). #endif // Homing speeds (mm/m) diff --git a/Marlin/example_configurations/Creality/CR-10/Configuration.h b/Marlin/example_configurations/Creality/CR-10/Configuration.h index 535eec326..4fec96044 100644 --- a/Marlin/example_configurations/Creality/CR-10/Configuration.h +++ b/Marlin/example_configurations/Creality/CR-10/Configuration.h @@ -765,12 +765,16 @@ // @section machine -// Travel limits after homing (units are in mm) +// The size of the print bed +#define X_BED_SIZE 300 +#define Y_BED_SIZE 300 + +// Travel limits (mm) after homing, corresponding to endstop positions. #define X_MIN_POS 0 #define Y_MIN_POS 0 #define Z_MIN_POS 0 -#define X_MAX_POS 300 -#define Y_MAX_POS 300 +#define X_MAX_POS X_BED_SIZE +#define Y_MAX_POS Y_BED_SIZE #define Z_MAX_POS 400 // If enabled, axes won't move below MIN_POS in response to movement commands. @@ -977,8 +981,8 @@ //#define Z_SAFE_HOMING #if ENABLED(Z_SAFE_HOMING) - #define Z_SAFE_HOMING_X_POINT ((X_MIN_POS + X_MAX_POS) / 2) // X point for Z homing when homing all axis (G28). - #define Z_SAFE_HOMING_Y_POINT ((Y_MIN_POS + Y_MAX_POS) / 2) // Y point for Z homing when homing all axis (G28). + #define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axis (G28). + #define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axis (G28). #endif // Homing speeds (mm/m) diff --git a/Marlin/example_configurations/Felix/Configuration.h b/Marlin/example_configurations/Felix/Configuration.h index fd80205a7..d9aee3ff6 100644 --- a/Marlin/example_configurations/Felix/Configuration.h +++ b/Marlin/example_configurations/Felix/Configuration.h @@ -733,12 +733,16 @@ // @section machine -// Travel limits after homing (units are in mm) +// The size of the print bed +#define X_BED_SIZE 255 +#define Y_BED_SIZE 205 + +// Travel limits (mm) after homing, corresponding to endstop positions. #define X_MIN_POS 0 #define Y_MIN_POS 0 #define Z_MIN_POS 0 -#define X_MAX_POS 255 -#define Y_MAX_POS 205 +#define X_MAX_POS X_BED_SIZE +#define Y_MAX_POS Y_BED_SIZE #define Z_MAX_POS 235 // If enabled, axes won't move below MIN_POS in response to movement commands. @@ -946,8 +950,8 @@ //#define Z_SAFE_HOMING #if ENABLED(Z_SAFE_HOMING) - #define Z_SAFE_HOMING_X_POINT ((X_MIN_POS + X_MAX_POS) / 2) // X point for Z homing when homing all axis (G28). - #define Z_SAFE_HOMING_Y_POINT ((Y_MIN_POS + Y_MAX_POS) / 2) // Y point for Z homing when homing all axis (G28). + #define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axis (G28). + #define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axis (G28). #endif // Homing speeds (mm/m) diff --git a/Marlin/example_configurations/Felix/DUAL/Configuration.h b/Marlin/example_configurations/Felix/DUAL/Configuration.h index f1e5be4c3..8ac1bdcb8 100644 --- a/Marlin/example_configurations/Felix/DUAL/Configuration.h +++ b/Marlin/example_configurations/Felix/DUAL/Configuration.h @@ -733,12 +733,16 @@ // @section machine -// Travel limits after homing (units are in mm) +// The size of the print bed +#define X_BED_SIZE 255 +#define Y_BED_SIZE 205 + +// Travel limits (mm) after homing, corresponding to endstop positions. #define X_MIN_POS 0 #define Y_MIN_POS 0 #define Z_MIN_POS 0 -#define X_MAX_POS 255 -#define Y_MAX_POS 205 +#define X_MAX_POS X_BED_SIZE +#define Y_MAX_POS Y_BED_SIZE #define Z_MAX_POS 235 // If enabled, axes won't move below MIN_POS in response to movement commands. @@ -946,8 +950,8 @@ //#define Z_SAFE_HOMING #if ENABLED(Z_SAFE_HOMING) - #define Z_SAFE_HOMING_X_POINT ((X_MIN_POS + X_MAX_POS) / 2) // X point for Z homing when homing all axis (G28). - #define Z_SAFE_HOMING_Y_POINT ((Y_MIN_POS + Y_MAX_POS) / 2) // Y point for Z homing when homing all axis (G28). + #define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axis (G28). + #define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axis (G28). #endif // Homing speeds (mm/m) diff --git a/Marlin/example_configurations/Folger Tech/i3-2020/Configuration.h b/Marlin/example_configurations/Folger Tech/i3-2020/Configuration.h index 151f76271..b24c0c713 100644 --- a/Marlin/example_configurations/Folger Tech/i3-2020/Configuration.h +++ b/Marlin/example_configurations/Folger Tech/i3-2020/Configuration.h @@ -754,13 +754,18 @@ // @section machine -// Travel limits after homing (units are in mm) +// The size of the print bed +#define X_BED_SIZE 207 +#define Y_BED_SIZE 182 + +// Travel limits (mm) after homing, corresponding to endstop positions. #define X_MIN_POS 6 #define Y_MIN_POS 3 #define Z_MIN_POS 0 -#define X_MAX_POS 207 -#define Y_MAX_POS 182 +#define X_MAX_POS X_BED_SIZE +#define Y_MAX_POS Y_BED_SIZE #define Z_MAX_POS 175 + // If enabled, axes won't move below MIN_POS in response to movement commands. //#define MIN_SOFTWARE_ENDSTOPS // If enabled, axes won't move above MAX_POS in response to movement commands. @@ -968,8 +973,8 @@ #define Z_SAFE_HOMING #if ENABLED(Z_SAFE_HOMING) - #define Z_SAFE_HOMING_X_POINT ((X_MIN_POS + X_MAX_POS) / 2) // X point for Z homing when homing all axis (G28). - #define Z_SAFE_HOMING_Y_POINT ((Y_MIN_POS + Y_MAX_POS) / 2) // Y point for Z homing when homing all axis (G28). + #define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axis (G28). + #define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axis (G28). #endif // Homing speeds (mm/m) diff --git a/Marlin/example_configurations/Infitary/i3-M508/Configuration.h b/Marlin/example_configurations/Infitary/i3-M508/Configuration.h index f29594e42..1a303b7bd 100644 --- a/Marlin/example_configurations/Infitary/i3-M508/Configuration.h +++ b/Marlin/example_configurations/Infitary/i3-M508/Configuration.h @@ -759,12 +759,16 @@ // @section machine -// Travel limits after homing (units are in mm) +// The size of the print bed +#define X_BED_SIZE 205 +#define Y_BED_SIZE 205 + +// Travel limits (mm) after homing, corresponding to endstop positions. #define X_MIN_POS 0 #define Y_MIN_POS 0 #define Z_MIN_POS 0 -#define X_MAX_POS 205 -#define Y_MAX_POS 205 +#define X_MAX_POS X_BED_SIZE +#define Y_MAX_POS Y_BED_SIZE #define Z_MAX_POS 185 // If enabled, axes won't move below MIN_POS in response to movement commands. @@ -972,8 +976,8 @@ //#define Z_SAFE_HOMING #if ENABLED(Z_SAFE_HOMING) - #define Z_SAFE_HOMING_X_POINT ((X_MIN_POS + X_MAX_POS) / 2) // X point for Z homing when homing all axis (G28). - #define Z_SAFE_HOMING_Y_POINT ((Y_MIN_POS + Y_MAX_POS) / 2) // Y point for Z homing when homing all axis (G28). + #define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axis (G28). + #define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axis (G28). #endif // Homing speeds (mm/m) diff --git a/Marlin/example_configurations/Malyan/M150/Configuration.h b/Marlin/example_configurations/Malyan/M150/Configuration.h index ac3dcbaf9..a9857fd9e 100644 --- a/Marlin/example_configurations/Malyan/M150/Configuration.h +++ b/Marlin/example_configurations/Malyan/M150/Configuration.h @@ -774,12 +774,16 @@ // @section machine -// Travel limits after homing (units are in mm) +// The size of the print bed +#define X_BED_SIZE 200 +#define Y_BED_SIZE 200 + +// Travel limits (mm) after homing, corresponding to endstop positions. #define X_MIN_POS 0 #define Y_MIN_POS 0 #define Z_MIN_POS 0 -#define X_MAX_POS 200 -#define Y_MAX_POS 200 +#define X_MAX_POS X_BED_SIZE +#define Y_MAX_POS Y_BED_SIZE #define Z_MAX_POS 180 // If enabled, axes won't move below MIN_POS in response to movement commands. @@ -991,8 +995,8 @@ //#define Z_SAFE_HOMING #if ENABLED(Z_SAFE_HOMING) - #define Z_SAFE_HOMING_X_POINT ((X_MIN_POS + X_MAX_POS) / 2) // X point for Z homing when homing all axis (G28). - #define Z_SAFE_HOMING_Y_POINT ((Y_MIN_POS + Y_MAX_POS) / 2) // Y point for Z homing when homing all axis (G28). + #define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axis (G28). + #define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axis (G28). #endif // Homing speeds (mm/m) diff --git a/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h b/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h index f5f6eba19..761e9340f 100644 --- a/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h +++ b/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h @@ -751,12 +751,16 @@ // @section machine -// Travel limits after homing (units are in mm) +// The size of the print bed +#define X_BED_SIZE 200 +#define Y_BED_SIZE 200 + +// Travel limits (mm) after homing, corresponding to endstop positions. #define X_MIN_POS 0 #define Y_MIN_POS 0 #define Z_MIN_POS 0 -#define X_MAX_POS 200 -#define Y_MAX_POS 200 +#define X_MAX_POS X_BED_SIZE +#define Y_MAX_POS Y_BED_SIZE #define Z_MAX_POS 200 // If enabled, axes won't move below MIN_POS in response to movement commands. @@ -964,8 +968,8 @@ //#define Z_SAFE_HOMING #if ENABLED(Z_SAFE_HOMING) - #define Z_SAFE_HOMING_X_POINT ((X_MIN_POS + X_MAX_POS) / 2) // X point for Z homing when homing all axis (G28). - #define Z_SAFE_HOMING_Y_POINT ((Y_MIN_POS + Y_MAX_POS) / 2) // Y point for Z homing when homing all axis (G28). + #define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axis (G28). + #define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axis (G28). #endif // Homing speeds (mm/m) diff --git a/Marlin/example_configurations/RigidBot/Configuration.h b/Marlin/example_configurations/RigidBot/Configuration.h index 6c3cb72d1..5abc8e5e2 100644 --- a/Marlin/example_configurations/RigidBot/Configuration.h +++ b/Marlin/example_configurations/RigidBot/Configuration.h @@ -749,12 +749,16 @@ // @section machine -// Travel limits after homing (units are in mm) +// The size of the print bed +#define X_BED_SIZE 254 // RigidBot regular is 254mm, RigitBot Big is 406mm +#define Y_BED_SIZE 248 // RigidBot regular is 248mm, RigitBot Big is 304mm + +// Travel limits (mm) after homing, corresponding to endstop positions. #define X_MIN_POS 0 #define Y_MIN_POS 0 #define Z_MIN_POS 0 -#define X_MAX_POS 254 // RigidBot regular is 254mm, RigitBot Big is 406mm -#define Y_MAX_POS 248 // RigidBot regular is 248mm, RigitBot Big is 304mm +#define X_MAX_POS X_BED_SIZE +#define Y_MAX_POS Y_BED_SIZE #define Z_MAX_POS 254 // RigidBot regular and Big are 254mm // If enabled, axes won't move below MIN_POS in response to movement commands. @@ -962,8 +966,8 @@ //#define Z_SAFE_HOMING #if ENABLED(Z_SAFE_HOMING) - #define Z_SAFE_HOMING_X_POINT ((X_MIN_POS + X_MAX_POS) / 2) // X point for Z homing when homing all axis (G28). - #define Z_SAFE_HOMING_Y_POINT ((Y_MIN_POS + Y_MAX_POS) / 2) // Y point for Z homing when homing all axis (G28). + #define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axis (G28). + #define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axis (G28). #endif // Homing speeds (mm/m) diff --git a/Marlin/example_configurations/SCARA/Configuration.h b/Marlin/example_configurations/SCARA/Configuration.h index 71ab77c01..6d53d8737 100644 --- a/Marlin/example_configurations/SCARA/Configuration.h +++ b/Marlin/example_configurations/SCARA/Configuration.h @@ -763,12 +763,16 @@ // @section machine -// Travel limits after homing (units are in mm) +// The size of the print bed +#define X_BED_SIZE 200 +#define Y_BED_SIZE 200 + +// Travel limits (mm) after homing, corresponding to endstop positions. #define X_MIN_POS 0 #define Y_MIN_POS 0 #define Z_MIN_POS MANUAL_Z_HOME_POS -#define X_MAX_POS 200 -#define Y_MAX_POS 200 +#define X_MAX_POS X_BED_SIZE +#define Y_MAX_POS Y_BED_SIZE #define Z_MAX_POS 225 // If enabled, axes won't move below MIN_POS in response to movement commands. @@ -976,8 +980,8 @@ //#define Z_SAFE_HOMING #if ENABLED(Z_SAFE_HOMING) - #define Z_SAFE_HOMING_X_POINT ((X_MIN_POS + X_MAX_POS) / 2) // X point for Z homing when homing all axis (G28). - #define Z_SAFE_HOMING_Y_POINT ((Y_MIN_POS + Y_MAX_POS) / 2) // Y point for Z homing when homing all axis (G28). + #define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axis (G28). + #define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axis (G28). #endif // Homing speeds (mm/m) diff --git a/Marlin/example_configurations/TinyBoy2/Configuration.h b/Marlin/example_configurations/TinyBoy2/Configuration.h index f41e8a87b..bc80b61a5 100644 --- a/Marlin/example_configurations/TinyBoy2/Configuration.h +++ b/Marlin/example_configurations/TinyBoy2/Configuration.h @@ -802,13 +802,17 @@ // @section machine -// Travel limits after homing (units are in mm) +// The size of the print bed +// Tinyboy2: 100mm are marketed, actual length between endstop and end of rail is 98mm +#define X_BED_SIZE 98 +#define Y_BED_SIZE 98 + +// Travel limits (mm) after homing, corresponding to endstop positions. #define X_MIN_POS 0 #define Y_MIN_POS 0 #define Z_MIN_POS 0 -// Tinyboy2: 100mm are marketed, actual length between endstop and end of rail is 98mm -#define X_MAX_POS 98 -#define Y_MAX_POS 98 +#define X_MAX_POS X_BED_SIZE +#define Y_MAX_POS Y_BED_SIZE #if ENABLED(TB2_L10) #define Z_MAX_POS 98 #else @@ -1020,8 +1024,8 @@ //#define Z_SAFE_HOMING #if ENABLED(Z_SAFE_HOMING) - #define Z_SAFE_HOMING_X_POINT ((X_MIN_POS + X_MAX_POS) / 2) // X point for Z homing when homing all axis (G28). - #define Z_SAFE_HOMING_Y_POINT ((Y_MIN_POS + Y_MAX_POS) / 2) // Y point for Z homing when homing all axis (G28). + #define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axis (G28). + #define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axis (G28). #endif // Homing speeds (mm/m) diff --git a/Marlin/example_configurations/Velleman/K8200/Configuration.h b/Marlin/example_configurations/Velleman/K8200/Configuration.h index 0683fcbed..e314373e8 100644 --- a/Marlin/example_configurations/Velleman/K8200/Configuration.h +++ b/Marlin/example_configurations/Velleman/K8200/Configuration.h @@ -780,12 +780,16 @@ // @section machine -// Travel limits after homing (units are in mm) +// The size of the print bed +#define X_BED_SIZE 200 +#define Y_BED_SIZE 200 + +// Travel limits (mm) after homing, corresponding to endstop positions. #define X_MIN_POS 0 #define Y_MIN_POS 0 #define Z_MIN_POS 0 -#define X_MAX_POS 200 -#define Y_MAX_POS 200 +#define X_MAX_POS X_BED_SIZE +#define Y_MAX_POS Y_BED_SIZE #define Z_MAX_POS 200 // If enabled, axes won't move below MIN_POS in response to movement commands. @@ -993,8 +997,8 @@ //#define Z_SAFE_HOMING #if ENABLED(Z_SAFE_HOMING) - #define Z_SAFE_HOMING_X_POINT ((X_MIN_POS + X_MAX_POS) / 2) // X point for Z homing when homing all axis (G28). - #define Z_SAFE_HOMING_Y_POINT ((Y_MIN_POS + Y_MAX_POS) / 2) // Y point for Z homing when homing all axis (G28). + #define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axis (G28). + #define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axis (G28). #endif // Homing speeds (mm/m) diff --git a/Marlin/example_configurations/Velleman/K8400/Configuration.h b/Marlin/example_configurations/Velleman/K8400/Configuration.h index fa595b9a7..f93895aa9 100644 --- a/Marlin/example_configurations/Velleman/K8400/Configuration.h +++ b/Marlin/example_configurations/Velleman/K8400/Configuration.h @@ -751,12 +751,16 @@ // @section machine -// Travel limits after homing (units are in mm) +// The size of the print bed +#define X_BED_SIZE 200 +#define Y_BED_SIZE 200 + +// Travel limits (mm) after homing, corresponding to endstop positions. #define X_MIN_POS 0 #define Y_MIN_POS 20 #define Z_MIN_POS 0 -#define X_MAX_POS 200 -#define Y_MAX_POS 200 +#define X_MAX_POS X_BED_SIZE +#define Y_MAX_POS Y_BED_SIZE #define Z_MAX_POS 190 // If enabled, axes won't move below MIN_POS in response to movement commands. @@ -964,8 +968,8 @@ //#define Z_SAFE_HOMING #if ENABLED(Z_SAFE_HOMING) - #define Z_SAFE_HOMING_X_POINT ((X_MIN_POS + X_MAX_POS) / 2) // X point for Z homing when homing all axis (G28). - #define Z_SAFE_HOMING_Y_POINT ((Y_MIN_POS + Y_MAX_POS) / 2) // Y point for Z homing when homing all axis (G28). + #define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axis (G28). + #define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axis (G28). #endif // Homing speeds (mm/m) diff --git a/Marlin/example_configurations/Velleman/K8400/Dual-head/Configuration.h b/Marlin/example_configurations/Velleman/K8400/Dual-head/Configuration.h index b7ecf8ad3..bcbe50581 100644 --- a/Marlin/example_configurations/Velleman/K8400/Dual-head/Configuration.h +++ b/Marlin/example_configurations/Velleman/K8400/Dual-head/Configuration.h @@ -751,12 +751,16 @@ // @section machine -// Travel limits after homing (units are in mm) +// The size of the print bed +#define X_BED_SIZE 200 +#define Y_BED_SIZE 200 + +// Travel limits (mm) after homing, corresponding to endstop positions. #define X_MIN_POS 0 #define Y_MIN_POS 20 #define Z_MIN_POS 0 -#define X_MAX_POS 200 -#define Y_MAX_POS 200 +#define X_MAX_POS X_BED_SIZE +#define Y_MAX_POS Y_BED_SIZE #define Z_MAX_POS 190 // If enabled, axes won't move below MIN_POS in response to movement commands. @@ -964,8 +968,8 @@ //#define Z_SAFE_HOMING #if ENABLED(Z_SAFE_HOMING) - #define Z_SAFE_HOMING_X_POINT ((X_MIN_POS + X_MAX_POS) / 2) // X point for Z homing when homing all axis (G28). - #define Z_SAFE_HOMING_Y_POINT ((Y_MIN_POS + Y_MAX_POS) / 2) // Y point for Z homing when homing all axis (G28). + #define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axis (G28). + #define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axis (G28). #endif // Homing speeds (mm/m) diff --git a/Marlin/example_configurations/adafruit/ST7565/Configuration.h b/Marlin/example_configurations/adafruit/ST7565/Configuration.h index cef34701f..835cc3199 100644 --- a/Marlin/example_configurations/adafruit/ST7565/Configuration.h +++ b/Marlin/example_configurations/adafruit/ST7565/Configuration.h @@ -751,12 +751,16 @@ // @section machine -// Travel limits after homing (units are in mm) +// The size of the print bed +#define X_BED_SIZE 200 +#define Y_BED_SIZE 200 + +// Travel limits (mm) after homing, corresponding to endstop positions. #define X_MIN_POS 0 #define Y_MIN_POS 0 #define Z_MIN_POS 0 -#define X_MAX_POS 200 -#define Y_MAX_POS 200 +#define X_MAX_POS X_BED_SIZE +#define Y_MAX_POS Y_BED_SIZE #define Z_MAX_POS 200 // If enabled, axes won't move below MIN_POS in response to movement commands. @@ -964,8 +968,8 @@ //#define Z_SAFE_HOMING #if ENABLED(Z_SAFE_HOMING) - #define Z_SAFE_HOMING_X_POINT ((X_MIN_POS + X_MAX_POS) / 2) // X point for Z homing when homing all axis (G28). - #define Z_SAFE_HOMING_Y_POINT ((Y_MIN_POS + Y_MAX_POS) / 2) // Y point for Z homing when homing all axis (G28). + #define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axis (G28). + #define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axis (G28). #endif // Homing speeds (mm/m) diff --git a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h index c76ed5bf4..40a857ef0 100644 --- a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h +++ b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h @@ -875,7 +875,11 @@ // @section machine -// Travel limits after homing (units are in mm) +// The size of the print bed +#define X_BED_SIZE ((DELTA_PRINTABLE_RADIUS) * 2) +#define Y_BED_SIZE ((DELTA_PRINTABLE_RADIUS) * 2) + +// Travel limits (mm) after homing, corresponding to endstop positions. #define X_MIN_POS -(DELTA_PRINTABLE_RADIUS) #define Y_MIN_POS -(DELTA_PRINTABLE_RADIUS) #define Z_MIN_POS 0 diff --git a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h index dd685ced0..87b410c25 100644 --- a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h +++ b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h @@ -875,7 +875,11 @@ // @section machine -// Travel limits after homing (units are in mm) +// The size of the print bed +#define X_BED_SIZE ((DELTA_PRINTABLE_RADIUS) * 2) +#define Y_BED_SIZE ((DELTA_PRINTABLE_RADIUS) * 2) + +// Travel limits (mm) after homing, corresponding to endstop positions. #define X_MIN_POS -(DELTA_PRINTABLE_RADIUS) #define Y_MIN_POS -(DELTA_PRINTABLE_RADIUS) #define Z_MIN_POS 0 diff --git a/Marlin/example_configurations/delta/generic/Configuration.h b/Marlin/example_configurations/delta/generic/Configuration.h index 7919ff832..8633e20ac 100644 --- a/Marlin/example_configurations/delta/generic/Configuration.h +++ b/Marlin/example_configurations/delta/generic/Configuration.h @@ -862,7 +862,11 @@ // @section machine -// Travel limits after homing (units are in mm) +// The size of the print bed +#define X_BED_SIZE ((DELTA_PRINTABLE_RADIUS) * 2) +#define Y_BED_SIZE ((DELTA_PRINTABLE_RADIUS) * 2) + +// Travel limits (mm) after homing, corresponding to endstop positions. #define X_MIN_POS -(DELTA_PRINTABLE_RADIUS) #define Y_MIN_POS -(DELTA_PRINTABLE_RADIUS) #define Z_MIN_POS 0 diff --git a/Marlin/example_configurations/delta/kossel_mini/Configuration.h b/Marlin/example_configurations/delta/kossel_mini/Configuration.h index 0e6504820..2205fc014 100644 --- a/Marlin/example_configurations/delta/kossel_mini/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_mini/Configuration.h @@ -860,7 +860,11 @@ // @section machine -// Travel limits after homing (units are in mm) +// The size of the print bed +#define X_BED_SIZE ((DELTA_PRINTABLE_RADIUS) * 2) +#define Y_BED_SIZE ((DELTA_PRINTABLE_RADIUS) * 2) + +// Travel limits (mm) after homing, corresponding to endstop positions. #define X_MIN_POS -(DELTA_PRINTABLE_RADIUS) #define Y_MIN_POS -(DELTA_PRINTABLE_RADIUS) #define Z_MIN_POS 0 diff --git a/Marlin/example_configurations/delta/kossel_pro/Configuration.h b/Marlin/example_configurations/delta/kossel_pro/Configuration.h index 5ed569fd2..ad9d87e02 100644 --- a/Marlin/example_configurations/delta/kossel_pro/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_pro/Configuration.h @@ -865,7 +865,11 @@ // @section machine -// Travel limits after homing (units are in mm) +// The size of the print bed +#define X_BED_SIZE ((DELTA_PRINTABLE_RADIUS) * 2) +#define Y_BED_SIZE ((DELTA_PRINTABLE_RADIUS) * 2) + +// Travel limits (mm) after homing, corresponding to endstop positions. #define X_MIN_POS -(DELTA_PRINTABLE_RADIUS) #define Y_MIN_POS -(DELTA_PRINTABLE_RADIUS) #define Z_MIN_POS 0 diff --git a/Marlin/example_configurations/delta/kossel_xl/Configuration.h b/Marlin/example_configurations/delta/kossel_xl/Configuration.h index bca02a2d8..aad12e7a1 100644 --- a/Marlin/example_configurations/delta/kossel_xl/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_xl/Configuration.h @@ -928,7 +928,11 @@ // @section machine -// Travel limits after homing (units are in mm) +// The size of the print bed +#define X_BED_SIZE ((DELTA_PRINTABLE_RADIUS) * 2) +#define Y_BED_SIZE ((DELTA_PRINTABLE_RADIUS) * 2) + +// Travel limits (mm) after homing, corresponding to endstop positions. #define X_MIN_POS -(DELTA_PRINTABLE_RADIUS) #define Y_MIN_POS -(DELTA_PRINTABLE_RADIUS) #define Z_MIN_POS 0 diff --git a/Marlin/example_configurations/gCreate/gMax1.5+/Configuration.h b/Marlin/example_configurations/gCreate/gMax1.5+/Configuration.h index ec55d2aaa..bd9c125e3 100644 --- a/Marlin/example_configurations/gCreate/gMax1.5+/Configuration.h +++ b/Marlin/example_configurations/gCreate/gMax1.5+/Configuration.h @@ -766,13 +766,17 @@ // @section machine -// Travel limits after homing (units are in mm) +// The size of the print bed +#define X_BED_SIZE 420 // These numbers are not accurate for an unaltered gMax 1.5+ printer. My print bed +#define Y_BED_SIZE 420 // is inset a noticable amount from the edge of the bed. Combined with the inset, + // the nozzle can reach all cordinates of the mesh. + +// Travel limits (mm) after homing, corresponding to endstop positions. #define X_MIN_POS 0 #define Y_MIN_POS 0 #define Z_MIN_POS 0 -#define X_MAX_POS 420 // These numbers are not accurate for an unaltered gMax 1.5+ printer. My print bed -#define Y_MAX_POS 420 // is inset a noticable amount from the edge of the bed. Combined with the inset, - // the nozzle can reach all cordinates of the mesh. +#define X_MAX_POS X_BED_SIZE +#define Y_MAX_POS Y_BED_SIZE #define Z_MAX_POS 500 // If enabled, axes won't move below MIN_POS in response to movement commands. diff --git a/Marlin/example_configurations/makibox/Configuration.h b/Marlin/example_configurations/makibox/Configuration.h index 37b080d3b..ffb5d9e0c 100644 --- a/Marlin/example_configurations/makibox/Configuration.h +++ b/Marlin/example_configurations/makibox/Configuration.h @@ -754,12 +754,16 @@ // @section machine -// Travel limits after homing (units are in mm) +// The size of the print bed +#define X_BED_SIZE 110 +#define Y_BED_SIZE 150 + +// Travel limits (mm) after homing, corresponding to endstop positions. #define X_MIN_POS 0 #define Y_MIN_POS 0 #define Z_MIN_POS 0 -#define X_MAX_POS 110 -#define Y_MAX_POS 150 +#define X_MAX_POS X_BED_SIZE +#define Y_MAX_POS Y_BED_SIZE #define Z_MAX_POS 86 // If enabled, axes won't move below MIN_POS in response to movement commands. @@ -967,8 +971,8 @@ //#define Z_SAFE_HOMING #if ENABLED(Z_SAFE_HOMING) - #define Z_SAFE_HOMING_X_POINT ((X_MIN_POS + X_MAX_POS) / 2) // X point for Z homing when homing all axis (G28). - #define Z_SAFE_HOMING_Y_POINT ((Y_MIN_POS + Y_MAX_POS) / 2) // Y point for Z homing when homing all axis (G28). + #define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axis (G28). + #define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axis (G28). #endif // Homing speeds (mm/m) diff --git a/Marlin/example_configurations/tvrrug/Round2/Configuration.h b/Marlin/example_configurations/tvrrug/Round2/Configuration.h index 54c274207..112afb8cd 100644 --- a/Marlin/example_configurations/tvrrug/Round2/Configuration.h +++ b/Marlin/example_configurations/tvrrug/Round2/Configuration.h @@ -746,12 +746,16 @@ // @section machine -// Travel limits after homing (units are in mm) +// The size of the print bed +#define X_BED_SIZE 205 +#define Y_BED_SIZE 205 + +// Travel limits (mm) after homing, corresponding to endstop positions. #define X_MIN_POS 0 #define Y_MIN_POS 0 #define Z_MIN_POS 0 -#define X_MAX_POS 205 -#define Y_MAX_POS 205 +#define X_MAX_POS X_BED_SIZE +#define Y_MAX_POS Y_BED_SIZE #define Z_MAX_POS 120 // If enabled, axes won't move below MIN_POS in response to movement commands. @@ -959,8 +963,8 @@ //#define Z_SAFE_HOMING #if ENABLED(Z_SAFE_HOMING) - #define Z_SAFE_HOMING_X_POINT ((X_MIN_POS + X_MAX_POS) / 2) // X point for Z homing when homing all axis (G28). - #define Z_SAFE_HOMING_Y_POINT ((Y_MIN_POS + Y_MAX_POS) / 2) // Y point for Z homing when homing all axis (G28). + #define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axis (G28). + #define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axis (G28). #endif // Homing speeds (mm/m) diff --git a/Marlin/example_configurations/wt150/Configuration.h b/Marlin/example_configurations/wt150/Configuration.h index 8cdde10c2..fbfe75a47 100644 --- a/Marlin/example_configurations/wt150/Configuration.h +++ b/Marlin/example_configurations/wt150/Configuration.h @@ -757,12 +757,16 @@ // @section machine -// Travel limits after homing (units are in mm) +// The size of the print bed +#define X_BED_SIZE 150 +#define Y_BED_SIZE 150 + +// Travel limits (mm) after homing, corresponding to endstop positions. #define X_MIN_POS 0 #define Y_MIN_POS 0 #define Z_MIN_POS 0 -#define X_MAX_POS 150 -#define Y_MAX_POS 150 +#define X_MAX_POS X_BED_SIZE +#define Y_MAX_POS Y_BED_SIZE #define Z_MAX_POS 143.0 // If enabled, axes won't move below MIN_POS in response to movement commands. @@ -970,8 +974,8 @@ //#define Z_SAFE_HOMING #if ENABLED(Z_SAFE_HOMING) - #define Z_SAFE_HOMING_X_POINT ((X_MIN_POS + X_MAX_POS) / 2) // X point for Z homing when homing all axis (G28). - #define Z_SAFE_HOMING_Y_POINT ((Y_MIN_POS + Y_MAX_POS) / 2) // Y point for Z homing when homing all axis (G28). + #define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axis (G28). + #define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axis (G28). #endif // Homing speeds (mm/m) diff --git a/Marlin/ubl_G29.cpp b/Marlin/ubl_G29.cpp index 24ea39445..bc645fb2c 100644 --- a/Marlin/ubl_G29.cpp +++ b/Marlin/ubl_G29.cpp @@ -467,8 +467,8 @@ g29_x_pos = X_HOME_POS; g29_y_pos = Y_HOME_POS; #else // cartesian - g29_x_pos = X_PROBE_OFFSET_FROM_EXTRUDER > 0 ? X_MAX_POS : X_MIN_POS; - g29_y_pos = Y_PROBE_OFFSET_FROM_EXTRUDER < 0 ? Y_MAX_POS : Y_MIN_POS; + g29_x_pos = X_PROBE_OFFSET_FROM_EXTRUDER > 0 ? X_BED_SIZE : 0; + g29_y_pos = Y_PROBE_OFFSET_FROM_EXTRUDER < 0 ? Y_BED_SIZE : 0; #endif } @@ -1132,12 +1132,12 @@ SERIAL_PROTOCOLLNPGM("Both X & Y locations must be specified.\n"); err_flag = true; } - if (!WITHIN(RAW_X_POSITION(g29_x_pos), X_MIN_POS, X_MAX_POS)) { + if (!WITHIN(RAW_X_POSITION(g29_x_pos), X_MIN_BED, X_MAX_BED)) { SERIAL_PROTOCOLLNPGM("Invalid X location specified.\n"); err_flag = true; } - if (!WITHIN(RAW_Y_POSITION(g29_y_pos), Y_MIN_POS, Y_MAX_POS)) { + if (!WITHIN(RAW_Y_POSITION(g29_y_pos), Y_MIN_BED, Y_MAX_BED)) { SERIAL_PROTOCOLLNPGM("Invalid Y location specified.\n"); err_flag = true; } From 283d15a8d04ac40f53119058339f14577b1be25e Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 18 Jul 2017 03:28:20 -0500 Subject: [PATCH 039/112] Add a Travis CI test for FWRETRACT --- .travis.yml | 9 ++++----- 1 file changed, 4 insertions(+), 5 deletions(-) diff --git a/.travis.yml b/.travis.yml index 370b4ea26..cbd29896b 100644 --- a/.travis.yml +++ b/.travis.yml @@ -76,7 +76,8 @@ script: - build_marlin # # Test 2 extruders (one MAX6675) and heated bed on basic RAMPS 1.4 - # plus a "Fix Mounted" Probe with Safe Homing and some arc options + # Test a "Fix Mounted" Probe with Safe Homing, some arc options, + # linear bed leveling, M48, leveling debug, and firmware retraction. # - opt_set MOTHERBOARD BOARD_RAMPS_14_EEB - opt_set EXTRUDERS 2 @@ -84,12 +85,10 @@ script: - opt_set TEMP_SENSOR_1 1 - opt_set TEMP_SENSOR_BED 1 - opt_enable PIDTEMPBED FIX_MOUNTED_PROBE Z_SAFE_HOMING ARC_P_CIRCLES CNC_WORKSPACE_PLANES + - opt_enable REPRAP_DISCOUNT_SMART_CONTROLLER SDSUPPORT EEPROM_SETTINGS - opt_enable BLINKM PCA9632 RGB_LED NEOPIXEL_RGBW_LED - - build_marlin - # - # ...with AUTO_BED_LEVELING_LINEAR, Z_MIN_PROBE_REPEATABILITY_TEST, and DEBUG_LEVELING_FEATURE - # - opt_enable AUTO_BED_LEVELING_LINEAR Z_MIN_PROBE_REPEATABILITY_TEST DEBUG_LEVELING_FEATURE + - opt_enable_adv FWRETRACT - opt_set ABL_GRID_POINTS_X 16 - opt_set ABL_GRID_POINTS_Y 16 - build_marlin From 423b0f3a1e28d2607ff39e13057162dbf18e38df Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 24 Jul 2017 12:13:25 -0500 Subject: [PATCH 040/112] Replace MIN_RETRACT with MIN_AUTORETRACT, MAX_AUTORETRACT --- Marlin/Conditionals_post.h | 7 +++++++ Marlin/Configuration_adv.h | 5 +++-- Marlin/Marlin_main.cpp | 2 +- Marlin/SanityCheck.h | 2 ++ .../AlephObjects/TAZ4/Configuration_adv.h | 5 +++-- Marlin/example_configurations/Anet/A6/Configuration_adv.h | 5 +++-- Marlin/example_configurations/Anet/A8/Configuration_adv.h | 5 +++-- .../BQ/Hephestos/Configuration_adv.h | 5 +++-- .../BQ/Hephestos_2/Configuration_adv.h | 5 +++-- .../example_configurations/BQ/WITBOX/Configuration_adv.h | 5 +++-- Marlin/example_configurations/Cartesio/Configuration_adv.h | 5 +++-- Marlin/example_configurations/Felix/Configuration_adv.h | 5 +++-- .../Folger Tech/i3-2020/Configuration_adv.h | 5 +++-- .../Infitary/i3-M508/Configuration_adv.h | 5 +++-- .../example_configurations/Malyan/M150/Configuration_adv.h | 5 +++-- Marlin/example_configurations/RigidBot/Configuration_adv.h | 5 +++-- Marlin/example_configurations/SCARA/Configuration_adv.h | 5 +++-- Marlin/example_configurations/TinyBoy2/Configuration_adv.h | 5 +++-- .../Velleman/K8200/Configuration_adv.h | 5 +++-- .../Velleman/K8400/Configuration_adv.h | 5 +++-- .../delta/FLSUN/auto_calibrate/Configuration_adv.h | 5 +++-- .../delta/FLSUN/kossel_mini/Configuration_adv.h | 5 +++-- .../delta/generic/Configuration_adv.h | 5 +++-- .../delta/kossel_mini/Configuration_adv.h | 5 +++-- .../delta/kossel_pro/Configuration_adv.h | 5 +++-- .../delta/kossel_xl/Configuration_adv.h | 5 +++-- .../gCreate/gMax1.5+/Configuration_adv.h | 5 +++-- Marlin/example_configurations/makibox/Configuration_adv.h | 5 +++-- .../tvrrug/Round2/Configuration_adv.h | 5 +++-- Marlin/example_configurations/wt150/Configuration_adv.h | 5 +++-- 30 files changed, 91 insertions(+), 55 deletions(-) diff --git a/Marlin/Conditionals_post.h b/Marlin/Conditionals_post.h index c8dacd335..998863d12 100644 --- a/Marlin/Conditionals_post.h +++ b/Marlin/Conditionals_post.h @@ -189,6 +189,13 @@ #define DEFAULT_KEEPALIVE_INTERVAL 2 #endif + /** + * Provide a MAX_AUTORETRACT for older configs + */ + #if ENABLED(FWRETRACT) && !defined(MAX_AUTORETRACT) + #define MAX_AUTORETRACT 99 + #endif + /** * MAX_STEP_FREQUENCY differs for TOSHIBA */ diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 18276639c..3a8a8cc8c 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -764,7 +764,7 @@ * Use M207 and M208 to define parameters for retract / recover. * * Use M209 to enable or disable auto-retract. - * With auto-retract enabled, all G1 E moves over the MIN_RETRACT length + * With auto-retract enabled, all G1 E moves within the set range * will be converted to firmware-based retract/recover moves. * * Be sure to turn off auto-retract during filament change. @@ -774,7 +774,8 @@ */ //#define FWRETRACT // ONLY PARTIALLY TESTED #if ENABLED(FWRETRACT) - #define MIN_RETRACT 0.1 // A retract/recover of this length or longer can be converted to auto-retract + #define MIN_AUTORETRACT 0.1 // When auto-retract is on, convert E moves of this length and over + #define MAX_AUTORETRACT 10.0 // Upper limit for auto-retract conversion #define RETRACT_LENGTH 3 // Default retract length (positive mm) #define RETRACT_LENGTH_SWAP 13 // Default swap retract length (positive mm), for extruder change #define RETRACT_FEEDRATE 45 // Default feedrate for retracting (mm/s) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 21daeae79..51e4c4b5f 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -3281,7 +3281,7 @@ inline void gcode_G0_G1( if (autoretract_enabled && !(parser.seen('X') || parser.seen('Y') || parser.seen('Z')) && parser.seen('E')) { const float echange = destination[E_AXIS] - current_position[E_AXIS]; // Is this move an attempt to retract or recover? - if ((echange < -(MIN_RETRACT) && !retracted[active_extruder]) || (echange > MIN_RETRACT && retracted[active_extruder])) { + if (WITHIN(FABS(echange), MIN_AUTORETRACT, MAX_AUTORETRACT) && retracted[active_extruder] == (echange > 0.0)) { current_position[E_AXIS] = destination[E_AXIS]; // hide the slicer-generated retract/recover from calculations sync_plan_position_e(); // AND from the planner retract(!retracted[active_extruder]); diff --git a/Marlin/SanityCheck.h b/Marlin/SanityCheck.h index 448be0f04..117378add 100644 --- a/Marlin/SanityCheck.h +++ b/Marlin/SanityCheck.h @@ -206,6 +206,8 @@ #error "Replace SLED_PIN with SOL1_PIN (applies to both Z_PROBE_SLED and SOLENOID_PROBE)." #elif defined(CONTROLLERFAN_PIN) #error "CONTROLLERFAN_PIN is now CONTROLLER_FAN_PIN, enabled with USE_CONTROLLER_FAN. Please update your Configuration_adv.h." +#elif defined(MIN_RETRACT) + #error "MIN_RETRACT is now MIN_AUTORETRACT and MAX_AUTORETRACT. Please update your Configuration_adv.h." #endif /** diff --git a/Marlin/example_configurations/AlephObjects/TAZ4/Configuration_adv.h b/Marlin/example_configurations/AlephObjects/TAZ4/Configuration_adv.h index 0fbb97caa..4e0e75df3 100644 --- a/Marlin/example_configurations/AlephObjects/TAZ4/Configuration_adv.h +++ b/Marlin/example_configurations/AlephObjects/TAZ4/Configuration_adv.h @@ -757,7 +757,7 @@ * Use M207 and M208 to define parameters for retract / recover. * * Use M209 to enable or disable auto-retract. - * With auto-retract enabled, all G1 E moves over the MIN_RETRACT length + * With auto-retract enabled, all G1 E moves within the set range * will be converted to firmware-based retract/recover moves. * * Be sure to turn off auto-retract during filament change. @@ -767,7 +767,8 @@ */ //#define FWRETRACT // ONLY PARTIALLY TESTED #if ENABLED(FWRETRACT) - #define MIN_RETRACT 0.1 // A retract/recover of this length or longer can be converted to auto-retract + #define MIN_AUTORETRACT 0.1 // When auto-retract is on, convert E moves of this length and over + #define MAX_AUTORETRACT 10.0 // Upper limit for auto-retract conversion #define RETRACT_LENGTH 3 // Default retract length (positive mm) #define RETRACT_LENGTH_SWAP 13 // Default swap retract length (positive mm), for extruder change #define RETRACT_FEEDRATE 45 // Default feedrate for retracting (mm/s) diff --git a/Marlin/example_configurations/Anet/A6/Configuration_adv.h b/Marlin/example_configurations/Anet/A6/Configuration_adv.h index 5e0ce3bc6..815d3c50e 100644 --- a/Marlin/example_configurations/Anet/A6/Configuration_adv.h +++ b/Marlin/example_configurations/Anet/A6/Configuration_adv.h @@ -764,7 +764,7 @@ * Use M207 and M208 to define parameters for retract / recover. * * Use M209 to enable or disable auto-retract. - * With auto-retract enabled, all G1 E moves over the MIN_RETRACT length + * With auto-retract enabled, all G1 E moves within the set range * will be converted to firmware-based retract/recover moves. * * Be sure to turn off auto-retract during filament change. @@ -774,7 +774,8 @@ */ //#define FWRETRACT // ONLY PARTIALLY TESTED #if ENABLED(FWRETRACT) - #define MIN_RETRACT 0.1 // A retract/recover of this length or longer can be converted to auto-retract + #define MIN_AUTORETRACT 0.1 // When auto-retract is on, convert E moves of this length and over + #define MAX_AUTORETRACT 10.0 // Upper limit for auto-retract conversion #define RETRACT_LENGTH 3 // Default retract length (positive mm) #define RETRACT_LENGTH_SWAP 13 // Default swap retract length (positive mm), for extruder change #define RETRACT_FEEDRATE 45 // Default feedrate for retracting (mm/s) diff --git a/Marlin/example_configurations/Anet/A8/Configuration_adv.h b/Marlin/example_configurations/Anet/A8/Configuration_adv.h index 84ae70044..001517038 100644 --- a/Marlin/example_configurations/Anet/A8/Configuration_adv.h +++ b/Marlin/example_configurations/Anet/A8/Configuration_adv.h @@ -764,7 +764,7 @@ * Use M207 and M208 to define parameters for retract / recover. * * Use M209 to enable or disable auto-retract. - * With auto-retract enabled, all G1 E moves over the MIN_RETRACT length + * With auto-retract enabled, all G1 E moves within the set range * will be converted to firmware-based retract/recover moves. * * Be sure to turn off auto-retract during filament change. @@ -774,7 +774,8 @@ */ //#define FWRETRACT // ONLY PARTIALLY TESTED #if ENABLED(FWRETRACT) - #define MIN_RETRACT 0.1 // A retract/recover of this length or longer can be converted to auto-retract + #define MIN_AUTORETRACT 0.1 // When auto-retract is on, convert E moves of this length and over + #define MAX_AUTORETRACT 10.0 // Upper limit for auto-retract conversion #define RETRACT_LENGTH 3 // Default retract length (positive mm) #define RETRACT_LENGTH_SWAP 13 // Default swap retract length (positive mm), for extruder change #define RETRACT_FEEDRATE 45 // Default feedrate for retracting (mm/s) diff --git a/Marlin/example_configurations/BQ/Hephestos/Configuration_adv.h b/Marlin/example_configurations/BQ/Hephestos/Configuration_adv.h index 599709549..a02bb7874 100644 --- a/Marlin/example_configurations/BQ/Hephestos/Configuration_adv.h +++ b/Marlin/example_configurations/BQ/Hephestos/Configuration_adv.h @@ -757,7 +757,7 @@ * Use M207 and M208 to define parameters for retract / recover. * * Use M209 to enable or disable auto-retract. - * With auto-retract enabled, all G1 E moves over the MIN_RETRACT length + * With auto-retract enabled, all G1 E moves within the set range * will be converted to firmware-based retract/recover moves. * * Be sure to turn off auto-retract during filament change. @@ -767,7 +767,8 @@ */ //#define FWRETRACT // ONLY PARTIALLY TESTED #if ENABLED(FWRETRACT) - #define MIN_RETRACT 0.1 // A retract/recover of this length or longer can be converted to auto-retract + #define MIN_AUTORETRACT 0.1 // When auto-retract is on, convert E moves of this length and over + #define MAX_AUTORETRACT 10.0 // Upper limit for auto-retract conversion #define RETRACT_LENGTH 3 // Default retract length (positive mm) #define RETRACT_LENGTH_SWAP 13 // Default swap retract length (positive mm), for extruder change #define RETRACT_FEEDRATE 45 // Default feedrate for retracting (mm/s) diff --git a/Marlin/example_configurations/BQ/Hephestos_2/Configuration_adv.h b/Marlin/example_configurations/BQ/Hephestos_2/Configuration_adv.h index 9a01afa9b..6abb987ba 100644 --- a/Marlin/example_configurations/BQ/Hephestos_2/Configuration_adv.h +++ b/Marlin/example_configurations/BQ/Hephestos_2/Configuration_adv.h @@ -740,7 +740,7 @@ * Use M207 and M208 to define parameters for retract / recover. * * Use M209 to enable or disable auto-retract. - * With auto-retract enabled, all G1 E moves over the MIN_RETRACT length + * With auto-retract enabled, all G1 E moves within the set range * will be converted to firmware-based retract/recover moves. * * Be sure to turn off auto-retract during filament change. @@ -750,7 +750,8 @@ */ //#define FWRETRACT // ONLY PARTIALLY TESTED #if ENABLED(FWRETRACT) - #define MIN_RETRACT 0.1 // A retract/recover of this length or longer can be converted to auto-retract + #define MIN_AUTORETRACT 0.1 // When auto-retract is on, convert E moves of this length and over + #define MAX_AUTORETRACT 10.0 // Upper limit for auto-retract conversion #define RETRACT_LENGTH 3 // Default retract length (positive mm) #define RETRACT_LENGTH_SWAP 13 // Default swap retract length (positive mm), for extruder change #define RETRACT_FEEDRATE 45 // Default feedrate for retracting (mm/s) diff --git a/Marlin/example_configurations/BQ/WITBOX/Configuration_adv.h b/Marlin/example_configurations/BQ/WITBOX/Configuration_adv.h index 599709549..a02bb7874 100644 --- a/Marlin/example_configurations/BQ/WITBOX/Configuration_adv.h +++ b/Marlin/example_configurations/BQ/WITBOX/Configuration_adv.h @@ -757,7 +757,7 @@ * Use M207 and M208 to define parameters for retract / recover. * * Use M209 to enable or disable auto-retract. - * With auto-retract enabled, all G1 E moves over the MIN_RETRACT length + * With auto-retract enabled, all G1 E moves within the set range * will be converted to firmware-based retract/recover moves. * * Be sure to turn off auto-retract during filament change. @@ -767,7 +767,8 @@ */ //#define FWRETRACT // ONLY PARTIALLY TESTED #if ENABLED(FWRETRACT) - #define MIN_RETRACT 0.1 // A retract/recover of this length or longer can be converted to auto-retract + #define MIN_AUTORETRACT 0.1 // When auto-retract is on, convert E moves of this length and over + #define MAX_AUTORETRACT 10.0 // Upper limit for auto-retract conversion #define RETRACT_LENGTH 3 // Default retract length (positive mm) #define RETRACT_LENGTH_SWAP 13 // Default swap retract length (positive mm), for extruder change #define RETRACT_FEEDRATE 45 // Default feedrate for retracting (mm/s) diff --git a/Marlin/example_configurations/Cartesio/Configuration_adv.h b/Marlin/example_configurations/Cartesio/Configuration_adv.h index ddcbf5dca..a02849482 100644 --- a/Marlin/example_configurations/Cartesio/Configuration_adv.h +++ b/Marlin/example_configurations/Cartesio/Configuration_adv.h @@ -757,7 +757,7 @@ * Use M207 and M208 to define parameters for retract / recover. * * Use M209 to enable or disable auto-retract. - * With auto-retract enabled, all G1 E moves over the MIN_RETRACT length + * With auto-retract enabled, all G1 E moves within the set range * will be converted to firmware-based retract/recover moves. * * Be sure to turn off auto-retract during filament change. @@ -767,7 +767,8 @@ */ //#define FWRETRACT // ONLY PARTIALLY TESTED #if ENABLED(FWRETRACT) - #define MIN_RETRACT 0.1 // A retract/recover of this length or longer can be converted to auto-retract + #define MIN_AUTORETRACT 0.1 // When auto-retract is on, convert E moves of this length and over + #define MAX_AUTORETRACT 10.0 // Upper limit for auto-retract conversion #define RETRACT_LENGTH 3 // Default retract length (positive mm) #define RETRACT_LENGTH_SWAP 13 // Default swap retract length (positive mm), for extruder change #define RETRACT_FEEDRATE 45 // Default feedrate for retracting (mm/s) diff --git a/Marlin/example_configurations/Felix/Configuration_adv.h b/Marlin/example_configurations/Felix/Configuration_adv.h index c86bbb5d9..e592fdb5f 100644 --- a/Marlin/example_configurations/Felix/Configuration_adv.h +++ b/Marlin/example_configurations/Felix/Configuration_adv.h @@ -757,7 +757,7 @@ * Use M207 and M208 to define parameters for retract / recover. * * Use M209 to enable or disable auto-retract. - * With auto-retract enabled, all G1 E moves over the MIN_RETRACT length + * With auto-retract enabled, all G1 E moves within the set range * will be converted to firmware-based retract/recover moves. * * Be sure to turn off auto-retract during filament change. @@ -767,7 +767,8 @@ */ //#define FWRETRACT // ONLY PARTIALLY TESTED #if ENABLED(FWRETRACT) - #define MIN_RETRACT 0.1 // A retract/recover of this length or longer can be converted to auto-retract + #define MIN_AUTORETRACT 0.1 // When auto-retract is on, convert E moves of this length and over + #define MAX_AUTORETRACT 10.0 // Upper limit for auto-retract conversion #define RETRACT_LENGTH 3 // Default retract length (positive mm) #define RETRACT_LENGTH_SWAP 13 // Default swap retract length (positive mm), for extruder change #define RETRACT_FEEDRATE 45 // Default feedrate for retracting (mm/s) diff --git a/Marlin/example_configurations/Folger Tech/i3-2020/Configuration_adv.h b/Marlin/example_configurations/Folger Tech/i3-2020/Configuration_adv.h index bb45cf54d..f92a5eb9b 100644 --- a/Marlin/example_configurations/Folger Tech/i3-2020/Configuration_adv.h +++ b/Marlin/example_configurations/Folger Tech/i3-2020/Configuration_adv.h @@ -764,7 +764,7 @@ * Use M207 and M208 to define parameters for retract / recover. * * Use M209 to enable or disable auto-retract. - * With auto-retract enabled, all G1 E moves over the MIN_RETRACT length + * With auto-retract enabled, all G1 E moves within the set range * will be converted to firmware-based retract/recover moves. * * Be sure to turn off auto-retract during filament change. @@ -774,7 +774,8 @@ */ //#define FWRETRACT // ONLY PARTIALLY TESTED #if ENABLED(FWRETRACT) - #define MIN_RETRACT 0.1 // A retract/recover of this length or longer can be converted to auto-retract + #define MIN_AUTORETRACT 0.1 // When auto-retract is on, convert E moves of this length and over + #define MAX_AUTORETRACT 10.0 // Upper limit for auto-retract conversion #define RETRACT_LENGTH 3 // Default retract length (positive mm) #define RETRACT_LENGTH_SWAP 13 // Default swap retract length (positive mm), for extruder change #define RETRACT_FEEDRATE 45 // Default feedrate for retracting (mm/s) diff --git a/Marlin/example_configurations/Infitary/i3-M508/Configuration_adv.h b/Marlin/example_configurations/Infitary/i3-M508/Configuration_adv.h index 289d2a226..e2686ad1d 100644 --- a/Marlin/example_configurations/Infitary/i3-M508/Configuration_adv.h +++ b/Marlin/example_configurations/Infitary/i3-M508/Configuration_adv.h @@ -754,7 +754,7 @@ * Use M207 and M208 to define parameters for retract / recover. * * Use M209 to enable or disable auto-retract. - * With auto-retract enabled, all G1 E moves over the MIN_RETRACT length + * With auto-retract enabled, all G1 E moves within the set range * will be converted to firmware-based retract/recover moves. * * Be sure to turn off auto-retract during filament change. @@ -764,7 +764,8 @@ */ //#define FWRETRACT // ONLY PARTIALLY TESTED #if ENABLED(FWRETRACT) - #define MIN_RETRACT 0.1 // A retract/recover of this length or longer can be converted to auto-retract + #define MIN_AUTORETRACT 0.1 // When auto-retract is on, convert E moves of this length and over + #define MAX_AUTORETRACT 10.0 // Upper limit for auto-retract conversion #define RETRACT_LENGTH 3 // Default retract length (positive mm) #define RETRACT_LENGTH_SWAP 13 // Default swap retract length (positive mm), for extruder change #define RETRACT_FEEDRATE 45 // Default feedrate for retracting (mm/s) diff --git a/Marlin/example_configurations/Malyan/M150/Configuration_adv.h b/Marlin/example_configurations/Malyan/M150/Configuration_adv.h index 744a52b5b..23fa37df4 100644 --- a/Marlin/example_configurations/Malyan/M150/Configuration_adv.h +++ b/Marlin/example_configurations/Malyan/M150/Configuration_adv.h @@ -764,7 +764,7 @@ * Use M207 and M208 to define parameters for retract / recover. * * Use M209 to enable or disable auto-retract. - * With auto-retract enabled, all G1 E moves over the MIN_RETRACT length + * With auto-retract enabled, all G1 E moves within the set range * will be converted to firmware-based retract/recover moves. * * Be sure to turn off auto-retract during filament change. @@ -774,7 +774,8 @@ */ //#define FWRETRACT // ONLY PARTIALLY TESTED #if ENABLED(FWRETRACT) - #define MIN_RETRACT 0.1 // A retract/recover of this length or longer can be converted to auto-retract + #define MIN_AUTORETRACT 0.1 // When auto-retract is on, convert E moves of this length and over + #define MAX_AUTORETRACT 10.0 // Upper limit for auto-retract conversion #define RETRACT_LENGTH 3 // Default retract length (positive mm) #define RETRACT_LENGTH_SWAP 13 // Default swap retract length (positive mm), for extruder change #define RETRACT_FEEDRATE 45 // Default feedrate for retracting (mm/s) diff --git a/Marlin/example_configurations/RigidBot/Configuration_adv.h b/Marlin/example_configurations/RigidBot/Configuration_adv.h index 11d859273..4a4a9547b 100644 --- a/Marlin/example_configurations/RigidBot/Configuration_adv.h +++ b/Marlin/example_configurations/RigidBot/Configuration_adv.h @@ -757,7 +757,7 @@ * Use M207 and M208 to define parameters for retract / recover. * * Use M209 to enable or disable auto-retract. - * With auto-retract enabled, all G1 E moves over the MIN_RETRACT length + * With auto-retract enabled, all G1 E moves within the set range * will be converted to firmware-based retract/recover moves. * * Be sure to turn off auto-retract during filament change. @@ -767,7 +767,8 @@ */ //#define FWRETRACT // ONLY PARTIALLY TESTED #if ENABLED(FWRETRACT) - #define MIN_RETRACT 0.1 // A retract/recover of this length or longer can be converted to auto-retract + #define MIN_AUTORETRACT 0.1 // When auto-retract is on, convert E moves of this length and over + #define MAX_AUTORETRACT 10.0 // Upper limit for auto-retract conversion #define RETRACT_LENGTH 3 // Default retract length (positive mm) #define RETRACT_LENGTH_SWAP 13 // Default swap retract length (positive mm), for extruder change #define RETRACT_FEEDRATE 45 // Default feedrate for retracting (mm/s) diff --git a/Marlin/example_configurations/SCARA/Configuration_adv.h b/Marlin/example_configurations/SCARA/Configuration_adv.h index ec2f78530..83c9cd85a 100644 --- a/Marlin/example_configurations/SCARA/Configuration_adv.h +++ b/Marlin/example_configurations/SCARA/Configuration_adv.h @@ -757,7 +757,7 @@ * Use M207 and M208 to define parameters for retract / recover. * * Use M209 to enable or disable auto-retract. - * With auto-retract enabled, all G1 E moves over the MIN_RETRACT length + * With auto-retract enabled, all G1 E moves within the set range * will be converted to firmware-based retract/recover moves. * * Be sure to turn off auto-retract during filament change. @@ -767,7 +767,8 @@ */ //#define FWRETRACT // ONLY PARTIALLY TESTED #if ENABLED(FWRETRACT) - #define MIN_RETRACT 0.1 // A retract/recover of this length or longer can be converted to auto-retract + #define MIN_AUTORETRACT 0.1 // When auto-retract is on, convert E moves of this length and over + #define MAX_AUTORETRACT 10.0 // Upper limit for auto-retract conversion #define RETRACT_LENGTH 3 // Default retract length (positive mm) #define RETRACT_LENGTH_SWAP 13 // Default swap retract length (positive mm), for extruder change #define RETRACT_FEEDRATE 35 // Default feedrate for retracting (mm/s) diff --git a/Marlin/example_configurations/TinyBoy2/Configuration_adv.h b/Marlin/example_configurations/TinyBoy2/Configuration_adv.h index ed8194cfe..25f03db77 100644 --- a/Marlin/example_configurations/TinyBoy2/Configuration_adv.h +++ b/Marlin/example_configurations/TinyBoy2/Configuration_adv.h @@ -760,7 +760,7 @@ * Use M207 and M208 to define parameters for retract / recover. * * Use M209 to enable or disable auto-retract. - * With auto-retract enabled, all G1 E moves over the MIN_RETRACT length + * With auto-retract enabled, all G1 E moves within the set range * will be converted to firmware-based retract/recover moves. * * Be sure to turn off auto-retract during filament change. @@ -770,7 +770,8 @@ */ //#define FWRETRACT // ONLY PARTIALLY TESTED #if ENABLED(FWRETRACT) - #define MIN_RETRACT 0.1 // A retract/recover of this length or longer can be converted to auto-retract + #define MIN_AUTORETRACT 0.1 // When auto-retract is on, convert E moves of this length and over + #define MAX_AUTORETRACT 10.0 // Upper limit for auto-retract conversion #define RETRACT_LENGTH 3 // Default retract length (positive mm) #define RETRACT_LENGTH_SWAP 13 // Default swap retract length (positive mm), for extruder change #define RETRACT_FEEDRATE 45 // Default feedrate for retracting (mm/s) diff --git a/Marlin/example_configurations/Velleman/K8200/Configuration_adv.h b/Marlin/example_configurations/Velleman/K8200/Configuration_adv.h index 3b3a74d53..1cc82b071 100644 --- a/Marlin/example_configurations/Velleman/K8200/Configuration_adv.h +++ b/Marlin/example_configurations/Velleman/K8200/Configuration_adv.h @@ -770,7 +770,7 @@ * Use M207 and M208 to define parameters for retract / recover. * * Use M209 to enable or disable auto-retract. - * With auto-retract enabled, all G1 E moves over the MIN_RETRACT length + * With auto-retract enabled, all G1 E moves within the set range * will be converted to firmware-based retract/recover moves. * * Be sure to turn off auto-retract during filament change. @@ -780,7 +780,8 @@ */ //#define FWRETRACT // ONLY PARTIALLY TESTED #if ENABLED(FWRETRACT) - #define MIN_RETRACT 0.1 // A retract/recover of this length or longer can be converted to auto-retract + #define MIN_AUTORETRACT 0.1 // When auto-retract is on, convert E moves of this length and over + #define MAX_AUTORETRACT 10.0 // Upper limit for auto-retract conversion #define RETRACT_LENGTH 3 // Default retract length (positive mm) #define RETRACT_LENGTH_SWAP 13 // Default swap retract length (positive mm), for extruder change #define RETRACT_FEEDRATE 45 // Default feedrate for retracting (mm/s) diff --git a/Marlin/example_configurations/Velleman/K8400/Configuration_adv.h b/Marlin/example_configurations/Velleman/K8400/Configuration_adv.h index ae067b567..3089cf4ba 100644 --- a/Marlin/example_configurations/Velleman/K8400/Configuration_adv.h +++ b/Marlin/example_configurations/Velleman/K8400/Configuration_adv.h @@ -757,7 +757,7 @@ * Use M207 and M208 to define parameters for retract / recover. * * Use M209 to enable or disable auto-retract. - * With auto-retract enabled, all G1 E moves over the MIN_RETRACT length + * With auto-retract enabled, all G1 E moves within the set range * will be converted to firmware-based retract/recover moves. * * Be sure to turn off auto-retract during filament change. @@ -767,7 +767,8 @@ */ //#define FWRETRACT // ONLY PARTIALLY TESTED #if ENABLED(FWRETRACT) - #define MIN_RETRACT 0.1 // A retract/recover of this length or longer can be converted to auto-retract + #define MIN_AUTORETRACT 0.1 // When auto-retract is on, convert E moves of this length and over + #define MAX_AUTORETRACT 10.0 // Upper limit for auto-retract conversion #define RETRACT_LENGTH 3 // Default retract length (positive mm) #define RETRACT_LENGTH_SWAP 13 // Default swap retract length (positive mm), for extruder change #define RETRACT_FEEDRATE 45 // Default feedrate for retracting (mm/s) diff --git a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h index e6b328383..4944a6af5 100644 --- a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h +++ b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h @@ -762,7 +762,7 @@ * Use M207 and M208 to define parameters for retract / recover. * * Use M209 to enable or disable auto-retract. - * With auto-retract enabled, all G1 E moves over the MIN_RETRACT length + * With auto-retract enabled, all G1 E moves within the set range * will be converted to firmware-based retract/recover moves. * * Be sure to turn off auto-retract during filament change. @@ -772,7 +772,8 @@ */ //#define FWRETRACT // ONLY PARTIALLY TESTED #if ENABLED(FWRETRACT) - #define MIN_RETRACT 0.1 // A retract/recover of this length or longer can be converted to auto-retract + #define MIN_AUTORETRACT 0.1 // When auto-retract is on, convert E moves of this length and over + #define MAX_AUTORETRACT 10.0 // Upper limit for auto-retract conversion #define RETRACT_LENGTH 3 // Default retract length (positive mm) #define RETRACT_LENGTH_SWAP 13 // Default swap retract length (positive mm), for extruder change #define RETRACT_FEEDRATE 45 // Default feedrate for retracting (mm/s) diff --git a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h index b25b49b1a..f227e01ce 100644 --- a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h +++ b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h @@ -761,7 +761,7 @@ * Use M207 and M208 to define parameters for retract / recover. * * Use M209 to enable or disable auto-retract. - * With auto-retract enabled, all G1 E moves over the MIN_RETRACT length + * With auto-retract enabled, all G1 E moves within the set range * will be converted to firmware-based retract/recover moves. * * Be sure to turn off auto-retract during filament change. @@ -771,7 +771,8 @@ */ //#define FWRETRACT // ONLY PARTIALLY TESTED #if ENABLED(FWRETRACT) - #define MIN_RETRACT 0.1 // A retract/recover of this length or longer can be converted to auto-retract + #define MIN_AUTORETRACT 0.1 // When auto-retract is on, convert E moves of this length and over + #define MAX_AUTORETRACT 10.0 // Upper limit for auto-retract conversion #define RETRACT_LENGTH 3 // Default retract length (positive mm) #define RETRACT_LENGTH_SWAP 13 // Default swap retract length (positive mm), for extruder change #define RETRACT_FEEDRATE 45 // Default feedrate for retracting (mm/s) diff --git a/Marlin/example_configurations/delta/generic/Configuration_adv.h b/Marlin/example_configurations/delta/generic/Configuration_adv.h index 739d2d640..8393ea2be 100644 --- a/Marlin/example_configurations/delta/generic/Configuration_adv.h +++ b/Marlin/example_configurations/delta/generic/Configuration_adv.h @@ -759,7 +759,7 @@ * Use M207 and M208 to define parameters for retract / recover. * * Use M209 to enable or disable auto-retract. - * With auto-retract enabled, all G1 E moves over the MIN_RETRACT length + * With auto-retract enabled, all G1 E moves within the set range * will be converted to firmware-based retract/recover moves. * * Be sure to turn off auto-retract during filament change. @@ -769,7 +769,8 @@ */ //#define FWRETRACT // ONLY PARTIALLY TESTED #if ENABLED(FWRETRACT) - #define MIN_RETRACT 0.1 // A retract/recover of this length or longer can be converted to auto-retract + #define MIN_AUTORETRACT 0.1 // When auto-retract is on, convert E moves of this length and over + #define MAX_AUTORETRACT 10.0 // Upper limit for auto-retract conversion #define RETRACT_LENGTH 3 // Default retract length (positive mm) #define RETRACT_LENGTH_SWAP 13 // Default swap retract length (positive mm), for extruder change #define RETRACT_FEEDRATE 45 // Default feedrate for retracting (mm/s) diff --git a/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h index 739d2d640..8393ea2be 100644 --- a/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h @@ -759,7 +759,7 @@ * Use M207 and M208 to define parameters for retract / recover. * * Use M209 to enable or disable auto-retract. - * With auto-retract enabled, all G1 E moves over the MIN_RETRACT length + * With auto-retract enabled, all G1 E moves within the set range * will be converted to firmware-based retract/recover moves. * * Be sure to turn off auto-retract during filament change. @@ -769,7 +769,8 @@ */ //#define FWRETRACT // ONLY PARTIALLY TESTED #if ENABLED(FWRETRACT) - #define MIN_RETRACT 0.1 // A retract/recover of this length or longer can be converted to auto-retract + #define MIN_AUTORETRACT 0.1 // When auto-retract is on, convert E moves of this length and over + #define MAX_AUTORETRACT 10.0 // Upper limit for auto-retract conversion #define RETRACT_LENGTH 3 // Default retract length (positive mm) #define RETRACT_LENGTH_SWAP 13 // Default swap retract length (positive mm), for extruder change #define RETRACT_FEEDRATE 45 // Default feedrate for retracting (mm/s) diff --git a/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h index e08ff0b48..dfa3b1461 100644 --- a/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h @@ -764,7 +764,7 @@ * Use M207 and M208 to define parameters for retract / recover. * * Use M209 to enable or disable auto-retract. - * With auto-retract enabled, all G1 E moves over the MIN_RETRACT length + * With auto-retract enabled, all G1 E moves within the set range * will be converted to firmware-based retract/recover moves. * * Be sure to turn off auto-retract during filament change. @@ -774,7 +774,8 @@ */ //#define FWRETRACT // ONLY PARTIALLY TESTED #if ENABLED(FWRETRACT) - #define MIN_RETRACT 0.1 // A retract/recover of this length or longer can be converted to auto-retract + #define MIN_AUTORETRACT 0.1 // When auto-retract is on, convert E moves of this length and over + #define MAX_AUTORETRACT 10.0 // Upper limit for auto-retract conversion #define RETRACT_LENGTH 3 // Default retract length (positive mm) #define RETRACT_LENGTH_SWAP 13 // Default swap retract length (positive mm), for extruder change #define RETRACT_FEEDRATE 45 // Default feedrate for retracting (mm/s) diff --git a/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h index 3b9b4ddcd..6eaa071a0 100644 --- a/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h @@ -759,7 +759,7 @@ * Use M207 and M208 to define parameters for retract / recover. * * Use M209 to enable or disable auto-retract. - * With auto-retract enabled, all G1 E moves over the MIN_RETRACT length + * With auto-retract enabled, all G1 E moves within the set range * will be converted to firmware-based retract/recover moves. * * Be sure to turn off auto-retract during filament change. @@ -769,7 +769,8 @@ */ //#define FWRETRACT // ONLY PARTIALLY TESTED #if ENABLED(FWRETRACT) - #define MIN_RETRACT 0.1 // A retract/recover of this length or longer can be converted to auto-retract + #define MIN_AUTORETRACT 0.1 // When auto-retract is on, convert E moves of this length and over + #define MAX_AUTORETRACT 10.0 // Upper limit for auto-retract conversion #define RETRACT_LENGTH 3 // Default retract length (positive mm) #define RETRACT_LENGTH_SWAP 13 // Default swap retract length (positive mm), for extruder change #define RETRACT_FEEDRATE 45 // Default feedrate for retracting (mm/s) diff --git a/Marlin/example_configurations/gCreate/gMax1.5+/Configuration_adv.h b/Marlin/example_configurations/gCreate/gMax1.5+/Configuration_adv.h index 7f003a4b8..ee3267cc3 100644 --- a/Marlin/example_configurations/gCreate/gMax1.5+/Configuration_adv.h +++ b/Marlin/example_configurations/gCreate/gMax1.5+/Configuration_adv.h @@ -764,7 +764,7 @@ * Use M207 and M208 to define parameters for retract / recover. * * Use M209 to enable or disable auto-retract. - * With auto-retract enabled, all G1 E moves over the MIN_RETRACT length + * With auto-retract enabled, all G1 E moves within the set range * will be converted to firmware-based retract/recover moves. * * Be sure to turn off auto-retract during filament change. @@ -774,7 +774,8 @@ */ //#define FWRETRACT // ONLY PARTIALLY TESTED #if ENABLED(FWRETRACT) - #define MIN_RETRACT 0.1 // A retract/recover of this length or longer can be converted to auto-retract + #define MIN_AUTORETRACT 0.1 // When auto-retract is on, convert E moves of this length and over + #define MAX_AUTORETRACT 10.0 // Upper limit for auto-retract conversion #define RETRACT_LENGTH 3 // Default retract length (positive mm) #define RETRACT_LENGTH_SWAP 13 // Default swap retract length (positive mm), for extruder change #define RETRACT_FEEDRATE 45 // Default feedrate for retracting (mm/s) diff --git a/Marlin/example_configurations/makibox/Configuration_adv.h b/Marlin/example_configurations/makibox/Configuration_adv.h index 1f616b5b0..88ecc16cf 100644 --- a/Marlin/example_configurations/makibox/Configuration_adv.h +++ b/Marlin/example_configurations/makibox/Configuration_adv.h @@ -757,7 +757,7 @@ * Use M207 and M208 to define parameters for retract / recover. * * Use M209 to enable or disable auto-retract. - * With auto-retract enabled, all G1 E moves over the MIN_RETRACT length + * With auto-retract enabled, all G1 E moves within the set range * will be converted to firmware-based retract/recover moves. * * Be sure to turn off auto-retract during filament change. @@ -767,7 +767,8 @@ */ //#define FWRETRACT // ONLY PARTIALLY TESTED #if ENABLED(FWRETRACT) - #define MIN_RETRACT 0.1 // A retract/recover of this length or longer can be converted to auto-retract + #define MIN_AUTORETRACT 0.1 // When auto-retract is on, convert E moves of this length and over + #define MAX_AUTORETRACT 10.0 // Upper limit for auto-retract conversion #define RETRACT_LENGTH 3 // Default retract length (positive mm) #define RETRACT_LENGTH_SWAP 13 // Default swap retract length (positive mm), for extruder change #define RETRACT_FEEDRATE 45 // Default feedrate for retracting (mm/s) diff --git a/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h b/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h index b1cafd031..824587af3 100644 --- a/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h +++ b/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h @@ -757,7 +757,7 @@ * Use M207 and M208 to define parameters for retract / recover. * * Use M209 to enable or disable auto-retract. - * With auto-retract enabled, all G1 E moves over the MIN_RETRACT length + * With auto-retract enabled, all G1 E moves within the set range * will be converted to firmware-based retract/recover moves. * * Be sure to turn off auto-retract during filament change. @@ -767,7 +767,8 @@ */ //#define FWRETRACT // ONLY PARTIALLY TESTED #if ENABLED(FWRETRACT) - #define MIN_RETRACT 0.1 // A retract/recover of this length or longer can be converted to auto-retract + #define MIN_AUTORETRACT 0.1 // When auto-retract is on, convert E moves of this length and over + #define MAX_AUTORETRACT 10.0 // Upper limit for auto-retract conversion #define RETRACT_LENGTH 3 // Default retract length (positive mm) #define RETRACT_LENGTH_SWAP 13 // Default swap retract length (positive mm), for extruder change #define RETRACT_FEEDRATE 45 // Default feedrate for retracting (mm/s) diff --git a/Marlin/example_configurations/wt150/Configuration_adv.h b/Marlin/example_configurations/wt150/Configuration_adv.h index afbeb5701..a5b9f070c 100644 --- a/Marlin/example_configurations/wt150/Configuration_adv.h +++ b/Marlin/example_configurations/wt150/Configuration_adv.h @@ -764,7 +764,7 @@ * Use M207 and M208 to define parameters for retract / recover. * * Use M209 to enable or disable auto-retract. - * With auto-retract enabled, all G1 E moves over the MIN_RETRACT length + * With auto-retract enabled, all G1 E moves within the set range * will be converted to firmware-based retract/recover moves. * * Be sure to turn off auto-retract during filament change. @@ -774,7 +774,8 @@ */ //#define FWRETRACT // ONLY PARTIALLY TESTED #if ENABLED(FWRETRACT) - #define MIN_RETRACT 0.1 // A retract/recover of this length or longer can be converted to auto-retract + #define MIN_AUTORETRACT 0.1 // When auto-retract is on, convert E moves of this length and over + #define MAX_AUTORETRACT 10.0 // Upper limit for auto-retract conversion #define RETRACT_LENGTH 3 // Default retract length (positive mm) #define RETRACT_LENGTH_SWAP 13 // Default swap retract length (positive mm), for extruder change #define RETRACT_FEEDRATE 45 // Default feedrate for retracting (mm/s) From fee696db5d293d9a93997e25facc6448f6ee4abf Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 17 Jul 2017 22:01:41 -0500 Subject: [PATCH 041/112] Improve retract() for G10/G11/autoretract --- Marlin/Marlin.h | 13 ++- Marlin/Marlin_main.cpp | 161 +++++++++++++++++++++++---------- Marlin/configuration_store.cpp | 138 +++++++++++++--------------- 3 files changed, 185 insertions(+), 127 deletions(-) diff --git a/Marlin/Marlin.h b/Marlin/Marlin.h index 543fbcc5e..33c813645 100644 --- a/Marlin/Marlin.h +++ b/Marlin/Marlin.h @@ -383,10 +383,15 @@ extern float soft_endstop_min[XYZ], soft_endstop_max[XYZ]; #endif #if ENABLED(FWRETRACT) - extern bool autoretract_enabled; - extern bool retracted[EXTRUDERS]; // extruder[n].retracted - extern float retract_length, retract_length_swap, retract_feedrate_mm_s, retract_zlift; - extern float retract_recover_length, retract_recover_length_swap, retract_recover_feedrate_mm_s; + extern bool autoretract_enabled; // M209 S - Autoretract switch + extern float retract_length, // M207 S - G10 Retract length + retract_feedrate_mm_s, // M207 F - G10 Retract feedrate + retract_zlift, // M207 Z - G10 Retract hop size + retract_recover_length, // M208 S - G11 Recover length + retract_recover_feedrate_mm_s, // M208 F - G11 Recover feedrate + retract_length_swap, // M207 W - G10 Swap Retract length + retract_recover_length_swap, // M208 W - G11 Swap Recover length + swap_retract_recover_feedrate_mm_s; // M208 R - G11 Swap Recover feedrate #endif // Print job timer diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 51e4c4b5f..20c71945e 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -557,20 +557,22 @@ static uint8_t target_extruder; baricuda_e_to_p_pressure = 0; #endif -#if ENABLED(FWRETRACT) - - bool autoretract_enabled = false; - bool retracted[EXTRUDERS] = { false }; - bool retracted_swap[EXTRUDERS] = { false }; - - float retract_length = RETRACT_LENGTH; - float retract_length_swap = RETRACT_LENGTH_SWAP; - float retract_feedrate_mm_s = RETRACT_FEEDRATE; - float retract_zlift = RETRACT_ZLIFT; - float retract_recover_length = RETRACT_RECOVER_LENGTH; - float retract_recover_length_swap = RETRACT_RECOVER_LENGTH_SWAP; - float retract_recover_feedrate_mm_s = RETRACT_RECOVER_FEEDRATE; - +#if ENABLED(FWRETRACT) // Initialized by settings.load()... + bool autoretract_enabled, // M209 S - Autoretract switch + retracted[EXTRUDERS] = { false }; // Which extruders are currently retracted + float retract_length, // M207 S - G10 Retract length + retract_feedrate_mm_s, // M207 F - G10 Retract feedrate + retract_zlift, // M207 Z - G10 Retract hop size + retract_recover_length, // M208 S - G11 Recover length + retract_recover_feedrate_mm_s, // M208 F - G11 Recover feedrate + retract_length_swap, // M207 W - G10 Swap Retract length + retract_recover_length_swap, // M208 W - G11 Swap Recover length + swap_retract_recover_feedrate_mm_s; // M208 R - G11 Swap Recover feedrate + #if EXTRUDERS > 1 + bool retracted_swap[EXTRUDERS] = { false }; // Which extruders are swap-retracted + #else + constexpr bool retracted_swap[1] = { false }; + #endif #endif // FWRETRACT #if HAS_POWER_SWITCH @@ -3100,55 +3102,120 @@ static void homeaxis(const AxisEnum axis) { #if ENABLED(FWRETRACT) - void retract(const bool retracting, const bool swapping = false) { + /** + * Retract or recover according to firmware settings + * + * This function handles retract/recover moves for G10 and G11, + * plus auto-retract moves sent from G0/G1 when E-only moves are done. + * + * To simplify the logic, doubled retract/recover moves are ignored. + * + * Note: Z lift is done transparently to the planner. Aborting + * a print between G10 and G11 may corrupt the Z position. + * + * Note: Auto-retract will apply the set Z hop in addition to any Z hop + * included in the G-code. Use M207 Z0 to to prevent double hop. + */ + void retract(const bool retracting + #if EXTRUDERS > 1 + , bool swapping = false + #endif + ) { + + static float hop_height, // Remember where the Z height started + hop_amount = 0.0; // Total amount lifted, for use in recover - static float hop_height; + // Simply never allow two retracts or recovers in a row + if (retracted[active_extruder] == retracting) return; + + #if EXTRUDERS < 2 + bool swapping = false; + #endif + if (!retracting) swapping = retracted_swap[active_extruder]; + + /* // debugging + SERIAL_ECHOLNPAIR("retracting ", retracting); + SERIAL_ECHOLNPAIR("swapping ", swapping); + SERIAL_ECHOLNPAIR("active extruder ", active_extruder); + for (uint8_t i = 0; i < EXTRUDERS; ++i) { + SERIAL_ECHOPAIR("retracted[", i); + SERIAL_ECHOLNPAIR("] ", retracted[i]); + SERIAL_ECHOPAIR("retracted_swap[", i); + SERIAL_ECHOLNPAIR("] ", retracted_swap[i]); + } + SERIAL_ECHOLNPAIR("current_position[z] ", current_position[Z_AXIS]); + SERIAL_ECHOLNPAIR("hop_amount ", hop_amount); + //*/ - if (retracting == retracted[active_extruder]) return; + const bool has_zhop = retract_zlift > 0.01; // Is there a hop set? const float old_feedrate_mm_s = feedrate_mm_s; + // The current position will be the destination for E and Z moves set_destination_to_current(); if (retracting) { + // Remember the Z height since G-code may include its own Z-hop + // For best results turn off Z hop if G-code already includes it + hop_height = destination[Z_AXIS]; + // Retract by moving from a faux E position back to the current E position 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(); - if (retract_zlift > 0.01) { - hop_height = current_position[Z_AXIS]; - // Pretend current position is lower - current_position[Z_AXIS] -= retract_zlift; - SYNC_PLAN_POSITION_KINEMATIC(); - // Raise up to the old current_position - prepare_move_to_destination(); + // Is a Z hop set, and has the hop not yet been done? + if (has_zhop) { + hop_amount += retract_zlift; // Carriage is raised for retraction hop + current_position[Z_AXIS] -= retract_zlift; // Pretend current pos is lower. Next move raises Z. + SYNC_PLAN_POSITION_KINEMATIC(); // Set the planner to the new position + prepare_move_to_destination(); // Raise up to the old current pos } } else { - - // If the height hasn't been lowered, undo the Z hop - if (retract_zlift > 0.01 && hop_height <= current_position[Z_AXIS]) { - // Pretend current position is higher. Z will lower on the next move - current_position[Z_AXIS] += retract_zlift; - SYNC_PLAN_POSITION_KINEMATIC(); - // Lower Z - prepare_move_to_destination(); + // If a hop was done and Z hasn't changed, undo the Z hop + if (hop_amount && NEAR(hop_height, destination[Z_AXIS])) { + current_position[Z_AXIS] += hop_amount; // Pretend current pos is higher. Next move lowers Z. + SYNC_PLAN_POSITION_KINEMATIC(); // Set the planner to the new position + prepare_move_to_destination(); // Lower to the old current pos + hop_amount = 0.0; } - feedrate_mm_s = retract_recover_feedrate_mm_s; + // A retract multiplier has been added here to get faster swap recovery + feedrate_mm_s = swapping ? swap_retract_recover_feedrate_mm_s : retract_recover_feedrate_mm_s; + const 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(); - // Recover E - prepare_move_to_destination(); + prepare_move_to_destination(); // Recover E } feedrate_mm_s = old_feedrate_mm_s; + + // The active extruder is now retracted or recovered retracted[active_extruder] = retracting; + // If swap retract/recover then update the retracted_swap flag too + #if EXTRUDERS > 1 + if (swapping) retracted_swap[active_extruder] = retracting; + #endif + + /* // debugging + SERIAL_ECHOLNPAIR("retracting ", retracting); + SERIAL_ECHOLNPAIR("swapping ", swapping); + SERIAL_ECHOLNPAIR("active_extruder ", active_extruder); + for (uint8_t i = 0; i < EXTRUDERS; ++i) { + SERIAL_ECHOPAIR("retracted[", i); + SERIAL_ECHOLNPAIR("] ", retracted[i]); + SERIAL_ECHOPAIR("retracted_swap[", i); + SERIAL_ECHOLNPAIR("] ", retracted_swap[i]); + } + SERIAL_ECHOLNPAIR("current_position[z] ", current_position[Z_AXIS]); + SERIAL_ECHOLNPAIR("hop_amount ", hop_amount); + //*/ + } // retract() #endif // FWRETRACT @@ -3277,18 +3344,16 @@ inline void gcode_G0_G1( gcode_get_destination(); // For X Y Z E F #if ENABLED(FWRETRACT) - - if (autoretract_enabled && !(parser.seen('X') || parser.seen('Y') || parser.seen('Z')) && parser.seen('E')) { + // When M209 Autoretract is enabled, convert E-only moves to firmware retract/recover moves + if (autoretract_enabled && parser.seen('E') && !(parser.seen('X') || parser.seen('Y') || parser.seen('Z'))) { const float echange = destination[E_AXIS] - current_position[E_AXIS]; - // Is this move an attempt to retract or recover? + // Is this a retract or recover move? if (WITHIN(FABS(echange), MIN_AUTORETRACT, MAX_AUTORETRACT) && retracted[active_extruder] == (echange > 0.0)) { - current_position[E_AXIS] = destination[E_AXIS]; // hide the slicer-generated retract/recover from calculations - sync_plan_position_e(); // AND from the planner - retract(!retracted[active_extruder]); - return; + current_position[E_AXIS] = destination[E_AXIS]; // Hide a G1-based retract/recover from calculations + sync_plan_position_e(); // AND from the planner + return retract(echange < 0.0); // Firmware-based retract/recover (double-retract ignored) } } - #endif // FWRETRACT #if IS_SCARA @@ -8489,9 +8554,7 @@ inline void gcode_M205() { if (parser.seen('S')) retract_length = parser.value_axis_units(E_AXIS); if (parser.seen('F')) retract_feedrate_mm_s = MMM_TO_MMS(parser.value_axis_units(E_AXIS)); if (parser.seen('Z')) retract_zlift = parser.value_linear_units(); - #if EXTRUDERS > 1 - if (parser.seen('W')) retract_length_swap = parser.value_axis_units(E_AXIS); - #endif + if (parser.seen('W')) retract_length_swap = parser.value_axis_units(E_AXIS); } /** @@ -8500,13 +8563,13 @@ inline void gcode_M205() { * S[+units] retract_recover_length (in addition to M207 S*) * W[+units] retract_recover_length_swap (multi-extruder) * F[units/min] retract_recover_feedrate_mm_s + * R[units/min] swap_retract_recover_feedrate_mm_s */ inline void gcode_M208() { if (parser.seen('S')) retract_recover_length = parser.value_axis_units(E_AXIS); if (parser.seen('F')) retract_recover_feedrate_mm_s = MMM_TO_MMS(parser.value_axis_units(E_AXIS)); - #if EXTRUDERS > 1 - if (parser.seen('W')) retract_recover_length_swap = parser.value_axis_units(E_AXIS); - #endif + if (parser.seen('R')) swap_retract_recover_feedrate_mm_s = MMM_TO_MMS(parser.value_axis_units(E_AXIS)); + if (parser.seen('W')) retract_recover_length_swap = parser.value_axis_units(E_AXIS); } /** diff --git a/Marlin/configuration_store.cpp b/Marlin/configuration_store.cpp index c86ba0859..6fa2ff969 100644 --- a/Marlin/configuration_store.cpp +++ b/Marlin/configuration_store.cpp @@ -36,7 +36,7 @@ * */ -#define EEPROM_VERSION "V39" +#define EEPROM_VERSION "V40" // Change EEPROM version if these are changed: #define EEPROM_OFFSET 100 @@ -125,44 +125,45 @@ * DOGLCD: 2 bytes * 502 M250 C lcd_contrast (uint16_t) * - * FWRETRACT: 29 bytes + * FWRETRACT: 33 bytes * 504 M209 S autoretract_enabled (bool) * 505 M207 S retract_length (float) - * 509 M207 W retract_length_swap (float) - * 513 M207 F retract_feedrate_mm_s (float) - * 517 M207 Z retract_zlift (float) - * 521 M208 S retract_recover_length (float) - * 525 M208 W retract_recover_length_swap (float) - * 529 M208 F retract_recover_feedrate_mm_s (float) + * 509 M207 F retract_feedrate_mm_s (float) + * 513 M207 Z retract_zlift (float) + * 517 M208 S retract_recover_length (float) + * 521 M208 F retract_recover_feedrate_mm_s (float) + * 525 M207 W retract_length_swap (float) + * 529 M208 W retract_recover_length_swap (float) + * 533 M208 R swap_retract_recover_feedrate_mm_s (float) * * Volumetric Extrusion: 21 bytes - * 533 M200 D volumetric_enabled (bool) - * 534 M200 T D filament_size (float x5) (T0..3) + * 537 M200 D volumetric_enabled (bool) + * 538 M200 T D filament_size (float x5) (T0..3) * * HAVE_TMC2130: 20 bytes - * 554 M906 X Stepper X current (uint16_t) - * 556 M906 Y Stepper Y current (uint16_t) - * 558 M906 Z Stepper Z current (uint16_t) - * 560 M906 X2 Stepper X2 current (uint16_t) - * 562 M906 Y2 Stepper Y2 current (uint16_t) - * 564 M906 Z2 Stepper Z2 current (uint16_t) - * 566 M906 E0 Stepper E0 current (uint16_t) - * 568 M906 E1 Stepper E1 current (uint16_t) - * 570 M906 E2 Stepper E2 current (uint16_t) - * 572 M906 E3 Stepper E3 current (uint16_t) - * 576 M906 E4 Stepper E4 current (uint16_t) + * 558 M906 X Stepper X current (uint16_t) + * 560 M906 Y Stepper Y current (uint16_t) + * 562 M906 Z Stepper Z current (uint16_t) + * 564 M906 X2 Stepper X2 current (uint16_t) + * 566 M906 Y2 Stepper Y2 current (uint16_t) + * 568 M906 Z2 Stepper Z2 current (uint16_t) + * 570 M906 E0 Stepper E0 current (uint16_t) + * 572 M906 E1 Stepper E1 current (uint16_t) + * 574 M906 E2 Stepper E2 current (uint16_t) + * 576 M906 E3 Stepper E3 current (uint16_t) + * 580 M906 E4 Stepper E4 current (uint16_t) * * LIN_ADVANCE: 8 bytes - * 580 M900 K extruder_advance_k (float) - * 584 M900 WHD advance_ed_ratio (float) + * 584 M900 K extruder_advance_k (float) + * 588 M900 WHD advance_ed_ratio (float) * * HAS_MOTOR_CURRENT_PWM: - * 588 M907 X Stepper XY current (uint32_t) - * 592 M907 Z Stepper Z current (uint32_t) - * 596 M907 E Stepper E current (uint32_t) + * 592 M907 X Stepper XY current (uint32_t) + * 596 M907 Z Stepper Z current (uint32_t) + * 600 M907 E Stepper E current (uint32_t) * - * 600 Minimum end-point - * 1921 (600 + 36 + 9 + 288 + 988) Maximum end-point + * 604 Minimum end-point + * 1925 (604 + 36 + 9 + 288 + 988) Maximum end-point * * ======================================================================== * meshes_begin (between max and min end-point, directly above) @@ -520,26 +521,26 @@ void MarlinSettings::postprocess() { #endif EEPROM_WRITE(lcd_contrast); - #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); - #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 + #if DISABLED(FWRETRACT) + const bool autoretract_enabled = false; + const float retract_length = 3, + retract_feedrate_mm_s = 45, + retract_zlift = 0, + retract_recover_length = 0, + retract_recover_feedrate_mm_s = 0, + retract_length_swap = 13, + retract_recover_length_swap = 0, + swap_retract_recover_feedrate_mm_s = 8; + #endif + EEPROM_WRITE(autoretract_enabled); + EEPROM_WRITE(retract_length); + EEPROM_WRITE(retract_feedrate_mm_s); + EEPROM_WRITE(retract_zlift); + EEPROM_WRITE(retract_recover_length); + EEPROM_WRITE(retract_recover_feedrate_mm_s); + EEPROM_WRITE(retract_length_swap); + EEPROM_WRITE(retract_recover_length_swap); + EEPROM_WRITE(swap_retract_recover_feedrate_mm_s); EEPROM_WRITE(volumetric_enabled); @@ -620,7 +621,7 @@ void MarlinSettings::postprocess() { EEPROM_WRITE(val); #else val = 0; - for (uint8_t q = 0; q < 11; ++q) EEPROM_WRITE(val); + for (uint8_t q = 11; q--;) EEPROM_WRITE(val); #endif // @@ -701,6 +702,7 @@ void MarlinSettings::postprocess() { } else { float dummy = 0; + bool dummyb; working_crc = 0; //clear before reading first "real data" @@ -830,7 +832,6 @@ void MarlinSettings::postprocess() { EEPROM_READ(ubl.state.z_offset); EEPROM_READ(ubl.state.storage_slot); #else - bool dummyb; uint8_t dummyui8; EEPROM_READ(dummyb); EEPROM_READ(dummy); @@ -915,21 +916,17 @@ void MarlinSettings::postprocess() { #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(retract_length_swap); + EEPROM_READ(retract_recover_length_swap); + EEPROM_READ(swap_retract_recover_feedrate_mm_s); + #else + EEPROM_READ(dummyb); + for (uint8_t q=8; q--;) EEPROM_READ(dummy); + #endif EEPROM_READ(volumetric_enabled); @@ -1291,17 +1288,14 @@ void MarlinSettings::reset() { #if ENABLED(FWRETRACT) autoretract_enabled = false; retract_length = RETRACT_LENGTH; - #if EXTRUDERS > 1 - retract_length_swap = RETRACT_LENGTH_SWAP; - #endif retract_feedrate_mm_s = RETRACT_FEEDRATE; retract_zlift = RETRACT_ZLIFT; retract_recover_length = RETRACT_RECOVER_LENGTH; - #if EXTRUDERS > 1 - retract_recover_length_swap = RETRACT_RECOVER_LENGTH_SWAP; - #endif retract_recover_feedrate_mm_s = RETRACT_RECOVER_FEEDRATE; - #endif + retract_length_swap = RETRACT_LENGTH_SWAP; + retract_recover_length_swap = RETRACT_RECOVER_LENGTH_SWAP; + swap_retract_recover_feedrate_mm_s = RETRACT_RECOVER_FEEDRATE_SWAP; + #endif // FWRETRACT volumetric_enabled = #if ENABLED(VOLUMETRIC_DEFAULT_ON) @@ -1753,9 +1747,7 @@ void MarlinSettings::reset() { } CONFIG_ECHO_START; SERIAL_ECHOPAIR(" M207 S", LINEAR_UNIT(retract_length)); - #if EXTRUDERS > 1 - SERIAL_ECHOPAIR(" W", LINEAR_UNIT(retract_length_swap)); - #endif + SERIAL_ECHOPAIR(" W", LINEAR_UNIT(retract_length_swap)); SERIAL_ECHOPAIR(" F", MMS_TO_MMM(LINEAR_UNIT(retract_feedrate_mm_s))); SERIAL_ECHOLNPAIR(" Z", LINEAR_UNIT(retract_zlift)); @@ -1765,9 +1757,7 @@ void MarlinSettings::reset() { } CONFIG_ECHO_START; SERIAL_ECHOPAIR(" M208 S", LINEAR_UNIT(retract_recover_length)); - #if EXTRUDERS > 1 - SERIAL_ECHOPAIR(" W", LINEAR_UNIT(retract_recover_length_swap)); - #endif + SERIAL_ECHOPAIR(" W", LINEAR_UNIT(retract_recover_length_swap)); SERIAL_ECHOLNPAIR(" F", MMS_TO_MMM(LINEAR_UNIT(retract_recover_feedrate_mm_s))); if (!forReplay) { From 9fc72422e49cdb01c5e23462d35757f20702d925 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 21 Jul 2017 14:12:41 -0500 Subject: [PATCH 042/112] Don't let the flow multiplier affect retract/recover length --- Marlin/Marlin_main.cpp | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 20c71945e..4bc128645 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -3150,6 +3150,10 @@ static void homeaxis(const AxisEnum axis) { const bool has_zhop = retract_zlift > 0.01; // Is there a hop set? const float old_feedrate_mm_s = feedrate_mm_s; + const int16_t old_flow = flow_percentage[active_extruder]; + + // Don't apply flow multiplication to retract/recover + flow_percentage[active_extruder] = 100; // The current position will be the destination for E and Z moves set_destination_to_current(); @@ -3192,6 +3196,8 @@ static void homeaxis(const AxisEnum axis) { prepare_move_to_destination(); // Recover E } + // Restore flow and feedrate + flow_percentage[active_extruder] = old_flow; feedrate_mm_s = old_feedrate_mm_s; // The active extruder is now retracted or recovered From 14482d2f2a172b9b992783c9c076297e5dbd40e0 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 23 Jul 2017 18:56:56 -0500 Subject: [PATCH 043/112] Strip auto-retract for impossible M(IN|AX)_AUTORETRACT combo --- Marlin/Marlin_main.cpp | 32 ++++++++++++++++++-------------- Marlin/configuration_store.cpp | 2 +- 2 files changed, 19 insertions(+), 15 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 4bc128645..7aa6a02b9 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -558,8 +558,8 @@ static uint8_t target_extruder; #endif #if ENABLED(FWRETRACT) // Initialized by settings.load()... - bool autoretract_enabled, // M209 S - Autoretract switch - retracted[EXTRUDERS] = { false }; // Which extruders are currently retracted + bool autoretract_enabled, // M209 S - Autoretract switch + retracted[EXTRUDERS] = { false }; // Which extruders are currently retracted float retract_length, // M207 S - G10 Retract length retract_feedrate_mm_s, // M207 F - G10 Retract feedrate retract_zlift, // M207 Z - G10 Retract hop size @@ -3350,14 +3350,16 @@ inline void gcode_G0_G1( gcode_get_destination(); // For X Y Z E F #if ENABLED(FWRETRACT) - // When M209 Autoretract is enabled, convert E-only moves to firmware retract/recover moves - if (autoretract_enabled && parser.seen('E') && !(parser.seen('X') || parser.seen('Y') || parser.seen('Z'))) { - const float echange = destination[E_AXIS] - current_position[E_AXIS]; - // Is this a retract or recover move? - if (WITHIN(FABS(echange), MIN_AUTORETRACT, MAX_AUTORETRACT) && retracted[active_extruder] == (echange > 0.0)) { - current_position[E_AXIS] = destination[E_AXIS]; // Hide a G1-based retract/recover from calculations - sync_plan_position_e(); // AND from the planner - return retract(echange < 0.0); // Firmware-based retract/recover (double-retract ignored) + if (MIN_AUTORETRACT <= MAX_AUTORETRACT) { + // When M209 Autoretract is enabled, convert E-only moves to firmware retract/recover moves + if (autoretract_enabled && parser.seen('E') && !(parser.seen('X') || parser.seen('Y') || parser.seen('Z'))) { + const float echange = destination[E_AXIS] - current_position[E_AXIS]; + // Is this a retract or recover move? + if (WITHIN(FABS(echange), MIN_AUTORETRACT, MAX_AUTORETRACT) && retracted[active_extruder] == (echange > 0.0)) { + current_position[E_AXIS] = destination[E_AXIS]; // Hide a G1-based retract/recover from calculations + sync_plan_position_e(); // AND from the planner + return retract(echange < 0.0); // Firmware-based retract/recover (double-retract ignored) + } } } #endif // FWRETRACT @@ -8584,9 +8586,11 @@ inline void gcode_M205() { * moves will be classified as retraction. */ inline void gcode_M209() { - if (parser.seen('S')) { - autoretract_enabled = parser.value_bool(); - for (int i = 0; i < EXTRUDERS; i++) retracted[i] = false; + if (MIN_AUTORETRACT <= MAX_AUTORETRACT) { + if (parser.seen('S')) { + autoretract_enabled = parser.value_bool(); + for (uint8_t i = 0; i < EXTRUDERS; i++) retracted[i] = false; + } } } @@ -11051,7 +11055,7 @@ void process_next_command() { gcode_M208(); break; case 209: // M209: Turn Automatic Retract Detection on/off - gcode_M209(); + if (MIN_AUTORETRACT <= MAX_AUTORETRACT) gcode_M209(); break; #endif // FWRETRACT diff --git a/Marlin/configuration_store.cpp b/Marlin/configuration_store.cpp index 6fa2ff969..0c27f05bb 100644 --- a/Marlin/configuration_store.cpp +++ b/Marlin/configuration_store.cpp @@ -1762,7 +1762,7 @@ void MarlinSettings::reset() { if (!forReplay) { CONFIG_ECHO_START; - SERIAL_ECHOLNPGM("Auto-Retract: S=0 to disable, 1 to interpret extrude-only moves as retracts or recoveries"); + SERIAL_ECHOLNPGM("Auto-Retract: S=0 to disable, 1 to interpret E-only moves as retract/recover"); } CONFIG_ECHO_START; SERIAL_ECHOLNPAIR(" M209 S", autoretract_enabled ? 1 : 0); From 4eff18854b7d3bc4e1ca3d23fdc514f505017823 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 26 Jul 2017 22:11:22 -0500 Subject: [PATCH 044/112] Rename options with swap_ prefix --- Marlin/Marlin.h | 4 ++-- Marlin/Marlin_main.cpp | 16 ++++++++-------- Marlin/configuration_store.cpp | 24 ++++++++++++------------ Marlin/language_zh_CN.h | 4 ++-- Marlin/language_zh_TW.h | 4 ++-- Marlin/ultralcd.cpp | 4 ++-- 6 files changed, 28 insertions(+), 28 deletions(-) diff --git a/Marlin/Marlin.h b/Marlin/Marlin.h index 33c813645..1e65d1b4e 100644 --- a/Marlin/Marlin.h +++ b/Marlin/Marlin.h @@ -389,8 +389,8 @@ extern float soft_endstop_min[XYZ], soft_endstop_max[XYZ]; retract_zlift, // M207 Z - G10 Retract hop size retract_recover_length, // M208 S - G11 Recover length retract_recover_feedrate_mm_s, // M208 F - G11 Recover feedrate - retract_length_swap, // M207 W - G10 Swap Retract length - retract_recover_length_swap, // M208 W - G11 Swap Recover length + swap_retract_length, // M207 W - G10 Swap Retract length + swap_retract_recover_length, // M208 W - G11 Swap Recover length swap_retract_recover_feedrate_mm_s; // M208 R - G11 Swap Recover feedrate #endif diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 7aa6a02b9..d637b801b 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -565,8 +565,8 @@ static uint8_t target_extruder; retract_zlift, // M207 Z - G10 Retract hop size retract_recover_length, // M208 S - G11 Recover length retract_recover_feedrate_mm_s, // M208 F - G11 Recover feedrate - retract_length_swap, // M207 W - G10 Swap Retract length - retract_recover_length_swap, // M208 W - G11 Swap Recover length + swap_retract_length, // M207 W - G10 Swap Retract length + swap_retract_recover_length, // M208 W - G11 Swap Recover length swap_retract_recover_feedrate_mm_s; // M208 R - G11 Swap Recover feedrate #if EXTRUDERS > 1 bool retracted_swap[EXTRUDERS] = { false }; // Which extruders are swap-retracted @@ -3165,7 +3165,7 @@ static void homeaxis(const AxisEnum axis) { // Retract by moving from a faux E position back to the current E position feedrate_mm_s = retract_feedrate_mm_s; - current_position[E_AXIS] += (swapping ? retract_length_swap : retract_length) / volumetric_multiplier[active_extruder]; + current_position[E_AXIS] += (swapping ? swap_retract_length : retract_length) / volumetric_multiplier[active_extruder]; sync_plan_position_e(); prepare_move_to_destination(); @@ -3189,7 +3189,7 @@ static void homeaxis(const AxisEnum axis) { // A retract multiplier has been added here to get faster swap recovery feedrate_mm_s = swapping ? swap_retract_recover_feedrate_mm_s : retract_recover_feedrate_mm_s; - const float move_e = swapping ? retract_length_swap + retract_recover_length_swap : retract_length + retract_recover_length; + const float move_e = swapping ? swap_retract_length + swap_retract_recover_length : retract_length + retract_recover_length; current_position[E_AXIS] -= move_e / volumetric_multiplier[active_extruder]; sync_plan_position_e(); @@ -8554,7 +8554,7 @@ inline void gcode_M205() { * M207: Set firmware retraction values * * S[+units] retract_length - * W[+units] retract_length_swap (multi-extruder) + * W[+units] swap_retract_length (multi-extruder) * F[units/min] retract_feedrate_mm_s * Z[units] retract_zlift */ @@ -8562,14 +8562,14 @@ inline void gcode_M205() { if (parser.seen('S')) retract_length = parser.value_axis_units(E_AXIS); if (parser.seen('F')) retract_feedrate_mm_s = MMM_TO_MMS(parser.value_axis_units(E_AXIS)); if (parser.seen('Z')) retract_zlift = parser.value_linear_units(); - if (parser.seen('W')) retract_length_swap = parser.value_axis_units(E_AXIS); + if (parser.seen('W')) swap_retract_length = parser.value_axis_units(E_AXIS); } /** * M208: Set firmware un-retraction values * * S[+units] retract_recover_length (in addition to M207 S*) - * W[+units] retract_recover_length_swap (multi-extruder) + * W[+units] swap_retract_recover_length (multi-extruder) * F[units/min] retract_recover_feedrate_mm_s * R[units/min] swap_retract_recover_feedrate_mm_s */ @@ -8577,7 +8577,7 @@ inline void gcode_M205() { if (parser.seen('S')) retract_recover_length = parser.value_axis_units(E_AXIS); if (parser.seen('F')) retract_recover_feedrate_mm_s = MMM_TO_MMS(parser.value_axis_units(E_AXIS)); if (parser.seen('R')) swap_retract_recover_feedrate_mm_s = MMM_TO_MMS(parser.value_axis_units(E_AXIS)); - if (parser.seen('W')) retract_recover_length_swap = parser.value_axis_units(E_AXIS); + if (parser.seen('W')) swap_retract_recover_length = parser.value_axis_units(E_AXIS); } /** diff --git a/Marlin/configuration_store.cpp b/Marlin/configuration_store.cpp index 0c27f05bb..aa34f9633 100644 --- a/Marlin/configuration_store.cpp +++ b/Marlin/configuration_store.cpp @@ -132,8 +132,8 @@ * 513 M207 Z retract_zlift (float) * 517 M208 S retract_recover_length (float) * 521 M208 F retract_recover_feedrate_mm_s (float) - * 525 M207 W retract_length_swap (float) - * 529 M208 W retract_recover_length_swap (float) + * 525 M207 W swap_retract_length (float) + * 529 M208 W swap_retract_recover_length (float) * 533 M208 R swap_retract_recover_feedrate_mm_s (float) * * Volumetric Extrusion: 21 bytes @@ -528,8 +528,8 @@ void MarlinSettings::postprocess() { retract_zlift = 0, retract_recover_length = 0, retract_recover_feedrate_mm_s = 0, - retract_length_swap = 13, - retract_recover_length_swap = 0, + swap_retract_length = 13, + swap_retract_recover_length = 0, swap_retract_recover_feedrate_mm_s = 8; #endif EEPROM_WRITE(autoretract_enabled); @@ -538,8 +538,8 @@ void MarlinSettings::postprocess() { EEPROM_WRITE(retract_zlift); EEPROM_WRITE(retract_recover_length); EEPROM_WRITE(retract_recover_feedrate_mm_s); - EEPROM_WRITE(retract_length_swap); - EEPROM_WRITE(retract_recover_length_swap); + EEPROM_WRITE(swap_retract_length); + EEPROM_WRITE(swap_retract_recover_length); EEPROM_WRITE(swap_retract_recover_feedrate_mm_s); EEPROM_WRITE(volumetric_enabled); @@ -920,8 +920,8 @@ void MarlinSettings::postprocess() { EEPROM_READ(retract_zlift); EEPROM_READ(retract_recover_length); EEPROM_READ(retract_recover_feedrate_mm_s); - EEPROM_READ(retract_length_swap); - EEPROM_READ(retract_recover_length_swap); + EEPROM_READ(swap_retract_length); + EEPROM_READ(swap_retract_recover_length); EEPROM_READ(swap_retract_recover_feedrate_mm_s); #else EEPROM_READ(dummyb); @@ -1292,8 +1292,8 @@ void MarlinSettings::reset() { retract_zlift = RETRACT_ZLIFT; retract_recover_length = RETRACT_RECOVER_LENGTH; retract_recover_feedrate_mm_s = RETRACT_RECOVER_FEEDRATE; - retract_length_swap = RETRACT_LENGTH_SWAP; - retract_recover_length_swap = RETRACT_RECOVER_LENGTH_SWAP; + swap_retract_length = RETRACT_LENGTH_SWAP; + swap_retract_recover_length = RETRACT_RECOVER_LENGTH_SWAP; swap_retract_recover_feedrate_mm_s = RETRACT_RECOVER_FEEDRATE_SWAP; #endif // FWRETRACT @@ -1747,7 +1747,7 @@ void MarlinSettings::reset() { } CONFIG_ECHO_START; SERIAL_ECHOPAIR(" M207 S", LINEAR_UNIT(retract_length)); - SERIAL_ECHOPAIR(" W", LINEAR_UNIT(retract_length_swap)); + SERIAL_ECHOPAIR(" W", LINEAR_UNIT(swap_retract_length)); SERIAL_ECHOPAIR(" F", MMS_TO_MMM(LINEAR_UNIT(retract_feedrate_mm_s))); SERIAL_ECHOLNPAIR(" Z", LINEAR_UNIT(retract_zlift)); @@ -1757,7 +1757,7 @@ void MarlinSettings::reset() { } CONFIG_ECHO_START; SERIAL_ECHOPAIR(" M208 S", LINEAR_UNIT(retract_recover_length)); - SERIAL_ECHOPAIR(" W", LINEAR_UNIT(retract_recover_length_swap)); + SERIAL_ECHOPAIR(" W", LINEAR_UNIT(swap_retract_recover_length)); SERIAL_ECHOLNPAIR(" F", MMS_TO_MMM(LINEAR_UNIT(retract_recover_feedrate_mm_s))); if (!forReplay) { diff --git a/Marlin/language_zh_CN.h b/Marlin/language_zh_CN.h index 4ee33b4c7..1332d7655 100644 --- a/Marlin/language_zh_CN.h +++ b/Marlin/language_zh_CN.h @@ -134,11 +134,11 @@ #define MSG_KILLED _UxGT("已杀掉") //"KILLED. " #define MSG_STOPPED _UxGT("已停止") //"STOPPED. " #define MSG_CONTROL_RETRACT _UxGT("回抽长度mm") //"Retract mm" retract_length, retract length (positive mm) -#define MSG_CONTROL_RETRACT_SWAP _UxGT("换手回抽长度mm") //"Swap Re.mm" retract_length_swap, swap retract length (positive mm), for extruder change +#define MSG_CONTROL_RETRACT_SWAP _UxGT("换手回抽长度mm") //"Swap Re.mm" swap_retract_length, swap retract length (positive mm), for extruder change #define MSG_CONTROL_RETRACTF _UxGT("回抽速率mm/s") //"Retract V" retract_feedrate_mm_s, feedrate for retracting (mm/s) #define MSG_CONTROL_RETRACT_ZLIFT _UxGT("Hop mm") //"Hop mm" retract_zlift, retract Z-lift #define MSG_CONTROL_RETRACT_RECOVER _UxGT("回抽恢复长度mm") //"UnRet +mm" retract_recover_length, additional recover length (mm, added to retract length when recovering) -#define MSG_CONTROL_RETRACT_RECOVER_SWAP _UxGT("换手回抽恢复长度mm") //"S UnRet+mm" retract_recover_length_swap, additional swap recover length (mm, added to retract length when recovering from extruder change) +#define MSG_CONTROL_RETRACT_RECOVER_SWAP _UxGT("换手回抽恢复长度mm") //"S UnRet+mm" swap_retract_recover_length, additional swap recover length (mm, added to retract length when recovering from extruder change) #define MSG_CONTROL_RETRACT_RECOVERF _UxGT("回抽恢复后进料速率mm/s") //"UnRet V" retract_recover_feedrate_mm_s, feedrate for recovering from retraction (mm/s) #define MSG_AUTORETRACT _UxGT("自动抽回") //"AutoRetr." autoretract_enabled, #define MSG_FILAMENTCHANGE _UxGT("更换丝料") //"Change filament" diff --git a/Marlin/language_zh_TW.h b/Marlin/language_zh_TW.h index c7563e786..1ac9aaf09 100644 --- a/Marlin/language_zh_TW.h +++ b/Marlin/language_zh_TW.h @@ -134,11 +134,11 @@ #define MSG_KILLED _UxGT("已殺掉") //"KILLED. " #define MSG_STOPPED _UxGT("已停止") //"STOPPED. " #define MSG_CONTROL_RETRACT _UxGT("回抽長度mm") //"Retract mm" retract_length, retract length (positive mm) -#define MSG_CONTROL_RETRACT_SWAP _UxGT("換手回抽長度mm") //"Swap Re.mm" retract_length_swap, swap retract length (positive mm), for extruder change +#define MSG_CONTROL_RETRACT_SWAP _UxGT("換手回抽長度mm") //"Swap Re.mm" swap_retract_length, swap retract length (positive mm), for extruder change #define MSG_CONTROL_RETRACTF _UxGT("回抽速率mm/s") //"Retract V" retract_feedrate_mm_s, feedrate for retracting (mm/s) #define MSG_CONTROL_RETRACT_ZLIFT _UxGT("Hop mm") //"Hop mm" retract_zlift, retract Z-lift #define MSG_CONTROL_RETRACT_RECOVER _UxGT("回抽恢複長度mm") //"UnRet +mm" retract_recover_length, additional recover length (mm, added to retract length when recovering) -#define MSG_CONTROL_RETRACT_RECOVER_SWAP _UxGT("換手回抽恢複長度mm") //"S UnRet+mm" retract_recover_length_swap, additional swap recover length (mm, added to retract length when recovering from extruder change) +#define MSG_CONTROL_RETRACT_RECOVER_SWAP _UxGT("換手回抽恢複長度mm") //"S UnRet+mm" swap_retract_recover_length, additional swap recover length (mm, added to retract length when recovering from extruder change) #define MSG_CONTROL_RETRACT_RECOVERF _UxGT("回抽恢複後進料速率mm/s") //"UnRet V" retract_recover_feedrate_mm_s, feedrate for recovering from retraction (mm/s) #define MSG_AUTORETRACT _UxGT("自動抽回") //"AutoRetr." autoretract_enabled, #define MSG_FILAMENTCHANGE _UxGT("更換絲料") //"Change filament" diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index 2acfd3d33..15ab6d657 100644 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -3373,13 +3373,13 @@ void kill_screen(const char* lcd_msg) { MENU_ITEM_EDIT(bool, MSG_AUTORETRACT, &autoretract_enabled); MENU_ITEM_EDIT(float52, MSG_CONTROL_RETRACT, &retract_length, 0, 100); #if EXTRUDERS > 1 - MENU_ITEM_EDIT(float52, MSG_CONTROL_RETRACT_SWAP, &retract_length_swap, 0, 100); + MENU_ITEM_EDIT(float52, MSG_CONTROL_RETRACT_SWAP, &swap_retract_length, 0, 100); #endif MENU_ITEM_EDIT(float3, MSG_CONTROL_RETRACTF, &retract_feedrate_mm_s, 1, 999); MENU_ITEM_EDIT(float52, MSG_CONTROL_RETRACT_ZLIFT, &retract_zlift, 0, 999); MENU_ITEM_EDIT(float52, MSG_CONTROL_RETRACT_RECOVER, &retract_recover_length, -100, 100); #if EXTRUDERS > 1 - MENU_ITEM_EDIT(float52, MSG_CONTROL_RETRACT_RECOVER_SWAP, &retract_recover_length_swap, -100, 100); + MENU_ITEM_EDIT(float52, MSG_CONTROL_RETRACT_RECOVER_SWAP, &swap_retract_recover_length, -100, 100); #endif MENU_ITEM_EDIT(float3, MSG_CONTROL_RETRACT_RECOVERF, &retract_recover_feedrate_mm_s, 1, 999); END_MENU(); From af83c512b84b744baf59895f365f2e33836b7b7c Mon Sep 17 00:00:00 2001 From: Marcio Teixeira Date: Thu, 27 Jul 2017 07:46:27 -0600 Subject: [PATCH 045/112] Added support for U8G. --- Marlin/Makefile | 24 ++++++++++++++++++++++-- 1 file changed, 22 insertions(+), 2 deletions(-) diff --git a/Marlin/Makefile b/Marlin/Makefile index eb6ea73b1..98d035d95 100644 --- a/Marlin/Makefile +++ b/Marlin/Makefile @@ -82,6 +82,13 @@ LIQUID_TWI2 ?= 0 # this defines if Wire is needed WIRE ?= 0 +# this defines if U8GLIB is needed (may require RELOC_WORKAROUND) +U8GLIB ?= 1 + +# this defines whether to add a workaround for the avr-gcc relocation bug +# https://www.stix.id.au/wiki/AVR_relocation_truncations_workaround +RELOC_WORKAROUND ?= 1 + ############################################################################ # Below here nothing should be changed... @@ -273,6 +280,10 @@ endif ifeq ($(NEOPIXEL), 1) VPATH += $(ARDUINO_INSTALL_DIR)/libraries/Adafruit_NeoPixel endif +ifeq ($(U8GLIB), 1) +VPATH += $(ARDUINO_INSTALL_DIR)/libraries/U8glib +VPATH += $(ARDUINO_INSTALL_DIR)/libraries/U8glib/utility +endif ifeq ($(HARDWARE_VARIANT), arduino) HARDWARE_SUB_VARIANT ?= mega @@ -299,7 +310,7 @@ CXXSRC = WMath.cpp WString.cpp Print.cpp Marlin_main.cpp \ temperature.cpp cardreader.cpp configuration_store.cpp \ watchdog.cpp SPI.cpp servo.cpp Tone.cpp ultralcd.cpp digipot_mcp4451.cpp \ dac_mcp4728.cpp vector_3.cpp least_squares_fit.cpp endstops.cpp stopwatch.cpp utility.cpp \ - printcounter.cpp nozzle.cpp serial.cpp + printcounter.cpp nozzle.cpp serial.cpp gcode.cpp ifeq ($(NEOPIXEL), 1) CXXSRC += Adafruit_NeoPixel.cpp endif @@ -315,6 +326,15 @@ SRC += twi.c CXXSRC += Wire.cpp endif +ifeq ($(U8GLIB), 1) +SRC += u8g_ll_api.c u8g_bitmap.c u8g_clip.c u8g_com_null.c u8g_delay.c u8g_page.c u8g_pb.c u8g_pb16h1.c u8g_rect.c u8g_state.c u8g_font.c u8g_font_data.c +endif + +ifeq ($(RELOC_WORKAROUND), 1) +LD_PREFIX=-nodefaultlibs +LD_SUFFIX=-lm -lgcc -lc -lgcc +endif + #Check for Arduino 1.0.0 or higher and use the correct source files for that version ifeq ($(shell [ $(ARDUINO_VERSION) -ge 100 ] && echo true), true) CXXSRC += main.cpp @@ -493,7 +513,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,--relax -o $@ -L. $(OBJ) $(LDFLAGS) + $P $(CC) $(LD_PREFIX) $(ALL_CXXFLAGS) -Wl,--gc-sections,--relax -o $@ -L. $(OBJ) $(LDFLAGS) $(LD_SUFFIX) $(BUILD_DIR)/%.o: %.c Configuration.h Configuration_adv.h $(MAKEFILE) $(Pecho) " CC $<" From be7a9a07c5d412180dc479c4363b7ed70d7da226 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 27 Jul 2017 22:47:43 -0500 Subject: [PATCH 046/112] Don't reset grid with `G29 Q` + PROBE_MANUALLY --- Marlin/Marlin_main.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 21daeae79..bf5984c9b 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -4575,6 +4575,9 @@ void home_all_axes() { gcode_G28(true); } #if ENABLED(AUTO_BED_LEVELING_BILINEAR) + #if ENABLED(PROBE_MANUALLY) + if (!no_action) + #endif if ( xGridSpacing != bilinear_grid_spacing[X_AXIS] || yGridSpacing != bilinear_grid_spacing[Y_AXIS] || left_probe_bed_position != LOGICAL_X_POSITION(bilinear_start[X_AXIS]) From 48c5f3dddf54320586757a530bba81530240466e Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 27 Jul 2017 23:42:01 -0500 Subject: [PATCH 047/112] Tweak kill action #ifdef --- Marlin/Marlin_main.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index bf5984c9b..a415754b4 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -12954,7 +12954,7 @@ void kill(const char* lcd_msg) { _delay_ms(250); //Wait to ensure all interrupts routines stopped thermalManager.disable_all_heaters(); //turn off heaters again - #if defined(ACTION_ON_KILL) + #ifdef ACTION_ON_KILL SERIAL_ECHOLNPGM("//action:" ACTION_ON_KILL); #endif From bfd396c13ad65ac42898889dbfd104ac3e316f3d Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 28 Jul 2017 02:19:50 -0500 Subject: [PATCH 048/112] Patch to fix some compiler warnings --- Marlin/Marlin_main.cpp | 18 ++++++++++-------- Marlin/pca9632.cpp | 16 +++++++++------- Marlin/ultralcd.cpp | 5 ++++- 3 files changed, 23 insertions(+), 16 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index a415754b4..82cea9819 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -1014,7 +1014,7 @@ void servo_init() { #if ENABLED(NEOPIXEL_RGBW_LED) const uint32_t color = pixels.Color(r, g, b, w); - static int nextLed = 0; + static uint16_t nextLed = 0; if (!isSequence) set_neopixel_color(color); @@ -5602,12 +5602,14 @@ void home_all_axes() { gcode_G28(true); } 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); - } + #if ENABLED(PROBE_DOUBLE_TOUCH) + // 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); + } + #endif stepper.synchronize(); // wait until the machine is idle @@ -5671,7 +5673,7 @@ void home_all_axes() { gcode_G28(true); } // If any axis has enough movement, do the move LOOP_XYZ(i) if (FABS(destination[i] - current_position[i]) >= G38_MINIMUM_MOVE) { - if (!parser.seenval('F')) feedrate_mm_s = homing_feedrate(i); + if (!parser.seenval('F')) feedrate_mm_s = homing_feedrate((AxisEnum)i); // If G38.2 fails throw an error if (!G38_run_probe() && is_38_2) { SERIAL_ERROR_START(); diff --git a/Marlin/pca9632.cpp b/Marlin/pca9632.cpp index d8853c465..fe0647639 100644 --- a/Marlin/pca9632.cpp +++ b/Marlin/pca9632.cpp @@ -88,13 +88,15 @@ static void PCA9632_WriteAllRegisters(const byte addr, const byte regadd, const Wire.endTransmission(); } -static byte PCA9632_ReadRegister(const byte addr, const byte regadd) { - Wire.beginTransmission(addr); - Wire.write(regadd); - const byte value = Wire.read(); - Wire.endTransmission(); - return value; -} +#if 0 + static byte PCA9632_ReadRegister(const byte addr, const byte regadd) { + Wire.beginTransmission(addr); + Wire.write(regadd); + const byte value = Wire.read(); + Wire.endTransmission(); + return value; + } +#endif void PCA9632_SetColor(const byte r, const byte g, const byte b) { if (!PCA_init) { diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index 2acfd3d33..2f894e1bc 100644 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -1838,7 +1838,6 @@ void kill_screen(const char* lcd_msg) { void _lcd_ubl_level_bed(); static int16_t ubl_storage_slot = 0, - custom_bed_temp = 50, custom_hotend_temp = 190, side_points = 3, ubl_fillin_amount = 5, @@ -1847,6 +1846,10 @@ void kill_screen(const char* lcd_msg) { x_plot = 0, y_plot = 0; + #if HAS_TEMP_BED + static int16_t custom_bed_temp = 50; + #endif + /** * UBL Build Custom Mesh Command */ From 15e009b6cae4989e0eaa2d973ee4da405f5267d1 Mon Sep 17 00:00:00 2001 From: Thomas Moore Date: Fri, 28 Jul 2017 08:33:18 -0500 Subject: [PATCH 049/112] Move Delta Calibration menu to the Prepare menu --- Marlin/ultralcd.cpp | 10 +++++++--- 1 file changed, 7 insertions(+), 3 deletions(-) diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index 2acfd3d33..ef1fc5746 100644 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -915,9 +915,6 @@ void kill_screen(const char* lcd_msg) { } else { MENU_ITEM(submenu, MSG_PREPARE, lcd_prepare_menu); - #if ENABLED(DELTA_CALIBRATION_MENU) - MENU_ITEM(submenu, MSG_DELTA_CALIBRATE, lcd_delta_calibrate_menu); - #endif } MENU_ITEM(submenu, MSG_CONTROL, lcd_control_menu); @@ -2466,6 +2463,13 @@ void kill_screen(const char* lcd_msg) { MENU_ITEM(function, MSG_AUTOSTART, lcd_autostart_sd); #endif + // + // Delta Calibration + // + #if ENABLED(DELTA_CALIBRATION_MENU) + MENU_ITEM(submenu, MSG_DELTA_CALIBRATE, lcd_delta_calibrate_menu); + #endif + END_MENU(); } From 894608f8a31d756cb33a4bf8396110b3a31d0c24 Mon Sep 17 00:00:00 2001 From: Wilfried Chauveau Date: Mon, 24 Jul 2017 21:15:03 +0200 Subject: [PATCH 050/112] Manual Bed Leveling: Goto previous Z height at each probe point --- Marlin/Marlin_main.cpp | 6 +++--- Marlin/ultralcd.cpp | 3 ++- 2 files changed, 5 insertions(+), 4 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 82cea9819..b88504359 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -3998,10 +3998,10 @@ void home_all_axes() { gcode_G28(true); } inline void _manual_goto_xy(const float &x, const float &y) { const float old_feedrate_mm_s = feedrate_mm_s; - #if MANUAL_PROBE_HEIGHT > 0 + const float prev_z = current_position[Z_AXIS]; feedrate_mm_s = homing_feedrate(Z_AXIS); - current_position[Z_AXIS] = LOGICAL_Z_POSITION(Z_MIN_POS) + MANUAL_PROBE_HEIGHT; + current_position[Z_AXIS] = LOGICAL_Z_POSITION(MANUAL_PROBE_HEIGHT); line_to_current_position(); #endif @@ -4012,7 +4012,7 @@ void home_all_axes() { gcode_G28(true); } #if MANUAL_PROBE_HEIGHT > 0 feedrate_mm_s = homing_feedrate(Z_AXIS); - current_position[Z_AXIS] = LOGICAL_Z_POSITION(Z_MIN_POS); // just slightly over the bed + current_position[Z_AXIS] = prev_z; // move back to the previous Z. line_to_current_position(); #endif diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index aaa78fe3b..18424a026 100644 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -1586,13 +1586,14 @@ void kill_screen(const char* lcd_msg) { // Utility to go to the next mesh point inline void _manual_probe_goto_xy(float x, float y) { #if MANUAL_PROBE_HEIGHT > 0 + const float prev_z = current_position[Z_AXIS]; line_to_z(LOGICAL_Z_POSITION(Z_MIN_POS) + MANUAL_PROBE_HEIGHT); #endif 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 MANUAL_PROBE_HEIGHT > 0 - line_to_z(LOGICAL_Z_POSITION(Z_MIN_POS)); + line_to_z(prev_z); #endif lcd_synchronize(); } From 936d00dda816bd75add6e3acc265325c477bcda5 Mon Sep 17 00:00:00 2001 From: teemuatlut Date: Thu, 13 Jul 2017 19:15:59 +0300 Subject: [PATCH 051/112] Implement probing delay for piezo sensors --- Marlin/Conditionals_post.h | 2 +- Marlin/Configuration.h | 11 ++++++----- Marlin/Marlin_main.cpp | 8 +++++++- .../AlephObjects/TAZ4/Configuration.h | 11 ++++++----- .../AliExpress/CL-260/Configuration.h | 11 ++++++----- Marlin/example_configurations/Anet/A6/Configuration.h | 11 ++++++----- Marlin/example_configurations/Anet/A8/Configuration.h | 11 ++++++----- .../BQ/Hephestos/Configuration.h | 11 ++++++----- .../BQ/Hephestos_2/Configuration.h | 11 ++++++----- .../example_configurations/BQ/WITBOX/Configuration.h | 11 ++++++----- .../example_configurations/Cartesio/Configuration.h | 11 ++++++----- .../Creality/CR-10/Configuration.h | 11 ++++++----- Marlin/example_configurations/Felix/Configuration.h | 11 ++++++----- .../example_configurations/Felix/DUAL/Configuration.h | 11 ++++++----- .../Folger Tech/i3-2020/Configuration.h | 11 ++++++----- .../Infitary/i3-M508/Configuration.h | 11 ++++++----- .../Malyan/M150/Configuration.h | 11 ++++++----- .../RepRapWorld/Megatronics/Configuration.h | 11 ++++++----- .../example_configurations/RigidBot/Configuration.h | 11 ++++++----- Marlin/example_configurations/SCARA/Configuration.h | 11 ++++++----- .../example_configurations/TinyBoy2/Configuration.h | 11 ++++++----- .../Velleman/K8200/Configuration.h | 11 ++++++----- .../Velleman/K8400/Configuration.h | 11 ++++++----- .../Velleman/K8400/Dual-head/Configuration.h | 11 ++++++----- .../adafruit/ST7565/Configuration.h | 11 ++++++----- .../delta/FLSUN/auto_calibrate/Configuration.h | 11 ++++++----- .../delta/FLSUN/kossel_mini/Configuration.h | 11 ++++++----- .../delta/generic/Configuration.h | 11 ++++++----- .../delta/kossel_mini/Configuration.h | 11 ++++++----- .../delta/kossel_pro/Configuration.h | 11 ++++++----- .../delta/kossel_xl/Configuration.h | 11 ++++++----- .../gCreate/gMax1.5+/Configuration.h | 11 ++++++----- Marlin/example_configurations/makibox/Configuration.h | 11 ++++++----- .../tvrrug/Round2/Configuration.h | 11 ++++++----- Marlin/example_configurations/wt150/Configuration.h | 11 ++++++----- 35 files changed, 206 insertions(+), 167 deletions(-) diff --git a/Marlin/Conditionals_post.h b/Marlin/Conditionals_post.h index 998863d12..7d4a4a457 100644 --- a/Marlin/Conditionals_post.h +++ b/Marlin/Conditionals_post.h @@ -688,7 +688,7 @@ #if FAN_COUNT == 0 #undef PROBING_FANS_OFF #endif - #define QUIET_PROBING (HAS_BED_PROBE && (ENABLED(PROBING_HEATERS_OFF) || ENABLED(PROBING_FANS_OFF))) + #define QUIET_PROBING (HAS_BED_PROBE && (ENABLED(PROBING_HEATERS_OFF) || ENABLED(PROBING_FANS_OFF) || DELAY_BEFORE_PROBING > 0)) #define HEATER_IDLE_HANDLER (ENABLED(ADVANCED_PAUSE_FEATURE) || ENABLED(PROBING_HEATERS_OFF)) /** diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 35a6aaabb..9f9780a8a 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -624,14 +624,15 @@ #endif /** - * Enable if probing seems unreliable. Heaters and/or fans - consistent with the - * options selected below - will be disabled during probing so as to minimize - * potential EM interference by quieting/silencing the source of the 'noise' (the change - * in current flowing through the wires). This is likely most useful to users of the - * BLTouch probe, but may also help those with inductive or other probe types. + * Enable one or more of the following if probing seems unreliable. + * Heaters and/or fans can be disabled during probing to minimize electrical + * noise. A delay can also be added to allow noise and vibration to settle. + * These options are most useful for the BLTouch probe, but may also improve + * readings with inductive probes and piezo sensors. */ //#define PROBING_HEATERS_OFF // Turn heaters off when probing //#define PROBING_FANS_OFF // Turn fans off when probing +//#define DELAY_BEFORE_PROBING 200 // (ms) To prevent vibrations from triggering piezo sensors // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN) //#define SOLENOID_PROBE diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 9cdb75cf5..ee5426df3 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -2089,7 +2089,13 @@ static void clean_up_after_endstop_or_probe_move() { #if ENABLED(PROBING_FANS_OFF) fans_pause(p); #endif - if (p) safe_delay(25); + if (p) safe_delay( + #if DELAY_BEFORE_PROBING > 25 + DELAY_BEFORE_PROBING + #else + 25 + #endif + ); } #endif // QUIET_PROBING diff --git a/Marlin/example_configurations/AlephObjects/TAZ4/Configuration.h b/Marlin/example_configurations/AlephObjects/TAZ4/Configuration.h index 3ed5c5474..85be76208 100644 --- a/Marlin/example_configurations/AlephObjects/TAZ4/Configuration.h +++ b/Marlin/example_configurations/AlephObjects/TAZ4/Configuration.h @@ -639,14 +639,15 @@ #endif /** - * Enable if probing seems unreliable. Heaters and/or fans - consistent with the - * options selected below - will be disabled during probing so as to minimize - * potential EM interference by quieting/silencing the source of the 'noise' (the change - * in current flowing through the wires). This is likely most useful to users of the - * BLTouch probe, but may also help those with inductive or other probe types. + * Enable one or more of the following if probing seems unreliable. + * Heaters and/or fans can be disabled during probing to minimize electrical + * noise. A delay can also be added to allow noise and vibration to settle. + * These options are most useful for the BLTouch probe, but may also improve + * readings with inductive probes and piezo sensors. */ //#define PROBING_HEATERS_OFF // Turn heaters off when probing //#define PROBING_FANS_OFF // Turn fans off when probing +//#define DELAY_BEFORE_PROBING 200 // (ms) To prevent vibrations from triggering piezo sensors // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN) //#define SOLENOID_PROBE diff --git a/Marlin/example_configurations/AliExpress/CL-260/Configuration.h b/Marlin/example_configurations/AliExpress/CL-260/Configuration.h index a1e1630d3..520e64a18 100644 --- a/Marlin/example_configurations/AliExpress/CL-260/Configuration.h +++ b/Marlin/example_configurations/AliExpress/CL-260/Configuration.h @@ -621,14 +621,15 @@ #endif /** - * Enable if probing seems unreliable. Heaters and/or fans - consistent with the - * options selected below - will be disabled during probing so as to minimize - * potential EM interference by quieting/silencing the source of the 'noise' (the change - * in current flowing through the wires). This is likely most useful to users of the - * BLTouch probe, but may also help those with inductive or other probe types. + * Enable one or more of the following if probing seems unreliable. + * Heaters and/or fans can be disabled during probing to minimize electrical + * noise. A delay can also be added to allow noise and vibration to settle. + * These options are most useful for the BLTouch probe, but may also improve + * readings with inductive probes and piezo sensors. */ //#define PROBING_HEATERS_OFF // Turn heaters off when probing //#define PROBING_FANS_OFF // Turn fans off when probing +//#define DELAY_BEFORE_PROBING 200 // (ms) To prevent vibrations from triggering piezo sensors // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN) //#define SOLENOID_PROBE diff --git a/Marlin/example_configurations/Anet/A6/Configuration.h b/Marlin/example_configurations/Anet/A6/Configuration.h index 766bde1a7..90f7bdffd 100644 --- a/Marlin/example_configurations/Anet/A6/Configuration.h +++ b/Marlin/example_configurations/Anet/A6/Configuration.h @@ -681,14 +681,15 @@ #endif /** - * Enable if probing seems unreliable. Heaters and/or fans - consistent with the - * options selected below - will be disabled during probing so as to minimize - * potential EM interference by quieting/silencing the source of the 'noise' (the change - * in current flowing through the wires). This is likely most useful to users of the - * BLTouch probe, but may also help those with inductive or other probe types. + * Enable one or more of the following if probing seems unreliable. + * Heaters and/or fans can be disabled during probing to minimize electrical + * noise. A delay can also be added to allow noise and vibration to settle. + * These options are most useful for the BLTouch probe, but may also improve + * readings with inductive probes and piezo sensors. */ #define PROBING_HEATERS_OFF // Turn heaters off when probing #define PROBING_FANS_OFF // Turn fans off when probing +//#define DELAY_BEFORE_PROBING 200 // (ms) To prevent vibrations from triggering piezo sensors // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN) //#define SOLENOID_PROBE diff --git a/Marlin/example_configurations/Anet/A8/Configuration.h b/Marlin/example_configurations/Anet/A8/Configuration.h index d02cdb921..e57bb2fb3 100644 --- a/Marlin/example_configurations/Anet/A8/Configuration.h +++ b/Marlin/example_configurations/Anet/A8/Configuration.h @@ -630,14 +630,15 @@ #endif /** - * Enable if probing seems unreliable. Heaters and/or fans - consistent with the - * options selected below - will be disabled during probing so as to minimize - * potential EM interference by quieting/silencing the source of the 'noise' (the change - * in current flowing through the wires). This is likely most useful to users of the - * BLTouch probe, but may also help those with inductive or other probe types. + * Enable one or more of the following if probing seems unreliable. + * Heaters and/or fans can be disabled during probing to minimize electrical + * noise. A delay can also be added to allow noise and vibration to settle. + * These options are most useful for the BLTouch probe, but may also improve + * readings with inductive probes and piezo sensors. */ //#define PROBING_HEATERS_OFF // Turn heaters off when probing //#define PROBING_FANS_OFF // Turn fans off when probing +//#define DELAY_BEFORE_PROBING 200 // (ms) To prevent vibrations from triggering piezo sensors // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN) //#define SOLENOID_PROBE diff --git a/Marlin/example_configurations/BQ/Hephestos/Configuration.h b/Marlin/example_configurations/BQ/Hephestos/Configuration.h index 4d2da2cbb..59db32e9e 100644 --- a/Marlin/example_configurations/BQ/Hephestos/Configuration.h +++ b/Marlin/example_configurations/BQ/Hephestos/Configuration.h @@ -610,14 +610,15 @@ #endif /** - * Enable if probing seems unreliable. Heaters and/or fans - consistent with the - * options selected below - will be disabled during probing so as to minimize - * potential EM interference by quieting/silencing the source of the 'noise' (the change - * in current flowing through the wires). This is likely most useful to users of the - * BLTouch probe, but may also help those with inductive or other probe types. + * Enable one or more of the following if probing seems unreliable. + * Heaters and/or fans can be disabled during probing to minimize electrical + * noise. A delay can also be added to allow noise and vibration to settle. + * These options are most useful for the BLTouch probe, but may also improve + * readings with inductive probes and piezo sensors. */ //#define PROBING_HEATERS_OFF // Turn heaters off when probing //#define PROBING_FANS_OFF // Turn fans off when probing +//#define DELAY_BEFORE_PROBING 200 // (ms) To prevent vibrations from triggering piezo sensors // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN) //#define SOLENOID_PROBE diff --git a/Marlin/example_configurations/BQ/Hephestos_2/Configuration.h b/Marlin/example_configurations/BQ/Hephestos_2/Configuration.h index f4bff19f7..ae9ee3ddf 100644 --- a/Marlin/example_configurations/BQ/Hephestos_2/Configuration.h +++ b/Marlin/example_configurations/BQ/Hephestos_2/Configuration.h @@ -621,14 +621,15 @@ #endif /** - * Enable if probing seems unreliable. Heaters and/or fans - consistent with the - * options selected below - will be disabled during probing so as to minimize - * potential EM interference by quieting/silencing the source of the 'noise' (the change - * in current flowing through the wires). This is likely most useful to users of the - * BLTouch probe, but may also help those with inductive or other probe types. + * Enable one or more of the following if probing seems unreliable. + * Heaters and/or fans can be disabled during probing to minimize electrical + * noise. A delay can also be added to allow noise and vibration to settle. + * These options are most useful for the BLTouch probe, but may also improve + * readings with inductive probes and piezo sensors. */ //#define PROBING_HEATERS_OFF // Turn heaters off when probing //#define PROBING_FANS_OFF // Turn fans off when probing +//#define DELAY_BEFORE_PROBING 200 // (ms) To prevent vibrations from triggering piezo sensors // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN) //#define SOLENOID_PROBE diff --git a/Marlin/example_configurations/BQ/WITBOX/Configuration.h b/Marlin/example_configurations/BQ/WITBOX/Configuration.h index 870f6057d..c0a12efa5 100644 --- a/Marlin/example_configurations/BQ/WITBOX/Configuration.h +++ b/Marlin/example_configurations/BQ/WITBOX/Configuration.h @@ -610,14 +610,15 @@ #endif /** - * Enable if probing seems unreliable. Heaters and/or fans - consistent with the - * options selected below - will be disabled during probing so as to minimize - * potential EM interference by quieting/silencing the source of the 'noise' (the change - * in current flowing through the wires). This is likely most useful to users of the - * BLTouch probe, but may also help those with inductive or other probe types. + * Enable one or more of the following if probing seems unreliable. + * Heaters and/or fans can be disabled during probing to minimize electrical + * noise. A delay can also be added to allow noise and vibration to settle. + * These options are most useful for the BLTouch probe, but may also improve + * readings with inductive probes and piezo sensors. */ //#define PROBING_HEATERS_OFF // Turn heaters off when probing //#define PROBING_FANS_OFF // Turn fans off when probing +//#define DELAY_BEFORE_PROBING 200 // (ms) To prevent vibrations from triggering piezo sensors // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN) //#define SOLENOID_PROBE diff --git a/Marlin/example_configurations/Cartesio/Configuration.h b/Marlin/example_configurations/Cartesio/Configuration.h index 7e8672468..2ab76fc88 100644 --- a/Marlin/example_configurations/Cartesio/Configuration.h +++ b/Marlin/example_configurations/Cartesio/Configuration.h @@ -618,14 +618,15 @@ #endif /** - * Enable if probing seems unreliable. Heaters and/or fans - consistent with the - * options selected below - will be disabled during probing so as to minimize - * potential EM interference by quieting/silencing the source of the 'noise' (the change - * in current flowing through the wires). This is likely most useful to users of the - * BLTouch probe, but may also help those with inductive or other probe types. + * Enable one or more of the following if probing seems unreliable. + * Heaters and/or fans can be disabled during probing to minimize electrical + * noise. A delay can also be added to allow noise and vibration to settle. + * These options are most useful for the BLTouch probe, but may also improve + * readings with inductive probes and piezo sensors. */ //#define PROBING_HEATERS_OFF // Turn heaters off when probing //#define PROBING_FANS_OFF // Turn fans off when probing +//#define DELAY_BEFORE_PROBING 200 // (ms) To prevent vibrations from triggering piezo sensors // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN) //#define SOLENOID_PROBE diff --git a/Marlin/example_configurations/Creality/CR-10/Configuration.h b/Marlin/example_configurations/Creality/CR-10/Configuration.h index 4fec96044..5c3bc375f 100644 --- a/Marlin/example_configurations/Creality/CR-10/Configuration.h +++ b/Marlin/example_configurations/Creality/CR-10/Configuration.h @@ -634,14 +634,15 @@ #endif /** - * Enable if probing seems unreliable. Heaters and/or fans - consistent with the - * options selected below - will be disabled during probing so as to minimize - * potential EM interference by quieting/silencing the source of the 'noise' (the change - * in current flowing through the wires). This is likely most useful to users of the - * BLTouch probe, but may also help those with inductive or other probe types. + * Enable one or more of the following if probing seems unreliable. + * Heaters and/or fans can be disabled during probing to minimize electrical + * noise. A delay can also be added to allow noise and vibration to settle. + * These options are most useful for the BLTouch probe, but may also improve + * readings with inductive probes and piezo sensors. */ //#define PROBING_HEATERS_OFF // Turn heaters off when probing //#define PROBING_FANS_OFF // Turn fans off when probing +//#define DELAY_BEFORE_PROBING 200 // (ms) To prevent vibrations from triggering piezo sensors // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN) //#define SOLENOID_PROBE diff --git a/Marlin/example_configurations/Felix/Configuration.h b/Marlin/example_configurations/Felix/Configuration.h index d9aee3ff6..dd2d419c3 100644 --- a/Marlin/example_configurations/Felix/Configuration.h +++ b/Marlin/example_configurations/Felix/Configuration.h @@ -602,14 +602,15 @@ #endif /** - * Enable if probing seems unreliable. Heaters and/or fans - consistent with the - * options selected below - will be disabled during probing so as to minimize - * potential EM interference by quieting/silencing the source of the 'noise' (the change - * in current flowing through the wires). This is likely most useful to users of the - * BLTouch probe, but may also help those with inductive or other probe types. + * Enable one or more of the following if probing seems unreliable. + * Heaters and/or fans can be disabled during probing to minimize electrical + * noise. A delay can also be added to allow noise and vibration to settle. + * These options are most useful for the BLTouch probe, but may also improve + * readings with inductive probes and piezo sensors. */ //#define PROBING_HEATERS_OFF // Turn heaters off when probing //#define PROBING_FANS_OFF // Turn fans off when probing +//#define DELAY_BEFORE_PROBING 200 // (ms) To prevent vibrations from triggering piezo sensors // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN) //#define SOLENOID_PROBE diff --git a/Marlin/example_configurations/Felix/DUAL/Configuration.h b/Marlin/example_configurations/Felix/DUAL/Configuration.h index 8ac1bdcb8..f2c5ac626 100644 --- a/Marlin/example_configurations/Felix/DUAL/Configuration.h +++ b/Marlin/example_configurations/Felix/DUAL/Configuration.h @@ -602,14 +602,15 @@ #endif /** - * Enable if probing seems unreliable. Heaters and/or fans - consistent with the - * options selected below - will be disabled during probing so as to minimize - * potential EM interference by quieting/silencing the source of the 'noise' (the change - * in current flowing through the wires). This is likely most useful to users of the - * BLTouch probe, but may also help those with inductive or other probe types. + * Enable one or more of the following if probing seems unreliable. + * Heaters and/or fans can be disabled during probing to minimize electrical + * noise. A delay can also be added to allow noise and vibration to settle. + * These options are most useful for the BLTouch probe, but may also improve + * readings with inductive probes and piezo sensors. */ //#define PROBING_HEATERS_OFF // Turn heaters off when probing //#define PROBING_FANS_OFF // Turn fans off when probing +//#define DELAY_BEFORE_PROBING 200 // (ms) To prevent vibrations from triggering piezo sensors // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN) //#define SOLENOID_PROBE diff --git a/Marlin/example_configurations/Folger Tech/i3-2020/Configuration.h b/Marlin/example_configurations/Folger Tech/i3-2020/Configuration.h index b24c0c713..ee40be09d 100644 --- a/Marlin/example_configurations/Folger Tech/i3-2020/Configuration.h +++ b/Marlin/example_configurations/Folger Tech/i3-2020/Configuration.h @@ -626,14 +626,15 @@ #endif /** - * Enable if probing seems unreliable. Heaters and/or fans - consistent with the - * options selected below - will be disabled during probing so as to minimize - * potential EM interference by quieting/silencing the source of the 'noise' (the change - * in current flowing through the wires). This is likely most useful to users of the - * BLTouch probe, but may also help those with inductive or other probe types. + * Enable one or more of the following if probing seems unreliable. + * Heaters and/or fans can be disabled during probing to minimize electrical + * noise. A delay can also be added to allow noise and vibration to settle. + * These options are most useful for the BLTouch probe, but may also improve + * readings with inductive probes and piezo sensors. */ //#define PROBING_HEATERS_OFF // Turn heaters off when probing //#define PROBING_FANS_OFF // Turn fans off when probing +//#define DELAY_BEFORE_PROBING 200 // (ms) To prevent vibrations from triggering piezo sensors // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN) //#define SOLENOID_PROBE diff --git a/Marlin/example_configurations/Infitary/i3-M508/Configuration.h b/Marlin/example_configurations/Infitary/i3-M508/Configuration.h index 1a303b7bd..32cf0b547 100644 --- a/Marlin/example_configurations/Infitary/i3-M508/Configuration.h +++ b/Marlin/example_configurations/Infitary/i3-M508/Configuration.h @@ -628,14 +628,15 @@ #endif /** - * Enable if probing seems unreliable. Heaters and/or fans - consistent with the - * options selected below - will be disabled during probing so as to minimize - * potential EM interference by quieting/silencing the source of the 'noise' (the change - * in current flowing through the wires). This is likely most useful to users of the - * BLTouch probe, but may also help those with inductive or other probe types. + * Enable one or more of the following if probing seems unreliable. + * Heaters and/or fans can be disabled during probing to minimize electrical + * noise. A delay can also be added to allow noise and vibration to settle. + * These options are most useful for the BLTouch probe, but may also improve + * readings with inductive probes and piezo sensors. */ //#define PROBING_HEATERS_OFF // Turn heaters off when probing //#define PROBING_FANS_OFF // Turn fans off when probing +//#define DELAY_BEFORE_PROBING 200 // (ms) To prevent vibrations from triggering piezo sensors // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN) //#define SOLENOID_PROBE diff --git a/Marlin/example_configurations/Malyan/M150/Configuration.h b/Marlin/example_configurations/Malyan/M150/Configuration.h index a9857fd9e..fbd4f4f55 100644 --- a/Marlin/example_configurations/Malyan/M150/Configuration.h +++ b/Marlin/example_configurations/Malyan/M150/Configuration.h @@ -639,14 +639,15 @@ #endif /** - * Enable if probing seems unreliable. Heaters and/or fans - consistent with the - * options selected below - will be disabled during probing so as to minimize - * potential EM interference by quieting/silencing the source of the 'noise' (the change - * in current flowing through the wires). This is likely most useful to users of the - * BLTouch probe, but may also help those with inductive or other probe types. + * Enable one or more of the following if probing seems unreliable. + * Heaters and/or fans can be disabled during probing to minimize electrical + * noise. A delay can also be added to allow noise and vibration to settle. + * These options are most useful for the BLTouch probe, but may also improve + * readings with inductive probes and piezo sensors. */ //#define PROBING_HEATERS_OFF // Turn heaters off when probing //#define PROBING_FANS_OFF // Turn fans off when probing +//#define DELAY_BEFORE_PROBING 200 // (ms) To prevent vibrations from triggering piezo sensors // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN) //#define SOLENOID_PROBE diff --git a/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h b/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h index 761e9340f..8a0b3ab80 100644 --- a/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h +++ b/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h @@ -620,14 +620,15 @@ #endif /** - * Enable if probing seems unreliable. Heaters and/or fans - consistent with the - * options selected below - will be disabled during probing so as to minimize - * potential EM interference by quieting/silencing the source of the 'noise' (the change - * in current flowing through the wires). This is likely most useful to users of the - * BLTouch probe, but may also help those with inductive or other probe types. + * Enable one or more of the following if probing seems unreliable. + * Heaters and/or fans can be disabled during probing to minimize electrical + * noise. A delay can also be added to allow noise and vibration to settle. + * These options are most useful for the BLTouch probe, but may also improve + * readings with inductive probes and piezo sensors. */ //#define PROBING_HEATERS_OFF // Turn heaters off when probing //#define PROBING_FANS_OFF // Turn fans off when probing +//#define DELAY_BEFORE_PROBING 200 // (ms) To prevent vibrations from triggering piezo sensors // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN) //#define SOLENOID_PROBE diff --git a/Marlin/example_configurations/RigidBot/Configuration.h b/Marlin/example_configurations/RigidBot/Configuration.h index 5abc8e5e2..60a809b62 100644 --- a/Marlin/example_configurations/RigidBot/Configuration.h +++ b/Marlin/example_configurations/RigidBot/Configuration.h @@ -618,14 +618,15 @@ #endif /** - * Enable if probing seems unreliable. Heaters and/or fans - consistent with the - * options selected below - will be disabled during probing so as to minimize - * potential EM interference by quieting/silencing the source of the 'noise' (the change - * in current flowing through the wires). This is likely most useful to users of the - * BLTouch probe, but may also help those with inductive or other probe types. + * Enable one or more of the following if probing seems unreliable. + * Heaters and/or fans can be disabled during probing to minimize electrical + * noise. A delay can also be added to allow noise and vibration to settle. + * These options are most useful for the BLTouch probe, but may also improve + * readings with inductive probes and piezo sensors. */ //#define PROBING_HEATERS_OFF // Turn heaters off when probing //#define PROBING_FANS_OFF // Turn fans off when probing +//#define DELAY_BEFORE_PROBING 200 // (ms) To prevent vibrations from triggering piezo sensors // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN) //#define SOLENOID_PROBE diff --git a/Marlin/example_configurations/SCARA/Configuration.h b/Marlin/example_configurations/SCARA/Configuration.h index 6d53d8737..2cc6a7f48 100644 --- a/Marlin/example_configurations/SCARA/Configuration.h +++ b/Marlin/example_configurations/SCARA/Configuration.h @@ -632,14 +632,15 @@ #endif /** - * Enable if probing seems unreliable. Heaters and/or fans - consistent with the - * options selected below - will be disabled during probing so as to minimize - * potential EM interference by quieting/silencing the source of the 'noise' (the change - * in current flowing through the wires). This is likely most useful to users of the - * BLTouch probe, but may also help those with inductive or other probe types. + * Enable one or more of the following if probing seems unreliable. + * Heaters and/or fans can be disabled during probing to minimize electrical + * noise. A delay can also be added to allow noise and vibration to settle. + * These options are most useful for the BLTouch probe, but may also improve + * readings with inductive probes and piezo sensors. */ //#define PROBING_HEATERS_OFF // Turn heaters off when probing //#define PROBING_FANS_OFF // Turn fans off when probing +//#define DELAY_BEFORE_PROBING 200 // (ms) To prevent vibrations from triggering piezo sensors // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN) //#define SOLENOID_PROBE diff --git a/Marlin/example_configurations/TinyBoy2/Configuration.h b/Marlin/example_configurations/TinyBoy2/Configuration.h index bc80b61a5..ad677c363 100644 --- a/Marlin/example_configurations/TinyBoy2/Configuration.h +++ b/Marlin/example_configurations/TinyBoy2/Configuration.h @@ -671,14 +671,15 @@ #endif /** - * Enable if probing seems unreliable. Heaters and/or fans - consistent with the - * options selected below - will be disabled during probing so as to minimize - * potential EM interference by quieting/silencing the source of the 'noise' (the change - * in current flowing through the wires). This is likely most useful to users of the - * BLTouch probe, but may also help those with inductive or other probe types. + * Enable one or more of the following if probing seems unreliable. + * Heaters and/or fans can be disabled during probing to minimize electrical + * noise. A delay can also be added to allow noise and vibration to settle. + * These options are most useful for the BLTouch probe, but may also improve + * readings with inductive probes and piezo sensors. */ //#define PROBING_HEATERS_OFF // Turn heaters off when probing //#define PROBING_FANS_OFF // Turn fans off when probing +//#define DELAY_BEFORE_PROBING 200 // (ms) To prevent vibrations from triggering piezo sensors // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN) //#define SOLENOID_PROBE diff --git a/Marlin/example_configurations/Velleman/K8200/Configuration.h b/Marlin/example_configurations/Velleman/K8200/Configuration.h index e314373e8..f61b4ae4e 100644 --- a/Marlin/example_configurations/Velleman/K8200/Configuration.h +++ b/Marlin/example_configurations/Velleman/K8200/Configuration.h @@ -649,14 +649,15 @@ #endif /** - * Enable if probing seems unreliable. Heaters and/or fans - consistent with the - * options selected below - will be disabled during probing so as to minimize - * potential EM interference by quieting/silencing the source of the 'noise' (the change - * in current flowing through the wires). This is likely most useful to users of the - * BLTouch probe, but may also help those with inductive or other probe types. + * Enable one or more of the following if probing seems unreliable. + * Heaters and/or fans can be disabled during probing to minimize electrical + * noise. A delay can also be added to allow noise and vibration to settle. + * These options are most useful for the BLTouch probe, but may also improve + * readings with inductive probes and piezo sensors. */ //#define PROBING_HEATERS_OFF // Turn heaters off when probing //#define PROBING_FANS_OFF // Turn fans off when probing +//#define DELAY_BEFORE_PROBING 200 // (ms) To prevent vibrations from triggering piezo sensors // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN) //#define SOLENOID_PROBE diff --git a/Marlin/example_configurations/Velleman/K8400/Configuration.h b/Marlin/example_configurations/Velleman/K8400/Configuration.h index f93895aa9..0b2c70c8b 100644 --- a/Marlin/example_configurations/Velleman/K8400/Configuration.h +++ b/Marlin/example_configurations/Velleman/K8400/Configuration.h @@ -620,14 +620,15 @@ #endif /** - * Enable if probing seems unreliable. Heaters and/or fans - consistent with the - * options selected below - will be disabled during probing so as to minimize - * potential EM interference by quieting/silencing the source of the 'noise' (the change - * in current flowing through the wires). This is likely most useful to users of the - * BLTouch probe, but may also help those with inductive or other probe types. + * Enable one or more of the following if probing seems unreliable. + * Heaters and/or fans can be disabled during probing to minimize electrical + * noise. A delay can also be added to allow noise and vibration to settle. + * These options are most useful for the BLTouch probe, but may also improve + * readings with inductive probes and piezo sensors. */ //#define PROBING_HEATERS_OFF // Turn heaters off when probing //#define PROBING_FANS_OFF // Turn fans off when probing +//#define DELAY_BEFORE_PROBING 200 // (ms) To prevent vibrations from triggering piezo sensors // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN) //#define SOLENOID_PROBE diff --git a/Marlin/example_configurations/Velleman/K8400/Dual-head/Configuration.h b/Marlin/example_configurations/Velleman/K8400/Dual-head/Configuration.h index bcbe50581..0f63c5c29 100644 --- a/Marlin/example_configurations/Velleman/K8400/Dual-head/Configuration.h +++ b/Marlin/example_configurations/Velleman/K8400/Dual-head/Configuration.h @@ -620,14 +620,15 @@ #endif /** - * Enable if probing seems unreliable. Heaters and/or fans - consistent with the - * options selected below - will be disabled during probing so as to minimize - * potential EM interference by quieting/silencing the source of the 'noise' (the change - * in current flowing through the wires). This is likely most useful to users of the - * BLTouch probe, but may also help those with inductive or other probe types. + * Enable one or more of the following if probing seems unreliable. + * Heaters and/or fans can be disabled during probing to minimize electrical + * noise. A delay can also be added to allow noise and vibration to settle. + * These options are most useful for the BLTouch probe, but may also improve + * readings with inductive probes and piezo sensors. */ //#define PROBING_HEATERS_OFF // Turn heaters off when probing //#define PROBING_FANS_OFF // Turn fans off when probing +//#define DELAY_BEFORE_PROBING 200 // (ms) To prevent vibrations from triggering piezo sensors // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN) //#define SOLENOID_PROBE diff --git a/Marlin/example_configurations/adafruit/ST7565/Configuration.h b/Marlin/example_configurations/adafruit/ST7565/Configuration.h index 835cc3199..c4cb9ca08 100644 --- a/Marlin/example_configurations/adafruit/ST7565/Configuration.h +++ b/Marlin/example_configurations/adafruit/ST7565/Configuration.h @@ -620,14 +620,15 @@ #endif /** - * Enable if probing seems unreliable. Heaters and/or fans - consistent with the - * options selected below - will be disabled during probing so as to minimize - * potential EM interference by quieting/silencing the source of the 'noise' (the change - * in current flowing through the wires). This is likely most useful to users of the - * BLTouch probe, but may also help those with inductive or other probe types. + * Enable one or more of the following if probing seems unreliable. + * Heaters and/or fans can be disabled during probing to minimize electrical + * noise. A delay can also be added to allow noise and vibration to settle. + * These options are most useful for the BLTouch probe, but may also improve + * readings with inductive probes and piezo sensors. */ //#define PROBING_HEATERS_OFF // Turn heaters off when probing //#define PROBING_FANS_OFF // Turn fans off when probing +//#define DELAY_BEFORE_PROBING 200 // (ms) To prevent vibrations from triggering piezo sensors // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN) //#define SOLENOID_PROBE diff --git a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h index 40a857ef0..7d1dc6df6 100644 --- a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h +++ b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h @@ -694,14 +694,15 @@ #endif /** - * Enable if probing seems unreliable. Heaters and/or fans - consistent with the - * options selected below - will be disabled during probing so as to minimize - * potential EM interference by quieting/silencing the source of the 'noise' (the change - * in current flowing through the wires). This is likely most useful to users of the - * BLTouch probe, but may also help those with inductive or other probe types. + * Enable one or more of the following if probing seems unreliable. + * Heaters and/or fans can be disabled during probing to minimize electrical + * noise. A delay can also be added to allow noise and vibration to settle. + * These options are most useful for the BLTouch probe, but may also improve + * readings with inductive probes and piezo sensors. */ //#define PROBING_HEATERS_OFF // Turn heaters off when probing //#define PROBING_FANS_OFF // Turn fans off when probing +//#define DELAY_BEFORE_PROBING 200 // (ms) To prevent vibrations from triggering piezo sensors // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN) //#define SOLENOID_PROBE diff --git a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h index 87b410c25..f4b14be19 100644 --- a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h +++ b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h @@ -694,14 +694,15 @@ #endif /** - * Enable if probing seems unreliable. Heaters and/or fans - consistent with the - * options selected below - will be disabled during probing so as to minimize - * potential EM interference by quieting/silencing the source of the 'noise' (the change - * in current flowing through the wires). This is likely most useful to users of the - * BLTouch probe, but may also help those with inductive or other probe types. + * Enable one or more of the following if probing seems unreliable. + * Heaters and/or fans can be disabled during probing to minimize electrical + * noise. A delay can also be added to allow noise and vibration to settle. + * These options are most useful for the BLTouch probe, but may also improve + * readings with inductive probes and piezo sensors. */ //#define PROBING_HEATERS_OFF // Turn heaters off when probing //#define PROBING_FANS_OFF // Turn fans off when probing +//#define DELAY_BEFORE_PROBING 200 // (ms) To prevent vibrations from triggering piezo sensors // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN) //#define SOLENOID_PROBE diff --git a/Marlin/example_configurations/delta/generic/Configuration.h b/Marlin/example_configurations/delta/generic/Configuration.h index 8633e20ac..d079bf45b 100644 --- a/Marlin/example_configurations/delta/generic/Configuration.h +++ b/Marlin/example_configurations/delta/generic/Configuration.h @@ -684,14 +684,15 @@ #endif /** - * Enable if probing seems unreliable. Heaters and/or fans - consistent with the - * options selected below - will be disabled during probing so as to minimize - * potential EM interference by quieting/silencing the source of the 'noise' (the change - * in current flowing through the wires). This is likely most useful to users of the - * BLTouch probe, but may also help those with inductive or other probe types. + * Enable one or more of the following if probing seems unreliable. + * Heaters and/or fans can be disabled during probing to minimize electrical + * noise. A delay can also be added to allow noise and vibration to settle. + * These options are most useful for the BLTouch probe, but may also improve + * readings with inductive probes and piezo sensors. */ //#define PROBING_HEATERS_OFF // Turn heaters off when probing //#define PROBING_FANS_OFF // Turn fans off when probing +//#define DELAY_BEFORE_PROBING 200 // (ms) To prevent vibrations from triggering piezo sensors // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN) //#define SOLENOID_PROBE diff --git a/Marlin/example_configurations/delta/kossel_mini/Configuration.h b/Marlin/example_configurations/delta/kossel_mini/Configuration.h index 2205fc014..13b7787a6 100644 --- a/Marlin/example_configurations/delta/kossel_mini/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_mini/Configuration.h @@ -679,14 +679,15 @@ #endif /** - * Enable if probing seems unreliable. Heaters and/or fans - consistent with the - * options selected below - will be disabled during probing so as to minimize - * potential EM interference by quieting/silencing the source of the 'noise' (the change - * in current flowing through the wires). This is likely most useful to users of the - * BLTouch probe, but may also help those with inductive or other probe types. + * Enable one or more of the following if probing seems unreliable. + * Heaters and/or fans can be disabled during probing to minimize electrical + * noise. A delay can also be added to allow noise and vibration to settle. + * These options are most useful for the BLTouch probe, but may also improve + * readings with inductive probes and piezo sensors. */ //#define PROBING_HEATERS_OFF // Turn heaters off when probing //#define PROBING_FANS_OFF // Turn fans off when probing +//#define DELAY_BEFORE_PROBING 200 // (ms) To prevent vibrations from triggering piezo sensors // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN) //#define SOLENOID_PROBE diff --git a/Marlin/example_configurations/delta/kossel_pro/Configuration.h b/Marlin/example_configurations/delta/kossel_pro/Configuration.h index ad9d87e02..9418ce8b7 100644 --- a/Marlin/example_configurations/delta/kossel_pro/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_pro/Configuration.h @@ -677,14 +677,15 @@ #endif /** - * Enable if probing seems unreliable. Heaters and/or fans - consistent with the - * options selected below - will be disabled during probing so as to minimize - * potential EM interference by quieting/silencing the source of the 'noise' (the change - * in current flowing through the wires). This is likely most useful to users of the - * BLTouch probe, but may also help those with inductive or other probe types. + * Enable one or more of the following if probing seems unreliable. + * Heaters and/or fans can be disabled during probing to minimize electrical + * noise. A delay can also be added to allow noise and vibration to settle. + * These options are most useful for the BLTouch probe, but may also improve + * readings with inductive probes and piezo sensors. */ //#define PROBING_HEATERS_OFF // Turn heaters off when probing //#define PROBING_FANS_OFF // Turn fans off when probing +//#define DELAY_BEFORE_PROBING 200 // (ms) To prevent vibrations from triggering piezo sensors // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN) //#define SOLENOID_PROBE diff --git a/Marlin/example_configurations/delta/kossel_xl/Configuration.h b/Marlin/example_configurations/delta/kossel_xl/Configuration.h index aad12e7a1..469eef478 100644 --- a/Marlin/example_configurations/delta/kossel_xl/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_xl/Configuration.h @@ -696,14 +696,15 @@ #endif /** - * Enable if probing seems unreliable. Heaters and/or fans - consistent with the - * options selected below - will be disabled during probing so as to minimize - * potential EM interference by quieting/silencing the source of the 'noise' (the change - * in current flowing through the wires). This is likely most useful to users of the - * BLTouch probe, but may also help those with inductive or other probe types. + * Enable one or more of the following if probing seems unreliable. + * Heaters and/or fans can be disabled during probing to minimize electrical + * noise. A delay can also be added to allow noise and vibration to settle. + * These options are most useful for the BLTouch probe, but may also improve + * readings with inductive probes and piezo sensors. */ //#define PROBING_HEATERS_OFF // Turn heaters off when probing //#define PROBING_FANS_OFF // Turn fans off when probing +//#define DELAY_BEFORE_PROBING 200 // (ms) To prevent vibrations from triggering piezo sensors // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN) //#define SOLENOID_PROBE diff --git a/Marlin/example_configurations/gCreate/gMax1.5+/Configuration.h b/Marlin/example_configurations/gCreate/gMax1.5+/Configuration.h index bd9c125e3..f25e8b3b9 100644 --- a/Marlin/example_configurations/gCreate/gMax1.5+/Configuration.h +++ b/Marlin/example_configurations/gCreate/gMax1.5+/Configuration.h @@ -635,14 +635,15 @@ #endif /** - * Enable if probing seems unreliable. Heaters and/or fans - consistent with the - * options selected below - will be disabled during probing so as to minimize - * potential EM interference by quieting/silencing the source of the 'noise' (the change - * in current flowing through the wires). This is likely most useful to users of the - * BLTouch probe, but may also help those with inductive or other probe types. + * Enable one or more of the following if probing seems unreliable. + * Heaters and/or fans can be disabled during probing to minimize electrical + * noise. A delay can also be added to allow noise and vibration to settle. + * These options are most useful for the BLTouch probe, but may also improve + * readings with inductive probes and piezo sensors. */ //#define PROBING_HEATERS_OFF // Turn heaters off when probing //#define PROBING_FANS_OFF // Turn fans off when probing +//#define DELAY_BEFORE_PROBING 200 // (ms) To prevent vibrations from triggering piezo sensors // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN) //#define SOLENOID_PROBE diff --git a/Marlin/example_configurations/makibox/Configuration.h b/Marlin/example_configurations/makibox/Configuration.h index ffb5d9e0c..144b6fc8b 100644 --- a/Marlin/example_configurations/makibox/Configuration.h +++ b/Marlin/example_configurations/makibox/Configuration.h @@ -623,14 +623,15 @@ #endif /** - * Enable if probing seems unreliable. Heaters and/or fans - consistent with the - * options selected below - will be disabled during probing so as to minimize - * potential EM interference by quieting/silencing the source of the 'noise' (the change - * in current flowing through the wires). This is likely most useful to users of the - * BLTouch probe, but may also help those with inductive or other probe types. + * Enable one or more of the following if probing seems unreliable. + * Heaters and/or fans can be disabled during probing to minimize electrical + * noise. A delay can also be added to allow noise and vibration to settle. + * These options are most useful for the BLTouch probe, but may also improve + * readings with inductive probes and piezo sensors. */ //#define PROBING_HEATERS_OFF // Turn heaters off when probing //#define PROBING_FANS_OFF // Turn fans off when probing +//#define DELAY_BEFORE_PROBING 200 // (ms) To prevent vibrations from triggering piezo sensors // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN) //#define SOLENOID_PROBE diff --git a/Marlin/example_configurations/tvrrug/Round2/Configuration.h b/Marlin/example_configurations/tvrrug/Round2/Configuration.h index 112afb8cd..462b33d1e 100644 --- a/Marlin/example_configurations/tvrrug/Round2/Configuration.h +++ b/Marlin/example_configurations/tvrrug/Round2/Configuration.h @@ -615,14 +615,15 @@ #endif /** - * Enable if probing seems unreliable. Heaters and/or fans - consistent with the - * options selected below - will be disabled during probing so as to minimize - * potential EM interference by quieting/silencing the source of the 'noise' (the change - * in current flowing through the wires). This is likely most useful to users of the - * BLTouch probe, but may also help those with inductive or other probe types. + * Enable one or more of the following if probing seems unreliable. + * Heaters and/or fans can be disabled during probing to minimize electrical + * noise. A delay can also be added to allow noise and vibration to settle. + * These options are most useful for the BLTouch probe, but may also improve + * readings with inductive probes and piezo sensors. */ //#define PROBING_HEATERS_OFF // Turn heaters off when probing //#define PROBING_FANS_OFF // Turn fans off when probing +//#define DELAY_BEFORE_PROBING 200 // (ms) To prevent vibrations from triggering piezo sensors // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN) //#define SOLENOID_PROBE diff --git a/Marlin/example_configurations/wt150/Configuration.h b/Marlin/example_configurations/wt150/Configuration.h index fbfe75a47..d3242e1fb 100644 --- a/Marlin/example_configurations/wt150/Configuration.h +++ b/Marlin/example_configurations/wt150/Configuration.h @@ -626,14 +626,15 @@ #endif /** - * Enable if probing seems unreliable. Heaters and/or fans - consistent with the - * options selected below - will be disabled during probing so as to minimize - * potential EM interference by quieting/silencing the source of the 'noise' (the change - * in current flowing through the wires). This is likely most useful to users of the - * BLTouch probe, but may also help those with inductive or other probe types. + * Enable one or more of the following if probing seems unreliable. + * Heaters and/or fans can be disabled during probing to minimize electrical + * noise. A delay can also be added to allow noise and vibration to settle. + * These options are most useful for the BLTouch probe, but may also improve + * readings with inductive probes and piezo sensors. */ //#define PROBING_HEATERS_OFF // Turn heaters off when probing //#define PROBING_FANS_OFF // Turn fans off when probing +//#define DELAY_BEFORE_PROBING 200 // (ms) To prevent vibrations from triggering piezo sensors // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN) //#define SOLENOID_PROBE From e948f77cf9eda6c24ddd05972242aed305be847c Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?=C3=98ystein=20Krog?= Date: Mon, 31 Jul 2017 18:39:33 +0200 Subject: [PATCH 052/112] Fix DUAL_X_CARRIAGE not moving at all Axis would only move when homing. Bug introduced in 91841d75c9a473e15932bd4589d64ee59efe947e. Fixes #6956, fixes #7050 and fixes #7291 --- Marlin/Marlin_main.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 750361ccd..185dfb413 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -12251,7 +12251,7 @@ void prepare_move_to_destination() { #elif IS_KINEMATIC prepare_kinematic_move_to(destination) #elif ENABLED(DUAL_X_CARRIAGE) - prepare_move_to_destination_dualx() + prepare_move_to_destination_dualx() || prepare_move_to_destination_cartesian() #else prepare_move_to_destination_cartesian() #endif From ffe3013bb5e7302f0f7964a7288e65fbec8ef5b2 Mon Sep 17 00:00:00 2001 From: Kai Date: Tue, 1 Aug 2017 21:45:41 +0200 Subject: [PATCH 053/112] Fix for #7395 Filament change causes freeze during paused print. This PR disables Filament change in the prepare menu when a print from SD Card is paused. See #7395 --- Marlin/ultralcd.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index 51fa0247a..e154e40f6 100644 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -2412,7 +2412,7 @@ void kill_screen(const char* lcd_msg) { // Change filament // #if ENABLED(ADVANCED_PAUSE_FEATURE) - if (!thermalManager.tooColdToExtrude(active_extruder)) + if (!thermalManager.tooColdToExtrude(active_extruder) && !card.sdprinting) MENU_ITEM(function, MSG_FILAMENTCHANGE, lcd_enqueue_filament_change); #endif From 936dfb965c0f0bfd479a20d14cc176d605cd3638 Mon Sep 17 00:00:00 2001 From: Dave Johnson Date: Tue, 1 Aug 2017 14:13:54 -0700 Subject: [PATCH 054/112] Clarify LCD_BED_LEVELING requirements LCD_BED_LEVELING requires PROBE_MANUALLY with auto bed leveling enabled. See #7396 --- Marlin/SanityCheck.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/SanityCheck.h b/Marlin/SanityCheck.h index 117378add..eeda19ca6 100644 --- a/Marlin/SanityCheck.h +++ b/Marlin/SanityCheck.h @@ -728,7 +728,7 @@ static_assert(1 >= 0 #if DISABLED(ULTIPANEL) #error "LCD_BED_LEVELING requires an LCD controller." #elif DISABLED(MESH_BED_LEVELING) && !(HAS_ABL && ENABLED(PROBE_MANUALLY)) - #error "LCD_BED_LEVELING requires MESH_BED_LEVELING or PROBE_MANUALLY." + #error "LCD_BED_LEVELING requires MESH_BED_LEVELING or PROBE_MANUALLY with auto bed leveling enabled." #endif #endif From 650e5274c475a91b788ed5b0018c289927066753 Mon Sep 17 00:00:00 2001 From: Florian Heilmann Date: Wed, 2 Aug 2017 21:16:46 +0200 Subject: [PATCH 055/112] Update Russian Translation --- Marlin/language_ru.h | 50 +++++++++++++++++++++++++++++++++++++++----- 1 file changed, 45 insertions(+), 5 deletions(-) diff --git a/Marlin/language_ru.h b/Marlin/language_ru.h index 0ed8ff1d8..c2ceff7e9 100644 --- a/Marlin/language_ru.h +++ b/Marlin/language_ru.h @@ -60,11 +60,13 @@ #define MSG_PREHEAT_1_ALL MSG_PREHEAT_1 _UxGT(" Всё") #define MSG_PREHEAT_1_END MSG_PREHEAT_1 _UxGT(" Сопло") #define MSG_PREHEAT_1_BEDONLY MSG_PREHEAT_1 _UxGT(" Стол") +#define MSG_PREHEAT_1_SETTINGS MSG_PREHEAT_1 _UxGT(" Настр.") #define MSG_PREHEAT_2 _UxGT("Преднагрев ABS") #define MSG_PREHEAT_2_N MSG_PREHEAT_2 _UxGT(" ") #define MSG_PREHEAT_2_ALL MSG_PREHEAT_2 _UxGT(" Всё") #define MSG_PREHEAT_2_END MSG_PREHEAT_2 _UxGT(" Сопло") #define MSG_PREHEAT_2_BEDONLY MSG_PREHEAT_2 _UxGT(" Стол") +#define MSG_PREHEAT_2_SETTINGS MSG_PREHEAT_2 _UxGT(" Настр.") #define MSG_COOLDOWN _UxGT("Охлаждение") #define MSG_SWITCH_PS_ON _UxGT("Включить Питание") #define MSG_SWITCH_PS_OFF _UxGT("Отключить Питание") @@ -73,10 +75,16 @@ #define MSG_MOVE_AXIS _UxGT("Движение по осям") #define MSG_BED_LEVELING _UxGT("Калибровать стол") #define MSG_LEVEL_BED _UxGT("Калибровать стол") +#define MSG_EDITING_STOPPED _UxGT("Ред. сетки завершена") +#define MSG_USER_MENU _UxGT("Свои комманды") #define MSG_UBL_DOING_G29 _UxGT("Выполняем G29") #define MSG_UBL_UNHOMED _UxGT("Паркуем сначала XYZ") #define MSG_UBL_TOOLS _UxGT("Утилиты UBL") +#define MSG_UBL_LEVEL_BED _UxGT("Калибровка UBL") +#define MSG_UBL_MANUAL_MESH _UxGT("Постр. сетку от руки") +#define MSG_UBL_BC_INSERT _UxGT("Пост. шимм и измер.") #define MSG_UBL_BC_INSERT2 _UxGT("Измерение") +#define MSG_UBL_BC_REMOVE _UxGT("Удал. и измер. стол") #define MSG_UBL_MOVING_TO_NEXT _UxGT("Двигаемся дальше") #define MSG_UBL_ACTIVATE_MESH _UxGT("Активировать UBL") #define MSG_UBL_DEACTIVATE_MESH _UxGT("Выключить UBL") @@ -85,31 +93,48 @@ #define MSG_UBL_SET_HOTEND_TEMP _UxGT("Температура сопла") #define MSG_UBL_CUSTOM_HOTEND_TEMP MSG_UBL_SET_HOTEND_TEMP #define MSG_UBL_MESH_EDIT _UxGT("Редактор сеток") +#define MSG_UBL_EDIT_CUSTOM_MESH _UxGT("Редакт. свою сетку") +#define MSG_UBL_FINE_TUNE_MESH _UxGT("Точ. настройка сетки") +#define MSG_UBL_DONE_EDITING_MESH _UxGT("Ред. сетки завершено") #define MSG_UBL_BUILD_CUSTOM_MESH _UxGT("Построить свою сетку") #define MSG_UBL_BUILD_MESH_MENU _UxGT("Построить сетку") #define MSG_UBL_BUILD_PLA_MESH _UxGT("Построить сетку PLA") #define MSG_UBL_BUILD_ABS_MESH _UxGT("Построить сетку ABS") +#define MSG_UBL_BUILD_COLD_MESH _UxGT("Построить хол. сетку") +#define MSG_UBL_MESH_HEIGHT_ADJUST _UxGT("Устан. высоту сетки") #define MSG_UBL_MESH_HEIGHT_AMOUNT _UxGT("Высота") #define MSG_UBL_VALIDATE_MESH_MENU _UxGT("Проверить сетку") #define MSG_UBL_VALIDATE_PLA_MESH _UxGT("Проверить сетку PLA") #define MSG_UBL_VALIDATE_ABS_MESH _UxGT("Проверить сетку ABS") #define MSG_UBL_VALIDATE_CUSTOM_MESH _UxGT("Проверить свою сетку") -#define MSG_UBL_MESH_LEVEL _UxGT("Выровнять сетку") +#define MSG_UBL_CONTINUE_MESH _UxGT("Продолжить сетку") +#define MSG_UBL_MESH_LEVELING _UxGT("Калибровка сетки") +#define MSG_UBL_3POINT_MESH_LEVELING _UxGT("Калибровка 3-х точек") +#define MSG_UBL_GRID_MESH_LEVELING _UxGT("Калибровка растера") +#define MSG_UBL_MESH_LEVEL _UxGT("Выровнить сетку") #define MSG_UBL_SIDE_POINTS _UxGT("Крайние точки") -#define MSG_UBL_MAP_TYPE _UxGT("Типа карты") +#define MSG_UBL_MAP_TYPE _UxGT("Тип карты") #define MSG_UBL_OUTPUT_MAP _UxGT("Вывести карту сетки") #define MSG_UBL_OUTPUT_MAP_HOST _UxGT("Вывести на хост") #define MSG_UBL_OUTPUT_MAP_CSV _UxGT("Вывести в CSV") #define MSG_UBL_OUTPUT_MAP_BACKUP _UxGT("Забекапить сетку") +#define MSG_UBL_INFO_UBL _UxGT("Выдача инфор. UBL") #define MSG_UBL_EDIT_MESH_MENU _UxGT("Редактировать сетку") #define MSG_UBL_FILLIN_AMOUNT _UxGT("Заполнить значения") #define MSG_UBL_MANUAL_FILLIN _UxGT("Ручное заполнение") #define MSG_UBL_SMART_FILLIN _UxGT("Уменое заполнение") #define MSG_UBL_FILLIN_MESH _UxGT("Заполнить сетку") #define MSG_UBL_INVALIDATE_ALL _UxGT("Аннулировать всё") +#define MSG_UBL_INVALIDATE_CLOSEST _UxGT("Аннулир. ближ. точку") +#define MSG_UBL_FINE_TUNE_ALL _UxGT("Точ. настройка всего") +#define MSG_UBL_FINE_TUNE_CLOSEST _UxGT("Настр. ближ. точки") #define MSG_UBL_STORAGE_MESH_MENU _UxGT("Хранилище сетей") #define MSG_UBL_STORAGE_SLOT _UxGT("Слот памяти") +#define MSG_UBL_LOAD_MESH _UxGT("Загрузить стол сетки") +#define MSG_UBL_SAVE_MESH _UxGT("Сохранить стол сетки") +#define MSG_UBL_SAVE_ERROR _UxGT("Ошибка: Сохр. UBL") #define MSG_UBL_RESTORE_ERROR _UxGT("Ошибка: Загрузки UBL") +#define MSG_UBL_Z_OFFSET_STOPPED _UxGT("Смещение Z останов.") #define MSG_UBL_STEP_BY_STEP_MENU _UxGT("Пошаговый UBL") #define MSG_MOVING _UxGT("Движемся...") #define MSG_FREE_XY _UxGT("Освобождаем XY") @@ -117,9 +142,9 @@ #define MSG_MOVE_Y _UxGT("Движение по Y") #define MSG_MOVE_Z _UxGT("Движение по Z") #define MSG_MOVE_E _UxGT("Экструдер") -#define MSG_MOVE_01MM _UxGT("Движение XYZ 0.1mm") -#define MSG_MOVE_1MM _UxGT("Движение XYZ 1mm") -#define MSG_MOVE_10MM _UxGT("Движение XY 10mm") +#define MSG_MOVE_01MM _UxGT("Движение 0.1mm") +#define MSG_MOVE_1MM _UxGT("Движение 1mm") +#define MSG_MOVE_10MM _UxGT("Движение 10mm") #define MSG_SPEED _UxGT("Скорость") #define MSG_BED_Z _UxGT("Z стола") #define MSG_NOZZLE LCD_STR_THERMOMETER _UxGT(" Сопло") @@ -172,6 +197,7 @@ #define MSG_STORE_EEPROM _UxGT("Сохранить в EEPROM") #define MSG_LOAD_EEPROM _UxGT("Считать из EEPROM") #define MSG_RESTORE_FAILSAFE _UxGT("Сброс EEPROM") +#define MSG_INIT_EEPROM _UxGT("Иниц. EEPROM") #define MSG_REFRESH _UxGT("Обновить") #define MSG_WATCH _UxGT("Обзор") #define MSG_PREPARE _UxGT("Действия") @@ -182,6 +208,7 @@ #define MSG_CARD_MENU _UxGT("Обзор карты") #define MSG_NO_CARD _UxGT("Нет карты") #define MSG_DWELL _UxGT("Сон...") +#define MSG_USERWAIT _UxGT("Продолжить...") #define MSG_PRINT_PAUSED _UxGT("Печать остановлена") #define MSG_RESUMING _UxGT("Возобновление...") #define MSG_PRINT_ABORTED _UxGT("Отмена печати") @@ -213,6 +240,7 @@ #define MSG_BABYSTEP_Z _UxGT("Микрошаг Z") #define MSG_ENDSTOP_ABORT _UxGT("Сработал концевик") #define MSG_HEATING_FAILED_LCD _UxGT("Разогрев не удался") +#define MSG_ERR_REDUNDANT_TEMP _UxGT("Ошибка: T ред.") #define MSG_THERMAL_RUNAWAY _UxGT("ТЕПЛО УБЕГАНИЯ!") #define MSG_ERR_MAXTEMP _UxGT("Ошибка: Т макс.") #define MSG_ERR_MINTEMP _UxGT("Ошибка: Т мин.") @@ -233,10 +261,18 @@ #define MSG_DELTA_CALIBRATE_Y _UxGT("Калибровать Y") #define MSG_DELTA_CALIBRATE_Z _UxGT("Калибровать Z") #define MSG_DELTA_CALIBRATE_CENTER _UxGT("Калибровать центр") +#define MSG_DELTA_SETTINGS _UxGT("Пок. настройки Delta") #define MSG_DELTA_AUTO_CALIBRATE _UxGT("Авто калибровка") #define MSG_DELTA_HEIGHT_CALIBRATE _UxGT("Задать высоту Delta") #define MSG_INFO_MENU _UxGT("О принтере") +#define MSG_INFO_PRINTER_MENU _UxGT("Инф. о принтере") +#define MSG_3POINT_LEVELING _UxGT("Калибровка 3-х точек") +#define MSG_LINEAR_LEVELING _UxGT("Линейная калибровка") +#define MSG_BILINEAR_LEVELING _UxGT("Билинейная калибр.") +#define MSG_UBL_LEVELING _UxGT("Калибровка UBL") +#define MSG_MESH_LEVELING _UxGT("Калибровка сетки") #define MSG_INFO_STATS_MENU _UxGT("Статистика принтера") +#define MSG_INFO_BOARD_MENU _UxGT("Информация о плате") #define MSG_INFO_THERMISTOR_MENU _UxGT("Термисторы") #define MSG_INFO_EXTRUDERS _UxGT("Экструдеры") #define MSG_INFO_BAUDRATE _UxGT("Бод") @@ -254,13 +290,17 @@ #define MSG_INFO_PRINT_LONGEST _UxGT("Наибольшее") #define MSG_INFO_PRINT_FILAMENT _UxGT("Выдавлено") #endif +#define MSG_INFO_MIN_TEMP _UxGT("Мин. Т") +#define MSG_INFO_MAX_TEMP _UxGT("Макс. Т") #define MSG_INFO_PSU _UxGT("Блок питания") #define MSG_DRIVE_STRENGTH _UxGT("Сила привода") #define MSG_DAC_PERCENT _UxGT("Привод %") #define MSG_DAC_EEPROM_WRITE _UxGT("Записи DAC EEPROM") #define MSG_FILAMENT_CHANGE_HEADER _UxGT("ПЕЧАТЬ ОСТАНОВЛЕНА") +#define MSG_FILAMENT_CHANGE_OPTION_HEADER _UxGT("ОПЦИИ ВОЗОБНОВЛЕНИЯ:") #define MSG_FILAMENT_CHANGE_OPTION_EXTRUDE _UxGT("Выдавить ещё") #define MSG_FILAMENT_CHANGE_OPTION_RESUME _UxGT("Возобновить печать") +#define MSG_FILAMENT_CHANGE_MINTEMP _UxGT("Мин. температура") #define MSG_FILAMENT_CHANGE_NOZZLE _UxGT(" Сопла: ") // // Filament Change screens show up to 3 lines on a 4-line display From 2cbdc0ebb6bbf64daa3f8b0ea9ab615778633e49 Mon Sep 17 00:00:00 2001 From: Roxy-3D Date: Wed, 2 Aug 2017 16:51:04 -0500 Subject: [PATCH 056/112] Fix large Z corrections when nozzle moves off of UBL mesh (#7415) --- Marlin/ubl.h | 27 +++++++++++++++++++-------- Marlin/ubl_motion.cpp | 13 +++++++++++-- 2 files changed, 30 insertions(+), 10 deletions(-) diff --git a/Marlin/ubl.h b/Marlin/ubl.h index 2c2ca1ec3..90de810a6 100644 --- a/Marlin/ubl.h +++ b/Marlin/ubl.h @@ -152,7 +152,7 @@ static void save_ubl_active_state_and_disable(); static void restore_ubl_active_state_and_leave(); static void display_map(const int); - static mesh_index_pair find_closest_mesh_point_of_type(const MeshPointType, const float&, const float&, const bool, unsigned int[16], bool); + static mesh_index_pair find_closest_mesh_point_of_type(const MeshPointType, const float&, const float&, const bool, uint16_t[16], bool); static void reset(); static void invalidate(); static void set_all_mesh_points_to_value(float); @@ -247,10 +247,10 @@ /** * z_correction_for_x_on_horizontal_mesh_line is an optimization for - * the rare occasion when a point lies exactly on a Mesh line (denoted by index yi). + * the case where the printer is making a vertical line that only crosses horizontal mesh lines. */ inline static float z_correction_for_x_on_horizontal_mesh_line(const float &lx0, const int x1_i, const int yi) { - if (!WITHIN(x1_i, 0, GRID_MAX_POINTS_X - 1) || !WITHIN(yi, 0, GRID_MAX_POINTS_Y - 1)) { + if (!WITHIN(x1_i, 0, GRID_MAX_POINTS_X - 2) || !WITHIN(yi, 0, GRID_MAX_POINTS_Y - 1)) { serialprintPGM( !WITHIN(x1_i, 0, GRID_MAX_POINTS_X - 1) ? PSTR("x1l_i") : PSTR("yi") ); SERIAL_ECHOPAIR(" out of bounds in z_correction_for_x_on_horizontal_mesh_line(lx0=", lx0); SERIAL_ECHOPAIR(",x1_i=", x1_i); @@ -270,7 +270,7 @@ // See comments above for z_correction_for_x_on_horizontal_mesh_line // inline static float z_correction_for_y_on_vertical_mesh_line(const float &ly0, const int xi, const int y1_i) { - if (!WITHIN(xi, 0, GRID_MAX_POINTS_X - 1) || !WITHIN(y1_i, 0, GRID_MAX_POINTS_Y - 1)) { + if (!WITHIN(xi, 0, GRID_MAX_POINTS_X - 1) || !WITHIN(y1_i, 0, GRID_MAX_POINTS_Y - 2)) { serialprintPGM( !WITHIN(xi, 0, GRID_MAX_POINTS_X - 1) ? PSTR("xi") : PSTR("yl_i") ); SERIAL_ECHOPAIR(" out of bounds in z_correction_for_y_on_vertical_mesh_line(ly0=", ly0); SERIAL_ECHOPAIR(", xi=", xi); @@ -296,7 +296,7 @@ const int8_t cx = get_cell_index_x(RAW_X_POSITION(lx0)), cy = get_cell_index_y(RAW_Y_POSITION(ly0)); - if (!WITHIN(cx, 0, GRID_MAX_POINTS_X - 1) || !WITHIN(cy, 0, GRID_MAX_POINTS_Y - 1)) { + if (!WITHIN(cx, 0, GRID_MAX_POINTS_X - 2) || !WITHIN(cy, 0, GRID_MAX_POINTS_Y - 2)) { SERIAL_ECHOPAIR("? in get_z_correction(lx0=", lx0); SERIAL_ECHOPAIR(", ly0=", ly0); @@ -307,7 +307,7 @@ strcpy(lcd_status_message, "get_z_correction() indexes out of range."); lcd_quick_feedback(); #endif - return 0.0; // this used to return state.z_offset + return NAN; // this used to return state.z_offset } const float z1 = calc_z0(RAW_X_POSITION(lx0), @@ -384,8 +384,19 @@ FORCE_INLINE static float fade_scaling_factor_for_z(const float &lz) { return 1.0; } #endif - FORCE_INLINE static float mesh_index_to_xpos(const uint8_t i) { return pgm_read_float(&_mesh_index_to_xpos[i]); } - FORCE_INLINE static float mesh_index_to_ypos(const uint8_t i) { return pgm_read_float(&_mesh_index_to_ypos[i]); } + FORCE_INLINE static float mesh_index_to_xpos(const uint8_t i) { + if (i= GRID_MAX_POINTS_X-1) { + z1 = 0.0; + z2 = 0.0; + } + // we are done with the fractional X distance into the cell. Now with the two Z-Heights we have calculated, we // are going to apply the Y-Distance into the cell to interpolate the final Z correction. @@ -186,6 +192,9 @@ float z0 = z1 + (z2 - z1) * yratio; + if ( cell_dest_yi >= GRID_MAX_POINTS_Y-1) + z0 = 0.0; + z0 *= fade_scaling_factor_for_z(end[Z_AXIS]); /** From c6509076c450c73811c373fc08e9c08c1503e19a Mon Sep 17 00:00:00 2001 From: Dave Johnson Date: Thu, 3 Aug 2017 07:06:59 -0700 Subject: [PATCH 057/112] Force legacy "precise" build dist for TravisCI (#7422) TravisCI "trusty" build dist isn't picking up build path causing travis checks to fail. Reverting to legacy "precise" dist while we investigate pristine != precise --- .travis.yml | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/.travis.yml b/.travis.yml index cbd29896b..babaaa3d5 100644 --- a/.travis.yml +++ b/.travis.yml @@ -1,4 +1,5 @@ ---- +dist: precise + # language: c # notifications: From 65a36948c0bff2889c6e6ed88a153ae666a1acbe Mon Sep 17 00:00:00 2001 From: Dave Johnson Date: Thu, 3 Aug 2017 08:33:53 -0700 Subject: [PATCH 058/112] Support travis new build environment (#7425) move from legacy precise to trusty build image fix PATH not including buildroot/bin remove symolic link to ~/bin enable sudo trusty travis image doesn't source ~/bin by default avr requires sude --- .travis.yml | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/.travis.yml b/.travis.yml index babaaa3d5..515abf734 100644 --- a/.travis.yml +++ b/.travis.yml @@ -1,4 +1,5 @@ -dist: precise +dist: trusty +sudo: true # language: c # @@ -12,7 +13,7 @@ before_install: # # Publish the buildroot script folder - chmod +x ${TRAVIS_BUILD_DIR}/buildroot/bin/* - - ln -s ${TRAVIS_BUILD_DIR}/buildroot/bin/ ~/bin + - export PATH=${TRAVIS_BUILD_DIR}/buildroot/bin/:${PATH} # # Start fb X server - "/sbin/start-stop-daemon --start --quiet --pidfile /tmp/custom_xvfb_1.pid --make-pidfile --background --exec /usr/bin/Xvfb -- :1 -ac -screen 0 1280x1024x16" From 622048ffb08b716019259e56c97ff07c10a8338e Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 3 Aug 2017 11:20:03 -0500 Subject: [PATCH 059/112] Clean up whitespace, trailing space, bad tab conversion, etc. --- .travis.yml | 2 +- Marlin/ubl.h | 14 ++++---------- Marlin/ubl_motion.cpp | 19 +++++-------------- 3 files changed, 10 insertions(+), 25 deletions(-) diff --git a/.travis.yml b/.travis.yml index 515abf734..2b1a1a773 100644 --- a/.travis.yml +++ b/.travis.yml @@ -1,5 +1,5 @@ dist: trusty -sudo: true +sudo: true # language: c # diff --git a/Marlin/ubl.h b/Marlin/ubl.h index 90de810a6..b1d3bed78 100644 --- a/Marlin/ubl.h +++ b/Marlin/ubl.h @@ -384,18 +384,12 @@ FORCE_INLINE static float fade_scaling_factor_for_z(const float &lz) { return 1.0; } #endif - FORCE_INLINE static float mesh_index_to_xpos(const uint8_t i) { - if (i= GRID_MAX_POINTS_X-1) { - z1 = 0.0; - z2 = 0.0; - } + if (cell_dest_xi >= GRID_MAX_POINTS_X - 1) z1 = z2 = 0.0; // we are done with the fractional X distance into the cell. Now with the two Z-Heights we have calculated, we // are going to apply the Y-Distance into the cell to interpolate the final Z correction. const float yratio = (RAW_Y_POSITION(end[Y_AXIS]) - mesh_index_to_ypos(cell_dest_yi)) * (1.0 / (MESH_Y_DIST)); - - float z0 = z1 + (z2 - z1) * yratio; - - if ( cell_dest_yi >= GRID_MAX_POINTS_Y-1) - z0 = 0.0; - - z0 *= fade_scaling_factor_for_z(end[Z_AXIS]); + float z0 = cell_dest_yi < GRID_MAX_POINTS_Y - 1 ? z1 + (z2 - z1) * yratio * fade_scaling_factor_for_z(end[Z_AXIS]) : 0.0; /** * If part of the Mesh is undefined, it will show up as NAN From 3497153cf161122afb7b505d654c1896db9f079a Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 3 Aug 2017 14:44:13 -0500 Subject: [PATCH 060/112] Followup cleanup patch Fix regression in #7428 --- Marlin/ubl_motion.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/ubl_motion.cpp b/Marlin/ubl_motion.cpp index 55604df9e..be5fe3c20 100644 --- a/Marlin/ubl_motion.cpp +++ b/Marlin/ubl_motion.cpp @@ -186,7 +186,7 @@ // are going to apply the Y-Distance into the cell to interpolate the final Z correction. const float yratio = (RAW_Y_POSITION(end[Y_AXIS]) - mesh_index_to_ypos(cell_dest_yi)) * (1.0 / (MESH_Y_DIST)); - float z0 = cell_dest_yi < GRID_MAX_POINTS_Y - 1 ? z1 + (z2 - z1) * yratio * fade_scaling_factor_for_z(end[Z_AXIS]) : 0.0; + float z0 = cell_dest_yi < GRID_MAX_POINTS_Y - 1 ? (z1 + (z2 - z1) * yratio) * fade_scaling_factor_for_z(end[Z_AXIS]) : 0.0; /** * If part of the Mesh is undefined, it will show up as NAN From 6827a162bbc1d3a059d1699ef482139ddfe7025d Mon Sep 17 00:00:00 2001 From: Florian Heilmann Date: Wed, 2 Aug 2017 14:18:02 +0200 Subject: [PATCH 061/112] Update language_de.h Add MSG_BLTOUCH MSG_DELTA_SETTINGS MSG_UBL_MESH_EDIT MSG_UBL_OUTPUT_MAP_BACKUP MSG_UBL_STEP_BY_STEP_MENU MSG_Z_FADE_HEIGHT --- Marlin/language_de.h | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/Marlin/language_de.h b/Marlin/language_de.h index a765b42fd..806992929 100644 --- a/Marlin/language_de.h +++ b/Marlin/language_de.h @@ -53,6 +53,7 @@ #define MSG_LEVEL_BED_WAITING _UxGT("Klick für Start") #define MSG_LEVEL_BED_NEXT_POINT _UxGT("Nächste Koordinate") #define MSG_LEVEL_BED_DONE _UxGT("Fertig") +#define MSG_Z_FADE_HEIGHT _UxGT("Niv. Ausblendhöhe") #define MSG_SET_HOME_OFFSETS _UxGT("Setze Homeversatz") #define MSG_HOME_OFFSETS_APPLIED _UxGT("Homeversatz aktiv") #define MSG_SET_ORIGIN _UxGT("Setze Nullpunkt") //"G92 X0 Y0 Z0" commented out in ultralcd.cpp @@ -169,6 +170,7 @@ #define MSG_INIT_SDCARD _UxGT("SD-Karte erkennen") // Manually initialize the SD-card via user interface #define MSG_CNG_SDCARD _UxGT("SD-Karte getauscht") // SD-card changed by user. For machines with no autocarddetect. Both send "M21" #define MSG_ZPROBE_OUT _UxGT("Sensor ausserhalb") +#define MSG_BLTOUCH _UxGT("BLTouch") #define MSG_BLTOUCH_SELFTEST _UxGT("BLTouch Test") #define MSG_BLTOUCH_RESET _UxGT("BLTouch Reset") #define MSG_BLTOUCH_DEPLOY _UxGT("BLTouch ausfahren") @@ -202,6 +204,7 @@ #define MSG_DELTA_CALIBRATE_Y _UxGT("Kalibriere Y") #define MSG_DELTA_CALIBRATE_Z _UxGT("Kalibriere Z") #define MSG_DELTA_CALIBRATE_CENTER _UxGT("Kalibriere Mitte") +#define MSG_DELTA_SETTINGS _UxGT("Delta Einst. anzeig.") #define MSG_DELTA_AUTO_CALIBRATE _UxGT("Autom. Kalibrierung") #define MSG_DELTA_HEIGHT_CALIBRATE _UxGT("Delta Höhe setzen") @@ -236,6 +239,7 @@ #define MSG_UBL_CUSTOM_BED_TEMP MSG_UBL_SET_BED_TEMP #define MSG_UBL_SET_HOTEND_TEMP _UxGT("Hotend Temp.") #define MSG_UBL_CUSTOM_HOTEND_TEMP MSG_UBL_SET_HOTEND_TEMP +#define MSG_UBL_MESH_EDIT _UxGT("Netz bearbeiten") #define MSG_UBL_EDIT_CUSTOM_MESH _UxGT("Eigenes Netz bearb.") #define MSG_UBL_FINE_TUNE_MESH _UxGT("Feineinstellung...") #define MSG_UBL_DONE_EDITING_MESH _UxGT("Bearbeitung beendet") @@ -260,6 +264,7 @@ #define MSG_UBL_OUTPUT_MAP _UxGT("Karte ausgeben") #define MSG_UBL_OUTPUT_MAP_HOST _UxGT("Ausgabe für Host") #define MSG_UBL_OUTPUT_MAP_CSV _UxGT("Ausgabe für CSV") +#define MSG_UBL_OUTPUT_MAP_BACKUP _UxGT("Externe Sicherung") #define MSG_UBL_INFO_UBL _UxGT("UBL Info ausgeben") #define MSG_UBL_EDIT_MESH_MENU _UxGT("Netz bearbeiten") #define MSG_UBL_FILLIN_AMOUNT _UxGT("Menge an Fill-in") @@ -277,6 +282,7 @@ #define MSG_UBL_SAVE_ERROR _UxGT("ERR:UBL speichern") #define MSG_UBL_RESTORE_ERROR _UxGT("ERR:UBL wiederherst.") #define MSG_UBL_Z_OFFSET_STOPPED _UxGT("Z-Versatz angehalten") +#define MSG_UBL_STEP_BY_STEP_MENU _UxGT("Schrittweises UBL") #if LCD_WIDTH >= 20 #define MSG_INFO_PRINT_COUNT _UxGT("Gesamte Drucke") From 8443872d1076b3f2985f4712641c6bc93c472680 Mon Sep 17 00:00:00 2001 From: Ben Lye Date: Thu, 3 Aug 2017 09:00:37 +0100 Subject: [PATCH 062/112] Ignore VScode directory PlatformIO can be used with VSCode. VSCode creates a .vscode directory which should be ignored. --- .gitignore | 3 +++ 1 file changed, 3 insertions(+) diff --git a/.gitignore b/.gitignore index 74f5a99dd..8c7053826 100755 --- a/.gitignore +++ b/.gitignore @@ -129,6 +129,9 @@ Marlin/Debug/ Marlin/__vm/ Marlin/.vs/ +#VScode +.vscode + #cmake CMakeLists.txt Marlin/CMakeLists.txt From 24af9e1bf447c9596e61299adbb2abe582c6bef3 Mon Sep 17 00:00:00 2001 From: benlye Date: Wed, 2 Aug 2017 20:21:32 +0100 Subject: [PATCH 063/112] Make audible user script feedback optional Add a parameter to enable/disable audible user script feedback --- Marlin/Configuration_adv.h | 1 + .../AlephObjects/TAZ4/Configuration_adv.h | 1 + Marlin/example_configurations/Anet/A6/Configuration_adv.h | 1 + Marlin/example_configurations/Anet/A8/Configuration_adv.h | 1 + .../example_configurations/BQ/Hephestos/Configuration_adv.h | 1 + .../example_configurations/BQ/Hephestos_2/Configuration_adv.h | 1 + Marlin/example_configurations/BQ/WITBOX/Configuration_adv.h | 1 + Marlin/example_configurations/Cartesio/Configuration_adv.h | 1 + Marlin/example_configurations/Felix/Configuration_adv.h | 1 + .../Folger Tech/i3-2020/Configuration_adv.h | 1 + .../Infitary/i3-M508/Configuration_adv.h | 1 + Marlin/example_configurations/Malyan/M150/Configuration_adv.h | 1 + Marlin/example_configurations/RigidBot/Configuration_adv.h | 1 + Marlin/example_configurations/SCARA/Configuration_adv.h | 1 + Marlin/example_configurations/TinyBoy2/Configuration_adv.h | 1 + .../example_configurations/Velleman/K8200/Configuration_adv.h | 1 + .../example_configurations/Velleman/K8400/Configuration_adv.h | 1 + .../delta/FLSUN/auto_calibrate/Configuration_adv.h | 1 + .../delta/FLSUN/kossel_mini/Configuration_adv.h | 1 + .../example_configurations/delta/generic/Configuration_adv.h | 1 + .../delta/kossel_mini/Configuration_adv.h | 1 + .../delta/kossel_pro/Configuration_adv.h | 1 + .../delta/kossel_xl/Configuration_adv.h | 1 + .../gCreate/gMax1.5+/Configuration_adv.h | 1 + Marlin/example_configurations/makibox/Configuration_adv.h | 1 + .../example_configurations/tvrrug/Round2/Configuration_adv.h | 1 + Marlin/example_configurations/wt150/Configuration_adv.h | 1 + Marlin/ultralcd.cpp | 4 +++- 28 files changed, 30 insertions(+), 1 deletion(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 3a8a8cc8c..50885b39b 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1262,6 +1262,7 @@ //#define CUSTOM_USER_MENUS #if ENABLED(CUSTOM_USER_MENUS) #define USER_SCRIPT_DONE "M117 User Script Done" + #define USER_SCRIPT_AUDIBLE_FEEDBACK #define USER_DESC_1 "Home & UBL Info" #define USER_GCODE_1 "G28\nG29 W" diff --git a/Marlin/example_configurations/AlephObjects/TAZ4/Configuration_adv.h b/Marlin/example_configurations/AlephObjects/TAZ4/Configuration_adv.h index 4e0e75df3..640ad7650 100644 --- a/Marlin/example_configurations/AlephObjects/TAZ4/Configuration_adv.h +++ b/Marlin/example_configurations/AlephObjects/TAZ4/Configuration_adv.h @@ -1255,6 +1255,7 @@ //#define CUSTOM_USER_MENUS #if ENABLED(CUSTOM_USER_MENUS) #define USER_SCRIPT_DONE "M117 User Script Done" + #define USER_SCRIPT_AUDIBLE_FEEDBACK #define USER_DESC_1 "Home & UBL Info" #define USER_GCODE_1 "G28\nG29 W" diff --git a/Marlin/example_configurations/Anet/A6/Configuration_adv.h b/Marlin/example_configurations/Anet/A6/Configuration_adv.h index 815d3c50e..613915570 100644 --- a/Marlin/example_configurations/Anet/A6/Configuration_adv.h +++ b/Marlin/example_configurations/Anet/A6/Configuration_adv.h @@ -1262,6 +1262,7 @@ //#define CUSTOM_USER_MENUS #if ENABLED(CUSTOM_USER_MENUS) #define USER_SCRIPT_DONE "M117 User Script Done" + #define USER_SCRIPT_AUDIBLE_FEEDBACK #define USER_DESC_1 "Home & UBL Info" #define USER_GCODE_1 "G28\nG29 W" diff --git a/Marlin/example_configurations/Anet/A8/Configuration_adv.h b/Marlin/example_configurations/Anet/A8/Configuration_adv.h index 001517038..09ed18575 100644 --- a/Marlin/example_configurations/Anet/A8/Configuration_adv.h +++ b/Marlin/example_configurations/Anet/A8/Configuration_adv.h @@ -1262,6 +1262,7 @@ //#define CUSTOM_USER_MENUS #if ENABLED(CUSTOM_USER_MENUS) #define USER_SCRIPT_DONE "M117 User Script Done" + #define USER_SCRIPT_AUDIBLE_FEEDBACK #define USER_DESC_1 "Home & UBL Info" #define USER_GCODE_1 "G28\nG29 W" diff --git a/Marlin/example_configurations/BQ/Hephestos/Configuration_adv.h b/Marlin/example_configurations/BQ/Hephestos/Configuration_adv.h index a02bb7874..41b4b3ac2 100644 --- a/Marlin/example_configurations/BQ/Hephestos/Configuration_adv.h +++ b/Marlin/example_configurations/BQ/Hephestos/Configuration_adv.h @@ -1255,6 +1255,7 @@ //#define CUSTOM_USER_MENUS #if ENABLED(CUSTOM_USER_MENUS) #define USER_SCRIPT_DONE "M117 User Script Done" + #define USER_SCRIPT_AUDIBLE_FEEDBACK #define USER_DESC_1 "Home & UBL Info" #define USER_GCODE_1 "G28\nG29 W" diff --git a/Marlin/example_configurations/BQ/Hephestos_2/Configuration_adv.h b/Marlin/example_configurations/BQ/Hephestos_2/Configuration_adv.h index 6abb987ba..143c1ca51 100644 --- a/Marlin/example_configurations/BQ/Hephestos_2/Configuration_adv.h +++ b/Marlin/example_configurations/BQ/Hephestos_2/Configuration_adv.h @@ -1238,6 +1238,7 @@ //#define CUSTOM_USER_MENUS #if ENABLED(CUSTOM_USER_MENUS) #define USER_SCRIPT_DONE "M117 User Script Done" + #define USER_SCRIPT_AUDIBLE_FEEDBACK #define USER_DESC_1 "Home & UBL Info" #define USER_GCODE_1 "G28\nG29 W" diff --git a/Marlin/example_configurations/BQ/WITBOX/Configuration_adv.h b/Marlin/example_configurations/BQ/WITBOX/Configuration_adv.h index a02bb7874..41b4b3ac2 100644 --- a/Marlin/example_configurations/BQ/WITBOX/Configuration_adv.h +++ b/Marlin/example_configurations/BQ/WITBOX/Configuration_adv.h @@ -1255,6 +1255,7 @@ //#define CUSTOM_USER_MENUS #if ENABLED(CUSTOM_USER_MENUS) #define USER_SCRIPT_DONE "M117 User Script Done" + #define USER_SCRIPT_AUDIBLE_FEEDBACK #define USER_DESC_1 "Home & UBL Info" #define USER_GCODE_1 "G28\nG29 W" diff --git a/Marlin/example_configurations/Cartesio/Configuration_adv.h b/Marlin/example_configurations/Cartesio/Configuration_adv.h index a02849482..ea19d073c 100644 --- a/Marlin/example_configurations/Cartesio/Configuration_adv.h +++ b/Marlin/example_configurations/Cartesio/Configuration_adv.h @@ -1255,6 +1255,7 @@ //#define CUSTOM_USER_MENUS #if ENABLED(CUSTOM_USER_MENUS) #define USER_SCRIPT_DONE "M117 User Script Done" + #define USER_SCRIPT_AUDIBLE_FEEDBACK #define USER_DESC_1 "Home & UBL Info" #define USER_GCODE_1 "G28\nG29 W" diff --git a/Marlin/example_configurations/Felix/Configuration_adv.h b/Marlin/example_configurations/Felix/Configuration_adv.h index e592fdb5f..1bc5e0d57 100644 --- a/Marlin/example_configurations/Felix/Configuration_adv.h +++ b/Marlin/example_configurations/Felix/Configuration_adv.h @@ -1255,6 +1255,7 @@ //#define CUSTOM_USER_MENUS #if ENABLED(CUSTOM_USER_MENUS) #define USER_SCRIPT_DONE "M117 User Script Done" + #define USER_SCRIPT_AUDIBLE_FEEDBACK #define USER_DESC_1 "Home & UBL Info" #define USER_GCODE_1 "G28\nG29 W" diff --git a/Marlin/example_configurations/Folger Tech/i3-2020/Configuration_adv.h b/Marlin/example_configurations/Folger Tech/i3-2020/Configuration_adv.h index f92a5eb9b..46f925406 100644 --- a/Marlin/example_configurations/Folger Tech/i3-2020/Configuration_adv.h +++ b/Marlin/example_configurations/Folger Tech/i3-2020/Configuration_adv.h @@ -1268,6 +1268,7 @@ //#define CUSTOM_USER_MENUS #if ENABLED(CUSTOM_USER_MENUS) #define USER_SCRIPT_DONE "M117 User Script Done" + #define USER_SCRIPT_AUDIBLE_FEEDBACK #define USER_DESC_1 "Home & UBL Info" #define USER_GCODE_1 "G28\nG29 W" diff --git a/Marlin/example_configurations/Infitary/i3-M508/Configuration_adv.h b/Marlin/example_configurations/Infitary/i3-M508/Configuration_adv.h index e2686ad1d..2c8db64fe 100644 --- a/Marlin/example_configurations/Infitary/i3-M508/Configuration_adv.h +++ b/Marlin/example_configurations/Infitary/i3-M508/Configuration_adv.h @@ -1251,6 +1251,7 @@ //#define CUSTOM_USER_MENUS #if ENABLED(CUSTOM_USER_MENUS) #define USER_SCRIPT_DONE "M117 User Script Done" + #define USER_SCRIPT_AUDIBLE_FEEDBACK #define USER_DESC_1 "Home & UBL Info" #define USER_GCODE_1 "G28\nG29 W" diff --git a/Marlin/example_configurations/Malyan/M150/Configuration_adv.h b/Marlin/example_configurations/Malyan/M150/Configuration_adv.h index 23fa37df4..ad1ecad8f 100644 --- a/Marlin/example_configurations/Malyan/M150/Configuration_adv.h +++ b/Marlin/example_configurations/Malyan/M150/Configuration_adv.h @@ -1262,6 +1262,7 @@ //#define CUSTOM_USER_MENUS #if ENABLED(CUSTOM_USER_MENUS) #define USER_SCRIPT_DONE "M117 User Script Done" + #define USER_SCRIPT_AUDIBLE_FEEDBACK #define USER_DESC_1 "Home & UBL Info" #define USER_GCODE_1 "G28\nG29 W" diff --git a/Marlin/example_configurations/RigidBot/Configuration_adv.h b/Marlin/example_configurations/RigidBot/Configuration_adv.h index 4a4a9547b..ad61814cb 100644 --- a/Marlin/example_configurations/RigidBot/Configuration_adv.h +++ b/Marlin/example_configurations/RigidBot/Configuration_adv.h @@ -1255,6 +1255,7 @@ //#define CUSTOM_USER_MENUS #if ENABLED(CUSTOM_USER_MENUS) #define USER_SCRIPT_DONE "M117 User Script Done" + #define USER_SCRIPT_AUDIBLE_FEEDBACK #define USER_DESC_1 "Home & UBL Info" #define USER_GCODE_1 "G28\nG29 W" diff --git a/Marlin/example_configurations/SCARA/Configuration_adv.h b/Marlin/example_configurations/SCARA/Configuration_adv.h index 83c9cd85a..d431de86d 100644 --- a/Marlin/example_configurations/SCARA/Configuration_adv.h +++ b/Marlin/example_configurations/SCARA/Configuration_adv.h @@ -1255,6 +1255,7 @@ //#define CUSTOM_USER_MENUS #if ENABLED(CUSTOM_USER_MENUS) #define USER_SCRIPT_DONE "M117 User Script Done" + #define USER_SCRIPT_AUDIBLE_FEEDBACK #define USER_DESC_1 "Home & UBL Info" #define USER_GCODE_1 "G28\nG29 W" diff --git a/Marlin/example_configurations/TinyBoy2/Configuration_adv.h b/Marlin/example_configurations/TinyBoy2/Configuration_adv.h index 25f03db77..87a74abd6 100644 --- a/Marlin/example_configurations/TinyBoy2/Configuration_adv.h +++ b/Marlin/example_configurations/TinyBoy2/Configuration_adv.h @@ -1258,6 +1258,7 @@ //#define CUSTOM_USER_MENUS #if ENABLED(CUSTOM_USER_MENUS) #define USER_SCRIPT_DONE "M117 User Script Done" + #define USER_SCRIPT_AUDIBLE_FEEDBACK #define USER_DESC_1 "Home & UBL Info" #define USER_GCODE_1 "G28\nG29 W" diff --git a/Marlin/example_configurations/Velleman/K8200/Configuration_adv.h b/Marlin/example_configurations/Velleman/K8200/Configuration_adv.h index 1cc82b071..203e03bb2 100644 --- a/Marlin/example_configurations/Velleman/K8200/Configuration_adv.h +++ b/Marlin/example_configurations/Velleman/K8200/Configuration_adv.h @@ -1268,6 +1268,7 @@ //#define CUSTOM_USER_MENUS #if ENABLED(CUSTOM_USER_MENUS) #define USER_SCRIPT_DONE "M117 User Script Done" + #define USER_SCRIPT_AUDIBLE_FEEDBACK #define USER_DESC_1 "Home & UBL Info" #define USER_GCODE_1 "G28\nG29 W" diff --git a/Marlin/example_configurations/Velleman/K8400/Configuration_adv.h b/Marlin/example_configurations/Velleman/K8400/Configuration_adv.h index 3089cf4ba..c94748d02 100644 --- a/Marlin/example_configurations/Velleman/K8400/Configuration_adv.h +++ b/Marlin/example_configurations/Velleman/K8400/Configuration_adv.h @@ -1255,6 +1255,7 @@ //#define CUSTOM_USER_MENUS #if ENABLED(CUSTOM_USER_MENUS) #define USER_SCRIPT_DONE "M117 User Script Done" + #define USER_SCRIPT_AUDIBLE_FEEDBACK #define USER_DESC_1 "Home & UBL Info" #define USER_GCODE_1 "G28\nG29 W" diff --git a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h index 4944a6af5..003fd19b4 100644 --- a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h +++ b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h @@ -1260,6 +1260,7 @@ //#define CUSTOM_USER_MENUS #if ENABLED(CUSTOM_USER_MENUS) #define USER_SCRIPT_DONE "M117 User Script Done" + #define USER_SCRIPT_AUDIBLE_FEEDBACK #define USER_DESC_1 "Home & UBL Info" #define USER_GCODE_1 "G28\nG29 W" diff --git a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h index f227e01ce..577d7427c 100644 --- a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h +++ b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h @@ -1259,6 +1259,7 @@ //#define CUSTOM_USER_MENUS #if ENABLED(CUSTOM_USER_MENUS) #define USER_SCRIPT_DONE "M117 User Script Done" + #define USER_SCRIPT_AUDIBLE_FEEDBACK #define USER_DESC_1 "Home & UBL Info" #define USER_GCODE_1 "G28\nG29 W" diff --git a/Marlin/example_configurations/delta/generic/Configuration_adv.h b/Marlin/example_configurations/delta/generic/Configuration_adv.h index 8393ea2be..392e3a972 100644 --- a/Marlin/example_configurations/delta/generic/Configuration_adv.h +++ b/Marlin/example_configurations/delta/generic/Configuration_adv.h @@ -1257,6 +1257,7 @@ //#define CUSTOM_USER_MENUS #if ENABLED(CUSTOM_USER_MENUS) #define USER_SCRIPT_DONE "M117 User Script Done" + #define USER_SCRIPT_AUDIBLE_FEEDBACK #define USER_DESC_1 "Home & UBL Info" #define USER_GCODE_1 "G28\nG29 W" diff --git a/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h index 8393ea2be..392e3a972 100644 --- a/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h @@ -1257,6 +1257,7 @@ //#define CUSTOM_USER_MENUS #if ENABLED(CUSTOM_USER_MENUS) #define USER_SCRIPT_DONE "M117 User Script Done" + #define USER_SCRIPT_AUDIBLE_FEEDBACK #define USER_DESC_1 "Home & UBL Info" #define USER_GCODE_1 "G28\nG29 W" diff --git a/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h index dfa3b1461..39c18ba43 100644 --- a/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h @@ -1262,6 +1262,7 @@ //#define CUSTOM_USER_MENUS #if ENABLED(CUSTOM_USER_MENUS) #define USER_SCRIPT_DONE "M117 User Script Done" + #define USER_SCRIPT_AUDIBLE_FEEDBACK #define USER_DESC_1 "Home & UBL Info" #define USER_GCODE_1 "G28\nG29 W" diff --git a/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h index 6eaa071a0..3ec32bc63 100644 --- a/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h @@ -1257,6 +1257,7 @@ //#define CUSTOM_USER_MENUS #if ENABLED(CUSTOM_USER_MENUS) #define USER_SCRIPT_DONE "M117 User Script Done" + #define USER_SCRIPT_AUDIBLE_FEEDBACK #define USER_DESC_1 "Home & UBL Info" #define USER_GCODE_1 "G28\nG29 W" diff --git a/Marlin/example_configurations/gCreate/gMax1.5+/Configuration_adv.h b/Marlin/example_configurations/gCreate/gMax1.5+/Configuration_adv.h index ee3267cc3..50c8560e4 100644 --- a/Marlin/example_configurations/gCreate/gMax1.5+/Configuration_adv.h +++ b/Marlin/example_configurations/gCreate/gMax1.5+/Configuration_adv.h @@ -1264,6 +1264,7 @@ //#define CUSTOM_USER_MENUS #if ENABLED(CUSTOM_USER_MENUS) #define USER_SCRIPT_DONE "M117 User Script Done" + #define USER_SCRIPT_AUDIBLE_FEEDBACK #define USER_DESC_1 "Home & UBL Info" #define USER_GCODE_1 "G28\nG29 W" diff --git a/Marlin/example_configurations/makibox/Configuration_adv.h b/Marlin/example_configurations/makibox/Configuration_adv.h index 88ecc16cf..6e0dc15a2 100644 --- a/Marlin/example_configurations/makibox/Configuration_adv.h +++ b/Marlin/example_configurations/makibox/Configuration_adv.h @@ -1255,6 +1255,7 @@ //#define CUSTOM_USER_MENUS #if ENABLED(CUSTOM_USER_MENUS) #define USER_SCRIPT_DONE "M117 User Script Done" + #define USER_SCRIPT_AUDIBLE_FEEDBACK #define USER_DESC_1 "Home & UBL Info" #define USER_GCODE_1 "G28\nG29 W" diff --git a/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h b/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h index 824587af3..32c920c24 100644 --- a/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h +++ b/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h @@ -1255,6 +1255,7 @@ //#define CUSTOM_USER_MENUS #if ENABLED(CUSTOM_USER_MENUS) #define USER_SCRIPT_DONE "M117 User Script Done" + #define USER_SCRIPT_AUDIBLE_FEEDBACK #define USER_DESC_1 "Home & UBL Info" #define USER_GCODE_1 "G28\nG29 W" diff --git a/Marlin/example_configurations/wt150/Configuration_adv.h b/Marlin/example_configurations/wt150/Configuration_adv.h index a5b9f070c..a146b0998 100644 --- a/Marlin/example_configurations/wt150/Configuration_adv.h +++ b/Marlin/example_configurations/wt150/Configuration_adv.h @@ -1262,6 +1262,7 @@ //#define CUSTOM_USER_MENUS #if ENABLED(CUSTOM_USER_MENUS) #define USER_SCRIPT_DONE "M117 User Script Done" + #define USER_SCRIPT_AUDIBLE_FEEDBACK #define USER_DESC_1 "Home & UBL Info" #define USER_GCODE_1 "G28\nG29 W" diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index e154e40f6..034c4c456 100644 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -836,7 +836,9 @@ void kill_screen(const char* lcd_msg) { void _lcd_user_gcode(const char * const cmd) { enqueue_and_echo_commands_P(cmd); - lcd_completion_feedback(); + #if ENABLED(USER_SCRIPT_AUDIBLE_FEEDBACK) + lcd_completion_feedback(); + #endif } #if defined(USER_DESC_1) && defined(USER_GCODE_1) From 0fd2923a9f817ce2e97d31fcea0db04846724c50 Mon Sep 17 00:00:00 2001 From: Florian Heilmann Date: Sat, 5 Aug 2017 09:58:38 +0200 Subject: [PATCH 064/112] Fix compilation with ADVANCED_PAUSE_FEATURE without SDSUPPORT (#7412) * Fix compilation of ADVANCED_PAUSE_FEATURE without SDSUPPORT * Fix Identation * Make use of IS_SD_PRINTING macro as per @MagoKimbra --- Marlin/ultralcd.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index e154e40f6..992c15577 100644 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -2412,7 +2412,7 @@ void kill_screen(const char* lcd_msg) { // Change filament // #if ENABLED(ADVANCED_PAUSE_FEATURE) - if (!thermalManager.tooColdToExtrude(active_extruder) && !card.sdprinting) + if (!thermalManager.tooColdToExtrude(active_extruder) && !IS_SD_PRINTING) MENU_ITEM(function, MSG_FILAMENTCHANGE, lcd_enqueue_filament_change); #endif From 804818b4d9bf3f111b259b5d11c05f6d6116abfb Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 3 Aug 2017 15:26:54 -0500 Subject: [PATCH 065/112] Bring configs up to date --- Marlin/Configuration.h | 15 +- Marlin/Configuration_adv.h | 6 +- .../AlephObjects/TAZ4/Configuration.h | 30 ++-- .../AlephObjects/TAZ4/Configuration_adv.h | 14 +- .../AliExpress/CL-260/Configuration.h | 16 +- .../Anet/A6/Configuration.h | 15 +- .../Anet/A6/Configuration_adv.h | 7 +- .../Anet/A8/Configuration.h | 18 +-- .../Anet/A8/Configuration_adv.h | 7 +- .../BQ/Hephestos/Configuration.h | 18 ++- .../BQ/Hephestos/Configuration_adv.h | 14 +- .../BQ/Hephestos_2/Configuration.h | 15 +- .../BQ/Hephestos_2/Configuration_adv.h | 31 +++- .../BQ/WITBOX/Configuration.h | 16 +- .../BQ/WITBOX/Configuration_adv.h | 14 +- .../Cartesio/Configuration.h | 16 +- .../Cartesio/Configuration_adv.h | 14 +- .../Creality/CR-10/Configuration.h | 20 +-- .../Felix/Configuration.h | 17 ++- .../Felix/Configuration_adv.h | 14 +- .../Felix/DUAL/Configuration.h | 15 +- .../Folger Tech/i3-2020/Configuration.h | 19 ++- .../Folger Tech/i3-2020/Configuration_adv.h | 13 +- .../Infitary/i3-M508/Configuration.h | 15 +- .../Infitary/i3-M508/Configuration_adv.h | 144 +++++++++++++++--- .../Malyan/M150/Configuration.h | 18 ++- .../Malyan/M150/Configuration_adv.h | 7 +- .../RepRapWorld/Megatronics/Configuration.h | 15 +- .../RigidBot/Configuration.h | 15 +- .../RigidBot/Configuration_adv.h | 14 +- .../SCARA/Configuration.h | 15 +- .../SCARA/Configuration_adv.h | 14 +- .../TinyBoy2/Configuration.h | 10 +- .../TinyBoy2/Configuration_adv.h | 11 +- .../Velleman/K8200/Configuration.h | 10 +- .../Velleman/K8200/Configuration_adv.h | 18 ++- .../Velleman/K8400/Configuration.h | 15 +- .../Velleman/K8400/Configuration_adv.h | 14 +- .../Velleman/K8400/Dual-head/Configuration.h | 15 +- .../adafruit/ST7565/Configuration.h | 17 ++- .../FLSUN/auto_calibrate/Configuration.h | 22 +-- .../FLSUN/auto_calibrate/Configuration_adv.h | 11 +- .../delta/FLSUN/kossel_mini/Configuration.h | 15 +- .../FLSUN/kossel_mini/Configuration_adv.h | 14 +- .../delta/generic/Configuration.h | 24 ++- .../delta/generic/Configuration_adv.h | 16 +- .../delta/kossel_mini/Configuration.h | 28 ++-- .../delta/kossel_mini/Configuration_adv.h | 16 +- .../delta/kossel_pro/Configuration.h | 19 ++- .../delta/kossel_pro/Configuration_adv.h | 16 +- .../delta/kossel_xl/Configuration.h | 78 ++-------- .../delta/kossel_xl/Configuration_adv.h | 16 +- .../gCreate/gMax1.5+/Configuration.h | 23 +-- .../gCreate/gMax1.5+/Configuration_adv.h | 9 +- .../makibox/Configuration.h | 21 +-- .../makibox/Configuration_adv.h | 14 +- .../tvrrug/Round2/Configuration.h | 15 +- .../tvrrug/Round2/Configuration_adv.h | 14 +- .../wt150/Configuration.h | 16 +- .../wt150/Configuration_adv.h | 90 +---------- 60 files changed, 710 insertions(+), 498 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 9f9780a8a..e44c7f8cf 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -551,7 +551,6 @@ #define DEFAULT_ZJERK 0.4 #define DEFAULT_EJERK 5.0 - //=========================================================================== //============================= Z Probe Options ============================= //=========================================================================== @@ -593,7 +592,7 @@ * Probe Type * * Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, etc. - * You must activate one of these to use Auto Bed Leveling below. + * Activate one of these to use Auto Bed Leveling below. */ /** @@ -1309,12 +1308,6 @@ // //#define ULTIPANEL -// -// Cartesio UI -// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface -// -//#define CARTESIO_UI - // // PanelOne from T3P3 (via RAMPS 1.4 AUX2/AUX3) // http://reprap.org/wiki/PanelOne @@ -1397,6 +1390,12 @@ // //#define BQ_LCD_SMART_CONTROLLER +// +// Cartesio UI +// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface +// +//#define CARTESIO_UI + // // ANET_10 Controller supported displays. // diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 50885b39b..43be4998e 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -284,7 +284,7 @@ #if ENABLED(Z_DUAL_ENDSTOPS) #define Z2_USE_ENDSTOP _XMAX_ - #define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // use M666 command to determine/test this value + #define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // Use M666 to determine/test this value #endif #endif // Z_DUAL_STEPPER_DRIVERS @@ -394,7 +394,7 @@ // Minimum planner junction speed. Sets the default minimum speed the planner plans for at the end // of the buffer and all stops. This should not be much greater than zero and should only be changed // if unwanted behavior is observed on a user's machine when running at very slow speeds. -#define MINIMUM_PLANNER_SPEED 0.05// (mm/sec) +#define MINIMUM_PLANNER_SPEED 0.05 // (mm/sec) // Microstep setting (Only functional when stepper driver microstep pins are connected to MCU. #define MICROSTEP_MODES {16,16,16,16,16} // [1,2,4,8,16] @@ -648,7 +648,7 @@ * * Set to 0 to auto-detect the ratio based on given Gcode G1 print moves. * - * Slic3r (including Průša Slic3r) produces Gcode compatible with the automatic mode. + * Slic3r (including Průša Control) produces Gcode compatible with the automatic mode. * Cura (as of this writing) may produce Gcode incompatible with the automatic mode. */ #define LIN_ADVANCE_E_D_RATIO 0 // The calculated ratio (or 0) according to the formula W * H / ((D / 2) ^ 2 * PI) diff --git a/Marlin/example_configurations/AlephObjects/TAZ4/Configuration.h b/Marlin/example_configurations/AlephObjects/TAZ4/Configuration.h index 85be76208..ce9250eb9 100644 --- a/Marlin/example_configurations/AlephObjects/TAZ4/Configuration.h +++ b/Marlin/example_configurations/AlephObjects/TAZ4/Configuration.h @@ -161,7 +161,10 @@ //#define SWITCHING_EXTRUDER #if ENABLED(SWITCHING_EXTRUDER) #define SWITCHING_EXTRUDER_SERVO_NR 0 - #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 + #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1[, E2, E3] + #if EXTRUDERS > 3 + #define SWITCHING_EXTRUDER_E23_SERVO_NR 1 + #endif #endif // A dual-nozzle that uses a servomotor to raise/lower one of the nozzles @@ -307,6 +310,7 @@ #define HEATER_1_MAXTEMP 250 #define HEATER_2_MAXTEMP 250 #define HEATER_3_MAXTEMP 250 +#define HEATER_4_MAXTEMP 250 #define BED_MAXTEMP 150 //=========================================================================== @@ -478,13 +482,13 @@ #if DISABLED(ENDSTOPPULLUPS) // fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined - #define ENDSTOPPULLUP_XMAX - #define ENDSTOPPULLUP_YMAX - #define ENDSTOPPULLUP_ZMAX - #define ENDSTOPPULLUP_XMIN - #define ENDSTOPPULLUP_YMIN - #define ENDSTOPPULLUP_ZMIN - #define ENDSTOPPULLUP_ZMIN_PROBE + //#define ENDSTOPPULLUP_XMAX + //#define ENDSTOPPULLUP_YMAX + //#define ENDSTOPPULLUP_ZMAX + //#define ENDSTOPPULLUP_XMIN + //#define ENDSTOPPULLUP_YMIN + //#define ENDSTOPPULLUP_ZMIN + //#define ENDSTOPPULLUP_ZMIN_PROBE #endif // Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup). @@ -1476,11 +1480,6 @@ // //#define U8GLIB_SSD1306 -// -// TinyBoy2 128x64 OLED / Encoder Panel -// -//#define OLED_PANEL_TINYBOY2 - // // SAV OLEd LCD module support using either SSD1306 or SH1106 based LCD modules // @@ -1498,6 +1497,11 @@ // //#define SAV_3DLCD +// +// TinyBoy2 128x64 OLED / Encoder Panel +// +//#define OLED_PANEL_TINYBOY2 + //============================================================================= //=============================== Extra Features ============================== //============================================================================= diff --git a/Marlin/example_configurations/AlephObjects/TAZ4/Configuration_adv.h b/Marlin/example_configurations/AlephObjects/TAZ4/Configuration_adv.h index 640ad7650..5511b1187 100644 --- a/Marlin/example_configurations/AlephObjects/TAZ4/Configuration_adv.h +++ b/Marlin/example_configurations/AlephObjects/TAZ4/Configuration_adv.h @@ -284,7 +284,7 @@ #if ENABLED(Z_DUAL_ENDSTOPS) #define Z2_USE_ENDSTOP _XMAX_ - #define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // use M666 command to determine this value + #define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // Use M666 to determine/test this value #endif #endif // Z_DUAL_STEPPER_DRIVERS @@ -394,7 +394,7 @@ // Minimum planner junction speed. Sets the default minimum speed the planner plans for at the end // of the buffer and all stops. This should not be much greater than zero and should only be changed // if unwanted behavior is observed on a user's machine when running at very slow speeds. -#define MINIMUM_PLANNER_SPEED 0.05// (mm/sec) +#define MINIMUM_PLANNER_SPEED 0.05 // (mm/sec) // Microstep setting (Only functional when stepper driver microstep pins are connected to MCU. #define MICROSTEP_MODES {16,16,4,16,16} // [1,2,4,8,16] @@ -452,6 +452,9 @@ // On the Info Screen, display XY with one decimal place when possible //#define LCD_DECIMAL_SMALL_XY +// The timeout (in ms) to return to the status screen from sub-menus +//#define LCD_TIMEOUT_TO_STATUS 15000 + #if ENABLED(SDSUPPORT) // Some RAMPS and other boards don't detect when an SD card is inserted. You can work @@ -645,7 +648,7 @@ * * Set to 0 to auto-detect the ratio based on given Gcode G1 print moves. * - * Slic3r (including Průša Slic3r) produces Gcode compatible with the automatic mode. + * Slic3r (including Průša Control) produces Gcode compatible with the automatic mode. * Cura (as of this writing) may produce Gcode incompatible with the automatic mode. */ #define LIN_ADVANCE_E_D_RATIO 0 // The calculated ratio (or 0) according to the formula W * H / ((D / 2) ^ 2 * PI) @@ -667,6 +670,10 @@ #define UBL_MESH_MAX_X (X_MAX_POS - (UBL_MESH_INSET)) #define UBL_MESH_MIN_Y (Y_MIN_POS + UBL_MESH_INSET) #define UBL_MESH_MAX_Y (Y_MAX_POS - (UBL_MESH_INSET)) + + // If this is defined, the currently active mesh will be saved in the + // current slot on M500. + #define UBL_SAVE_ACTIVE_ON_M500 #endif // @section extras @@ -1283,6 +1290,7 @@ //=========================================================================== //====================== I2C Position Encoder Settings ====================== //=========================================================================== + /** * I2C position encoders for closed loop control. * Developed by Chris Barr at Aus3D. diff --git a/Marlin/example_configurations/AliExpress/CL-260/Configuration.h b/Marlin/example_configurations/AliExpress/CL-260/Configuration.h index 520e64a18..5cbd95adf 100644 --- a/Marlin/example_configurations/AliExpress/CL-260/Configuration.h +++ b/Marlin/example_configurations/AliExpress/CL-260/Configuration.h @@ -161,7 +161,10 @@ //#define SWITCHING_EXTRUDER #if ENABLED(SWITCHING_EXTRUDER) #define SWITCHING_EXTRUDER_SERVO_NR 0 - #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 + #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1[, E2, E3] + #if EXTRUDERS > 3 + #define SWITCHING_EXTRUDER_E23_SERVO_NR 1 + #endif #endif // A dual-nozzle that uses a servomotor to raise/lower one of the nozzles @@ -548,7 +551,6 @@ #define DEFAULT_ZJERK 0.4 #define DEFAULT_EJERK 5.0 - //=========================================================================== //============================= Z Probe Options ============================= //=========================================================================== @@ -1458,11 +1460,6 @@ // //#define U8GLIB_SSD1306 -// -// TinyBoy2 128x64 OLED / Encoder Panel -// -//#define OLED_PANEL_TINYBOY2 - // // SAV OLEd LCD module support using either SSD1306 or SH1106 based LCD modules // @@ -1480,6 +1477,11 @@ // //#define SAV_3DLCD +// +// TinyBoy2 128x64 OLED / Encoder Panel +// +//#define OLED_PANEL_TINYBOY2 + //============================================================================= //=============================== Extra Features ============================== //============================================================================= diff --git a/Marlin/example_configurations/Anet/A6/Configuration.h b/Marlin/example_configurations/Anet/A6/Configuration.h index 90f7bdffd..319826393 100644 --- a/Marlin/example_configurations/Anet/A6/Configuration.h +++ b/Marlin/example_configurations/Anet/A6/Configuration.h @@ -608,7 +608,6 @@ //#define DEFAULT_ZJERK 0.3 //#define DEFAULT_EJERK 5.0 - //=========================================================================== //============================= Z Probe Options ============================= //=========================================================================== @@ -650,7 +649,7 @@ * Probe Type * * Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, etc. - * You must activate one of these to use Auto Bed Leveling below. + * Activate one of these to use Auto Bed Leveling below. */ /** @@ -1466,12 +1465,6 @@ // //#define ULTIPANEL -// -// Cartesio UI -// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface -// -//#define CARTESIO_UI - // // PanelOne from T3P3 (via RAMPS 1.4 AUX2/AUX3) // http://reprap.org/wiki/PanelOne @@ -1556,6 +1549,12 @@ // //#define BQ_LCD_SMART_CONTROLLER +// +// Cartesio UI +// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface +// +//#define CARTESIO_UI + // // ANET_10 Controller supported displays. // diff --git a/Marlin/example_configurations/Anet/A6/Configuration_adv.h b/Marlin/example_configurations/Anet/A6/Configuration_adv.h index 613915570..265f54429 100644 --- a/Marlin/example_configurations/Anet/A6/Configuration_adv.h +++ b/Marlin/example_configurations/Anet/A6/Configuration_adv.h @@ -284,7 +284,7 @@ #if ENABLED(Z_DUAL_ENDSTOPS) #define Z2_USE_ENDSTOP _XMAX_ - #define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // use M666 command to determine/test this value + #define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // Use M666 to determine/test this value #endif #endif // Z_DUAL_STEPPER_DRIVERS @@ -394,7 +394,7 @@ // Minimum planner junction speed. Sets the default minimum speed the planner plans for at the end // of the buffer and all stops. This should not be much greater than zero and should only be changed // if unwanted behavior is observed on a user's machine when running at very slow speeds. -#define MINIMUM_PLANNER_SPEED 0.05// (mm/sec) +#define MINIMUM_PLANNER_SPEED 0.05 // (mm/sec) // Microstep setting (Only functional when stepper driver microstep pins are connected to MCU. #define MICROSTEP_MODES {16,16,16,16,16} // [1,2,4,8,16] @@ -648,7 +648,7 @@ * * Set to 0 to auto-detect the ratio based on given Gcode G1 print moves. * - * Slic3r (including Prusa Slic3r) produces Gcode compatible with the automatic mode. + * Slic3r (including Průša Control) produces Gcode compatible with the automatic mode. * Cura (as of this writing) may produce Gcode incompatible with the automatic mode. */ #define LIN_ADVANCE_E_D_RATIO 0 // The calculated ratio (or 0) according to the formula W * H / ((D / 2) ^ 2 * PI) @@ -1290,6 +1290,7 @@ //=========================================================================== //====================== I2C Position Encoder Settings ====================== //=========================================================================== + /** * I2C position encoders for closed loop control. * Developed by Chris Barr at Aus3D. diff --git a/Marlin/example_configurations/Anet/A8/Configuration.h b/Marlin/example_configurations/Anet/A8/Configuration.h index e57bb2fb3..537a90468 100644 --- a/Marlin/example_configurations/Anet/A8/Configuration.h +++ b/Marlin/example_configurations/Anet/A8/Configuration.h @@ -557,7 +557,6 @@ #define DEFAULT_ZJERK 0.3 #define DEFAULT_EJERK 5.0 - //=========================================================================== //============================= Z Probe Options ============================= //=========================================================================== @@ -599,7 +598,7 @@ * Probe Type * * Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, etc. - * You must activate one of these to use Auto Bed Leveling below. + * Activate one of these to use Auto Bed Leveling below. */ /** @@ -1013,6 +1012,7 @@ // //#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 BUSY_WHILE_HEATING // Some hosts require "busy" messages even during heating // // M100 Free Memory Watcher @@ -1037,7 +1037,7 @@ #define PREHEAT_1_FAN_SPEED 0 // Value from 0 to 255 #define PREHEAT_2_TEMP_HOTEND 240 -#define PREHEAT_2_TEMP_BED 90 +#define PREHEAT_2_TEMP_BED 90 #define PREHEAT_2_FAN_SPEED 0 // Value from 0 to 255 /** @@ -1314,12 +1314,6 @@ // //#define ULTIPANEL -// -// Cartesio UI -// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface -// -//#define CARTESIO_UI - // // PanelOne from T3P3 (via RAMPS 1.4 AUX2/AUX3) // http://reprap.org/wiki/PanelOne @@ -1404,6 +1398,12 @@ // //#define BQ_LCD_SMART_CONTROLLER +// +// Cartesio UI +// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface +// +//#define CARTESIO_UI + // // ANET_10 Controller supported displays. // diff --git a/Marlin/example_configurations/Anet/A8/Configuration_adv.h b/Marlin/example_configurations/Anet/A8/Configuration_adv.h index 09ed18575..ee2229416 100644 --- a/Marlin/example_configurations/Anet/A8/Configuration_adv.h +++ b/Marlin/example_configurations/Anet/A8/Configuration_adv.h @@ -284,7 +284,7 @@ #if ENABLED(Z_DUAL_ENDSTOPS) #define Z2_USE_ENDSTOP _XMAX_ - #define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // use M666 command to determine/test this value + #define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // Use M666 to determine/test this value #endif #endif // Z_DUAL_STEPPER_DRIVERS @@ -394,7 +394,7 @@ // Minimum planner junction speed. Sets the default minimum speed the planner plans for at the end // of the buffer and all stops. This should not be much greater than zero and should only be changed // if unwanted behavior is observed on a user's machine when running at very slow speeds. -#define MINIMUM_PLANNER_SPEED 0.05// (mm/sec) +#define MINIMUM_PLANNER_SPEED 0.05 // (mm/sec) // Microstep setting (Only functional when stepper driver microstep pins are connected to MCU. #define MICROSTEP_MODES {16,16,16,16,16} // [1,2,4,8,16] @@ -648,7 +648,7 @@ * * Set to 0 to auto-detect the ratio based on given Gcode G1 print moves. * - * Slic3r (including Prusa Slic3r) produces Gcode compatible with the automatic mode. + * Slic3r (including Průša Control) produces Gcode compatible with the automatic mode. * Cura (as of this writing) may produce Gcode incompatible with the automatic mode. */ #define LIN_ADVANCE_E_D_RATIO 0 // The calculated ratio (or 0) according to the formula W * H / ((D / 2) ^ 2 * PI) @@ -1290,6 +1290,7 @@ //=========================================================================== //====================== I2C Position Encoder Settings ====================== //=========================================================================== + /** * I2C position encoders for closed loop control. * Developed by Chris Barr at Aus3D. diff --git a/Marlin/example_configurations/BQ/Hephestos/Configuration.h b/Marlin/example_configurations/BQ/Hephestos/Configuration.h index 59db32e9e..fd956dcdf 100644 --- a/Marlin/example_configurations/BQ/Hephestos/Configuration.h +++ b/Marlin/example_configurations/BQ/Hephestos/Configuration.h @@ -164,7 +164,10 @@ //#define SWITCHING_EXTRUDER #if ENABLED(SWITCHING_EXTRUDER) #define SWITCHING_EXTRUDER_SERVO_NR 0 - #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 + #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1[, E2, E3] + #if EXTRUDERS > 3 + #define SWITCHING_EXTRUDER_E23_SERVO_NR 1 + #endif #endif // A dual-nozzle that uses a servomotor to raise/lower one of the nozzles @@ -310,6 +313,7 @@ #define HEATER_1_MAXTEMP 260 #define HEATER_2_MAXTEMP 260 #define HEATER_3_MAXTEMP 260 +#define HEATER_4_MAXTEMP 260 #define BED_MAXTEMP 150 //=========================================================================== @@ -521,7 +525,7 @@ * M204 R Retract Acceleration * M204 T Travel Acceleration */ -#define DEFAULT_ACCELERATION 650 // X, Y, Z and E acceleration for printing moves +#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 @@ -1447,11 +1451,6 @@ // //#define U8GLIB_SSD1306 -// -// TinyBoy2 128x64 OLED / Encoder Panel -// -//#define OLED_PANEL_TINYBOY2 - // // SAV OLEd LCD module support using either SSD1306 or SH1106 based LCD modules // @@ -1469,6 +1468,11 @@ // //#define SAV_3DLCD +// +// TinyBoy2 128x64 OLED / Encoder Panel +// +//#define OLED_PANEL_TINYBOY2 + //============================================================================= //=============================== Extra Features ============================== //============================================================================= diff --git a/Marlin/example_configurations/BQ/Hephestos/Configuration_adv.h b/Marlin/example_configurations/BQ/Hephestos/Configuration_adv.h index 41b4b3ac2..611336851 100644 --- a/Marlin/example_configurations/BQ/Hephestos/Configuration_adv.h +++ b/Marlin/example_configurations/BQ/Hephestos/Configuration_adv.h @@ -284,7 +284,7 @@ #if ENABLED(Z_DUAL_ENDSTOPS) #define Z2_USE_ENDSTOP _XMAX_ - #define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // use M666 command to determine this value + #define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // Use M666 to determine/test this value #endif #endif // Z_DUAL_STEPPER_DRIVERS @@ -394,7 +394,7 @@ // Minimum planner junction speed. Sets the default minimum speed the planner plans for at the end // of the buffer and all stops. This should not be much greater than zero and should only be changed // if unwanted behavior is observed on a user's machine when running at very slow speeds. -#define MINIMUM_PLANNER_SPEED 0.05// (mm/sec) +#define MINIMUM_PLANNER_SPEED 0.05 // (mm/sec) // Microstep setting (Only functional when stepper driver microstep pins are connected to MCU. #define MICROSTEP_MODES {16,16,16,16,16} // [1,2,4,8,16] @@ -452,6 +452,9 @@ // On the Info Screen, display XY with one decimal place when possible //#define LCD_DECIMAL_SMALL_XY +// The timeout (in ms) to return to the status screen from sub-menus +//#define LCD_TIMEOUT_TO_STATUS 15000 + #if ENABLED(SDSUPPORT) // Some RAMPS and other boards don't detect when an SD card is inserted. You can work @@ -645,7 +648,7 @@ * * Set to 0 to auto-detect the ratio based on given Gcode G1 print moves. * - * Slic3r (including Průša Slic3r) produces Gcode compatible with the automatic mode. + * Slic3r (including Průša Control) produces Gcode compatible with the automatic mode. * Cura (as of this writing) may produce Gcode incompatible with the automatic mode. */ #define LIN_ADVANCE_E_D_RATIO 0 // The calculated ratio (or 0) according to the formula W * H / ((D / 2) ^ 2 * PI) @@ -667,6 +670,10 @@ #define UBL_MESH_MAX_X (X_MAX_POS - (UBL_MESH_INSET)) #define UBL_MESH_MIN_Y (Y_MIN_POS + UBL_MESH_INSET) #define UBL_MESH_MAX_Y (Y_MAX_POS - (UBL_MESH_INSET)) + + // If this is defined, the currently active mesh will be saved in the + // current slot on M500. + #define UBL_SAVE_ACTIVE_ON_M500 #endif // @section extras @@ -1283,6 +1290,7 @@ //=========================================================================== //====================== I2C Position Encoder Settings ====================== //=========================================================================== + /** * I2C position encoders for closed loop control. * Developed by Chris Barr at Aus3D. diff --git a/Marlin/example_configurations/BQ/Hephestos_2/Configuration.h b/Marlin/example_configurations/BQ/Hephestos_2/Configuration.h index ae9ee3ddf..fdba13b24 100644 --- a/Marlin/example_configurations/BQ/Hephestos_2/Configuration.h +++ b/Marlin/example_configurations/BQ/Hephestos_2/Configuration.h @@ -160,7 +160,10 @@ //#define SWITCHING_EXTRUDER #if ENABLED(SWITCHING_EXTRUDER) #define SWITCHING_EXTRUDER_SERVO_NR 0 - #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 + #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1[, E2, E3] + #if EXTRUDERS > 3 + #define SWITCHING_EXTRUDER_E23_SERVO_NR 1 + #endif #endif // A dual-nozzle that uses a servomotor to raise/lower one of the nozzles @@ -1458,11 +1461,6 @@ // //#define U8GLIB_SSD1306 -// -// TinyBoy2 128x64 OLED / Encoder Panel -// -//#define OLED_PANEL_TINYBOY2 - // // SAV OLEd LCD module support using either SSD1306 or SH1106 based LCD modules // @@ -1480,6 +1478,11 @@ // //#define SAV_3DLCD +// +// TinyBoy2 128x64 OLED / Encoder Panel +// +//#define OLED_PANEL_TINYBOY2 + //============================================================================= //=============================== Extra Features ============================== //============================================================================= diff --git a/Marlin/example_configurations/BQ/Hephestos_2/Configuration_adv.h b/Marlin/example_configurations/BQ/Hephestos_2/Configuration_adv.h index 143c1ca51..adde1b841 100644 --- a/Marlin/example_configurations/BQ/Hephestos_2/Configuration_adv.h +++ b/Marlin/example_configurations/BQ/Hephestos_2/Configuration_adv.h @@ -284,7 +284,7 @@ #if ENABLED(Z_DUAL_ENDSTOPS) #define Z2_USE_ENDSTOP _XMAX_ - #define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // use M666 command to determine this value + #define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // Use M666 to determine/test this value #endif #endif // Z_DUAL_STEPPER_DRIVERS @@ -452,6 +452,9 @@ // On the Info Screen, display XY with one decimal place when possible #define LCD_DECIMAL_SMALL_XY +// The timeout (in ms) to return to the status screen from sub-menus +//#define LCD_TIMEOUT_TO_STATUS 15000 + #if ENABLED(SDSUPPORT) // Some RAMPS and other boards don't detect when an SD card is inserted. You can work @@ -531,8 +534,25 @@ #endif // SDSUPPORT -// Some additional options are available for graphical displays: +/** + * Additional options for Graphical Displays + * + * Use the optimizations here to improve printing performance, + * which can be adversely affected by graphical display drawing, + * especially when doing several short moves, and when printing + * on DELTA and SCARA machines. + * + * Some of these options may result in the display lagging behind + * controller events, as there is a trade-off between reliable + * printing performance versus fast display updates. + */ #if ENABLED(DOGLCD) + // Enable to save many cycles by drawing a hollow frame on the Info Screen + #define XYZ_HOLLOW_FRAME + + // Enable to save many cycles by drawing a hollow frame on Menu Screens + #define MENU_HOLLOW_FRAME + // 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 @@ -628,7 +648,7 @@ * * Set to 0 to auto-detect the ratio based on given Gcode G1 print moves. * - * Slic3r (including Průša Slic3r) produces Gcode compatible with the automatic mode. + * Slic3r (including Průša Control) produces Gcode compatible with the automatic mode. * Cura (as of this writing) may produce Gcode incompatible with the automatic mode. */ #define LIN_ADVANCE_E_D_RATIO 0 // The calculated ratio (or 0) according to the formula W * H / ((D / 2) ^ 2 * PI) @@ -650,6 +670,10 @@ #define UBL_MESH_MAX_X (X_MAX_POS - (UBL_MESH_INSET)) #define UBL_MESH_MIN_Y (Y_MIN_POS + UBL_MESH_INSET) #define UBL_MESH_MAX_Y (Y_MAX_POS - (UBL_MESH_INSET)) + + // If this is defined, the currently active mesh will be saved in the + // current slot on M500. + #define UBL_SAVE_ACTIVE_ON_M500 #endif // @section extras @@ -1266,6 +1290,7 @@ //=========================================================================== //====================== I2C Position Encoder Settings ====================== //=========================================================================== + /** * I2C position encoders for closed loop control. * Developed by Chris Barr at Aus3D. diff --git a/Marlin/example_configurations/BQ/WITBOX/Configuration.h b/Marlin/example_configurations/BQ/WITBOX/Configuration.h index c0a12efa5..b8fbc1266 100644 --- a/Marlin/example_configurations/BQ/WITBOX/Configuration.h +++ b/Marlin/example_configurations/BQ/WITBOX/Configuration.h @@ -164,7 +164,10 @@ //#define SWITCHING_EXTRUDER #if ENABLED(SWITCHING_EXTRUDER) #define SWITCHING_EXTRUDER_SERVO_NR 0 - #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 + #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1[, E2, E3] + #if EXTRUDERS > 3 + #define SWITCHING_EXTRUDER_E23_SERVO_NR 1 + #endif #endif // A dual-nozzle that uses a servomotor to raise/lower one of the nozzles @@ -310,6 +313,7 @@ #define HEATER_1_MAXTEMP 260 #define HEATER_2_MAXTEMP 260 #define HEATER_3_MAXTEMP 260 +#define HEATER_4_MAXTEMP 260 #define BED_MAXTEMP 150 //=========================================================================== @@ -1447,11 +1451,6 @@ // //#define U8GLIB_SSD1306 -// -// TinyBoy2 128x64 OLED / Encoder Panel -// -//#define OLED_PANEL_TINYBOY2 - // // SAV OLEd LCD module support using either SSD1306 or SH1106 based LCD modules // @@ -1469,6 +1468,11 @@ // //#define SAV_3DLCD +// +// TinyBoy2 128x64 OLED / Encoder Panel +// +//#define OLED_PANEL_TINYBOY2 + //============================================================================= //=============================== Extra Features ============================== //============================================================================= diff --git a/Marlin/example_configurations/BQ/WITBOX/Configuration_adv.h b/Marlin/example_configurations/BQ/WITBOX/Configuration_adv.h index 41b4b3ac2..611336851 100644 --- a/Marlin/example_configurations/BQ/WITBOX/Configuration_adv.h +++ b/Marlin/example_configurations/BQ/WITBOX/Configuration_adv.h @@ -284,7 +284,7 @@ #if ENABLED(Z_DUAL_ENDSTOPS) #define Z2_USE_ENDSTOP _XMAX_ - #define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // use M666 command to determine this value + #define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // Use M666 to determine/test this value #endif #endif // Z_DUAL_STEPPER_DRIVERS @@ -394,7 +394,7 @@ // Minimum planner junction speed. Sets the default minimum speed the planner plans for at the end // of the buffer and all stops. This should not be much greater than zero and should only be changed // if unwanted behavior is observed on a user's machine when running at very slow speeds. -#define MINIMUM_PLANNER_SPEED 0.05// (mm/sec) +#define MINIMUM_PLANNER_SPEED 0.05 // (mm/sec) // Microstep setting (Only functional when stepper driver microstep pins are connected to MCU. #define MICROSTEP_MODES {16,16,16,16,16} // [1,2,4,8,16] @@ -452,6 +452,9 @@ // On the Info Screen, display XY with one decimal place when possible //#define LCD_DECIMAL_SMALL_XY +// The timeout (in ms) to return to the status screen from sub-menus +//#define LCD_TIMEOUT_TO_STATUS 15000 + #if ENABLED(SDSUPPORT) // Some RAMPS and other boards don't detect when an SD card is inserted. You can work @@ -645,7 +648,7 @@ * * Set to 0 to auto-detect the ratio based on given Gcode G1 print moves. * - * Slic3r (including Průša Slic3r) produces Gcode compatible with the automatic mode. + * Slic3r (including Průša Control) produces Gcode compatible with the automatic mode. * Cura (as of this writing) may produce Gcode incompatible with the automatic mode. */ #define LIN_ADVANCE_E_D_RATIO 0 // The calculated ratio (or 0) according to the formula W * H / ((D / 2) ^ 2 * PI) @@ -667,6 +670,10 @@ #define UBL_MESH_MAX_X (X_MAX_POS - (UBL_MESH_INSET)) #define UBL_MESH_MIN_Y (Y_MIN_POS + UBL_MESH_INSET) #define UBL_MESH_MAX_Y (Y_MAX_POS - (UBL_MESH_INSET)) + + // If this is defined, the currently active mesh will be saved in the + // current slot on M500. + #define UBL_SAVE_ACTIVE_ON_M500 #endif // @section extras @@ -1283,6 +1290,7 @@ //=========================================================================== //====================== I2C Position Encoder Settings ====================== //=========================================================================== + /** * I2C position encoders for closed loop control. * Developed by Chris Barr at Aus3D. diff --git a/Marlin/example_configurations/Cartesio/Configuration.h b/Marlin/example_configurations/Cartesio/Configuration.h index 2ab76fc88..9360232d6 100644 --- a/Marlin/example_configurations/Cartesio/Configuration.h +++ b/Marlin/example_configurations/Cartesio/Configuration.h @@ -162,7 +162,10 @@ //#define SWITCHING_EXTRUDER #if ENABLED(SWITCHING_EXTRUDER) #define SWITCHING_EXTRUDER_SERVO_NR 0 - #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 + #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1[, E2, E3] + #if EXTRUDERS > 3 + #define SWITCHING_EXTRUDER_E23_SERVO_NR 1 + #endif #endif // A dual-nozzle that uses a servomotor to raise/lower one of the nozzles @@ -308,6 +311,7 @@ #define HEATER_1_MAXTEMP 415 #define HEATER_2_MAXTEMP 415 #define HEATER_3_MAXTEMP 415 +#define HEATER_4_MAXTEMP 415 #define BED_MAXTEMP 165 //=========================================================================== @@ -1455,11 +1459,6 @@ // //#define U8GLIB_SSD1306 -// -// TinyBoy2 128x64 OLED / Encoder Panel -// -//#define OLED_PANEL_TINYBOY2 - // // SAV OLEd LCD module support using either SSD1306 or SH1106 based LCD modules // @@ -1477,6 +1476,11 @@ // //#define SAV_3DLCD +// +// TinyBoy2 128x64 OLED / Encoder Panel +// +//#define OLED_PANEL_TINYBOY2 + //============================================================================= //=============================== Extra Features ============================== //============================================================================= diff --git a/Marlin/example_configurations/Cartesio/Configuration_adv.h b/Marlin/example_configurations/Cartesio/Configuration_adv.h index ea19d073c..f8d170dca 100644 --- a/Marlin/example_configurations/Cartesio/Configuration_adv.h +++ b/Marlin/example_configurations/Cartesio/Configuration_adv.h @@ -284,7 +284,7 @@ #if ENABLED(Z_DUAL_ENDSTOPS) #define Z2_USE_ENDSTOP _XMAX_ - #define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // use M666 command to determine this value + #define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // Use M666 to determine/test this value #endif #endif // Z_DUAL_STEPPER_DRIVERS @@ -394,7 +394,7 @@ // Minimum planner junction speed. Sets the default minimum speed the planner plans for at the end // of the buffer and all stops. This should not be much greater than zero and should only be changed // if unwanted behavior is observed on a user's machine when running at very slow speeds. -#define MINIMUM_PLANNER_SPEED 0.05// (mm/sec) +#define MINIMUM_PLANNER_SPEED 0.05 // (mm/sec) // Microstep setting (Only functional when stepper driver microstep pins are connected to MCU. #define MICROSTEP_MODES {16,16,16,16,16} // [1,2,4,8,16] @@ -452,6 +452,9 @@ // On the Info Screen, display XY with one decimal place when possible //#define LCD_DECIMAL_SMALL_XY +// The timeout (in ms) to return to the status screen from sub-menus +//#define LCD_TIMEOUT_TO_STATUS 15000 + #if ENABLED(SDSUPPORT) // Some RAMPS and other boards don't detect when an SD card is inserted. You can work @@ -645,7 +648,7 @@ * * Set to 0 to auto-detect the ratio based on given Gcode G1 print moves. * - * Slic3r (including Průša Slic3r) produces Gcode compatible with the automatic mode. + * Slic3r (including Průša Control) produces Gcode compatible with the automatic mode. * Cura (as of this writing) may produce Gcode incompatible with the automatic mode. */ #define LIN_ADVANCE_E_D_RATIO 0 // The calculated ratio (or 0) according to the formula W * H / ((D / 2) ^ 2 * PI) @@ -667,6 +670,10 @@ #define UBL_MESH_MAX_X (X_MAX_POS - (UBL_MESH_INSET)) #define UBL_MESH_MIN_Y (Y_MIN_POS + UBL_MESH_INSET) #define UBL_MESH_MAX_Y (Y_MAX_POS - (UBL_MESH_INSET)) + + // If this is defined, the currently active mesh will be saved in the + // current slot on M500. + #define UBL_SAVE_ACTIVE_ON_M500 #endif // @section extras @@ -1283,6 +1290,7 @@ //=========================================================================== //====================== I2C Position Encoder Settings ====================== //=========================================================================== + /** * I2C position encoders for closed loop control. * Developed by Chris Barr at Aus3D. diff --git a/Marlin/example_configurations/Creality/CR-10/Configuration.h b/Marlin/example_configurations/Creality/CR-10/Configuration.h index 5c3bc375f..b4817e4ae 100644 --- a/Marlin/example_configurations/Creality/CR-10/Configuration.h +++ b/Marlin/example_configurations/Creality/CR-10/Configuration.h @@ -335,12 +335,12 @@ // If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it -// Stock CR-10 tuned for 70C + // Stock CR-10 tuned for 70C #define DEFAULT_Kp 22.57 #define DEFAULT_Ki 1.72 #define DEFAULT_Kd 73.96 -// Ultimaker + // Ultimaker //#define DEFAULT_Kp 22.2 //#define DEFAULT_Ki 1.08 //#define DEFAULT_Kd 114 @@ -561,7 +561,6 @@ #define DEFAULT_ZJERK 2.7 #define DEFAULT_EJERK 5.0 - //=========================================================================== //============================= Z Probe Options ============================= //=========================================================================== @@ -603,7 +602,7 @@ * Probe Type * * Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, etc. - * You must activate one of these to use Auto Bed Leveling below. + * Activate one of these to use Auto Bed Leveling below. */ /** @@ -1019,6 +1018,7 @@ // #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 BUSY_WHILE_HEATING // Some hosts require "busy" messages even during heating // // M100 Free Memory Watcher @@ -1320,12 +1320,6 @@ // //#define ULTIPANEL -// -// Cartesio UI -// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface -// -//#define CARTESIO_UI - // // PanelOne from T3P3 (via RAMPS 1.4 AUX2/AUX3) // http://reprap.org/wiki/PanelOne @@ -1408,6 +1402,12 @@ // //#define BQ_LCD_SMART_CONTROLLER +// +// Cartesio UI +// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface +// +//#define CARTESIO_UI + // // ANET_10 Controller supported displays. // diff --git a/Marlin/example_configurations/Felix/Configuration.h b/Marlin/example_configurations/Felix/Configuration.h index dd2d419c3..5b99d6dba 100644 --- a/Marlin/example_configurations/Felix/Configuration.h +++ b/Marlin/example_configurations/Felix/Configuration.h @@ -161,7 +161,10 @@ //#define SWITCHING_EXTRUDER #if ENABLED(SWITCHING_EXTRUDER) #define SWITCHING_EXTRUDER_SERVO_NR 0 - #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 + #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1[, E2, E3] + #if EXTRUDERS > 3 + #define SWITCHING_EXTRUDER_E23_SERVO_NR 1 + #endif #endif // A dual-nozzle that uses a servomotor to raise/lower one of the nozzles @@ -727,7 +730,7 @@ // Be sure you have this distance over your Z_MAX_POS in case. // 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 @@ -1439,11 +1442,6 @@ // //#define U8GLIB_SSD1306 -// -// TinyBoy2 128x64 OLED / Encoder Panel -// -//#define OLED_PANEL_TINYBOY2 - // // SAV OLEd LCD module support using either SSD1306 or SH1106 based LCD modules // @@ -1461,6 +1459,11 @@ // //#define SAV_3DLCD +// +// TinyBoy2 128x64 OLED / Encoder Panel +// +//#define OLED_PANEL_TINYBOY2 + //============================================================================= //=============================== Extra Features ============================== //============================================================================= diff --git a/Marlin/example_configurations/Felix/Configuration_adv.h b/Marlin/example_configurations/Felix/Configuration_adv.h index 1bc5e0d57..b954f1ddb 100644 --- a/Marlin/example_configurations/Felix/Configuration_adv.h +++ b/Marlin/example_configurations/Felix/Configuration_adv.h @@ -284,7 +284,7 @@ #if ENABLED(Z_DUAL_ENDSTOPS) #define Z2_USE_ENDSTOP _XMAX_ - #define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // use M666 command to determine this value + #define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // Use M666 to determine/test this value #endif #endif // Z_DUAL_STEPPER_DRIVERS @@ -394,7 +394,7 @@ // Minimum planner junction speed. Sets the default minimum speed the planner plans for at the end // of the buffer and all stops. This should not be much greater than zero and should only be changed // if unwanted behavior is observed on a user's machine when running at very slow speeds. -#define MINIMUM_PLANNER_SPEED 0.05// (mm/sec) +#define MINIMUM_PLANNER_SPEED 0.05 // (mm/sec) // Microstep setting (Only functional when stepper driver microstep pins are connected to MCU. #define MICROSTEP_MODES {16,16,16,16,16} // [1,2,4,8,16] @@ -452,6 +452,9 @@ // On the Info Screen, display XY with one decimal place when possible //#define LCD_DECIMAL_SMALL_XY +// The timeout (in ms) to return to the status screen from sub-menus +//#define LCD_TIMEOUT_TO_STATUS 15000 + #if ENABLED(SDSUPPORT) // Some RAMPS and other boards don't detect when an SD card is inserted. You can work @@ -645,7 +648,7 @@ * * Set to 0 to auto-detect the ratio based on given Gcode G1 print moves. * - * Slic3r (including Průša Slic3r) produces Gcode compatible with the automatic mode. + * Slic3r (including Průša Control) produces Gcode compatible with the automatic mode. * Cura (as of this writing) may produce Gcode incompatible with the automatic mode. */ #define LIN_ADVANCE_E_D_RATIO 0 // The calculated ratio (or 0) according to the formula W * H / ((D / 2) ^ 2 * PI) @@ -667,6 +670,10 @@ #define UBL_MESH_MAX_X (X_MAX_POS - (UBL_MESH_INSET)) #define UBL_MESH_MIN_Y (Y_MIN_POS + UBL_MESH_INSET) #define UBL_MESH_MAX_Y (Y_MAX_POS - (UBL_MESH_INSET)) + + // If this is defined, the currently active mesh will be saved in the + // current slot on M500. + #define UBL_SAVE_ACTIVE_ON_M500 #endif // @section extras @@ -1283,6 +1290,7 @@ //=========================================================================== //====================== I2C Position Encoder Settings ====================== //=========================================================================== + /** * I2C position encoders for closed loop control. * Developed by Chris Barr at Aus3D. diff --git a/Marlin/example_configurations/Felix/DUAL/Configuration.h b/Marlin/example_configurations/Felix/DUAL/Configuration.h index f2c5ac626..eeaaf0e7f 100644 --- a/Marlin/example_configurations/Felix/DUAL/Configuration.h +++ b/Marlin/example_configurations/Felix/DUAL/Configuration.h @@ -161,7 +161,10 @@ //#define SWITCHING_EXTRUDER #if ENABLED(SWITCHING_EXTRUDER) #define SWITCHING_EXTRUDER_SERVO_NR 0 - #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 + #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1[, E2, E3] + #if EXTRUDERS > 3 + #define SWITCHING_EXTRUDER_E23_SERVO_NR 1 + #endif #endif // A dual-nozzle that uses a servomotor to raise/lower one of the nozzles @@ -1439,11 +1442,6 @@ // //#define U8GLIB_SSD1306 -// -// TinyBoy2 128x64 OLED / Encoder Panel -// -//#define OLED_PANEL_TINYBOY2 - // // SAV OLEd LCD module support using either SSD1306 or SH1106 based LCD modules // @@ -1461,6 +1459,11 @@ // //#define SAV_3DLCD +// +// TinyBoy2 128x64 OLED / Encoder Panel +// +//#define OLED_PANEL_TINYBOY2 + //============================================================================= //=============================== Extra Features ============================== //============================================================================= diff --git a/Marlin/example_configurations/Folger Tech/i3-2020/Configuration.h b/Marlin/example_configurations/Folger Tech/i3-2020/Configuration.h index ee40be09d..b0a875840 100644 --- a/Marlin/example_configurations/Folger Tech/i3-2020/Configuration.h +++ b/Marlin/example_configurations/Folger Tech/i3-2020/Configuration.h @@ -161,7 +161,10 @@ //#define SWITCHING_EXTRUDER #if ENABLED(SWITCHING_EXTRUDER) #define SWITCHING_EXTRUDER_SERVO_NR 0 - #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 + #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1[, E2, E3] + #if EXTRUDERS > 3 + #define SWITCHING_EXTRUDER_E23_SERVO_NR 1 + #endif #endif // A dual-nozzle that uses a servomotor to raise/lower one of the nozzles @@ -553,7 +556,6 @@ #define DEFAULT_ZJERK 0.4 #define DEFAULT_EJERK 4.0 - //=========================================================================== //============================= Z Probe Options ============================= //=========================================================================== @@ -698,7 +700,8 @@ #define Z_CLEARANCE_DEPLOY_PROBE 3 // Z Clearance for Deploy/Stow #define Z_CLEARANCE_BETWEEN_PROBES 3 // Z Clearance between probe points -// For M851 give a range for adjusting the Z probe offset#define Z_PROBE_OFFSET_RANGE_MIN -20 +// For M851 give a range for adjusting the Z probe offset +#define Z_PROBE_OFFSET_RANGE_MIN -20 #define Z_PROBE_OFFSET_RANGE_MAX 20 // Enable the M48 repeatability test to test probe accuracy @@ -1462,11 +1465,6 @@ // //#define U8GLIB_SSD1306 -// -// TinyBoy2 128x64 OLED / Encoder Panel -// -//#define OLED_PANEL_TINYBOY2 - // // SAV OLEd LCD module support using either SSD1306 or SH1106 based LCD modules // @@ -1484,6 +1482,11 @@ // //#define SAV_3DLCD +// +// TinyBoy2 128x64 OLED / Encoder Panel +// +//#define OLED_PANEL_TINYBOY2 + //============================================================================= //=============================== Extra Features ============================== //============================================================================= diff --git a/Marlin/example_configurations/Folger Tech/i3-2020/Configuration_adv.h b/Marlin/example_configurations/Folger Tech/i3-2020/Configuration_adv.h index 46f925406..2bd673901 100644 --- a/Marlin/example_configurations/Folger Tech/i3-2020/Configuration_adv.h +++ b/Marlin/example_configurations/Folger Tech/i3-2020/Configuration_adv.h @@ -284,7 +284,7 @@ #if ENABLED(Z_DUAL_ENDSTOPS) #define Z2_USE_ENDSTOP _XMAX_ - #define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // use M666 command to determine/test this value + #define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // Use M666 to determine/test this value #endif #endif // Z_DUAL_STEPPER_DRIVERS @@ -394,7 +394,7 @@ // Minimum planner junction speed. Sets the default minimum speed the planner plans for at the end // of the buffer and all stops. This should not be much greater than zero and should only be changed // if unwanted behavior is observed on a user's machine when running at very slow speeds. -#define MINIMUM_PLANNER_SPEED 0.05// (mm/sec) +#define MINIMUM_PLANNER_SPEED 0.05 // (mm/sec) // Microstep setting (Only functional when stepper driver microstep pins are connected to MCU. #define MICROSTEP_MODES {16,16,16,16,16} // [1,2,4,8,16] @@ -648,7 +648,7 @@ * * Set to 0 to auto-detect the ratio based on given Gcode G1 print moves. * - * Slic3r (including Průša Slic3r) produces Gcode compatible with the automatic mode. + * Slic3r (including Průša Control) produces Gcode compatible with the automatic mode. * Cura (as of this writing) may produce Gcode incompatible with the automatic mode. */ #define LIN_ADVANCE_E_D_RATIO 0 // The calculated ratio (or 0) according to the formula W * H / ((D / 2) ^ 2 * PI) @@ -795,7 +795,6 @@ * Requires an LCD display. * This feature is required for the default FILAMENT_RUNOUT_SCRIPT. */ - #define ADVANCED_PAUSE_FEATURE #if ENABLED(ADVANCED_PAUSE_FEATURE) #define PAUSE_PARK_X_POS 10 // X position of hotend @@ -805,7 +804,6 @@ #define PAUSE_PARK_Z_FEEDRATE 5 // Z axis feedrate in mm/s (not used for delta printers) #define PAUSE_PARK_RETRACT_FEEDRATE 60 // Initial retract feedrate in mm/s #define PAUSE_PARK_RETRACT_LENGTH 2 // Initial retract in mm - // It is a short retract used immediately after print interrupt before move to filament exchange position #define FILAMENT_CHANGE_UNLOAD_FEEDRATE 10 // Unload filament feedrate in mm/s - filament unloading can be fast #define FILAMENT_CHANGE_UNLOAD_LENGTH 100 // Unload filament length from hotend in mm @@ -1211,15 +1209,11 @@ //#define SPEED_POWER_MAX 100 // 0-100% #endif -// @section debug - /** * M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins */ #define PINS_DEBUGGING -// @section extras - /** * Auto-report temperatures with M155 S */ @@ -1296,6 +1290,7 @@ //=========================================================================== //====================== I2C Position Encoder Settings ====================== //=========================================================================== + /** * I2C position encoders for closed loop control. * Developed by Chris Barr at Aus3D. diff --git a/Marlin/example_configurations/Infitary/i3-M508/Configuration.h b/Marlin/example_configurations/Infitary/i3-M508/Configuration.h index 32cf0b547..872870a76 100644 --- a/Marlin/example_configurations/Infitary/i3-M508/Configuration.h +++ b/Marlin/example_configurations/Infitary/i3-M508/Configuration.h @@ -555,7 +555,6 @@ #define DEFAULT_ZJERK 0.4 #define DEFAULT_EJERK 5.0 - //=========================================================================== //============================= Z Probe Options ============================= //=========================================================================== @@ -597,7 +596,7 @@ * Probe Type * * Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, etc. - * You must activate one of these to use Auto Bed Leveling below. + * Activate one of these to use Auto Bed Leveling below. */ /** @@ -1313,12 +1312,6 @@ // //#define ULTIPANEL -// -// Cartesio UI -// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface -// -//#define CARTESIO_UI - // // PanelOne from T3P3 (via RAMPS 1.4 AUX2/AUX3) // http://reprap.org/wiki/PanelOne @@ -1401,6 +1394,12 @@ // //#define BQ_LCD_SMART_CONTROLLER +// +// Cartesio UI +// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface +// +//#define CARTESIO_UI + // // ANET_10 Controller supported displays. // diff --git a/Marlin/example_configurations/Infitary/i3-M508/Configuration_adv.h b/Marlin/example_configurations/Infitary/i3-M508/Configuration_adv.h index 2c8db64fe..eb7127285 100644 --- a/Marlin/example_configurations/Infitary/i3-M508/Configuration_adv.h +++ b/Marlin/example_configurations/Infitary/i3-M508/Configuration_adv.h @@ -123,8 +123,8 @@ #define AUTOTEMP_OLDWEIGHT 0.98 #endif -//Show Temperature ADC value -//The M105 command return, besides traditional information, the ADC value read from temperature sensors. +// Show Temperature ADC value +// Enable for M105 to include ADC values read from temperature sensors. //#define SHOW_TEMP_ADC_VALUES /** @@ -220,12 +220,16 @@ #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 +/** + * M355 Case Light on-off / brightness + */ +//#define CASE_LIGHT_ENABLE +#if ENABLED(CASE_LIGHT_ENABLE) + //#define CASE_LIGHT_PIN 4 // Override the default pin if needed + #define INVERT_CASE_LIGHT false // Set true if Case Light is ON when pin is LOW + #define CASE_LIGHT_DEFAULT_ON true // Set default power-up state on + #define CASE_LIGHT_DEFAULT_BRIGHTNESS 105 // Set default power-up brightness (0-255, requires PWM pin) + //#define MENU_ITEM_CASE_LIGHT // Add a Case Light option to the LCD main menu #endif //=========================================================================== @@ -280,7 +284,7 @@ #if ENABLED(Z_DUAL_ENDSTOPS) #define Z2_USE_ENDSTOP _XMAX_ - #define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // use M666 command to determine/test this value + #define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // Use M666 to determine/test this value #endif #endif // Z_DUAL_STEPPER_DRIVERS @@ -390,7 +394,7 @@ // Minimum planner junction speed. Sets the default minimum speed the planner plans for at the end // of the buffer and all stops. This should not be much greater than zero and should only be changed // if unwanted behavior is observed on a user's machine when running at very slow speeds. -#define MINIMUM_PLANNER_SPEED 0.05// (mm/sec) +#define MINIMUM_PLANNER_SPEED 0.05 // (mm/sec) // Microstep setting (Only functional when stepper driver microstep pins are connected to MCU. #define MICROSTEP_MODES {16,16,16,16,16} // [1,2,4,8,16] @@ -415,16 +419,16 @@ * M908 - BQ_ZUM_MEGA_3D, RAMBO, PRINTRBOARD_REVF, RIGIDBOARD_V2 & SCOOVO_X9H * M909, M910 & LCD - only PRINTRBOARD_REVF & RIGIDBOARD_V2 */ -//#define PWM_MOTOR_CURRENT {1300, 1300, 1250} // Values in milliamps -#define DIGIPOT_MOTOR_CURRENT {135,135,135,135,135} // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A) -//#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 } // Default drive percent - X, Y, Z, E axis +//#define PWM_MOTOR_CURRENT { 1300, 1300, 1250 } // Values in milliamps +#define DIGIPOT_MOTOR_CURRENT { 135,135,135,135,135 } // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A) +//#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 } // Default drive percent - X, Y, Z, E axis // Uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro //#define DIGIPOT_I2C -//#define DIGIPOT_MCP4018 +//#define DIGIPOT_MCP4018 // Requires library from https://github.com/stawel/SlowSoftI2CMaster #define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4 AZTEEG_X3_PRO: 8 // Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS -#define DIGIPOT_I2C_MOTOR_CURRENTS {1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0} // AZTEEG_X3_PRO +#define DIGIPOT_I2C_MOTOR_CURRENTS { 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0 } // AZTEEG_X3_PRO //=========================================================================== //=============================Additional Features=========================== @@ -644,7 +648,7 @@ * * Set to 0 to auto-detect the ratio based on given Gcode G1 print moves. * - * Slic3r (including Prusa Slic3r) produces Gcode compatible with the automatic mode. + * Slic3r (including Průša Control) produces Gcode compatible with the automatic mode. * Cura (as of this writing) may produce Gcode incompatible with the automatic mode. */ #define LIN_ADVANCE_E_D_RATIO 0 // The calculated ratio (or 0) according to the formula W * H / ((D / 2) ^ 2 * PI) @@ -674,10 +678,16 @@ // @section extras -// Arc interpretation settings: -#define ARC_SUPPORT // Disabling this saves ~2738 bytes -#define MM_PER_ARC_SEGMENT 1 -#define N_ARC_CORRECTION 25 +// +// G2/G3 Arc Support +// +#define ARC_SUPPORT // Disable this feature to save ~3226 bytes +#if ENABLED(ARC_SUPPORT) + #define MM_PER_ARC_SEGMENT 1 // Length of each arc segment + #define N_ARC_CORRECTION 25 // Number of intertpolated segments between corrections + //#define ARC_P_CIRCLES // Enable the 'P' parameter to specify complete circles + //#define CNC_WORKSPACE_PLANES // Allow G2/G3 to operate in XY, ZX, or YZ planes +#endif // Support for G5 with XYZE destination and IJPQ offsets. Requires ~2666 bytes. //#define BEZIER_CURVE_SUPPORT @@ -814,6 +824,7 @@ #define PAUSE_PARK_NO_STEPPER_TIMEOUT // Enable to have stepper motors hold position during filament change // even if it takes longer than DEFAULT_STEPPER_DEACTIVE_TIME. //#define PARK_HEAD_ON_PAUSE // Go to filament change position on pause, return to print position on resume + //#define HOME_BEFORE_FILAMENT_CHANGE // Ensure homing has been completed prior to parking for filament change #endif // @section tmc @@ -1034,7 +1045,7 @@ */ #define TMC2130_ADV() { } -#endif // ENABLED(HAVE_TMC2130) +#endif // HAVE_TMC2130 // @section L6470 @@ -1269,4 +1280,95 @@ #define USER_GCODE_5 "G28\nM503" #endif +/** + * Specify an action command to send to the host when the printer is killed. + * Will be sent in the form '//action:ACTION_ON_KILL', e.g. '//action:poweroff'. + * The host must be configured to handle the action command. + */ +//#define ACTION_ON_KILL "poweroff" + +//=========================================================================== +//====================== I2C Position Encoder Settings ====================== +//=========================================================================== + +/** + * I2C position encoders for closed loop control. + * Developed by Chris Barr at Aus3D. + * + * Wiki: http://wiki.aus3d.com.au/Magnetic_Encoder + * Github: https://github.com/Aus3D/MagneticEncoder + * + * Supplier: http://aus3d.com.au/magnetic-encoder-module + * Alternative Supplier: http://reliabuild3d.com/ + * + * Reilabuild encoders have been modified to improve reliability. + */ + +//#define I2C_POSITION_ENCODERS +#if ENABLED(I2C_POSITION_ENCODERS) + + #define I2CPE_ENCODER_CNT 1 // The number of encoders installed; max of 5 + // encoders supported currently. + + #define I2CPE_ENC_1_ADDR I2CPE_PRESET_ADDR_X // I2C address of the encoder. 30-200. + #define I2CPE_ENC_1_AXIS X_AXIS // Axis the encoder module is installed on. _AXIS. + #define I2CPE_ENC_1_TYPE I2CPE_ENC_TYPE_LINEAR // Type of encoder: I2CPE_ENC_TYPE_LINEAR -or- + // I2CPE_ENC_TYPE_ROTARY. + #define I2CPE_ENC_1_TICKS_UNIT 2048 // 1024 for magnetic strips with 2mm poles; 2048 for + // 1mm poles. For linear encoders this is ticks / mm, + // for rotary encoders this is ticks / revolution. + //#define I2CPE_ENC_1_TICKS_REV (16 * 200) // Only needed for rotary encoders; number of stepper + // steps per full revolution (motor steps/rev * microstepping) + //#define I2CPE_ENC_1_INVERT // Invert the direction of axis travel. + #define I2CPE_ENC_1_EC_METHOD I2CPE_ECM_NONE // Type of error error correction. + #define I2CPE_ENC_1_EC_THRESH 0.10 // Threshold size for error (in mm) above which the + // printer will attempt to correct the error; errors + // smaller than this are ignored to minimize effects of + // measurement noise / latency (filter). + + #define I2CPE_ENC_2_ADDR I2CPE_PRESET_ADDR_Y // Same as above, but for encoder 2. + #define I2CPE_ENC_2_AXIS Y_AXIS + #define I2CPE_ENC_2_TYPE I2CPE_ENC_TYPE_LINEAR + #define I2CPE_ENC_2_TICKS_UNIT 2048 + //#define I2CPE_ENC_2_TICKS_REV (16 * 200) + //#define I2CPE_ENC_2_INVERT + #define I2CPE_ENC_2_EC_METHOD I2CPE_ECM_NONE + #define I2CPE_ENC_2_EC_THRESH 0.10 + + #define I2CPE_ENC_3_ADDR I2CPE_PRESET_ADDR_Z // Encoder 3. Add additional configuration options + #define I2CPE_ENC_3_AXIS Z_AXIS // as above, or use defaults below. + + #define I2CPE_ENC_4_ADDR I2CPE_PRESET_ADDR_E // Encoder 4. + #define I2CPE_ENC_4_AXIS E_AXIS + + #define I2CPE_ENC_5_ADDR 34 // Encoder 5. + #define I2CPE_ENC_5_AXIS E_AXIS + + // Default settings for encoders which are enabled, but without settings configured above. + #define I2CPE_DEF_TYPE I2CPE_ENC_TYPE_LINEAR + #define I2CPE_DEF_ENC_TICKS_UNIT 2048 + #define I2CPE_DEF_TICKS_REV (16 * 200) + #define I2CPE_DEF_EC_METHOD I2CPE_ECM_NONE + #define I2CPE_DEF_EC_THRESH 0.1 + + //#define I2CPE_ERR_THRESH_ABORT 100.0 // Threshold size for error (in mm) error on any given + // axis after which the printer will abort. Comment out to + // disable abort behaviour. + + #define I2CPE_TIME_TRUSTED 10000 // After an encoder fault, there must be no further fault + // for this amount of time (in ms) before the encoder + // is trusted again. + + /** + * Position is checked every time a new command is executed from the buffer but during long moves, + * this setting determines the minimum update time between checks. A value of 100 works well with + * error rolling average when attempting to correct only for skips and not for vibration. + */ + #define I2CPE_MIN_UPD_TIME_MS 100 // Minimum time in miliseconds between encoder checks. + + // Use a rolling average to identify persistant errors that indicate skips, as opposed to vibration and noise. + #define I2CPE_ERR_ROLLING_AVERAGE + +#endif // I2C_POSITION_ENCODERS + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/Malyan/M150/Configuration.h b/Marlin/example_configurations/Malyan/M150/Configuration.h index fbd4f4f55..501738266 100644 --- a/Marlin/example_configurations/Malyan/M150/Configuration.h +++ b/Marlin/example_configurations/Malyan/M150/Configuration.h @@ -166,7 +166,10 @@ //#define SWITCHING_EXTRUDER #if ENABLED(SWITCHING_EXTRUDER) #define SWITCHING_EXTRUDER_SERVO_NR 0 - #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 + #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1[, E2, E3] + #if EXTRUDERS > 3 + #define SWITCHING_EXTRUDER_E23_SERVO_NR 1 + #endif #endif // A dual-nozzle that uses a servomotor to raise/lower one of the nozzles @@ -305,6 +308,7 @@ #define HEATER_1_MINTEMP 5 #define HEATER_2_MINTEMP 5 #define HEATER_3_MINTEMP 5 +#define HEATER_4_MINTEMP 5 #define BED_MINTEMP 5 // When temperature exceeds max temp, your heater will be switched off. @@ -314,6 +318,7 @@ #define HEATER_1_MAXTEMP 275 #define HEATER_2_MAXTEMP 275 #define HEATER_3_MAXTEMP 275 +#define HEATER_4_MAXTEMP 275 #define BED_MAXTEMP 150 //=========================================================================== @@ -566,7 +571,6 @@ #define DEFAULT_ZJERK 0.40 #define DEFAULT_EJERK 5.0 - //=========================================================================== //============================= Z Probe Options ============================= //=========================================================================== @@ -1484,11 +1488,6 @@ // //#define U8GLIB_SSD1306 -// -// TinyBoy2 128x64 OLED / Encoder Panel -// -//#define OLED_PANEL_TINYBOY2 - // // SAV OLEd LCD module support using either SSD1306 or SH1106 based LCD modules // @@ -1506,6 +1505,11 @@ // //#define SAV_3DLCD +// +// TinyBoy2 128x64 OLED / Encoder Panel +// +//#define OLED_PANEL_TINYBOY2 + //============================================================================= //=============================== Extra Features ============================== //============================================================================= diff --git a/Marlin/example_configurations/Malyan/M150/Configuration_adv.h b/Marlin/example_configurations/Malyan/M150/Configuration_adv.h index ad1ecad8f..11403a7fb 100644 --- a/Marlin/example_configurations/Malyan/M150/Configuration_adv.h +++ b/Marlin/example_configurations/Malyan/M150/Configuration_adv.h @@ -284,7 +284,7 @@ #if ENABLED(Z_DUAL_ENDSTOPS) #define Z2_USE_ENDSTOP _XMAX_ - #define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // use M666 command to determine/test this value + #define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // Use M666 to determine/test this value #endif #endif // Z_DUAL_STEPPER_DRIVERS @@ -394,7 +394,7 @@ // Minimum planner junction speed. Sets the default minimum speed the planner plans for at the end // of the buffer and all stops. This should not be much greater than zero and should only be changed // if unwanted behavior is observed on a user's machine when running at very slow speeds. -#define MINIMUM_PLANNER_SPEED 0.05// (mm/sec) +#define MINIMUM_PLANNER_SPEED 0.05 // (mm/sec) // Microstep setting (Only functional when stepper driver microstep pins are connected to MCU. #define MICROSTEP_MODES {16,16,16,16,16} // [1,2,4,8,16] @@ -648,7 +648,7 @@ * * Set to 0 to auto-detect the ratio based on given Gcode G1 print moves. * - * Slic3r (including Průša Slic3r) produces Gcode compatible with the automatic mode. + * Slic3r (including Průša Control) produces Gcode compatible with the automatic mode. * Cura (as of this writing) may produce Gcode incompatible with the automatic mode. */ #define LIN_ADVANCE_E_D_RATIO 0 // The calculated ratio (or 0) according to the formula W * H / ((D / 2) ^ 2 * PI) @@ -1290,6 +1290,7 @@ //=========================================================================== //====================== I2C Position Encoder Settings ====================== //=========================================================================== + /** * I2C position encoders for closed loop control. * Developed by Chris Barr at Aus3D. diff --git a/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h b/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h index 8a0b3ab80..0f575a8fc 100644 --- a/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h +++ b/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h @@ -161,7 +161,10 @@ //#define SWITCHING_EXTRUDER #if ENABLED(SWITCHING_EXTRUDER) #define SWITCHING_EXTRUDER_SERVO_NR 0 - #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 + #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1[, E2, E3] + #if EXTRUDERS > 3 + #define SWITCHING_EXTRUDER_E23_SERVO_NR 1 + #endif #endif // A dual-nozzle that uses a servomotor to raise/lower one of the nozzles @@ -1457,11 +1460,6 @@ // //#define U8GLIB_SSD1306 -// -// TinyBoy2 128x64 OLED / Encoder Panel -// -//#define OLED_PANEL_TINYBOY2 - // // SAV OLEd LCD module support using either SSD1306 or SH1106 based LCD modules // @@ -1479,6 +1477,11 @@ // //#define SAV_3DLCD +// +// TinyBoy2 128x64 OLED / Encoder Panel +// +//#define OLED_PANEL_TINYBOY2 + //============================================================================= //=============================== Extra Features ============================== //============================================================================= diff --git a/Marlin/example_configurations/RigidBot/Configuration.h b/Marlin/example_configurations/RigidBot/Configuration.h index 60a809b62..ea744e8e8 100644 --- a/Marlin/example_configurations/RigidBot/Configuration.h +++ b/Marlin/example_configurations/RigidBot/Configuration.h @@ -164,7 +164,10 @@ //#define SWITCHING_EXTRUDER #if ENABLED(SWITCHING_EXTRUDER) #define SWITCHING_EXTRUDER_SERVO_NR 0 - #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 + #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1[, E2, E3] + #if EXTRUDERS > 3 + #define SWITCHING_EXTRUDER_E23_SERVO_NR 1 + #endif #endif // A dual-nozzle that uses a servomotor to raise/lower one of the nozzles @@ -1457,11 +1460,6 @@ // //#define U8GLIB_SSD1306 -// -// TinyBoy2 128x64 OLED / Encoder Panel -// -//#define OLED_PANEL_TINYBOY2 - // // SAV OLEd LCD module support using either SSD1306 or SH1106 based LCD modules // @@ -1479,6 +1477,11 @@ // //#define SAV_3DLCD +// +// TinyBoy2 128x64 OLED / Encoder Panel +// +//#define OLED_PANEL_TINYBOY2 + //============================================================================= //=============================== Extra Features ============================== //============================================================================= diff --git a/Marlin/example_configurations/RigidBot/Configuration_adv.h b/Marlin/example_configurations/RigidBot/Configuration_adv.h index ad61814cb..565ac51bf 100644 --- a/Marlin/example_configurations/RigidBot/Configuration_adv.h +++ b/Marlin/example_configurations/RigidBot/Configuration_adv.h @@ -284,7 +284,7 @@ #if ENABLED(Z_DUAL_ENDSTOPS) #define Z2_USE_ENDSTOP _XMAX_ - #define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // use M666 command to determine this value + #define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // Use M666 to determine/test this value #endif #endif // Z_DUAL_STEPPER_DRIVERS @@ -394,7 +394,7 @@ // Minimum planner junction speed. Sets the default minimum speed the planner plans for at the end // of the buffer and all stops. This should not be much greater than zero and should only be changed // if unwanted behavior is observed on a user's machine when running at very slow speeds. -#define MINIMUM_PLANNER_SPEED 0.05// (mm/sec) +#define MINIMUM_PLANNER_SPEED 0.05 // (mm/sec) // Microstep setting (Only functional when stepper driver microstep pins are connected to MCU. #define MICROSTEP_MODES {16,16,16,16,16} // [1,2,4,8,16] @@ -452,6 +452,9 @@ // On the Info Screen, display XY with one decimal place when possible //#define LCD_DECIMAL_SMALL_XY +// The timeout (in ms) to return to the status screen from sub-menus +//#define LCD_TIMEOUT_TO_STATUS 15000 + #if ENABLED(SDSUPPORT) // Some RAMPS and other boards don't detect when an SD card is inserted. You can work @@ -645,7 +648,7 @@ * * Set to 0 to auto-detect the ratio based on given Gcode G1 print moves. * - * Slic3r (including Průša Slic3r) produces Gcode compatible with the automatic mode. + * Slic3r (including Průša Control) produces Gcode compatible with the automatic mode. * Cura (as of this writing) may produce Gcode incompatible with the automatic mode. */ #define LIN_ADVANCE_E_D_RATIO 0 // The calculated ratio (or 0) according to the formula W * H / ((D / 2) ^ 2 * PI) @@ -667,6 +670,10 @@ #define UBL_MESH_MAX_X (X_MAX_POS - (UBL_MESH_INSET)) #define UBL_MESH_MIN_Y (Y_MIN_POS + UBL_MESH_INSET) #define UBL_MESH_MAX_Y (Y_MAX_POS - (UBL_MESH_INSET)) + + // If this is defined, the currently active mesh will be saved in the + // current slot on M500. + #define UBL_SAVE_ACTIVE_ON_M500 #endif // @section extras @@ -1283,6 +1290,7 @@ //=========================================================================== //====================== I2C Position Encoder Settings ====================== //=========================================================================== + /** * I2C position encoders for closed loop control. * Developed by Chris Barr at Aus3D. diff --git a/Marlin/example_configurations/SCARA/Configuration.h b/Marlin/example_configurations/SCARA/Configuration.h index 2cc6a7f48..aa5dcdac6 100644 --- a/Marlin/example_configurations/SCARA/Configuration.h +++ b/Marlin/example_configurations/SCARA/Configuration.h @@ -191,7 +191,10 @@ //#define SWITCHING_EXTRUDER #if ENABLED(SWITCHING_EXTRUDER) #define SWITCHING_EXTRUDER_SERVO_NR 0 - #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 + #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1[, E2, E3] + #if EXTRUDERS > 3 + #define SWITCHING_EXTRUDER_E23_SERVO_NR 1 + #endif #endif // A dual-nozzle that uses a servomotor to raise/lower one of the nozzles @@ -1469,11 +1472,6 @@ // //#define U8GLIB_SSD1306 -// -// TinyBoy2 128x64 OLED / Encoder Panel -// -//#define OLED_PANEL_TINYBOY2 - // // SAV OLEd LCD module support using either SSD1306 or SH1106 based LCD modules // @@ -1491,6 +1489,11 @@ // //#define SAV_3DLCD +// +// TinyBoy2 128x64 OLED / Encoder Panel +// +//#define OLED_PANEL_TINYBOY2 + //============================================================================= //=============================== Extra Features ============================== //============================================================================= diff --git a/Marlin/example_configurations/SCARA/Configuration_adv.h b/Marlin/example_configurations/SCARA/Configuration_adv.h index d431de86d..09771987b 100644 --- a/Marlin/example_configurations/SCARA/Configuration_adv.h +++ b/Marlin/example_configurations/SCARA/Configuration_adv.h @@ -284,7 +284,7 @@ #if ENABLED(Z_DUAL_ENDSTOPS) #define Z2_USE_ENDSTOP _XMAX_ - #define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // use M666 command to determine this value + #define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // Use M666 to determine/test this value #endif #endif // Z_DUAL_STEPPER_DRIVERS @@ -394,7 +394,7 @@ // Minimum planner junction speed. Sets the default minimum speed the planner plans for at the end // of the buffer and all stops. This should not be much greater than zero and should only be changed // if unwanted behavior is observed on a user's machine when running at very slow speeds. -#define MINIMUM_PLANNER_SPEED 0.05// (mm/sec) +#define MINIMUM_PLANNER_SPEED 0.05 // (mm/sec) // Microstep setting (Only functional when stepper driver microstep pins are connected to MCU. #define MICROSTEP_MODES {16,16,16,16,16} // [1,2,4,8,16] @@ -452,6 +452,9 @@ // On the Info Screen, display XY with one decimal place when possible //#define LCD_DECIMAL_SMALL_XY +// The timeout (in ms) to return to the status screen from sub-menus +//#define LCD_TIMEOUT_TO_STATUS 15000 + #if ENABLED(SDSUPPORT) // Some RAMPS and other boards don't detect when an SD card is inserted. You can work @@ -645,7 +648,7 @@ * * Set to 0 to auto-detect the ratio based on given Gcode G1 print moves. * - * Slic3r (including Průša Slic3r) produces Gcode compatible with the automatic mode. + * Slic3r (including Průša Control) produces Gcode compatible with the automatic mode. * Cura (as of this writing) may produce Gcode incompatible with the automatic mode. */ #define LIN_ADVANCE_E_D_RATIO 0 // The calculated ratio (or 0) according to the formula W * H / ((D / 2) ^ 2 * PI) @@ -667,6 +670,10 @@ #define UBL_MESH_MAX_X (X_MAX_POS - (UBL_MESH_INSET)) #define UBL_MESH_MIN_Y (Y_MIN_POS + UBL_MESH_INSET) #define UBL_MESH_MAX_Y (Y_MAX_POS - (UBL_MESH_INSET)) + + // If this is defined, the currently active mesh will be saved in the + // current slot on M500. + #define UBL_SAVE_ACTIVE_ON_M500 #endif // @section extras @@ -1283,6 +1290,7 @@ //=========================================================================== //====================== I2C Position Encoder Settings ====================== //=========================================================================== + /** * I2C position encoders for closed loop control. * Developed by Chris Barr at Aus3D. diff --git a/Marlin/example_configurations/TinyBoy2/Configuration.h b/Marlin/example_configurations/TinyBoy2/Configuration.h index ad677c363..480ba0a7a 100644 --- a/Marlin/example_configurations/TinyBoy2/Configuration.h +++ b/Marlin/example_configurations/TinyBoy2/Configuration.h @@ -183,7 +183,10 @@ //#define SWITCHING_EXTRUDER #if ENABLED(SWITCHING_EXTRUDER) #define SWITCHING_EXTRUDER_SERVO_NR 0 - #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 + #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1[, E2, E3] + #if EXTRUDERS > 3 + #define SWITCHING_EXTRUDER_E23_SERVO_NR 1 + #endif #endif // A dual-nozzle that uses a servomotor to raise/lower one of the nozzles @@ -1513,11 +1516,6 @@ // //#define U8GLIB_SSD1306 -// -// TinyBoy2 128x64 OLED / Encoder Panel -// -//#define OLED_PANEL_TINYBOY2 - // // SAV OLEd LCD module support using either SSD1306 or SH1106 based LCD modules // diff --git a/Marlin/example_configurations/TinyBoy2/Configuration_adv.h b/Marlin/example_configurations/TinyBoy2/Configuration_adv.h index 87a74abd6..f590111ee 100644 --- a/Marlin/example_configurations/TinyBoy2/Configuration_adv.h +++ b/Marlin/example_configurations/TinyBoy2/Configuration_adv.h @@ -284,7 +284,7 @@ #if ENABLED(Z_DUAL_ENDSTOPS) #define Z2_USE_ENDSTOP _XMAX_ - #define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // use M666 command to determine/test this value + #define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // Use M666 to determine/test this value #endif #endif // Z_DUAL_STEPPER_DRIVERS @@ -394,7 +394,7 @@ // Minimum planner junction speed. Sets the default minimum speed the planner plans for at the end // of the buffer and all stops. This should not be much greater than zero and should only be changed // if unwanted behavior is observed on a user's machine when running at very slow speeds. -#define MINIMUM_PLANNER_SPEED 0.05// (mm/sec) +#define MINIMUM_PLANNER_SPEED 0.05 // (mm/sec) // Microstep setting (Only functional when stepper driver microstep pins are connected to MCU. #define MICROSTEP_MODES {16,16,16,16,16} // [1,2,4,8,16] @@ -648,7 +648,7 @@ * * Set to 0 to auto-detect the ratio based on given Gcode G1 print moves. * - * Slic3r (including Průša Slic3r) produces Gcode compatible with the automatic mode. + * Slic3r (including Průša Control) produces Gcode compatible with the automatic mode. * Cura (as of this writing) may produce Gcode incompatible with the automatic mode. */ #define LIN_ADVANCE_E_D_RATIO 0 // The calculated ratio (or 0) according to the formula W * H / ((D / 2) ^ 2 * PI) @@ -670,6 +670,10 @@ #define UBL_MESH_MAX_X (X_MAX_POS - (UBL_MESH_INSET)) #define UBL_MESH_MIN_Y (Y_MIN_POS + UBL_MESH_INSET) #define UBL_MESH_MAX_Y (Y_MAX_POS - (UBL_MESH_INSET)) + + // If this is defined, the currently active mesh will be saved in the + // current slot on M500. + #define UBL_SAVE_ACTIVE_ON_M500 #endif // @section extras @@ -1286,6 +1290,7 @@ //=========================================================================== //====================== I2C Position Encoder Settings ====================== //=========================================================================== + /** * I2C position encoders for closed loop control. * Developed by Chris Barr at Aus3D. diff --git a/Marlin/example_configurations/Velleman/K8200/Configuration.h b/Marlin/example_configurations/Velleman/K8200/Configuration.h index f61b4ae4e..959713d3d 100644 --- a/Marlin/example_configurations/Velleman/K8200/Configuration.h +++ b/Marlin/example_configurations/Velleman/K8200/Configuration.h @@ -181,7 +181,10 @@ //#define SWITCHING_EXTRUDER #if ENABLED(SWITCHING_EXTRUDER) #define SWITCHING_EXTRUDER_SERVO_NR 0 - #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 + #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1[, E2, E3] + #if EXTRUDERS > 3 + #define SWITCHING_EXTRUDER_E23_SERVO_NR 1 + #endif #endif // A dual-nozzle that uses a servomotor to raise/lower one of the nozzles @@ -1489,11 +1492,6 @@ // //#define U8GLIB_SSD1306 -// -// TinyBoy2 128x64 OLED / Encoder Panel -// -//#define OLED_PANEL_TINYBOY2 - // // SAV OLEd LCD module support using either SSD1306 or SH1106 based LCD modules // diff --git a/Marlin/example_configurations/Velleman/K8200/Configuration_adv.h b/Marlin/example_configurations/Velleman/K8200/Configuration_adv.h index 203e03bb2..94f87feed 100644 --- a/Marlin/example_configurations/Velleman/K8200/Configuration_adv.h +++ b/Marlin/example_configurations/Velleman/K8200/Configuration_adv.h @@ -93,8 +93,8 @@ * Thermal Protection parameters for the bed are just as above for hotends. */ #if ENABLED(THERMAL_PROTECTION_BED) -// 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 + // 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 @@ -297,7 +297,7 @@ #if ENABLED(Z_DUAL_ENDSTOPS) #define Z2_USE_ENDSTOP _XMAX_ - #define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // use M666 command to determine this value + #define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // Use M666 to determine/test this value #endif #endif // Z_DUAL_STEPPER_DRIVERS @@ -407,7 +407,7 @@ // Minimum planner junction speed. Sets the default minimum speed the planner plans for at the end // of the buffer and all stops. This should not be much greater than zero and should only be changed // if unwanted behavior is observed on a user's machine when running at very slow speeds. -#define MINIMUM_PLANNER_SPEED 0.05// (mm/sec) +#define MINIMUM_PLANNER_SPEED 0.05 // (mm/sec) // Microstep setting (Only functional when stepper driver microstep pins are connected to MCU. #define MICROSTEP_MODES {16,16,16,16,16} // [1,2,4,8,16] @@ -465,6 +465,9 @@ // On the Info Screen, display XY with one decimal place when possible //#define LCD_DECIMAL_SMALL_XY +// The timeout (in ms) to return to the status screen from sub-menus +//#define LCD_TIMEOUT_TO_STATUS 15000 + #if ENABLED(SDSUPPORT) // Some RAMPS and other boards don't detect when an SD card is inserted. You can work @@ -658,7 +661,7 @@ * * Set to 0 to auto-detect the ratio based on given Gcode G1 print moves. * - * Slic3r (including Průša Slic3r) produces Gcode compatible with the automatic mode. + * Slic3r (including Průša Control) produces Gcode compatible with the automatic mode. * Cura (as of this writing) may produce Gcode incompatible with the automatic mode. */ #define LIN_ADVANCE_E_D_RATIO 0 // The calculated ratio (or 0) according to the formula W * H / ((D / 2) ^ 2 * PI) @@ -680,6 +683,10 @@ #define UBL_MESH_MAX_X (X_MAX_POS - (UBL_MESH_INSET)) #define UBL_MESH_MIN_Y (Y_MIN_POS + UBL_MESH_INSET) #define UBL_MESH_MAX_Y (Y_MAX_POS - (UBL_MESH_INSET)) + + // If this is defined, the currently active mesh will be saved in the + // current slot on M500. + #define UBL_SAVE_ACTIVE_ON_M500 #endif // @section extras @@ -1296,6 +1303,7 @@ //=========================================================================== //====================== I2C Position Encoder Settings ====================== //=========================================================================== + /** * I2C position encoders for closed loop control. * Developed by Chris Barr at Aus3D. diff --git a/Marlin/example_configurations/Velleman/K8400/Configuration.h b/Marlin/example_configurations/Velleman/K8400/Configuration.h index 0b2c70c8b..48ed7f53f 100644 --- a/Marlin/example_configurations/Velleman/K8400/Configuration.h +++ b/Marlin/example_configurations/Velleman/K8400/Configuration.h @@ -161,7 +161,10 @@ //#define SWITCHING_EXTRUDER #if ENABLED(SWITCHING_EXTRUDER) #define SWITCHING_EXTRUDER_SERVO_NR 0 - #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 + #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1[, E2, E3] + #if EXTRUDERS > 3 + #define SWITCHING_EXTRUDER_E23_SERVO_NR 1 + #endif #endif // A dual-nozzle that uses a servomotor to raise/lower one of the nozzles @@ -1457,11 +1460,6 @@ // //#define U8GLIB_SSD1306 -// -// TinyBoy2 128x64 OLED / Encoder Panel -// -//#define OLED_PANEL_TINYBOY2 - // // SAV OLEd LCD module support using either SSD1306 or SH1106 based LCD modules // @@ -1479,6 +1477,11 @@ // //#define SAV_3DLCD +// +// TinyBoy2 128x64 OLED / Encoder Panel +// +//#define OLED_PANEL_TINYBOY2 + //============================================================================= //=============================== Extra Features ============================== //============================================================================= diff --git a/Marlin/example_configurations/Velleman/K8400/Configuration_adv.h b/Marlin/example_configurations/Velleman/K8400/Configuration_adv.h index c94748d02..d910ab8ea 100644 --- a/Marlin/example_configurations/Velleman/K8400/Configuration_adv.h +++ b/Marlin/example_configurations/Velleman/K8400/Configuration_adv.h @@ -284,7 +284,7 @@ #if ENABLED(Z_DUAL_ENDSTOPS) #define Z2_USE_ENDSTOP _XMAX_ - #define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // use M666 command to determine this value + #define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // Use M666 to determine/test this value #endif #endif // Z_DUAL_STEPPER_DRIVERS @@ -394,7 +394,7 @@ // Minimum planner junction speed. Sets the default minimum speed the planner plans for at the end // of the buffer and all stops. This should not be much greater than zero and should only be changed // if unwanted behavior is observed on a user's machine when running at very slow speeds. -#define MINIMUM_PLANNER_SPEED 0.05// (mm/sec) +#define MINIMUM_PLANNER_SPEED 0.05 // (mm/sec) // Microstep setting (Only functional when stepper driver microstep pins are connected to MCU. #define MICROSTEP_MODES {16,16,16,16,16} // [1,2,4,8,16] @@ -452,6 +452,9 @@ // On the Info Screen, display XY with one decimal place when possible //#define LCD_DECIMAL_SMALL_XY +// The timeout (in ms) to return to the status screen from sub-menus +//#define LCD_TIMEOUT_TO_STATUS 15000 + #if ENABLED(SDSUPPORT) // Some RAMPS and other boards don't detect when an SD card is inserted. You can work @@ -645,7 +648,7 @@ * * Set to 0 to auto-detect the ratio based on given Gcode G1 print moves. * - * Slic3r (including Průša Slic3r) produces Gcode compatible with the automatic mode. + * Slic3r (including Průša Control) produces Gcode compatible with the automatic mode. * Cura (as of this writing) may produce Gcode incompatible with the automatic mode. */ #define LIN_ADVANCE_E_D_RATIO 0 // The calculated ratio (or 0) according to the formula W * H / ((D / 2) ^ 2 * PI) @@ -667,6 +670,10 @@ #define UBL_MESH_MAX_X (X_MAX_POS - (UBL_MESH_INSET)) #define UBL_MESH_MIN_Y (Y_MIN_POS + UBL_MESH_INSET) #define UBL_MESH_MAX_Y (Y_MAX_POS - (UBL_MESH_INSET)) + + // If this is defined, the currently active mesh will be saved in the + // current slot on M500. + #define UBL_SAVE_ACTIVE_ON_M500 #endif // @section extras @@ -1283,6 +1290,7 @@ //=========================================================================== //====================== I2C Position Encoder Settings ====================== //=========================================================================== + /** * I2C position encoders for closed loop control. * Developed by Chris Barr at Aus3D. diff --git a/Marlin/example_configurations/Velleman/K8400/Dual-head/Configuration.h b/Marlin/example_configurations/Velleman/K8400/Dual-head/Configuration.h index 0f63c5c29..1c24b7217 100644 --- a/Marlin/example_configurations/Velleman/K8400/Dual-head/Configuration.h +++ b/Marlin/example_configurations/Velleman/K8400/Dual-head/Configuration.h @@ -161,7 +161,10 @@ //#define SWITCHING_EXTRUDER #if ENABLED(SWITCHING_EXTRUDER) #define SWITCHING_EXTRUDER_SERVO_NR 0 - #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 + #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1[, E2, E3] + #if EXTRUDERS > 3 + #define SWITCHING_EXTRUDER_E23_SERVO_NR 1 + #endif #endif // A dual-nozzle that uses a servomotor to raise/lower one of the nozzles @@ -1457,11 +1460,6 @@ // //#define U8GLIB_SSD1306 -// -// TinyBoy2 128x64 OLED / Encoder Panel -// -//#define OLED_PANEL_TINYBOY2 - // // SAV OLEd LCD module support using either SSD1306 or SH1106 based LCD modules // @@ -1479,6 +1477,11 @@ // //#define SAV_3DLCD +// +// TinyBoy2 128x64 OLED / Encoder Panel +// +//#define OLED_PANEL_TINYBOY2 + //============================================================================= //=============================== Extra Features ============================== //============================================================================= diff --git a/Marlin/example_configurations/adafruit/ST7565/Configuration.h b/Marlin/example_configurations/adafruit/ST7565/Configuration.h index c4cb9ca08..4c99ee2f1 100644 --- a/Marlin/example_configurations/adafruit/ST7565/Configuration.h +++ b/Marlin/example_configurations/adafruit/ST7565/Configuration.h @@ -161,7 +161,10 @@ //#define SWITCHING_EXTRUDER #if ENABLED(SWITCHING_EXTRUDER) #define SWITCHING_EXTRUDER_SERVO_NR 0 - #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 + #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1[, E2, E3] + #if EXTRUDERS > 3 + #define SWITCHING_EXTRUDER_E23_SERVO_NR 1 + #endif #endif // A dual-nozzle that uses a servomotor to raise/lower one of the nozzles @@ -603,7 +606,7 @@ * A Fix-Mounted Probe either doesn't deploy or needs manual deployment. * (e.g., an inductive probe or a nozzle-based probe-switch.) */ - //#define FIX_MOUNTED_PROBE +//#define FIX_MOUNTED_PROBE /** * Z Servo Probe, such as an endstop switch on a rotating arm. @@ -1457,11 +1460,6 @@ // //#define U8GLIB_SSD1306 -// -// TinyBoy2 128x64 OLED / Encoder Panel -// -//#define OLED_PANEL_TINYBOY2 - // // SAV OLEd LCD module support using either SSD1306 or SH1106 based LCD modules // @@ -1479,6 +1477,11 @@ // //#define SAV_3DLCD +// +// TinyBoy2 128x64 OLED / Encoder Panel +// +//#define OLED_PANEL_TINYBOY2 + //============================================================================= //=============================== Extra Features ============================== //============================================================================= diff --git a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h index 7d1dc6df6..643d2e2ee 100644 --- a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h +++ b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h @@ -161,7 +161,10 @@ //#define SWITCHING_EXTRUDER #if ENABLED(SWITCHING_EXTRUDER) #define SWITCHING_EXTRUDER_SERVO_NR 0 - #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 + #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1[, E2, E3] + #if EXTRUDERS > 3 + #define SWITCHING_EXTRUDER_E23_SERVO_NR 1 + #endif #endif // A dual-nozzle that uses a servomotor to raise/lower one of the nozzles @@ -851,7 +854,7 @@ #define INVERT_Y_DIR true #define INVERT_Z_DIR true -// Enable this option for Toshiba steppers drivers +// Enable this option for Toshiba stepper drivers //#define CONFIG_STEPPERS_TOSHIBA // @section extruder @@ -974,6 +977,7 @@ #if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR) // Set the number of grid points per dimension. + // Works best with 5 or more points in each dimension. #define GRID_MAX_POINTS_X 7 #define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X @@ -1096,8 +1100,8 @@ //#define Z_SAFE_HOMING #if ENABLED(Z_SAFE_HOMING) - #define Z_SAFE_HOMING_X_POINT ((X_MIN_POS + X_MAX_POS) / 2) // X point for Z homing when homing all axis (G28). - #define Z_SAFE_HOMING_Y_POINT ((Y_MIN_POS + Y_MAX_POS) / 2) // Y point for Z homing when homing all axis (G28). + #define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axis (G28). + #define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axis (G28). #endif // Delta only homes to Z @@ -1584,11 +1588,6 @@ // //#define U8GLIB_SSD1306 -// -// TinyBoy2 128x64 OLED / Encoder Panel -// -//#define OLED_PANEL_TINYBOY2 - // // SAV OLEd LCD module support using either SSD1306 or SH1106 based LCD modules // @@ -1606,6 +1605,11 @@ // //#define SAV_3DLCD +// +// TinyBoy2 128x64 OLED / Encoder Panel +// +//#define OLED_PANEL_TINYBOY2 + //============================================================================= //=============================== Extra Features ============================== //============================================================================= diff --git a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h index 003fd19b4..9f2bba659 100644 --- a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h +++ b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h @@ -284,7 +284,7 @@ #if ENABLED(Z_DUAL_ENDSTOPS) #define Z2_USE_ENDSTOP _XMAX_ - #define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // use M666 command to determine/test this value + #define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // Use M666 to determine/test this value #endif #endif // Z_DUAL_STEPPER_DRIVERS @@ -396,7 +396,7 @@ // Minimum planner junction speed. Sets the default minimum speed the planner plans for at the end // of the buffer and all stops. This should not be much greater than zero and should only be changed // if unwanted behavior is observed on a user's machine when running at very slow speeds. -#define MINIMUM_PLANNER_SPEED 0.05// (mm/sec) +#define MINIMUM_PLANNER_SPEED 0.05 // (mm/sec) // Microstep setting (Only functional when stepper driver microstep pins are connected to MCU. #define MICROSTEP_MODES {16,16,16,16,16} // [1,2,4,8,16] @@ -650,7 +650,7 @@ * * Set to 0 to auto-detect the ratio based on given Gcode G1 print moves. * - * Slic3r (including Průša Slic3r) produces Gcode compatible with the automatic mode. + * Slic3r (including Průša Control) produces Gcode compatible with the automatic mode. * Cura (as of this writing) may produce Gcode incompatible with the automatic mode. */ #define LIN_ADVANCE_E_D_RATIO 0 // The calculated ratio (or 0) according to the formula W * H / ((D / 2) ^ 2 * PI) @@ -672,6 +672,10 @@ #define UBL_MESH_MAX_X (X_MAX_POS - (UBL_MESH_INSET)) #define UBL_MESH_MIN_Y (Y_MIN_POS + UBL_MESH_INSET) #define UBL_MESH_MAX_Y (Y_MAX_POS - (UBL_MESH_INSET)) + + // If this is defined, the currently active mesh will be saved in the + // current slot on M500. + #define UBL_SAVE_ACTIVE_ON_M500 #endif // @section extras @@ -1288,6 +1292,7 @@ //=========================================================================== //====================== I2C Position Encoder Settings ====================== //=========================================================================== + /** * I2C position encoders for closed loop control. * Developed by Chris Barr at Aus3D. diff --git a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h index f4b14be19..82de18e31 100644 --- a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h +++ b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h @@ -161,7 +161,10 @@ //#define SWITCHING_EXTRUDER #if ENABLED(SWITCHING_EXTRUDER) #define SWITCHING_EXTRUDER_SERVO_NR 0 - #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 + #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1[, E2, E3] + #if EXTRUDERS > 3 + #define SWITCHING_EXTRUDER_E23_SERVO_NR 1 + #endif #endif // A dual-nozzle that uses a servomotor to raise/lower one of the nozzles @@ -1578,11 +1581,6 @@ // //#define U8GLIB_SSD1306 -// -// TinyBoy2 128x64 OLED / Encoder Panel -// -//#define OLED_PANEL_TINYBOY2 - // // SAV OLEd LCD module support using either SSD1306 or SH1106 based LCD modules // @@ -1600,6 +1598,11 @@ // //#define SAV_3DLCD +// +// TinyBoy2 128x64 OLED / Encoder Panel +// +//#define OLED_PANEL_TINYBOY2 + //============================================================================= //=============================== Extra Features ============================== //============================================================================= diff --git a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h index 577d7427c..fdc226633 100644 --- a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h +++ b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h @@ -284,7 +284,7 @@ #if ENABLED(Z_DUAL_ENDSTOPS) #define Z2_USE_ENDSTOP _XMAX_ - #define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // use M666 command to determine this value + #define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // Use M666 to determine/test this value #endif #endif // Z_DUAL_STEPPER_DRIVERS @@ -337,7 +337,7 @@ //homing hits the endstop, then retracts by this distance, before it tries to slowly bump again: #define X_HOME_BUMP_MM 5 #define Y_HOME_BUMP_MM 5 -#define Z_HOME_BUMP_MM 5 // deltas need the same for all three axis +#define Z_HOME_BUMP_MM 5 // deltas need the same for all three axes #define HOMING_BUMP_DIVISOR {10, 10, 10} // Re-Bump Speed Divisor (Divides the Homing Feedrate) //#define QUICK_HOME //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially. @@ -396,7 +396,7 @@ // Minimum planner junction speed. Sets the default minimum speed the planner plans for at the end // of the buffer and all stops. This should not be much greater than zero and should only be changed // if unwanted behavior is observed on a user's machine when running at very slow speeds. -#define MINIMUM_PLANNER_SPEED 0.05// (mm/sec) +#define MINIMUM_PLANNER_SPEED 0.05 // (mm/sec) // Microstep setting (Only functional when stepper driver microstep pins are connected to MCU. #define MICROSTEP_MODES {16,16,16,16,16} // [1,2,4,8,16] @@ -650,7 +650,7 @@ * * Set to 0 to auto-detect the ratio based on given Gcode G1 print moves. * - * Slic3r (including Průša Slic3r) produces Gcode compatible with the automatic mode. + * Slic3r (including Průša Control) produces Gcode compatible with the automatic mode. * Cura (as of this writing) may produce Gcode incompatible with the automatic mode. */ #define LIN_ADVANCE_E_D_RATIO 0 // The calculated ratio (or 0) according to the formula W * H / ((D / 2) ^ 2 * PI) @@ -672,6 +672,10 @@ #define UBL_MESH_MAX_X (X_MAX_POS - (UBL_MESH_INSET)) #define UBL_MESH_MIN_Y (Y_MIN_POS + UBL_MESH_INSET) #define UBL_MESH_MAX_Y (Y_MAX_POS - (UBL_MESH_INSET)) + + // If this is defined, the currently active mesh will be saved in the + // current slot on M500. + #define UBL_SAVE_ACTIVE_ON_M500 #endif // @section extras @@ -691,6 +695,7 @@ //#define BEZIER_CURVE_SUPPORT // G38.2 and G38.3 Probe Target +// Enable PROBE_DOUBLE_TOUCH if you want G38 to double touch //#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) @@ -1287,6 +1292,7 @@ //=========================================================================== //====================== I2C Position Encoder Settings ====================== //=========================================================================== + /** * I2C position encoders for closed loop control. * Developed by Chris Barr at Aus3D. diff --git a/Marlin/example_configurations/delta/generic/Configuration.h b/Marlin/example_configurations/delta/generic/Configuration.h index d079bf45b..ce2b8ceec 100644 --- a/Marlin/example_configurations/delta/generic/Configuration.h +++ b/Marlin/example_configurations/delta/generic/Configuration.h @@ -161,7 +161,10 @@ //#define SWITCHING_EXTRUDER #if ENABLED(SWITCHING_EXTRUDER) #define SWITCHING_EXTRUDER_SERVO_NR 0 - #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 + #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1[, E2, E3] + #if EXTRUDERS > 3 + #define SWITCHING_EXTRUDER_E23_SERVO_NR 1 + #endif #endif // A dual-nozzle that uses a servomotor to raise/lower one of the nozzles @@ -981,6 +984,11 @@ //#define PROBE_Y_FIRST #if ENABLED(AUTO_BED_LEVELING_BILINEAR) + + // Beyond the probed grid, continue the implied tilt? + // Default is to maintain the height of the nearest edge. + //#define EXTRAPOLATE_BEYOND_GRID + // // Experimental Subdivision of the grid by Catmull-Rom method. // Synthesizes intermediate points to produce a more detailed mesh. @@ -1081,8 +1089,8 @@ //#define Z_SAFE_HOMING #if ENABLED(Z_SAFE_HOMING) - #define Z_SAFE_HOMING_X_POINT ((X_MIN_POS + X_MAX_POS) / 2) // X point for Z homing when homing all axis (G28). - #define Z_SAFE_HOMING_Y_POINT ((Y_MIN_POS + Y_MAX_POS) / 2) // Y point for Z homing when homing all axis (G28). + #define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axis (G28). + #define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axis (G28). #endif // Delta only homes to Z @@ -1568,11 +1576,6 @@ // //#define U8GLIB_SSD1306 -// -// TinyBoy2 128x64 OLED / Encoder Panel -// -//#define OLED_PANEL_TINYBOY2 - // // SAV OLEd LCD module support using either SSD1306 or SH1106 based LCD modules // @@ -1590,6 +1593,11 @@ // //#define SAV_3DLCD +// +// TinyBoy2 128x64 OLED / Encoder Panel +// +//#define OLED_PANEL_TINYBOY2 + //============================================================================= //=============================== Extra Features ============================== //============================================================================= diff --git a/Marlin/example_configurations/delta/generic/Configuration_adv.h b/Marlin/example_configurations/delta/generic/Configuration_adv.h index 392e3a972..fdc226633 100644 --- a/Marlin/example_configurations/delta/generic/Configuration_adv.h +++ b/Marlin/example_configurations/delta/generic/Configuration_adv.h @@ -284,7 +284,7 @@ #if ENABLED(Z_DUAL_ENDSTOPS) #define Z2_USE_ENDSTOP _XMAX_ - #define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // use M666 command to determine this value + #define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // Use M666 to determine/test this value #endif #endif // Z_DUAL_STEPPER_DRIVERS @@ -337,7 +337,7 @@ //homing hits the endstop, then retracts by this distance, before it tries to slowly bump again: #define X_HOME_BUMP_MM 5 #define Y_HOME_BUMP_MM 5 -#define Z_HOME_BUMP_MM 5 // deltas need the same for all three axis +#define Z_HOME_BUMP_MM 5 // deltas need the same for all three axes #define HOMING_BUMP_DIVISOR {10, 10, 10} // Re-Bump Speed Divisor (Divides the Homing Feedrate) //#define QUICK_HOME //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially. @@ -396,7 +396,7 @@ // Minimum planner junction speed. Sets the default minimum speed the planner plans for at the end // of the buffer and all stops. This should not be much greater than zero and should only be changed // if unwanted behavior is observed on a user's machine when running at very slow speeds. -#define MINIMUM_PLANNER_SPEED 0.05// (mm/sec) +#define MINIMUM_PLANNER_SPEED 0.05 // (mm/sec) // Microstep setting (Only functional when stepper driver microstep pins are connected to MCU. #define MICROSTEP_MODES {16,16,16,16,16} // [1,2,4,8,16] @@ -454,6 +454,9 @@ // On the Info Screen, display XY with one decimal place when possible //#define LCD_DECIMAL_SMALL_XY +// The timeout (in ms) to return to the status screen from sub-menus +//#define LCD_TIMEOUT_TO_STATUS 15000 + #if ENABLED(SDSUPPORT) // Some RAMPS and other boards don't detect when an SD card is inserted. You can work @@ -647,7 +650,7 @@ * * Set to 0 to auto-detect the ratio based on given Gcode G1 print moves. * - * Slic3r (including Průša Slic3r) produces Gcode compatible with the automatic mode. + * Slic3r (including Průša Control) produces Gcode compatible with the automatic mode. * Cura (as of this writing) may produce Gcode incompatible with the automatic mode. */ #define LIN_ADVANCE_E_D_RATIO 0 // The calculated ratio (or 0) according to the formula W * H / ((D / 2) ^ 2 * PI) @@ -669,6 +672,10 @@ #define UBL_MESH_MAX_X (X_MAX_POS - (UBL_MESH_INSET)) #define UBL_MESH_MIN_Y (Y_MIN_POS + UBL_MESH_INSET) #define UBL_MESH_MAX_Y (Y_MAX_POS - (UBL_MESH_INSET)) + + // If this is defined, the currently active mesh will be saved in the + // current slot on M500. + #define UBL_SAVE_ACTIVE_ON_M500 #endif // @section extras @@ -1285,6 +1292,7 @@ //=========================================================================== //====================== I2C Position Encoder Settings ====================== //=========================================================================== + /** * I2C position encoders for closed loop control. * Developed by Chris Barr at Aus3D. diff --git a/Marlin/example_configurations/delta/kossel_mini/Configuration.h b/Marlin/example_configurations/delta/kossel_mini/Configuration.h index 13b7787a6..75c03f697 100644 --- a/Marlin/example_configurations/delta/kossel_mini/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_mini/Configuration.h @@ -161,7 +161,10 @@ //#define SWITCHING_EXTRUDER #if ENABLED(SWITCHING_EXTRUDER) #define SWITCHING_EXTRUDER_SERVO_NR 0 - #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 + #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1[, E2, E3] + #if EXTRUDERS > 3 + #define SWITCHING_EXTRUDER_E23_SERVO_NR 1 + #endif #endif // A dual-nozzle that uses a servomotor to raise/lower one of the nozzles @@ -512,7 +515,7 @@ // extra connectors. Leave undefined any used for non-endstop and non-probe purposes. //#define USE_XMIN_PLUG //#define USE_YMIN_PLUG -#define USE_ZMIN_PLUG +#define USE_ZMIN_PLUG // a Z probe #define USE_XMAX_PLUG #define USE_YMAX_PLUG #define USE_ZMAX_PLUG @@ -656,7 +659,6 @@ * Activate one of these to use Auto Bed Leveling below. */ - /** * The "Manual Probe" provides a means to do "Auto" Bed Leveling without a probe. * Use G29 repeatedly, adjusting the Z height at each point with movement commands @@ -664,6 +666,12 @@ */ //#define PROBE_MANUALLY +/** + * A Fix-Mounted Probe either doesn't deploy or needs manual deployment. + * (e.g., an inductive probe or a nozzle-based probe-switch.) + */ +//#define FIX_MOUNTED_PROBE + /** * Z Servo Probe, such as an endstop switch on a rotating arm. */ @@ -1084,8 +1092,8 @@ //#define Z_SAFE_HOMING #if ENABLED(Z_SAFE_HOMING) - #define Z_SAFE_HOMING_X_POINT ((X_MIN_POS + X_MAX_POS) / 2) // X point for Z homing when homing all axis (G28). - #define Z_SAFE_HOMING_Y_POINT ((Y_MIN_POS + Y_MAX_POS) / 2) // Y point for Z homing when homing all axis (G28). + #define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axis (G28). + #define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axis (G28). #endif // Delta only homes to Z @@ -1571,11 +1579,6 @@ // //#define U8GLIB_SSD1306 -// -// TinyBoy2 128x64 OLED / Encoder Panel -// -//#define OLED_PANEL_TINYBOY2 - // // SAV OLEd LCD module support using either SSD1306 or SH1106 based LCD modules // @@ -1593,6 +1596,11 @@ // //#define SAV_3DLCD +// +// TinyBoy2 128x64 OLED / Encoder Panel +// +//#define OLED_PANEL_TINYBOY2 + //============================================================================= //=============================== Extra Features ============================== //============================================================================= diff --git a/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h index 392e3a972..fdc226633 100644 --- a/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h @@ -284,7 +284,7 @@ #if ENABLED(Z_DUAL_ENDSTOPS) #define Z2_USE_ENDSTOP _XMAX_ - #define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // use M666 command to determine this value + #define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // Use M666 to determine/test this value #endif #endif // Z_DUAL_STEPPER_DRIVERS @@ -337,7 +337,7 @@ //homing hits the endstop, then retracts by this distance, before it tries to slowly bump again: #define X_HOME_BUMP_MM 5 #define Y_HOME_BUMP_MM 5 -#define Z_HOME_BUMP_MM 5 // deltas need the same for all three axis +#define Z_HOME_BUMP_MM 5 // deltas need the same for all three axes #define HOMING_BUMP_DIVISOR {10, 10, 10} // Re-Bump Speed Divisor (Divides the Homing Feedrate) //#define QUICK_HOME //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially. @@ -396,7 +396,7 @@ // Minimum planner junction speed. Sets the default minimum speed the planner plans for at the end // of the buffer and all stops. This should not be much greater than zero and should only be changed // if unwanted behavior is observed on a user's machine when running at very slow speeds. -#define MINIMUM_PLANNER_SPEED 0.05// (mm/sec) +#define MINIMUM_PLANNER_SPEED 0.05 // (mm/sec) // Microstep setting (Only functional when stepper driver microstep pins are connected to MCU. #define MICROSTEP_MODES {16,16,16,16,16} // [1,2,4,8,16] @@ -454,6 +454,9 @@ // On the Info Screen, display XY with one decimal place when possible //#define LCD_DECIMAL_SMALL_XY +// The timeout (in ms) to return to the status screen from sub-menus +//#define LCD_TIMEOUT_TO_STATUS 15000 + #if ENABLED(SDSUPPORT) // Some RAMPS and other boards don't detect when an SD card is inserted. You can work @@ -647,7 +650,7 @@ * * Set to 0 to auto-detect the ratio based on given Gcode G1 print moves. * - * Slic3r (including Průša Slic3r) produces Gcode compatible with the automatic mode. + * Slic3r (including Průša Control) produces Gcode compatible with the automatic mode. * Cura (as of this writing) may produce Gcode incompatible with the automatic mode. */ #define LIN_ADVANCE_E_D_RATIO 0 // The calculated ratio (or 0) according to the formula W * H / ((D / 2) ^ 2 * PI) @@ -669,6 +672,10 @@ #define UBL_MESH_MAX_X (X_MAX_POS - (UBL_MESH_INSET)) #define UBL_MESH_MIN_Y (Y_MIN_POS + UBL_MESH_INSET) #define UBL_MESH_MAX_Y (Y_MAX_POS - (UBL_MESH_INSET)) + + // If this is defined, the currently active mesh will be saved in the + // current slot on M500. + #define UBL_SAVE_ACTIVE_ON_M500 #endif // @section extras @@ -1285,6 +1292,7 @@ //=========================================================================== //====================== I2C Position Encoder Settings ====================== //=========================================================================== + /** * I2C position encoders for closed loop control. * Developed by Chris Barr at Aus3D. diff --git a/Marlin/example_configurations/delta/kossel_pro/Configuration.h b/Marlin/example_configurations/delta/kossel_pro/Configuration.h index 9418ce8b7..259c923d0 100644 --- a/Marlin/example_configurations/delta/kossel_pro/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_pro/Configuration.h @@ -165,7 +165,10 @@ //#define SWITCHING_EXTRUDER #if ENABLED(SWITCHING_EXTRUDER) #define SWITCHING_EXTRUDER_SERVO_NR 0 - #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 + #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1[, E2, E3] + #if EXTRUDERS > 3 + #define SWITCHING_EXTRUDER_E23_SERVO_NR 1 + #endif #endif // A dual-nozzle that uses a servomotor to raise/lower one of the nozzles @@ -1089,8 +1092,8 @@ #define Z_SAFE_HOMING #if ENABLED(Z_SAFE_HOMING) - #define Z_SAFE_HOMING_X_POINT ((X_MIN_POS + X_MAX_POS) / 2) // X point for Z homing when homing all axis (G28). - #define Z_SAFE_HOMING_Y_POINT ((Y_MIN_POS + Y_MAX_POS) / 2) // Y point for Z homing when homing all axis (G28). + #define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axis (G28). + #define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axis (G28). #endif // Delta only homes to Z @@ -1576,11 +1579,6 @@ // //#define U8GLIB_SSD1306 -// -// TinyBoy2 128x64 OLED / Encoder Panel -// -//#define OLED_PANEL_TINYBOY2 - // // SAV OLEd LCD module support using either SSD1306 or SH1106 based LCD modules // @@ -1598,6 +1596,11 @@ // //#define SAV_3DLCD +// +// TinyBoy2 128x64 OLED / Encoder Panel +// +//#define OLED_PANEL_TINYBOY2 + //============================================================================= //=============================== Extra Features ============================== //============================================================================= diff --git a/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h index 39c18ba43..c01524728 100644 --- a/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h @@ -289,7 +289,7 @@ #if ENABLED(Z_DUAL_ENDSTOPS) #define Z2_USE_ENDSTOP _XMAX_ - #define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // use M666 command to determine this value + #define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // Use M666 to determine/test this value #endif #endif // Z_DUAL_STEPPER_DRIVERS @@ -342,7 +342,7 @@ //homing hits the endstop, then retracts by this distance, before it tries to slowly bump again: #define X_HOME_BUMP_MM 5 #define Y_HOME_BUMP_MM 5 -#define Z_HOME_BUMP_MM 5 // deltas need the same for all three axis +#define Z_HOME_BUMP_MM 5 // deltas need the same for all three axes #define HOMING_BUMP_DIVISOR {10, 10, 10} // Re-Bump Speed Divisor (Divides the Homing Feedrate) //#define QUICK_HOME //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially. @@ -401,7 +401,7 @@ // Minimum planner junction speed. Sets the default minimum speed the planner plans for at the end // of the buffer and all stops. This should not be much greater than zero and should only be changed // if unwanted behavior is observed on a user's machine when running at very slow speeds. -#define MINIMUM_PLANNER_SPEED 0.05// (mm/sec) +#define MINIMUM_PLANNER_SPEED 0.05 // (mm/sec) // Microstep setting (Only functional when stepper driver microstep pins are connected to MCU. #define MICROSTEP_MODES {16,16,16,16,16} // [1,2,4,8,16] @@ -459,6 +459,9 @@ // On the Info Screen, display XY with one decimal place when possible //#define LCD_DECIMAL_SMALL_XY +// The timeout (in ms) to return to the status screen from sub-menus +//#define LCD_TIMEOUT_TO_STATUS 15000 + #if ENABLED(SDSUPPORT) // Some RAMPS and other boards don't detect when an SD card is inserted. You can work @@ -652,7 +655,7 @@ * * Set to 0 to auto-detect the ratio based on given Gcode G1 print moves. * - * Slic3r (including Průša Slic3r) produces Gcode compatible with the automatic mode. + * Slic3r (including Průša Control) produces Gcode compatible with the automatic mode. * Cura (as of this writing) may produce Gcode incompatible with the automatic mode. */ #define LIN_ADVANCE_E_D_RATIO 0 // The calculated ratio (or 0) according to the formula W * H / ((D / 2) ^ 2 * PI) @@ -674,6 +677,10 @@ #define UBL_MESH_MAX_X (X_MAX_POS - (UBL_MESH_INSET)) #define UBL_MESH_MIN_Y (Y_MIN_POS + UBL_MESH_INSET) #define UBL_MESH_MAX_Y (Y_MAX_POS - (UBL_MESH_INSET)) + + // If this is defined, the currently active mesh will be saved in the + // current slot on M500. + #define UBL_SAVE_ACTIVE_ON_M500 #endif // @section extras @@ -1290,6 +1297,7 @@ //=========================================================================== //====================== I2C Position Encoder Settings ====================== //=========================================================================== + /** * I2C position encoders for closed loop control. * Developed by Chris Barr at Aus3D. diff --git a/Marlin/example_configurations/delta/kossel_xl/Configuration.h b/Marlin/example_configurations/delta/kossel_xl/Configuration.h index 469eef478..4231be068 100644 --- a/Marlin/example_configurations/delta/kossel_xl/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_xl/Configuration.h @@ -161,7 +161,10 @@ //#define SWITCHING_EXTRUDER #if ENABLED(SWITCHING_EXTRUDER) #define SWITCHING_EXTRUDER_SERVO_NR 0 - #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 + #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1[, E2, E3] + #if EXTRUDERS > 3 + #define SWITCHING_EXTRUDER_E23_SERVO_NR 1 + #endif #endif // A dual-nozzle that uses a servomotor to raise/lower one of the nozzles @@ -799,60 +802,6 @@ #endif // Z_PROBE_ALLEN_KEY -/** - * *** PLEASE READ ALL INSTRUCTIONS BELOW FOR SAFETY! *** - * - * - RAMPS 1.3/1.4 boards may be able to use the 5V, GND, and Aux4->D32 pin. - * - Use 5V for powered (usu. inductive) sensors. - * - Otherwise connect: - * - normally-closed switches to GND and D32. - * - normally-open switches to 5V and D32. - * - * Normally-closed switches are advised and are the default. - * - * - * PIN OPTIONS\SETUP FOR Z PROBES - * - * - * WARNING: - * Setting the wrong pin may have unexpected and potentially disastrous consequences. - * Use with caution and do your homework. - * - * - * All Z PROBE pin options are configured by defining (or not defining) - * the following five items: - * Z_MIN_PROBE_ENDSTOP – defined below - * Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN – defined below - * Z_MIN_PIN - defined in the pins_YOUR_BOARD.h file - * Z_MIN_PROBE_PIN - defined in the pins_YOUR_BOARD.h file - * - * If you're using a probe then you need to tell Marlin which pin to use as - * the Z MIN ENDSTOP. Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN determines if the - * Z_MIN_PIN or if the Z_MIN_PROBE_PIN is used. - * - * The pin selected for the probe is ONLY checked during probing operations. - * If you want to use the Z_MIN_PIN as an endstop AND you want to have a Z PROBE - * then you’ll need to use the Z_MIN_PROBE_PIN option. - * - * Z_MIN_PROBE_ENDSTOP also needs to be enabled if you want to use Z_MIN_PROBE_PIN. - * - * The settings needed to use the Z_MIN_PROBE_PIN are: - * 1. select the type of probe you're using - * 2. define Z_MIN_PROBE_PIN in your pins_YOUR_BOARD.h file - * 3. disable Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN - * 4. enable Z_MIN_PROBE_ENDSTOP - * NOTE – if Z_MIN_PIN is defined then it’ll be checked during all moves in the - * negative Z direction. - * - * The settings needed to use the Z_MIN_PIN are: - * 1. select the type of probe you're using - * 2. enable Z_MIN _PIN in your pins_YOUR_BOARD.h file - * 3. enable Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN - * 4. disable Z_MIN_PROBE_ENDSTOP - * NOTES – if Z_MIN_PROBE_PIN is defined in the pins_YOUR_BOARD.h file then it’ll be - * ignored by Marlin - */ - /** * Z probes require clearance when deploying, stowing, and moving between * probe points to avoid hitting the bed and other hardware. @@ -1047,6 +996,11 @@ //#define PROBE_Y_FIRST #if ENABLED(AUTO_BED_LEVELING_BILINEAR) + + // Beyond the probed grid, continue the implied tilt? + // Default is to maintain the height of the nearest edge. + //#define EXTRAPOLATE_BEYOND_GRID + // // Experimental Subdivision of the grid by Catmull-Rom method. // Synthesizes intermediate points to produce a more detailed mesh. @@ -1147,8 +1101,8 @@ //#define Z_SAFE_HOMING #if ENABLED(Z_SAFE_HOMING) - #define Z_SAFE_HOMING_X_POINT ((X_MIN_POS + X_MAX_POS) / 2) // X point for Z homing when homing all axis (G28). - #define Z_SAFE_HOMING_Y_POINT ((Y_MIN_POS + Y_MAX_POS) / 2) // Y point for Z homing when homing all axis (G28). + #define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axis (G28). + #define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axis (G28). #endif // Delta only homes to Z @@ -1634,11 +1588,6 @@ // //#define U8GLIB_SSD1306 -// -// TinyBoy2 128x64 OLED / Encoder Panel -// -//#define OLED_PANEL_TINYBOY2 - // // SAV OLEd LCD module support using either SSD1306 or SH1106 based LCD modules // @@ -1656,6 +1605,11 @@ // //#define SAV_3DLCD +// +// TinyBoy2 128x64 OLED / Encoder Panel +// +//#define OLED_PANEL_TINYBOY2 + //============================================================================= //=============================== Extra Features ============================== //============================================================================= diff --git a/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h index 3ec32bc63..a41212a88 100644 --- a/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h @@ -284,7 +284,7 @@ #if ENABLED(Z_DUAL_ENDSTOPS) #define Z2_USE_ENDSTOP _XMAX_ - #define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // use M666 command to determine this value + #define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // Use M666 to determine/test this value #endif #endif // Z_DUAL_STEPPER_DRIVERS @@ -337,7 +337,7 @@ //homing hits the endstop, then retracts by this distance, before it tries to slowly bump again: #define X_HOME_BUMP_MM 2 #define Y_HOME_BUMP_MM 2 -#define Z_HOME_BUMP_MM 2 // deltas need the same for all three axis +#define Z_HOME_BUMP_MM 2 // deltas need the same for all three axes #define HOMING_BUMP_DIVISOR {2, 2, 4} // Re-Bump Speed Divisor (Divides the Homing Feedrate) //#define QUICK_HOME //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially. @@ -396,7 +396,7 @@ // Minimum planner junction speed. Sets the default minimum speed the planner plans for at the end // of the buffer and all stops. This should not be much greater than zero and should only be changed // if unwanted behavior is observed on a user's machine when running at very slow speeds. -#define MINIMUM_PLANNER_SPEED 0.05// (mm/sec) +#define MINIMUM_PLANNER_SPEED 0.05 // (mm/sec) // Microstep setting (Only functional when stepper driver microstep pins are connected to MCU. #define MICROSTEP_MODES {16,16,16,16,16} // [1,2,4,8,16] @@ -454,6 +454,9 @@ // On the Info Screen, display XY with one decimal place when possible //#define LCD_DECIMAL_SMALL_XY +// The timeout (in ms) to return to the status screen from sub-menus +//#define LCD_TIMEOUT_TO_STATUS 15000 + #if ENABLED(SDSUPPORT) // Some RAMPS and other boards don't detect when an SD card is inserted. You can work @@ -647,7 +650,7 @@ * * Set to 0 to auto-detect the ratio based on given Gcode G1 print moves. * - * Slic3r (including Průša Slic3r) produces Gcode compatible with the automatic mode. + * Slic3r (including Průša Control) produces Gcode compatible with the automatic mode. * Cura (as of this writing) may produce Gcode incompatible with the automatic mode. */ #define LIN_ADVANCE_E_D_RATIO 0 // The calculated ratio (or 0) according to the formula W * H / ((D / 2) ^ 2 * PI) @@ -669,6 +672,10 @@ #define UBL_MESH_MAX_X (X_MAX_POS - (UBL_MESH_INSET)) #define UBL_MESH_MIN_Y (Y_MIN_POS + UBL_MESH_INSET) #define UBL_MESH_MAX_Y (Y_MAX_POS - (UBL_MESH_INSET)) + + // If this is defined, the currently active mesh will be saved in the + // current slot on M500. + #define UBL_SAVE_ACTIVE_ON_M500 #endif // @section extras @@ -1285,6 +1292,7 @@ //=========================================================================== //====================== I2C Position Encoder Settings ====================== //=========================================================================== + /** * I2C position encoders for closed loop control. * Developed by Chris Barr at Aus3D. diff --git a/Marlin/example_configurations/gCreate/gMax1.5+/Configuration.h b/Marlin/example_configurations/gCreate/gMax1.5+/Configuration.h index f25e8b3b9..a870e8da8 100644 --- a/Marlin/example_configurations/gCreate/gMax1.5+/Configuration.h +++ b/Marlin/example_configurations/gCreate/gMax1.5+/Configuration.h @@ -128,7 +128,7 @@ // Optional custom name for your RepStrap or other custom machine // Displayed in the LCD "Ready" message -#define CUSTOM_MACHINE_NAME "UBL v1.0 " +#define CUSTOM_MACHINE_NAME "gMax" // 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) @@ -166,7 +166,10 @@ //#define SWITCHING_EXTRUDER #if ENABLED(SWITCHING_EXTRUDER) #define SWITCHING_EXTRUDER_SERVO_NR 0 - #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 + #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1[, E2, E3] + #if EXTRUDERS > 3 + #define SWITCHING_EXTRUDER_E23_SERVO_NR 1 + #endif #endif // A dual-nozzle that uses a servomotor to raise/lower one of the nozzles @@ -570,7 +573,6 @@ // See http://marlinfw.org/configuration/probes.html // - /** * Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN * @@ -578,7 +580,6 @@ */ #define Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN - /** * Z_MIN_PROBE_ENDSTOP * @@ -985,8 +986,8 @@ #define Z_SAFE_HOMING #if ENABLED(Z_SAFE_HOMING) - #define Z_SAFE_HOMING_X_POINT (((X_MIN_POS + X_MAX_POS) / 2) - 4) // X point for Z homing when homing all axis (G28). - #define Z_SAFE_HOMING_Y_POINT (((Y_MIN_POS + Y_MAX_POS) / 2) + 4) // Y point for Z homing when homing all axis (G28). + #define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2 - 4) // X point for Z homing when homing all axis (G28). + #define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2 + 4) // Y point for Z homing when homing all axis (G28). #endif // Homing speeds (mm/m) @@ -1473,11 +1474,6 @@ // //#define U8GLIB_SSD1306 -// -// TinyBoy2 128x64 OLED / Encoder Panel -// -//#define OLED_PANEL_TINYBOY2 - // // SAV OLEd LCD module support using either SSD1306 or SH1106 based LCD modules // @@ -1495,6 +1491,11 @@ // //#define SAV_3DLCD +// +// TinyBoy2 128x64 OLED / Encoder Panel +// +//#define OLED_PANEL_TINYBOY2 + //============================================================================= //=============================== Extra Features ============================== //============================================================================= diff --git a/Marlin/example_configurations/gCreate/gMax1.5+/Configuration_adv.h b/Marlin/example_configurations/gCreate/gMax1.5+/Configuration_adv.h index 50c8560e4..f32a9354d 100644 --- a/Marlin/example_configurations/gCreate/gMax1.5+/Configuration_adv.h +++ b/Marlin/example_configurations/gCreate/gMax1.5+/Configuration_adv.h @@ -284,7 +284,7 @@ #if ENABLED(Z_DUAL_ENDSTOPS) #define Z2_USE_ENDSTOP _XMAX_ - #define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // use M666 command to determine/test this value + #define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // Use M666 to determine/test this value #endif #endif // Z_DUAL_STEPPER_DRIVERS @@ -394,7 +394,7 @@ // Minimum planner junction speed. Sets the default minimum speed the planner plans for at the end // of the buffer and all stops. This should not be much greater than zero and should only be changed // if unwanted behavior is observed on a user's machine when running at very slow speeds. -#define MINIMUM_PLANNER_SPEED 0.05// (mm/sec) +#define MINIMUM_PLANNER_SPEED 0.05 // (mm/sec) // Microstep setting (Only functional when stepper driver microstep pins are connected to MCU. #define MICROSTEP_MODES {16,16,16,16,16} // [1,2,4,8,16] @@ -648,7 +648,7 @@ * * Set to 0 to auto-detect the ratio based on given Gcode G1 print moves. * - * Slic3r (including Průša Slic3r) produces Gcode compatible with the automatic mode. + * Slic3r (including Průša Control) produces Gcode compatible with the automatic mode. * Cura (as of this writing) may produce Gcode incompatible with the automatic mode. */ #define LIN_ADVANCE_E_D_RATIO 0 // The calculated ratio (or 0) according to the formula W * H / ((D / 2) ^ 2 * PI) @@ -795,7 +795,6 @@ * Requires an LCD display. * This feature is required for the default FILAMENT_RUNOUT_SCRIPT. */ - #define ADVANCED_PAUSE_FEATURE #if ENABLED(ADVANCED_PAUSE_FEATURE) #define PAUSE_PARK_X_POS 75 // X position of hotend @@ -805,7 +804,6 @@ #define PAUSE_PARK_Z_FEEDRATE 5 // Z axis feedrate in mm/s (not used for delta printers) #define PAUSE_PARK_RETRACT_FEEDRATE 60 // Initial retract feedrate in mm/s #define PAUSE_PARK_RETRACT_LENGTH 2 // Initial retract in mm - // It is a short retract used immediately after print interrupt before move to filament exchange position #define FILAMENT_CHANGE_UNLOAD_FEEDRATE 10 // Unload filament feedrate in mm/s - filament unloading can be fast #define FILAMENT_CHANGE_UNLOAD_LENGTH 100 // Unload filament length from hotend in mm @@ -1292,6 +1290,7 @@ //=========================================================================== //====================== I2C Position Encoder Settings ====================== //=========================================================================== + /** * I2C position encoders for closed loop control. * Developed by Chris Barr at Aus3D. diff --git a/Marlin/example_configurations/makibox/Configuration.h b/Marlin/example_configurations/makibox/Configuration.h index 144b6fc8b..02f33df03 100644 --- a/Marlin/example_configurations/makibox/Configuration.h +++ b/Marlin/example_configurations/makibox/Configuration.h @@ -161,7 +161,10 @@ //#define SWITCHING_EXTRUDER #if ENABLED(SWITCHING_EXTRUDER) #define SWITCHING_EXTRUDER_SERVO_NR 0 - #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 + #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1[, E2, E3] + #if EXTRUDERS > 3 + #define SWITCHING_EXTRUDER_E23_SERVO_NR 1 + #endif #endif // A dual-nozzle that uses a servomotor to raise/lower one of the nozzles @@ -370,9 +373,9 @@ // setting this to anything other than 255 enables a form of PWM to the bed just like HEATER_BED_DUTY_CYCLE_DIVIDER did, // so you shouldn't use it unless you are OK with PWM on your bed. (see the comment on enabling PIDTEMPBED) #define MAX_BED_POWER 175 // limits duty cycle to bed; 255=full current -// This limit is set to 175 by default in the Makibox configuration and it can adjusted -// to increase the heat up rate. However, if changed, user must be aware of the safety concerns -// of drawing too much current from the power supply. +// This limit is set to 175 by default in the Makibox configuration and it can be adjusted +// to increase the heatup rate. However, if changed, be aware of the safety concerns of +// drawing too much current from the power supply. #if ENABLED(PIDTEMPBED) @@ -1460,11 +1463,6 @@ // //#define U8GLIB_SSD1306 -// -// TinyBoy2 128x64 OLED / Encoder Panel -// -//#define OLED_PANEL_TINYBOY2 - // // SAV OLEd LCD module support using either SSD1306 or SH1106 based LCD modules // @@ -1482,6 +1480,11 @@ // //#define SAV_3DLCD +// +// TinyBoy2 128x64 OLED / Encoder Panel +// +//#define OLED_PANEL_TINYBOY2 + //============================================================================= //=============================== Extra Features ============================== //============================================================================= diff --git a/Marlin/example_configurations/makibox/Configuration_adv.h b/Marlin/example_configurations/makibox/Configuration_adv.h index 6e0dc15a2..8a568f2f8 100644 --- a/Marlin/example_configurations/makibox/Configuration_adv.h +++ b/Marlin/example_configurations/makibox/Configuration_adv.h @@ -284,7 +284,7 @@ #if ENABLED(Z_DUAL_ENDSTOPS) #define Z2_USE_ENDSTOP _XMAX_ - #define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // use M666 command to determine this value + #define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // Use M666 to determine/test this value #endif #endif // Z_DUAL_STEPPER_DRIVERS @@ -394,7 +394,7 @@ // Minimum planner junction speed. Sets the default minimum speed the planner plans for at the end // of the buffer and all stops. This should not be much greater than zero and should only be changed // if unwanted behavior is observed on a user's machine when running at very slow speeds. -#define MINIMUM_PLANNER_SPEED 0.05// (mm/sec) +#define MINIMUM_PLANNER_SPEED 0.05 // (mm/sec) // Microstep setting (Only functional when stepper driver microstep pins are connected to MCU. #define MICROSTEP_MODES {16,16,16,16,16} // [1,2,4,8,16] @@ -452,6 +452,9 @@ // On the Info Screen, display XY with one decimal place when possible //#define LCD_DECIMAL_SMALL_XY +// The timeout (in ms) to return to the status screen from sub-menus +//#define LCD_TIMEOUT_TO_STATUS 15000 + #if ENABLED(SDSUPPORT) // Some RAMPS and other boards don't detect when an SD card is inserted. You can work @@ -645,7 +648,7 @@ * * Set to 0 to auto-detect the ratio based on given Gcode G1 print moves. * - * Slic3r (including Průša Slic3r) produces Gcode compatible with the automatic mode. + * Slic3r (including Průša Control) produces Gcode compatible with the automatic mode. * Cura (as of this writing) may produce Gcode incompatible with the automatic mode. */ #define LIN_ADVANCE_E_D_RATIO 0 // The calculated ratio (or 0) according to the formula W * H / ((D / 2) ^ 2 * PI) @@ -667,6 +670,10 @@ #define UBL_MESH_MAX_X (X_MAX_POS - (UBL_MESH_INSET)) #define UBL_MESH_MIN_Y (Y_MIN_POS + UBL_MESH_INSET) #define UBL_MESH_MAX_Y (Y_MAX_POS - (UBL_MESH_INSET)) + + // If this is defined, the currently active mesh will be saved in the + // current slot on M500. + #define UBL_SAVE_ACTIVE_ON_M500 #endif // @section extras @@ -1283,6 +1290,7 @@ //=========================================================================== //====================== I2C Position Encoder Settings ====================== //=========================================================================== + /** * I2C position encoders for closed loop control. * Developed by Chris Barr at Aus3D. diff --git a/Marlin/example_configurations/tvrrug/Round2/Configuration.h b/Marlin/example_configurations/tvrrug/Round2/Configuration.h index 462b33d1e..8212beb07 100644 --- a/Marlin/example_configurations/tvrrug/Round2/Configuration.h +++ b/Marlin/example_configurations/tvrrug/Round2/Configuration.h @@ -161,7 +161,10 @@ //#define SWITCHING_EXTRUDER #if ENABLED(SWITCHING_EXTRUDER) #define SWITCHING_EXTRUDER_SERVO_NR 0 - #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 + #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1[, E2, E3] + #if EXTRUDERS > 3 + #define SWITCHING_EXTRUDER_E23_SERVO_NR 1 + #endif #endif // A dual-nozzle that uses a servomotor to raise/lower one of the nozzles @@ -1452,11 +1455,6 @@ // //#define U8GLIB_SSD1306 -// -// TinyBoy2 128x64 OLED / Encoder Panel -// -//#define OLED_PANEL_TINYBOY2 - // // SAV OLEd LCD module support using either SSD1306 or SH1106 based LCD modules // @@ -1474,6 +1472,11 @@ // //#define SAV_3DLCD +// +// TinyBoy2 128x64 OLED / Encoder Panel +// +//#define OLED_PANEL_TINYBOY2 + //============================================================================= //=============================== Extra Features ============================== //============================================================================= diff --git a/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h b/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h index 32c920c24..0f75b95c7 100644 --- a/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h +++ b/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h @@ -284,7 +284,7 @@ #if ENABLED(Z_DUAL_ENDSTOPS) #define Z2_USE_ENDSTOP _XMAX_ - #define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // use M666 command to determine this value + #define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // Use M666 to determine/test this value #endif #endif // Z_DUAL_STEPPER_DRIVERS @@ -394,7 +394,7 @@ // Minimum planner junction speed. Sets the default minimum speed the planner plans for at the end // of the buffer and all stops. This should not be much greater than zero and should only be changed // if unwanted behavior is observed on a user's machine when running at very slow speeds. -#define MINIMUM_PLANNER_SPEED 0.05// (mm/sec) +#define MINIMUM_PLANNER_SPEED 0.05 // (mm/sec) // Microstep setting (Only functional when stepper driver microstep pins are connected to MCU. #define MICROSTEP_MODES {16,16,16,16,16} // [1,2,4,8,16] @@ -452,6 +452,9 @@ // On the Info Screen, display XY with one decimal place when possible //#define LCD_DECIMAL_SMALL_XY +// The timeout (in ms) to return to the status screen from sub-menus +//#define LCD_TIMEOUT_TO_STATUS 15000 + #if ENABLED(SDSUPPORT) // Some RAMPS and other boards don't detect when an SD card is inserted. You can work @@ -645,7 +648,7 @@ * * Set to 0 to auto-detect the ratio based on given Gcode G1 print moves. * - * Slic3r (including Průša Slic3r) produces Gcode compatible with the automatic mode. + * Slic3r (including Průša Control) produces Gcode compatible with the automatic mode. * Cura (as of this writing) may produce Gcode incompatible with the automatic mode. */ #define LIN_ADVANCE_E_D_RATIO 0 // The calculated ratio (or 0) according to the formula W * H / ((D / 2) ^ 2 * PI) @@ -667,6 +670,10 @@ #define UBL_MESH_MAX_X (X_MAX_POS - (UBL_MESH_INSET)) #define UBL_MESH_MIN_Y (Y_MIN_POS + UBL_MESH_INSET) #define UBL_MESH_MAX_Y (Y_MAX_POS - (UBL_MESH_INSET)) + + // If this is defined, the currently active mesh will be saved in the + // current slot on M500. + #define UBL_SAVE_ACTIVE_ON_M500 #endif // @section extras @@ -1283,6 +1290,7 @@ //=========================================================================== //====================== I2C Position Encoder Settings ====================== //=========================================================================== + /** * I2C position encoders for closed loop control. * Developed by Chris Barr at Aus3D. diff --git a/Marlin/example_configurations/wt150/Configuration.h b/Marlin/example_configurations/wt150/Configuration.h index d3242e1fb..2c468a942 100644 --- a/Marlin/example_configurations/wt150/Configuration.h +++ b/Marlin/example_configurations/wt150/Configuration.h @@ -161,7 +161,10 @@ //#define SWITCHING_EXTRUDER #if ENABLED(SWITCHING_EXTRUDER) #define SWITCHING_EXTRUDER_SERVO_NR 0 - #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 + #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1[, E2, E3] + #if EXTRUDERS > 3 + #define SWITCHING_EXTRUDER_E23_SERVO_NR 1 + #endif #endif // A dual-nozzle that uses a servomotor to raise/lower one of the nozzles @@ -553,7 +556,6 @@ #define DEFAULT_ZJERK 0.4 #define DEFAULT_EJERK 5.0 - //=========================================================================== //============================= Z Probe Options ============================= //=========================================================================== @@ -1463,11 +1465,6 @@ // //#define U8GLIB_SSD1306 -// -// TinyBoy2 128x64 OLED / Encoder Panel -// -//#define OLED_PANEL_TINYBOY2 - // // SAV OLEd LCD module support using either SSD1306 or SH1106 based LCD modules // @@ -1485,6 +1482,11 @@ // //#define SAV_3DLCD +// +// TinyBoy2 128x64 OLED / Encoder Panel +// +//#define OLED_PANEL_TINYBOY2 + //============================================================================= //=============================== Extra Features ============================== //============================================================================= diff --git a/Marlin/example_configurations/wt150/Configuration_adv.h b/Marlin/example_configurations/wt150/Configuration_adv.h index a146b0998..3501c7157 100644 --- a/Marlin/example_configurations/wt150/Configuration_adv.h +++ b/Marlin/example_configurations/wt150/Configuration_adv.h @@ -284,7 +284,7 @@ #if ENABLED(Z_DUAL_ENDSTOPS) #define Z2_USE_ENDSTOP _XMAX_ - #define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // use M666 command to determine/test this value + #define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // Use M666 to determine/test this value #endif #endif // Z_DUAL_STEPPER_DRIVERS @@ -394,7 +394,7 @@ // Minimum planner junction speed. Sets the default minimum speed the planner plans for at the end // of the buffer and all stops. This should not be much greater than zero and should only be changed // if unwanted behavior is observed on a user's machine when running at very slow speeds. -#define MINIMUM_PLANNER_SPEED 0.05// (mm/sec) +#define MINIMUM_PLANNER_SPEED 0.05 // (mm/sec) // Microstep setting (Only functional when stepper driver microstep pins are connected to MCU. #define MICROSTEP_MODES {16,16,16,16,16} // [1,2,4,8,16] @@ -648,7 +648,7 @@ * * Set to 0 to auto-detect the ratio based on given Gcode G1 print moves. * - * Slic3r (including Průša Slic3r) produces Gcode compatible with the automatic mode. + * Slic3r (including Průša Control) produces Gcode compatible with the automatic mode. * Cura (as of this writing) may produce Gcode incompatible with the automatic mode. */ #define LIN_ADVANCE_E_D_RATIO 0 // The calculated ratio (or 0) according to the formula W * H / ((D / 2) ^ 2 * PI) @@ -1280,89 +1280,6 @@ #define USER_GCODE_5 "G28\nM503" #endif -//=========================================================================== -//============================ I2C Encoder Settings ========================= -//=========================================================================== -/** - * I2C position encoders for closed loop control. - * Developed by Chris Barr at Aus3D. - * - * Wiki: http://wiki.aus3d.com.au/Magnetic_Encoder - * Github: https://github.com/Aus3D/MagneticEncoder - * - * Supplier: http://aus3d.com.au/magnetic-encoder-module - * Alternative Supplier: http://reliabuild3d.com/ - * - * Reilabuild encoders have been modified to improve reliability. - */ - -//#define I2C_POSITION_ENCODERS -#if ENABLED(I2C_POSITION_ENCODERS) - - #define I2CPE_ENCODER_CNT 1 // The number of encoders installed; max of 5 - // encoders supported currently. - - #define I2CPE_ENC_1_ADDR I2CPE_PRESET_ADDR_X // I2C address of the encoder. 30-200. - #define I2CPE_ENC_1_AXIS X_AXIS // Axis the encoder module is installed on. _AXIS. - #define I2CPE_ENC_1_TYPE I2CPE_ENC_TYPE_LINEAR // Type of encoder: I2CPE_ENC_TYPE_LINEAR -or- - // I2CPE_ENC_TYPE_ROTARY. - #define I2CPE_ENC_1_TICKS_UNIT 2048 // 1024 for magnetic strips with 2mm poles; 2048 for - // 1mm poles. For linear encoders this is ticks / mm, - // for rotary encoders this is ticks / revolution. - //#define I2CPE_ENC_1_TICKS_REV (16 * 200) // Only needed for rotary encoders; number of stepper - // steps per full revolution (motor steps/rev * microstepping) - //#define I2CPE_ENC_1_INVERT // Invert the direction of axis travel. - #define I2CPE_ENC_1_EC_METHOD I2CPE_ECM_NONE // Type of error error correction. - #define I2CPE_ENC_1_EC_THRESH 0.10 // Threshold size for error (in mm) above which the - // printer will attempt to correct the error; errors - // smaller than this are ignored to minimize effects of - // measurement noise / latency (filter). - - #define I2CPE_ENC_2_ADDR I2CPE_PRESET_ADDR_Y // Same as above, but for encoder 2. - #define I2CPE_ENC_2_AXIS Y_AXIS - #define I2CPE_ENC_2_TYPE I2CPE_ENC_TYPE_LINEAR - #define I2CPE_ENC_2_TICKS_UNIT 2048 - //#define I2CPE_ENC_2_TICKS_REV (16 * 200) - //#define I2CPE_ENC_2_INVERT - #define I2CPE_ENC_2_EC_METHOD I2CPE_ECM_NONE - #define I2CPE_ENC_2_EC_THRESH 0.10 - - #define I2CPE_ENC_3_ADDR I2CPE_PRESET_ADDR_Z // Encoder 3. Add additional configuration options - #define I2CPE_ENC_3_AXIS Z_AXIS // as above, or use defaults below. - - #define I2CPE_ENC_4_ADDR I2CPE_PRESET_ADDR_E // Encoder 4. - #define I2CPE_ENC_4_AXIS E_AXIS - - #define I2CPE_ENC_5_ADDR 34 // Encoder 5. - #define I2CPE_ENC_5_AXIS E_AXIS - - // Default settings for encoders which are enabled, but without settings configured above. - #define I2CPE_DEF_TYPE I2CPE_ENC_TYPE_LINEAR - #define I2CPE_DEF_ENC_TICKS_UNIT 2048 - #define I2CPE_DEF_TICKS_REV (16 * 200) - #define I2CPE_DEF_EC_METHOD I2CPE_ECM_NONE - #define I2CPE_DEF_EC_THRESH 0.1 - - //#define I2CPE_ERR_THRESH_ABORT 100.0 // Threshold size for error (in mm) error on any given - // axis after which the printer will abort. Comment out to - // disable abort behaviour. - - #define I2CPE_TIME_TRUSTED 10000 // After an encoder fault, there must be no further fault - // for this amount of time (in ms) before the encoder - // is trusted again. - - /** - * Position is checked every time a new command is executed from the buffer but during long moves, - * this setting determines the minimum update time between checks. A value of 100 works well with - * error rolling average when attempting to correct only for skips and not for vibration. - */ - #define I2CPE_MIN_UPD_TIME_MS 100 // Minimum time in miliseconds between encoder checks. - - // Use a rolling average to identify persistant errors that indicate skips, as opposed to vibration and noise. - #define I2CPE_ERR_ROLLING_AVERAGE - -#endif - /** * Specify an action command to send to the host when the printer is killed. * Will be sent in the form '//action:ACTION_ON_KILL', e.g. '//action:poweroff'. @@ -1373,6 +1290,7 @@ //=========================================================================== //====================== I2C Position Encoder Settings ====================== //=========================================================================== + /** * I2C position encoders for closed loop control. * Developed by Chris Barr at Aus3D. From b370906031a52d69993129903414577e999efdc9 Mon Sep 17 00:00:00 2001 From: richarddeweerd Date: Wed, 2 Aug 2017 15:25:51 +0200 Subject: [PATCH 066/112] Example config for Geeetech I3 Pro X with GT2560 controller --- .../Geeetech/I3_Pro_X-GT2560/Configuration.h | 1642 +++++++++++++++++ 1 file changed, 1642 insertions(+) create mode 100644 Marlin/example_configurations/Geeetech/I3_Pro_X-GT2560/Configuration.h diff --git a/Marlin/example_configurations/Geeetech/I3_Pro_X-GT2560/Configuration.h b/Marlin/example_configurations/Geeetech/I3_Pro_X-GT2560/Configuration.h new file mode 100644 index 000000000..d2cdbd18b --- /dev/null +++ b/Marlin/example_configurations/Geeetech/I3_Pro_X-GT2560/Configuration.h @@ -0,0 +1,1642 @@ +/** + * 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 . + * + */ + +/** + * Configuration.h + * + * Basic settings such as: + * + * - Type of electronics + * - Type of temperature sensor + * - Printer geometry + * - Endstop configuration + * - LCD controller + * - Extra features + * + * Advanced settings can be found in Configuration_adv.h + * + */ +#ifndef CONFIGURATION_H +#define CONFIGURATION_H +#define CONFIGURATION_H_VERSION 010100 + +//=========================================================================== +//============================= Getting Started ============================= +//=========================================================================== + +/** + * Here are some standard links for getting your machine calibrated: + * + * http://reprap.org/wiki/Calibration + * http://youtu.be/wAL9d7FgInk + * http://calculator.josefprusa.cz + * http://reprap.org/wiki/Triffid_Hunter%27s_Calibration_Guide + * http://www.thingiverse.com/thing:5573 + * https://sites.google.com/site/repraplogphase/calibration-of-your-reprap + * http://www.thingiverse.com/thing:298812 + */ + +//=========================================================================== +//============================= DELTA Printer =============================== +//=========================================================================== +// For a Delta printer start with one of the configuration files in the +// example_configurations/delta directory and customize for your machine. +// + +//=========================================================================== +//============================= SCARA Printer =============================== +//=========================================================================== +// For a SCARA printer start with the configuration files in +// example_configurations/SCARA and customize for your machine. +// + +// @section info + +// User-specified version info of this build to display in [Pronterface, etc] terminal window during +// startup. Implementation of an idea by Prof Braino to inform user that any changes made to this +// build by the user have been successfully uploaded into firmware. +#define STRING_CONFIG_H_AUTHOR "(R. de Weerd, I3 Pro X)" // Who made the changes. +#define SHOW_BOOTSCREEN +#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 ***************************************************** +// +// Marlin now allow you to have a vendor boot image to be displayed on machine +// start. When SHOW_CUSTOM_BOOTSCREEN is defined Marlin will first show your +// custom boot image and then the default Marlin boot image is shown. +// +// We suggest for you to take advantage of this new feature and keep the Marlin +// boot image unmodified. For an example have a look at the bq Hephestos 2 +// example configuration folder. +// +//#define SHOW_CUSTOM_BOOTSCREEN +// @section machine + +/** + * 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 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 +//#define BLUETOOTH + +// The following define selects which electronics board you have. +// Please choose the name from boards.h that matches your setup +#ifndef MOTHERBOARD + #define MOTHERBOARD BOARD_ULTIMAKER +#endif + +// Optional custom name for your RepStrap or other custom machine +// Displayed in the LCD "Ready" message +#define CUSTOM_MACHINE_NAME "RdW i3 Pro X" + +// 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 "00000000-0000-0000-0000-000000000000" + +// @section extruder + +// This defines the number of extruders +// :[1, 2, 3, 4, 5] +#define EXTRUDERS 1 + +// For Cyclops or any "multi-extruder" that shares a single nozzle. +//#define SINGLENOZZLE + +/** + * Průša MK2 Single Nozzle Multi-Material Multiplexer, and variants. + * + * This device allows one stepper driver on a control board to drive + * two to eight stepper motors, one at a time, in a manner suitable + * for extruders. + * + * This option only allows the multiplexer to switch on tool-change. + * Additional options to configure custom E moves are pending. + */ +//#define MK2_MULTIPLEXER +#if ENABLED(MK2_MULTIPLEXER) + // Override the default DIO selector pins here, if needed. + // Some pins files may provide defaults for these pins. + //#define E_MUX0_PIN 40 // Always Required + //#define E_MUX1_PIN 42 // Needed for 3 to 8 steppers + //#define E_MUX2_PIN 44 // Needed for 5 to 8 steppers +#endif + +// A dual extruder that uses a single stepper motor +//#define SWITCHING_EXTRUDER +#if ENABLED(SWITCHING_EXTRUDER) + #define SWITCHING_EXTRUDER_SERVO_NR 0 + #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1[, E2, E3] + #if EXTRUDERS > 3 + #define SWITCHING_EXTRUDER_E23_SERVO_NR 1 + #endif +#endif + +// A dual-nozzle that uses a servomotor to raise/lower one of the nozzles +//#define SWITCHING_NOZZLE +#if ENABLED(SWITCHING_NOZZLE) + #define SWITCHING_NOZZLE_SERVO_NR 0 + #define SWITCHING_NOZZLE_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 + //#define HOTEND_OFFSET_Z { 0.0, 0.0 } +#endif + +/** + * "Mixing Extruder" + * - Adds a new code, M165, to set the current mix factors. + * - Extends the stepping routines to move multiple steppers in proportion to the mix. + * - Optional support for Repetier Firmware M163, M164, and virtual extruder. + * - This implementation supports only a single extruder. + * - Enable DIRECT_MIXING_IN_G1 for Pia Taubert's reference implementation + */ +//#define MIXING_EXTRUDER +#if ENABLED(MIXING_EXTRUDER) + #define MIXING_STEPPERS 2 // Number of steppers in your mixing extruder + #define MIXING_VIRTUAL_TOOLS 16 // Use the Virtual Tool method with M163 and M164 + //#define DIRECT_MIXING_IN_G1 // Allow ABCDHI mix factors in G1 movement commands +#endif + +// Offset of the extruders (uncomment if using more than one and relying on firmware to position when changing). +// The offset has to be X=0, Y=0 for the extruder 0 hotend (default extruder). +// For the other hotends it is their distance from the extruder 0 hotend. +//#define 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 + +// @section machine + +/** + * 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 + +#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 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 + * 75 : 100k Generic Silicon Heat Pad with NTC 100K MGB18-104F39050L32 thermistor + * + * 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_4 0 +#define TEMP_SENSOR_BED 1 + +// 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 + +// Extruder temperature must be close to target for this long before M109 returns success +#define TEMP_RESIDENCY_TIME 10 // (seconds) +#define TEMP_HYSTERESIS 3 // (degC) range of +/- temperatures considered "close" to the target one +#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 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. + +// The minimal temperature defines the temperature below which the heater will not be enabled It is used +// to check that the wiring to the thermistor is not broken. +// Otherwise this would lead to the heater being powered on all the time. +#define HEATER_0_MINTEMP 5 +#define HEATER_1_MINTEMP 5 +#define HEATER_2_MINTEMP 5 +#define HEATER_3_MINTEMP 5 +#define HEATER_4_MINTEMP 5 +#define BED_MINTEMP 5 + +// When temperature exceeds max temp, your heater will be switched off. +// This feature exists to protect your hotend from overheating accidentally, but *NOT* from thermistor short/failure! +// You should use MINTEMP for thermistor short/failure protection. +#define HEATER_0_MAXTEMP 275 +#define HEATER_1_MAXTEMP 275 +#define HEATER_2_MAXTEMP 275 +#define HEATER_3_MAXTEMP 275 +#define HEATER_4_MAXTEMP 275 +#define BED_MAXTEMP 150 + +//=========================================================================== +//============================= PID Settings ================================ +//=========================================================================== +// PID Tuning Guide here: http://reprap.org/wiki/PID_Tuning + +// Comment the following line to disable PID and enable bang-bang. +#define PIDTEMP +#define BANG_MAX 255 // limits current to nozzle while in bang-bang mode; 255=full current +#define PID_MAX BANG_MAX // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current +#if ENABLED(PIDTEMP) + //#define PID_AUTOTUNE_MENU // Add PID Autotune to the LCD "Temperature" menu to run M303 and apply the result. + //#define PID_DEBUG // Sends debug data to the serial port. + //#define PID_OPENLOOP 1 // Puts PID in open loop. M104/M140 sets the output power from 0 to PID_MAX + //#define SLOW_PWM_HEATERS // PWM with very low frequency (roughly 0.125Hz=8s) and minimum state time of approximately 1s useful for heaters driven by a relay + //#define PID_PARAMS_PER_HOTEND // Uses separate PID parameters for each extruder (useful for mismatched extruders) + // 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 K1 0.95 //smoothing factor within the PID + + // If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it + + // Ultimaker + #define DEFAULT_Kp 22.2 + #define DEFAULT_Ki 1.08 + #define DEFAULT_Kd 114 + + // MakerGear + //#define DEFAULT_Kp 7.0 + //#define DEFAULT_Ki 0.1 + //#define DEFAULT_Kd 12 + + // Mendel Parts V9 on 12V + //#define DEFAULT_Kp 63.0 + //#define DEFAULT_Ki 2.25 + //#define DEFAULT_Kd 440 + +#endif // PIDTEMP + +//=========================================================================== +//============================= PID > Bed Temperature Control =============== +//=========================================================================== +// Select PID or bang-bang with PIDTEMPBED. If bang-bang, BED_LIMIT_SWITCHING will enable hysteresis +// +// Uncomment this to enable PID on the bed. It uses the same frequency PWM as the extruder. +// If your PID_dT is the default, and correct for your hardware/configuration, that means 7.689Hz, +// which is fine for driving a square wave into a resistive load and does not significantly impact you FET heating. +// This also works fine on a Fotek SSR-10DA Solid State Relay into a 250W heater. +// If your configuration is significantly different than this and you don't understand the issues involved, you probably +// shouldn't use bed PID until someone else verifies your hardware works. +// If this is enabled, find your own PID constants below. +//#define PIDTEMPBED + +//#define BED_LIMIT_SWITCHING + +// This sets the max power delivered to the bed, and replaces the HEATER_BED_DUTY_CYCLE_DIVIDER option. +// all forms of bed control obey this (PID, bang-bang, bang-bang with hysteresis) +// setting this to anything other than 255 enables a form of PWM to the bed just like HEATER_BED_DUTY_CYCLE_DIVIDER did, +// so you shouldn't use it unless you are OK with PWM on your bed. (see the comment on enabling PIDTEMPBED) +#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current + +#if ENABLED(PIDTEMPBED) + + //#define PID_BED_DEBUG // Sends debug data to the serial port. + + //120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+) + //from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10) + #define DEFAULT_bedKp 10.00 + #define DEFAULT_bedKi .023 + #define DEFAULT_bedKd 305.4 + + //120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+) + //from pidautotune + //#define DEFAULT_bedKp 97.1 + //#define DEFAULT_bedKi 1.41 + //#define DEFAULT_bedKd 1675.16 + + // FIND YOUR OWN: "M303 E-1 C8 S90" to run autotune on the bed at 90 degreesC for 8 cycles. +#endif // PIDTEMPBED + +// @section extruder + +// 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 + +// 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 300 + +//=========================================================================== +//======================== Thermal Runaway Protection ======================= +//=========================================================================== + +/** + * Thermal Protection protects your printer from damage and fire if a + * thermistor falls out or temperature sensors fail in any way. + * + * The issue: If a thermistor falls out or a temperature sensor fails, + * Marlin can no longer sense the actual temperature. Since a disconnected + * thermistor reads as a low temperature, the firmware will keep the heater on. + * + * If you get "Thermal Runaway" or "Heating failed" errors the + * details can be tuned in Configuration_adv.h + */ + +#define THERMAL_PROTECTION_HOTENDS // Enable thermal protection for all extruders +#define THERMAL_PROTECTION_BED // Enable thermal protection for the heated bed + +//=========================================================================== +//============================= Mechanical Settings ========================= +//=========================================================================== + +// @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 + +//=========================================================================== +//============================== Endstop Settings =========================== +//=========================================================================== + +// @section homing + +// Specify here all the endstop connectors that are connected to any endstop or probe. +// Almost all printers will be using one per axis. Probes will use one or more of the +// extra connectors. Leave undefined any used for non-endstop and non-probe purposes. +#define USE_XMIN_PLUG +#define USE_YMIN_PLUG +#define USE_ZMIN_PLUG +//#define USE_XMAX_PLUG +//#define USE_YMAX_PLUG +//#define USE_ZMAX_PLUG + +// coarse Endstop Settings +#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors + +#if DISABLED(ENDSTOPPULLUPS) + // fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined + //#define ENDSTOPPULLUP_XMAX + //#define ENDSTOPPULLUP_YMAX + //#define ENDSTOPPULLUP_ZMAX + //#define ENDSTOPPULLUP_XMIN + //#define ENDSTOPPULLUP_YMIN + //#define ENDSTOPPULLUP_ZMIN + //#define ENDSTOPPULLUP_ZMIN_PROBE +#endif + +// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup). +#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 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 probe. + +// 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 + * + * Note that if EEPROM is enabled, saved values will override these. + */ + +/** + * With this option each E stepper can have its own factors for the + * following movement settings. If fewer factors are given than the + * total number of extruders, the last value applies to the rest. + */ +//#define DISTINCT_E_FACTORS + +/** + * Default Axis Steps Per Unit (steps/mm) + * Override with M92 + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] + */ +#define DEFAULT_AXIS_STEPS_PER_UNIT { 80, 80, 2560, 93 } // MXL, Z M8=1.25, MK8 + +/** + * Default Max Feed Rate (mm/s) + * Override with M203 + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] + */ +#define DEFAULT_MAX_FEEDRATE { 400, 400, 2, 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[, E4]]]] + */ + +#define DEFAULT_MAX_ACCELERATION { 4000, 4000, 40, 4000 } + +/** + * 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 2000 // E acceleration for retracts +#define DEFAULT_TRAVEL_ACCELERATION 3000 // X, Y, Z acceleration for travel (non printing) moves + +/** + * Default Jerk (mm/s) + * Override with M205 X Y Z E + * + * "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.3 +#define DEFAULT_EJERK 4.0 + +//=========================================================================== +//============================= Z Probe Options ============================= +//=========================================================================== +// @section probes + +// +// See http://marlinfw.org/configuration/probes.html +// + +/** + * Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN + * + * Enable this option for a probe connected to the Z Min endstop pin. + */ +#define Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN + +/** + * Z_MIN_PROBE_ENDSTOP + * + * Enable this option for a probe connected to any pin except Z-Min. + * (By default Marlin assumes the Z-Max endstop pin.) + * To use a custom Z Probe pin, set Z_MIN_PROBE_PIN below. + * + * - The simplest option is to use a free endstop connector. + * - Use 5V for powered (usually inductive) sensors. + * + * - RAMPS 1.3/1.4 boards may use the 5V, GND, and Aux4->D32 pin: + * - For simple switches connect... + * - normally-closed switches to GND and D32. + * - normally-open switches to 5V and D32. + * + * WARNING: Setting the wrong pin may have unexpected and potentially + * disastrous consequences. Use with caution and do your homework. + * + */ +//#define Z_MIN_PROBE_ENDSTOP + +/** + * Probe Type + * + * Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, etc. + * Activate one of these to use Auto Bed Leveling below. + */ + +/** + * The "Manual Probe" provides a means to do "Auto" Bed Leveling without a probe. + * Use G29 repeatedly, adjusting the Z height at each point with movement commands + * or (with LCD_BED_LEVELING) the LCD controller. + */ +//#define PROBE_MANUALLY + +/** + * A Fix-Mounted Probe either doesn't deploy or needs manual deployment. + * (e.g., an inductive probe or a nozzle-based probe-switch.) + */ +//#define FIX_MOUNTED_PROBE + +/** + * Z Servo Probe, such as an endstop switch on a rotating arm. + */ +//#define Z_ENDSTOP_SERVO_NR 1 // Defaults to SERVO 0 connector. +//#define Z_SERVO_ANGLES {10,90} // Z Servo Deploy and Stow angles + +/** + * The BLTouch probe uses a Hall effect sensor and emulates a servo. + */ +//#define BLTOUCH +#if ENABLED(BLTOUCH) + #define BLTOUCH_DELAY 375 // (ms) Enable and increase if needed +#endif + +/** + * Enable one or more of the following if probing seems unreliable. + * Heaters and/or fans can be disabled during probing to minimize electrical + * noise. A delay can also be added to allow noise and vibration to settle. + * These options are most useful for the BLTouch probe, but may also improve + * readings with inductive probes and piezo sensors. + */ +//#define PROBING_HEATERS_OFF // Turn heaters off when probing +//#define PROBING_FANS_OFF // Turn fans off when probing +//#define DELAY_BEFORE_PROBING 200 // (ms) To prevent vibrations from triggering piezo sensors + +// A probe that is deployed and stowed with a solenoid pin (SOL1_PIN) +//#define SOLENOID_PROBE + +// A sled-mounted probe like those designed by Charles Bell. +//#define Z_PROBE_SLED +//#define SLED_DOCKING_OFFSET 5 // The extra distance the X axis must travel to pickup the sled. 0 should be fine but you can push it further if you'd like. + +// +// For Z_PROBE_ALLEN_KEY see the Delta example configurations. +// + +/** + * Z Probe to nozzle (X,Y) offset, relative to (0, 0). + * X and Y offsets must be integers. + * + * In the following example the X and Y offsets are both positive: + * #define X_PROBE_OFFSET_FROM_EXTRUDER 10 + * #define Y_PROBE_OFFSET_FROM_EXTRUDER 10 + * + * +-- BACK ---+ + * | | + * L | (+) P | R <-- probe (20,20) + * E | | I + * F | (-) N (+) | G <-- nozzle (10,10) + * T | | H + * | (-) | T + * | | + * O-- FRONT --+ + * (0,0) + */ +#define X_PROBE_OFFSET_FROM_EXTRUDER 10 // X offset: -left +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 + +// Speed for the first approach when double-probing (with PROBE_DOUBLE_TOUCH) +#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z + +// Speed for the "accurate" probe of each point +#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2) + +// Use double touch for probing +//#define PROBE_DOUBLE_TOUCH + +/** + * 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 6 // Z Clearance between probe points + +// For M851 give a range for adjusting the Z probe offset +#define Z_PROBE_OFFSET_RANGE_MIN -20 +#define Z_PROBE_OFFSET_RANGE_MAX 20 + +// Enable the M48 repeatability test to test probe accuracy +//#define Z_MIN_PROBE_REPEATABILITY_TEST + +// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1 +// :{ 0:'Low', 1:'High' } +#define X_ENABLE_ON 0 +#define Y_ENABLE_ON 0 +#define Z_ENABLE_ON 0 +#define E_ENABLE_ON 0 // For all extruders + +// Disables axis stepper immediately when it's not being used. +// 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 +// Warn on display about possibly reduced accuracy +//#define DISABLE_REDUCED_ACCURACY_WARNING + +// @section extruder + +#define DISABLE_E false // For all extruders +#define DISABLE_INACTIVE_EXTRUDER true // Keep only the active extruder enabled. + +// @section machine + +// Invert the stepper direction. Change (or reverse the motor connector) if an axis goes the wrong way. +#define INVERT_X_DIR true +#define INVERT_Y_DIR true +#define INVERT_Z_DIR false + +// Enable this option for Toshiba stepper drivers +//#define CONFIG_STEPPERS_TOSHIBA + +// @section extruder + +// For direct drive extruder v9 set to true, for geared extruder set to false. +#define INVERT_E0_DIR true +#define INVERT_E1_DIR false +#define INVERT_E2_DIR false +#define INVERT_E3_DIR false +#define INVERT_E4_DIR false + +// @section homing + +#define Z_HOMING_HEIGHT 8 // (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. + +// Direction of endstops when homing; 1=MAX, -1=MIN +// :[-1,1] +#define X_HOME_DIR -1 +#define Y_HOME_DIR -1 +#define Z_HOME_DIR -1 + +// @section machine + +// The size of the print bed +#define X_BED_SIZE 205 +#define Y_BED_SIZE 230 + +// Travel limits (mm) after homing, corresponding to endstop positions. +#define X_MIN_POS 0 +#define Y_MIN_POS 0 +#define Z_MIN_POS 0 +#define X_MAX_POS X_BED_SIZE +#define Y_MAX_POS Y_BED_SIZE +#define Z_MAX_POS 170 + +// If enabled, axes won't move below MIN_POS in response to movement commands. +#define MIN_SOFTWARE_ENDSTOPS +// If enabled, axes won't move above MAX_POS in response to movement commands. +#define MAX_SOFTWARE_ENDSTOPS + +/** + * Filament Runout Sensor + * A mechanical or opto endstop is used to check for the presence of filament. + * + * RAMPS-based boards use SERVO3_PIN. + * For other boards you may need to define FIL_RUNOUT_PIN. + * By default the firmware assumes HIGH = has filament, LOW = ran out + */ +//#define FILAMENT_RUNOUT_SENSOR +#if ENABLED(FILAMENT_RUNOUT_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 + +//=========================================================================== +//=============================== Bed Leveling ============================== +//=========================================================================== +// @section bedlevel + +/** + * Choose one of the options below to enable G29 Bed Leveling. The parameters + * and behavior of G29 will change depending on your selection. + * + * If using a Probe for Z Homing, enable Z_SAFE_HOMING also! + * + * - AUTO_BED_LEVELING_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. + * + * - AUTO_BED_LEVELING_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. + * + * - AUTO_BED_LEVELING_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. + * + * - AUTO_BED_LEVELING_UBL (Unified Bed Leveling) + * A comprehensive bed leveling system combining the features and benefits + * of other systems. UBL also includes integrated Mesh Generation, Mesh + * Validation and Mesh Editing systems. Currently, UBL is only checked out + * for Cartesian Printers. That said, it was primarily designed to correct + * poor quality Delta Printers. If you feel adventurous and have a Delta, + * please post an issue if something doesn't work correctly. Initially, + * you will need to set a reduced bed size so you have a rectangular area + * to test on. + * + * - MESH_BED_LEVELING + * Probe a grid manually + * The result is a mesh, suitable for large or uneven beds. (See BILINEAR.) + * For machines without a probe, Mesh Bed Leveling provides a method to perform + * leveling in steps so you can manually adjust the Z height at each grid-point. + * With an LCD controller the process is guided step-by-step. + */ +//#define AUTO_BED_LEVELING_3POINT +//#define AUTO_BED_LEVELING_LINEAR +//#define AUTO_BED_LEVELING_BILINEAR +//#define AUTO_BED_LEVELING_UBL +//#define MESH_BED_LEVELING + +/** + * 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(MESH_BED_LEVELING) || ENABLED(AUTO_BED_LEVELING_BILINEAR) || ENABLED(AUTO_BED_LEVELING_UBL) + // 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 + +#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR) + + // Set the number of grid points per dimension. + #define GRID_MAX_POINTS_X 3 + #define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X + + // 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 + + // The Z probe minimum outer margin (to validate G29 parameters). + #define MIN_PROBE_EDGE 8 + + // Probe along the Y axis, advancing X after each column + //#define PROBE_Y_FIRST + + #if ENABLED(AUTO_BED_LEVELING_BILINEAR) + + // Beyond the probed grid, continue the implied tilt? + // Default is to maintain the height of the nearest edge. + //#define EXTRAPOLATE_BEYOND_GRID + + // + // Experimental Subdivision of the grid by Catmull-Rom method. + // Synthesizes intermediate points to produce a more detailed mesh. + // + //#define ABL_BILINEAR_SUBDIVISION + #if ENABLED(ABL_BILINEAR_SUBDIVISION) + // Number of subdivisions between probe points + #define BILINEAR_SUBDIVISIONS 3 + #endif + + #endif + +#elif ENABLED(AUTO_BED_LEVELING_3POINT) + + // 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 + +#elif ENABLED(AUTO_BED_LEVELING_UBL) + + //=========================================================================== + //========================= Unified Bed Leveling ============================ + //=========================================================================== + + #define UBL_MESH_INSET 1 // Mesh inset margin on print area + #define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited. + #define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X + + #define UBL_PROBE_PT_1_X 39 // Probing points for 3-Point leveling of the mesh + #define UBL_PROBE_PT_1_Y 180 + #define UBL_PROBE_PT_2_X 39 + #define UBL_PROBE_PT_2_Y 20 + #define UBL_PROBE_PT_3_X 180 + #define UBL_PROBE_PT_3_Y 20 + + #define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation + #define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle + +#elif ENABLED(MESH_BED_LEVELING) + + //=========================================================================== + //=================================== Mesh ================================== + //=========================================================================== + + #define MESH_INSET 10 // Mesh inset margin on print area + #define GRID_MAX_POINTS_X 3 // Don't use more than 7 points per axis, implementation limited. + #define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X + + //#define MESH_G28_REST_ORIGIN // After homing all axes ('G28' or 'G28 XYZ') rest Z at Z_MIN_POS + +#endif // BED_LEVELING + +/** + * Use the LCD controller for bed leveling + * Requires MESH_BED_LEVELING or PROBE_MANUALLY + */ +//#define LCD_BED_LEVELING + +#if ENABLED(LCD_BED_LEVELING) + #define MBL_Z_STEP 0.025 // Step size while manually probing Z axis. + #define LCD_PROBE_Z_RANGE 4 // Z Range centered on Z_MIN_POS for LCD Z adjustment +#endif + +/** + * 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 + +// The center of the bed is at (X=0, Y=0) +//#define BED_CENTER_AT_0_0 + +// Manually set the home position. Leave these undefined for automatic settings. +// For DELTA this is the top-center of the Cartesian print volume. +//#define MANUAL_X_HOME_POS 0 +//#define MANUAL_Y_HOME_POS 0 +//#define MANUAL_Z_HOME_POS 0 + +// Use "Z Safe Homing" to avoid homing with a Z probe outside the bed area. +// +// With this feature enabled: +// +// - Allow Z homing only after X and Y homing AND stepper drivers still enabled. +// - If stepper drivers time out, it will need X and Y homing again before Z homing. +// - Move the Z probe (or nozzle) to a defined XY point before Z Homing when homing all axes (G28). +// - Prevent Z homing when the Z probe is outside bed area. +// +//#define Z_SAFE_HOMING + +#if ENABLED(Z_SAFE_HOMING) + #define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axis (G28). + #define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axis (G28). +#endif + +// Homing speeds (mm/m) +#define HOMING_FEEDRATE_XY (50*60) +#define HOMING_FEEDRATE_Z (4*60) + +//============================================================================= +//============================= Additional Features =========================== +//============================================================================= + +// @section extras + +// +// EEPROM +// +// The microcontroller can store settings in the EEPROM, e.g. max velocity... +// M500 - stores parameters in EEPROM +// 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 EEPROM_SETTINGS // Enable for M500 and M501 commands +//#define DISABLE_M503 // Saves ~2700 bytes of PROGMEM. Disable for release! +#define EEPROM_CHITCHAT // Give feedback on EEPROM commands. Disable to save PROGMEM. + +// +// Host Keepalive +// +// 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 4 // Number of seconds between "busy" messages. Set with M113. +#define BUSY_WHILE_HEATING // Some hosts require "busy" messages even during heating + +// +// M100 Free Memory Watcher +// +//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose + +// +// G20/G21 Inch mode support +// +//#define INCH_MODE_SUPPORT + +// +// M149 Set temperature units support +// +//#define TEMPERATURE_UNITS_SUPPORT + +// @section temperature + +// Preheat Constants +#define PREHEAT_1_TEMP_HOTEND 180 +#define PREHEAT_1_TEMP_BED 70 +#define PREHEAT_1_FAN_SPEED 0 // Value from 0 to 255 + +#define PREHEAT_2_TEMP_HOTEND 215 +#define PREHEAT_2_TEMP_BED 105 +#define PREHEAT_2_FAN_SPEED 0 // Value from 0 to 255 + +/** + * Nozzle Park -- EXPERIMENTAL + * + * Park the nozzle at the given XYZ position on idle or G27. + * + * The "P" parameter controls the action applied to the Z axis: + * + * P0 (Default) If Z is below park Z raise the nozzle. + * P1 Raise the nozzle always to Z-park height. + * P2 Raise the nozzle by Z-park amount, limited to Z_MAX_POS. + */ +//#define NOZZLE_PARK_FEATURE + +#if ENABLED(NOZZLE_PARK_FEATURE) + // Specify a park position as { X, Y, Z } + #define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 } +#endif + +/** + * Clean Nozzle Feature -- EXPERIMENTAL + * + * Adds the G12 command to perform a nozzle cleaning process. + * + * Parameters: + * P Pattern + * S Strokes / Repetitions + * T Triangles (P1 only) + * + * Patterns: + * P0 Straight line (default). This process requires a sponge type material + * at a fixed bed location. "S" specifies strokes (i.e. back-forth motions) + * between the start / end points. + * + * P1 Zig-zag pattern between (X0, Y0) and (X1, Y1), "T" specifies the + * number of zig-zag triangles to do. "S" defines the number of strokes. + * Zig-zags are done in whichever is the narrower dimension. + * For example, "G12 P1 S1 T3" will execute: + * + * -- + * | (X0, Y1) | /\ /\ /\ | (X1, Y1) + * | | / \ / \ / \ | + * A | | / \ / \ / \ | + * | | / \ / \ / \ | + * | (X0, Y0) | / \/ \/ \ | (X1, Y0) + * -- +--------------------------------+ + * |________|_________|_________| + * T1 T2 T3 + * + * P2 Circular pattern with middle at NOZZLE_CLEAN_CIRCLE_MIDDLE. + * "R" specifies the radius. "S" specifies the stroke count. + * Before starting, the nozzle moves to NOZZLE_CLEAN_START_POINT. + * + * Caveats: The ending Z should be the same as starting Z. + * Attention: EXPERIMENTAL. G-code arguments may change. + * + */ +//#define NOZZLE_CLEAN_FEATURE + +#if ENABLED(NOZZLE_CLEAN_FEATURE) + // Default number of pattern repetitions + #define NOZZLE_CLEAN_STROKES 12 + + // Default number of triangles + #define NOZZLE_CLEAN_TRIANGLES 3 + + // Specify positions as { X, Y, Z } + #define NOZZLE_CLEAN_START_POINT { 30, 30, (Z_MIN_POS + 1)} + #define NOZZLE_CLEAN_END_POINT {100, 60, (Z_MIN_POS + 1)} + + // Circular pattern radius + #define NOZZLE_CLEAN_CIRCLE_RADIUS 6.5 + // Circular pattern circle fragments number + #define NOZZLE_CLEAN_CIRCLE_FN 10 + // Middle point of circle + #define NOZZLE_CLEAN_CIRCLE_MIDDLE NOZZLE_CLEAN_START_POINT + + // Moves the nozzle to the initial position + #define NOZZLE_CLEAN_GOBACK +#endif + +/** + * Print Job Timer + * + * Automatically start and stop the print job timer on M104/M109/M190. + * + * M104 (hotend, no wait) - high temp = none, low temp = stop timer + * M109 (hotend, wait) - high temp = start timer, low temp = stop timer + * M190 (bed, wait) - high temp = start timer, low temp = none + * + * The timer can also be controlled with the following commands: + * + * M75 - Start the print job timer + * M76 - Pause the print job timer + * M77 - Stop the print job timer + */ +#define PRINTJOB_TIMER_AUTOSTART + +/** + * Print Counter + * + * Track statistical data such as: + * + * - Total print jobs + * - Total successful print jobs + * - Total failed print jobs + * - Total time printing + * + * View the current statistics with M78. + */ +//#define PRINTCOUNTER + +//============================================================================= +//============================= LCD and SD support ============================ +//============================================================================= + +// @section lcd + +/** + * LCD LANGUAGE + * + * Select the language to display on the LCD. These languages are available: + * + * en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr, + * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, + * zh_CN, zh_TW, test + * + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } + */ +#define LCD_LANGUAGE en + +/** + * LCD Character Set + * + * Note: This option is NOT applicable to Graphical Displays. + * + * All character-based LCDs provide ASCII plus one of these + * language extensions: + * + * - JAPANESE ... the most common + * - WESTERN ... with more accented characters + * - CYRILLIC ... for the Russian language + * + * To determine the language extension installed on your controller: + * + * - Compile and upload with LCD_LANGUAGE set to 'test' + * - Click the controller to view the LCD menu + * - The LCD will display Japanese, Western, or Cyrillic text + * + * See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language + * + * :['JAPANESE', 'WESTERN', 'CYRILLIC'] + */ +#define DISPLAY_CHARSET_HD44780 JAPANESE + +/** + * LCD TYPE + * + * Enable ULTRA_LCD for a 16x2, 16x4, 20x2, or 20x4 character-based LCD. + * Enable DOGLCD for a 128x64 (ST7565R) Full Graphical Display. + * (These options will be enabled automatically for most displays.) + * + * IMPORTANT: The U8glib library is required for Full Graphic Display! + * https://github.com/olikraus/U8glib_Arduino + */ +//#define ULTRA_LCD // Character based +//#define DOGLCD // Full graphics display + +/** + * SD CARD + * + * SD Card support is disabled by default. If your controller has an SD slot, + * you must uncomment the following option or it won't work. + * + */ +#define SDSUPPORT + +/** + * SD CARD: SPI SPEED + * + * Enable one of the following items for a slower SPI transfer speed. + * This may be required to resolve "volume init" errors. + */ +//#define SPI_SPEED SPI_HALF_SPEED +//#define SPI_SPEED SPI_QUARTER_SPEED +//#define SPI_SPEED SPI_EIGHTH_SPEED + +/** + * SD CARD: ENABLE CRC + * + * Use CRC checks and retries on the SD communication. + */ +//#define SD_CHECK_AND_RETRY + +// +// ENCODER SETTINGS +// +// 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 + +// +// 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 + +/** + * Encoder Direction Options + * + * Test your encoder's behavior first with both options disabled. + * + * Reversed Value Edit and Menu Nav? Enable REVERSE_ENCODER_DIRECTION. + * Reversed Menu Navigation only? Enable REVERSE_MENU_DIRECTION. + * Reversed Value Editing only? Enable BOTH options. + */ + +// +// This option reverses the encoder direction everywhere. +// +// Set this option if CLOCKWISE causes values to DECREASE +// +//#define REVERSE_ENCODER_DIRECTION + +// +// This option reverses the encoder direction for navigating LCD menus. +// +// If CLOCKWISE normally moves DOWN this makes it go UP. +// If CLOCKWISE normally moves UP this makes it go DOWN. +// +//#define REVERSE_MENU_DIRECTION + +// +// Individual Axis Homing +// +// Add individual axis homing items (Home X, Home Y, and Home Z) to the LCD menu. +// +//#define INDIVIDUAL_AXIS_HOMING_MENU + +// +// SPEAKER/BUZZER +// +// If you have a speaker that can produce tones, enable it here. +// By default Marlin assumes you have a buzzer with a fixed frequency. +// +//#define SPEAKER + +// +// The duration and frequency for the UI feedback sound. +// Set these to 0 to disable audio feedback in the LCD menus. +// +// Note: Test audio output with the G-Code: +// M300 S P +// +#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100 +#define LCD_FEEDBACK_FREQUENCY_HZ 1000 + +// +// CONTROLLER TYPE: Standard +// +// Marlin supports a wide variety of controllers. +// Enable one of the following options to specify your controller. +// + +// +// ULTIMAKER Controller. +// +//#define ULTIMAKERCONTROLLER + +// +// ULTIPANEL as seen on Thingiverse. +// +//#define ULTIPANEL + +// +// PanelOne from T3P3 (via RAMPS 1.4 AUX2/AUX3) +// http://reprap.org/wiki/PanelOne +// +//#define PANEL_ONE + +// +// MaKr3d Makr-Panel with graphic controller and SD support. +// http://reprap.org/wiki/MaKr3d_MaKrPanel +// +//#define MAKRPANEL + +// +// ReprapWorld Graphical LCD +// https://reprapworld.com/?products_details&products_id/1218 +// +//#define REPRAPWORLD_GRAPHICAL_LCD + +// +// Activate one of these if you have a Panucatt Devices +// Viki 2.0 or mini Viki with Graphic LCD +// http://panucatt.com +// +//#define VIKI2 +//#define miniVIKI + +// +// Adafruit ST7565 Full Graphic Controller. +// https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/ +// +//#define ELB_FULL_GRAPHIC_CONTROLLER + +// +// RepRapDiscount Smart Controller. +// http://reprap.org/wiki/RepRapDiscount_Smart_Controller +// +// Note: Usually sold with a white PCB. +// +#define REPRAP_DISCOUNT_SMART_CONTROLLER + +// +// GADGETS3D G3D LCD/SD Controller +// http://reprap.org/wiki/RAMPS_1.3/1.4_GADGETS3D_Shield_with_Panel +// +// Note: Usually sold with a blue PCB. +// +//#define G3D_PANEL + +// +// RepRapDiscount FULL GRAPHIC Smart Controller +// http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller +// +//#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER + +// +// MakerLab Mini Panel with graphic +// controller and SD support - http://reprap.org/wiki/Mini_panel +// +//#define MINIPANEL + +// +// RepRapWorld REPRAPWORLD_KEYPAD v1.1 +// http://reprapworld.com/?products_details&products_id=202&cPath=1591_1626 +// +// REPRAPWORLD_KEYPAD_MOVE_STEP sets how much should the robot move when a key +// is pressed, a value of 10.0 means 10mm per click. +// +//#define REPRAPWORLD_KEYPAD +//#define REPRAPWORLD_KEYPAD_MOVE_STEP 1.0 + +// +// RigidBot Panel V1.0 +// http://www.inventapart.com/ +// +//#define RIGIDBOT_PANEL + +// +// BQ LCD Smart Controller shipped by +// default with the BQ Hephestos 2 and Witbox 2. +// +//#define BQ_LCD_SMART_CONTROLLER + +// +// Cartesio UI +// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface +// +//#define CARTESIO_UI + +// +// ANET_10 Controller supported displays. +// +//#define ANET_KEYPAD_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin. + // This LCD is known to be susceptible to electrical interference + // which scrambles the display. Pressing any button clears it up. +//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6 + // A clone of the RepRapDiscount full graphics display but with + // different pins/wiring (see pins_ANET_10.h). + +// +// LCD for Melzi Card with Graphical LCD +// +//#define LCD_FOR_MELZI + +// +// CONTROLLER TYPE: I2C +// +// Note: These controllers require the installation of Arduino's LiquidCrystal_I2C +// library. For more info: https://github.com/kiyoshigawa/LiquidCrystal_I2C +// + +// +// Elefu RA Board Control Panel +// http://www.elefu.com/index.php?route=product/product&product_id=53 +// +//#define RA_CONTROL_PANEL + +// +// Sainsmart YW Robot (LCM1602) LCD Display +// +// Note: This controller requires F.Malpartida's LiquidCrystal_I2C library +// https://bitbucket.org/fmalpartida/new-liquidcrystal/wiki/Home +// +//#define LCD_I2C_SAINSMART_YWROBOT + +// +// Generic LCM1602 LCD adapter +// +//#define LCM1602 + +// +// PANELOLU2 LCD with status LEDs, +// separate encoder and click inputs. +// +// Note: This controller requires Arduino's LiquidTWI2 library v1.2.3 or later. +// For more info: https://github.com/lincomatic/LiquidTWI2 +// +// Note: The PANELOLU2 encoder click input can either be directly connected to +// a pin (if BTN_ENC defined to != -1) or read through I2C (when BTN_ENC == -1). +// +//#define LCD_I2C_PANELOLU2 + +// +// Panucatt VIKI LCD with status LEDs, +// integrated click & L/R/U/D buttons, separate encoder inputs. +// +//#define LCD_I2C_VIKI + +// +// SSD1306 OLED full graphics generic display +// +//#define U8GLIB_SSD1306 + +// +// SAV OLEd LCD module support using either SSD1306 or SH1106 based LCD modules +// +//#define SAV_3DGLCD +#if ENABLED(SAV_3DGLCD) + //#define U8GLIB_SSD1306 + #define U8GLIB_SH1106 +#endif + +// +// CONTROLLER TYPE: Shift register panels +// +// 2 wire Non-latching LCD SR from https://goo.gl/aJJ4sH +// LCD configuration: http://reprap.org/wiki/SAV_3D_LCD +// +//#define SAV_3DLCD + +// +// TinyBoy2 128x64 OLED / Encoder Panel +// +//#define OLED_PANEL_TINYBOY2 + +//============================================================================= +//=============================== Extra Features ============================== +//============================================================================= + +// @section extras + +// Increase the FAN PWM frequency. Removes the PWM noise but increases heating in the FET/Arduino +//#define FAST_PWM_FAN + +// Use software PWM to drive the fan, as for the heaters. This uses a very low frequency +// which is not as annoying as with the hardware PWM. On the other hand, if this frequency +// is too low, you should also increment SOFT_PWM_SCALE. +//#define FAN_SOFT_PWM + +// Incrementing this by 1 will double the software PWM frequency, +// affecting heaters, and the fan if FAN_SOFT_PWM is enabled. +// However, control resolution will be halved for each increment; +// at zero value, there are 128 effective control positions. +#define SOFT_PWM_SCALE 0 + +// If SOFT_PWM_SCALE is set to a value higher than 0, dithering can +// be used to mitigate the associated resolution loss. If enabled, +// some of the PWM cycles are stretched so on average the desired +// duty cycle is attained. +//#define SOFT_PWM_DITHER + +// Temperature status LEDs that display the hotend and bed temperature. +// If all hotends, bed temperature, and target temperature are under 54C +// then the BLUE led is on. Otherwise the RED led is on. (1C hysteresis) +//#define TEMP_STAT_LEDS + +// M240 Triggers a camera by emulating a Canon RC-1 Remote +// Data from: http://www.doc-diy.net/photo/rc-1_hacked/ +//#define PHOTOGRAPH_PIN 23 + +// SkeinForge sends the wrong arc g-codes when using Arc Point as fillet procedure +//#define SF_ARC_FIX + +// Support for the BariCUDA Paste Extruder +//#define BARICUDA + +// Support for BlinkM/CyzRgb +//#define BLINKM + +// Support for PCA9632 PWM LED driver +//#define PCA9632 + +/** + * RGB LED / LED Strip Control + * + * Enable support for an RGB LED connected to 5V digital pins, or + * an RGB Strip connected to MOSFETs controlled by digital pins. + * + * Adds the M150 command to set the LED (or LED strip) color. + * If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of + * luminance values can be set from 0 to 255. + * + * *** CAUTION *** + * LED Strips require a MOFSET Chip between PWM lines and LEDs, + * as the Arduino cannot handle the current the LEDs will require. + * Failure to follow this precaution can destroy your Arduino! + * *** CAUTION *** + * + */ +//#define RGB_LED +//#define RGBW_LED +#if ENABLED(RGB_LED) || ENABLED(RGBW_LED) + #define RGB_LED_R_PIN 34 + #define RGB_LED_G_PIN 43 + #define RGB_LED_B_PIN 35 + #define RGB_LED_W_PIN -1 +#endif + +// Support for Adafruit Neopixel LED driver +//#define NEOPIXEL_RGBW_LED +#if ENABLED(NEOPIXEL_RGBW_LED) + #define NEOPIXEL_PIN 4 // D4 (EXP2-5 on Printrboard) + #define NEOPIXEL_PIXELS 3 + //#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup +#endif + +/** + * Printer Event LEDs + * + * During printing, the LEDs will reflect the printer status: + * + * - Gradually change from blue to violet as the heated bed gets to target temp + * - Gradually change from violet to red as the hotend gets to temperature + * - Change to white to illuminate work surface + * - Change to green once print has finished + * - Turn off after the print has finished and the user has pushed a button + */ +#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_RGBW_LED) + #define PRINTER_EVENT_LEDS +#endif + +/*********************************************************************\ +* R/C SERVO support +* Sponsored by TrinityLabs, Reworked by codexmas +**********************************************************************/ + +// Number of servos +// +// If you select a configuration below, this will receive a default value and does not need to be set manually +// set it manually if you have more servos than extruders and wish to manually control some +// leaving it undefined or defining as 0 will disable the servo subsystem +// If unsure, leave commented / disabled +// +#define NUM_SERVOS 1 // Servo index starts with 0 for M280 command + +// Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle. +// 300ms is a good value but you can try less delay. +// If the servo can't reach the requested position, increase it. +#define SERVO_DELAY 300 + +// Servo deactivation +// +// With this option servos are powered only during movement, then turned off to prevent jitter. +//#define DEACTIVATE_SERVOS_AFTER_MOVE + +/** + * Filament Width Sensor + * + * Measures the filament width in real-time and adjusts + * flow rate to compensate for any irregularities. + * + * Also allows the measured filament diameter to set the + * extrusion rate, so the slicer only has to specify the + * volume. + * + * Only a single extruder is supported at this time. + * + * 34 RAMPS_14 : Analog input 5 on the AUX2 connector + * 81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E) + * 301 RAMBO : Analog input 3 + * + * Note: May require analog pins to be defined for other boards. + */ +//#define FILAMENT_WIDTH_SENSOR + +#define DEFAULT_NOMINAL_FILAMENT_DIA 1.75 // (mm) Diameter of the filament generally used (3.0 or 1.75mm), also used in the slicer. Used to validate sensor reading. + +#if ENABLED(FILAMENT_WIDTH_SENSOR) + #define FILAMENT_SENSOR_EXTRUDER_NUM 0 // Index of the extruder that has the filament sensor (0,1,2,3) + #define MEASUREMENT_DELAY_CM 14 // (cm) The distance from the filament sensor to the melting chamber + + #define MEASURED_UPPER_LIMIT 3.30 // (mm) Upper limit used to validate sensor reading + #define MEASURED_LOWER_LIMIT 1.90 // (mm) Lower limit used to validate sensor reading + #define MAX_MEASUREMENT_DELAY 20 // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM. + + #define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially + + // Display filament width on the LCD status line. Status messages will expire after 5 seconds. + //#define FILAMENT_LCD_DISPLAY +#endif + +#endif // CONFIGURATION_H From dd66d21749abbca4cf6e753c22c0b721b5b823ba Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 3 Aug 2017 16:53:55 -0500 Subject: [PATCH 067/112] Extend DEACTIVATE_SERVOS_AFTER_MOVE sanity-check As proposed in #7429 --- Marlin/SanityCheck.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/Marlin/SanityCheck.h b/Marlin/SanityCheck.h index eeda19ca6..41eb340eb 100644 --- a/Marlin/SanityCheck.h +++ b/Marlin/SanityCheck.h @@ -418,10 +418,10 @@ #endif /** - * Servo deactivation depends on servo endstops or switching nozzle + * Servo deactivation depends on servo endstops, switching nozzle, or switching extruder */ -#if ENABLED(DEACTIVATE_SERVOS_AFTER_MOVE) && !HAS_Z_SERVO_ENDSTOP && !defined(SWITCHING_NOZZLE_SERVO_NR) - #error "Z_ENDSTOP_SERVO_NR or switching nozzle is required for DEACTIVATE_SERVOS_AFTER_MOVE." +#if ENABLED(DEACTIVATE_SERVOS_AFTER_MOVE) && !HAS_Z_SERVO_ENDSTOP && !defined(SWITCHING_NOZZLE_SERVO_NR) && !defined(SWITCHING_EXTRUDER_SERVO_NR) + #error "Z_ENDSTOP_SERVO_NR, switching nozzle, or switching extruder is required for DEACTIVATE_SERVOS_AFTER_MOVE." #endif /** From a7e5c1bf19cdfeea1333b9d4d5df13b1cc52ad52 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 5 Aug 2017 02:33:20 -0500 Subject: [PATCH 068/112] Use float to init TMC2133 steps-per-mm --- Marlin/stepper_indirection.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/stepper_indirection.cpp b/Marlin/stepper_indirection.cpp index c2f302704..9e9d3bf99 100644 --- a/Marlin/stepper_indirection.cpp +++ b/Marlin/stepper_indirection.cpp @@ -171,7 +171,7 @@ // Use internal reference voltage for current calculations. This is the default. // Following values from Trinamic's spreadsheet with values for a NEMA17 (42BYGHW609) // https://www.trinamic.com/products/integrated-circuits/details/tmc2130/ - void tmc2130_init(TMC2130Stepper &st, const uint16_t microsteps, const uint32_t thrs, const uint32_t spmm) { + void tmc2130_init(TMC2130Stepper &st, const uint16_t microsteps, const uint32_t thrs, const float &spmm) { st.begin(); st.setCurrent(st.getCurrent(), R_SENSE, HOLD_MULTIPLIER); st.microsteps(microsteps); @@ -199,7 +199,7 @@ #define _TMC2130_INIT(ST, SPMM) tmc2130_init(stepper##ST, ST##_MICROSTEPS, ST##_HYBRID_THRESHOLD, SPMM) void tmc2130_init() { - constexpr uint16_t steps_per_mm[] = DEFAULT_AXIS_STEPS_PER_UNIT; + constexpr float steps_per_mm[] = DEFAULT_AXIS_STEPS_PER_UNIT; #if ENABLED(X_IS_TMC2130) _TMC2130_INIT( X, steps_per_mm[X_AXIS]); #if ENABLED(SENSORLESS_HOMING) From b2822a59f94a1cbe9297b649a1e23f580331d6ec Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 5 Aug 2017 03:28:30 -0500 Subject: [PATCH 069/112] Add a sanity check for valid bed size --- Marlin/SanityCheck.h | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/Marlin/SanityCheck.h b/Marlin/SanityCheck.h index 41eb340eb..6bb86b8a7 100644 --- a/Marlin/SanityCheck.h +++ b/Marlin/SanityCheck.h @@ -51,7 +51,7 @@ * Warnings for old configurations */ #if !defined(X_BED_SIZE) || !defined(Y_BED_SIZE) - #error "X_BED_SIZE and BED_Y_SIZE are now required! Please update your configuration." + #error "X_BED_SIZE and Y_BED_SIZE are now required! Please update your configuration." #elif 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)) @@ -244,6 +244,12 @@ #error "Z_DUAL_STEPPER_DRIVERS requires Z2 pins (and an extra E plug)." #endif +/** + * Validate that the bed size fits + */ +static_assert(X_MAX_LENGTH >= X_BED_SIZE && Y_MAX_LENGTH >= Y_BED_SIZE, + "Movement bounds ([XY]_MIN_POS, [XY]_MAX_POS) are too narrow to contain [XY]_BED_SIZE."); + /** * Progress Bar */ From 97c21e90071588a94fbc503e0b43c43dd2efee03 Mon Sep 17 00:00:00 2001 From: Jozsef Kiraly Date: Tue, 23 May 2017 22:53:29 +0200 Subject: [PATCH 070/112] Support for Geeetech GT2560 Rev.A/Rev.A+ --- Marlin/Configuration.h | 2 +- Marlin/boards.h | 2 + .../Geeetech/GT2560/Configuration.h | 1665 +++++++++++++++++ .../Geeetech/I3_Pro_X-GT2560/Configuration.h | 1 - Marlin/pins.h | 4 + Marlin/pins_GT2560_REV_A.h | 133 ++ Marlin/pins_GT2560_REV_A_PLUS.h | 31 + 7 files changed, 1836 insertions(+), 2 deletions(-) create mode 100644 Marlin/example_configurations/Geeetech/GT2560/Configuration.h create mode 100644 Marlin/pins_GT2560_REV_A.h create mode 100644 Marlin/pins_GT2560_REV_A_PLUS.h diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index e44c7f8cf..12d394fc3 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -914,7 +914,7 @@ #define UBL_PROBE_PT_3_X 180 #define UBL_PROBE_PT_3_Y 20 - #define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation + //#define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation #define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle #elif ENABLED(MESH_BED_LEVELING) diff --git a/Marlin/boards.h b/Marlin/boards.h index cec937980..398165e46 100644 --- a/Marlin/boards.h +++ b/Marlin/boards.h @@ -64,6 +64,8 @@ #define BOARD_ULTIMAKER 7 // Ultimaker #define BOARD_ULTIMAKER_OLD 71 // Ultimaker (Older electronics. Pre 1.5.4. This is rare) #define BOARD_ULTIMAIN_2 72 // Ultimainboard 2.x (Uses TEMP_SENSOR 20) +#define BOARD_GT2560_REV_A 74 // Geeetech GT2560 Rev. A +#define BOARD_GT2560_REV_A_PLUS 75 // Geeetech GT2560 Rev. A+ (with auto level probe) #define BOARD_3DRAG 77 // 3Drag Controller #define BOARD_K8200 78 // Velleman K8200 Controller (derived from 3Drag Controller) #define BOARD_K8400 79 // Velleman K8400 Controller (derived from 3Drag Controller) diff --git a/Marlin/example_configurations/Geeetech/GT2560/Configuration.h b/Marlin/example_configurations/Geeetech/GT2560/Configuration.h new file mode 100644 index 000000000..6cbc46bc0 --- /dev/null +++ b/Marlin/example_configurations/Geeetech/GT2560/Configuration.h @@ -0,0 +1,1665 @@ +/** + * 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 . + * + */ + +/** + * Configuration.h + * + * Basic settings such as: + * + * - Type of electronics + * - Type of temperature sensor + * - Printer geometry + * - Endstop configuration + * - LCD controller + * - Extra features + * + * Advanced settings can be found in Configuration_adv.h + * + */ +#ifndef CONFIGURATION_H +#define CONFIGURATION_H +#define CONFIGURATION_H_VERSION 010100 + +//=========================================================================== +//============================= Getting Started ============================= +//=========================================================================== + +/** + * Here are some standard links for getting your machine calibrated: + * + * http://reprap.org/wiki/Calibration + * http://youtu.be/wAL9d7FgInk + * http://calculator.josefprusa.cz + * http://reprap.org/wiki/Triffid_Hunter%27s_Calibration_Guide + * http://www.thingiverse.com/thing:5573 + * https://sites.google.com/site/repraplogphase/calibration-of-your-reprap + * http://www.thingiverse.com/thing:298812 + */ + +//=========================================================================== +//============================= DELTA Printer =============================== +//=========================================================================== +// For a Delta printer start with one of the configuration files in the +// example_configurations/delta directory and customize for your machine. +// + +//=========================================================================== +//============================= SCARA Printer =============================== +//=========================================================================== +// For a SCARA printer start with the configuration files in +// example_configurations/SCARA and customize for your machine. +// + +// @section info + +// User-specified version info of this build to display in [Pronterface, etc] terminal window during +// startup. Implementation of an idea by Prof Braino to inform user that any changes made to this +// 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 bootup in line 1 +#define STRING_SPLASH_LINE2 WEBSITE_URL // will be shown during bootup in line 2 + +// +// *** VENDORS PLEASE READ ***************************************************** +// +// Marlin now allow you to have a vendor boot image to be displayed on machine +// start. When SHOW_CUSTOM_BOOTSCREEN is defined Marlin will first show your +// custom boot image and then the default Marlin boot image is shown. +// +// We suggest for you to take advantage of this new feature and keep the Marlin +// boot image unmodified. For an example have a look at the bq Hephestos 2 +// example configuration folder. +// +//#define SHOW_CUSTOM_BOOTSCREEN +// @section machine + +/** + * 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 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 +//#define BLUETOOTH + +// The following define selects which electronics board you have. +// Please choose the name from boards.h that matches your setup +#ifndef MOTHERBOARD + #define MOTHERBOARD BOARD_GT2560_REV_A +#endif + +// Optional custom name for your RepStrap or other custom machine +// Displayed in the LCD "Ready" message +//#define CUSTOM_MACHINE_NAME "3D Printer" + +// 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 "00000000-0000-0000-0000-000000000000" + +// @section extruder + +// This defines the number of extruders +// :[1, 2, 3, 4, 5] +#define EXTRUDERS 1 + +// For Cyclops or any "multi-extruder" that shares a single nozzle. +//#define SINGLENOZZLE + +/** + * Průša MK2 Single Nozzle Multi-Material Multiplexer, and variants. + * + * This device allows one stepper driver on a control board to drive + * two to eight stepper motors, one at a time, in a manner suitable + * for extruders. + * + * This option only allows the multiplexer to switch on tool-change. + * Additional options to configure custom E moves are pending. + */ +//#define MK2_MULTIPLEXER +#if ENABLED(MK2_MULTIPLEXER) + // Override the default DIO selector pins here, if needed. + // Some pins files may provide defaults for these pins. + //#define E_MUX0_PIN 40 // Always Required + //#define E_MUX1_PIN 42 // Needed for 3 to 8 steppers + //#define E_MUX2_PIN 44 // Needed for 5 to 8 steppers +#endif + +// A dual extruder that uses a single stepper motor +//#define SWITCHING_EXTRUDER +#if ENABLED(SWITCHING_EXTRUDER) + #define SWITCHING_EXTRUDER_SERVO_NR 0 + #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1[, E2, E3] + #if EXTRUDERS > 3 + #define SWITCHING_EXTRUDER_E23_SERVO_NR 1 + #endif +#endif + +// A dual-nozzle that uses a servomotor to raise/lower one of the nozzles +//#define SWITCHING_NOZZLE +#if ENABLED(SWITCHING_NOZZLE) + #define SWITCHING_NOZZLE_SERVO_NR 0 + #define SWITCHING_NOZZLE_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 + //#define HOTEND_OFFSET_Z { 0.0, 0.0 } +#endif + +/** + * "Mixing Extruder" + * - Adds a new code, M165, to set the current mix factors. + * - Extends the stepping routines to move multiple steppers in proportion to the mix. + * - Optional support for Repetier Firmware M163, M164, and virtual extruder. + * - This implementation supports only a single extruder. + * - Enable DIRECT_MIXING_IN_G1 for Pia Taubert's reference implementation + */ +//#define MIXING_EXTRUDER +#if ENABLED(MIXING_EXTRUDER) + #define MIXING_STEPPERS 2 // Number of steppers in your mixing extruder + #define MIXING_VIRTUAL_TOOLS 16 // Use the Virtual Tool method with M163 and M164 + //#define DIRECT_MIXING_IN_G1 // Allow ABCDHI mix factors in G1 movement commands +#endif + +// Offset of the extruders (uncomment if using more than one and relying on firmware to position when changing). +// The offset has to be X=0, Y=0 for the extruder 0 hotend (default extruder). +// For the other hotends it is their distance from the extruder 0 hotend. +//#define 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 + +// @section machine + +/** + * 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 + +#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 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 + * 75 : 100k Generic Silicon Heat Pad with NTC 100K MGB18-104F39050L32 thermistor + * + * 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_4 0 +#define TEMP_SENSOR_BED 1 + +// 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 + +// Extruder temperature must be close to target for this long before M109 returns success +#define TEMP_RESIDENCY_TIME 10 // (seconds) +#define TEMP_HYSTERESIS 3 // (degC) range of +/- temperatures considered "close" to the target one +#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 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. + +// The minimal temperature defines the temperature below which the heater will not be enabled It is used +// to check that the wiring to the thermistor is not broken. +// Otherwise this would lead to the heater being powered on all the time. +#define HEATER_0_MINTEMP 5 +#define HEATER_1_MINTEMP 5 +#define HEATER_2_MINTEMP 5 +#define HEATER_3_MINTEMP 5 +#define HEATER_4_MINTEMP 5 +#define BED_MINTEMP 5 + +// When temperature exceeds max temp, your heater will be switched off. +// This feature exists to protect your hotend from overheating accidentally, but *NOT* from thermistor short/failure! +// You should use MINTEMP for thermistor short/failure protection. +#define HEATER_0_MAXTEMP 275 +#define HEATER_1_MAXTEMP 275 +#define HEATER_2_MAXTEMP 275 +#define HEATER_3_MAXTEMP 275 +#define HEATER_4_MAXTEMP 275 +#define BED_MAXTEMP 150 + +//=========================================================================== +//============================= PID Settings ================================ +//=========================================================================== +// PID Tuning Guide here: http://reprap.org/wiki/PID_Tuning + +// Comment the following line to disable PID and enable bang-bang. +#define PIDTEMP +#define BANG_MAX 255 // limits current to nozzle while in bang-bang mode; 255=full current +#define PID_MAX BANG_MAX // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current +#if ENABLED(PIDTEMP) + //#define PID_AUTOTUNE_MENU // Add PID Autotune to the LCD "Temperature" menu to run M303 and apply the result. + //#define PID_DEBUG // Sends debug data to the serial port. + //#define PID_OPENLOOP 1 // Puts PID in open loop. M104/M140 sets the output power from 0 to PID_MAX + //#define SLOW_PWM_HEATERS // PWM with very low frequency (roughly 0.125Hz=8s) and minimum state time of approximately 1s useful for heaters driven by a relay + //#define PID_PARAMS_PER_HOTEND // Uses separate PID parameters for each extruder (useful for mismatched extruders) + // 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 K1 0.95 //smoothing factor within the PID + + // Geeetech MK8 Extruder + #define DEFAULT_Kp 12.33 + #define DEFAULT_Ki 0.51 + #define DEFAULT_Kd 74.50 + + // CTC MK8 Extruder + //#define DEFAULT_Kp 19.86 + //#define DEFAULT_Ki 1.0 + //#define DEFAULT_Kd 98.83 + + // If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it + + // Ultimaker + //#define DEFAULT_Kp 22.2 + //#define DEFAULT_Ki 1.08 + //#define DEFAULT_Kd 114 + + // MakerGear + //#define DEFAULT_Kp 7.0 + //#define DEFAULT_Ki 0.1 + //#define DEFAULT_Kd 12 + + // Mendel Parts V9 on 12V + //#define DEFAULT_Kp 63.0 + //#define DEFAULT_Ki 2.25 + //#define DEFAULT_Kd 440 + +#endif // PIDTEMP + +//=========================================================================== +//============================= PID > Bed Temperature Control =============== +//=========================================================================== +// Select PID or bang-bang with PIDTEMPBED. If bang-bang, BED_LIMIT_SWITCHING will enable hysteresis +// +// Uncomment this to enable PID on the bed. It uses the same frequency PWM as the extruder. +// If your PID_dT is the default, and correct for your hardware/configuration, that means 7.689Hz, +// which is fine for driving a square wave into a resistive load and does not significantly impact you FET heating. +// This also works fine on a Fotek SSR-10DA Solid State Relay into a 250W heater. +// If your configuration is significantly different than this and you don't understand the issues involved, you probably +// shouldn't use bed PID until someone else verifies your hardware works. +// If this is enabled, find your own PID constants below. +//#define PIDTEMPBED + +//#define BED_LIMIT_SWITCHING + +// This sets the max power delivered to the bed, and replaces the HEATER_BED_DUTY_CYCLE_DIVIDER option. +// all forms of bed control obey this (PID, bang-bang, bang-bang with hysteresis) +// setting this to anything other than 255 enables a form of PWM to the bed just like HEATER_BED_DUTY_CYCLE_DIVIDER did, +// so you shouldn't use it unless you are OK with PWM on your bed. (see the comment on enabling PIDTEMPBED) +#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current + +#if ENABLED(PIDTEMPBED) + + //#define PID_BED_DEBUG // Sends debug data to the serial port. + + //12v (120 watt?) MK2a PCB Heatbed into 4mm borosilicate (Geeetech Prusa i3 Pro, Pro/B/C/X) + #define DEFAULT_bedKp 234.88 + #define DEFAULT_bedKi 42.79 + #define DEFAULT_bedKd 322.28 + + //120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+) + //from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10) + //#define DEFAULT_bedKp 10.00 + //#define DEFAULT_bedKi .023 + //#define DEFAULT_bedKd 305.4 + + //120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+) + //from pidautotune + //#define DEFAULT_bedKp 97.1 + //#define DEFAULT_bedKi 1.41 + //#define DEFAULT_bedKd 1675.16 + + // FIND YOUR OWN: "M303 E-1 C8 S90" to run autotune on the bed at 90 degreesC for 8 cycles. +#endif // PIDTEMPBED + +// @section extruder + +// 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 + +// 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 ======================= +//=========================================================================== + +/** + * Thermal Protection protects your printer from damage and fire if a + * thermistor falls out or temperature sensors fail in any way. + * + * The issue: If a thermistor falls out or a temperature sensor fails, + * Marlin can no longer sense the actual temperature. Since a disconnected + * thermistor reads as a low temperature, the firmware will keep the heater on. + * + * If you get "Thermal Runaway" or "Heating failed" errors the + * details can be tuned in Configuration_adv.h + */ + +#define THERMAL_PROTECTION_HOTENDS // Enable thermal protection for all extruders +#define THERMAL_PROTECTION_BED // Enable thermal protection for the heated bed + +//=========================================================================== +//============================= Mechanical Settings ========================= +//=========================================================================== + +// @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 + +//=========================================================================== +//============================== Endstop Settings =========================== +//=========================================================================== + +// @section homing + +// Specify here all the endstop connectors that are connected to any endstop or probe. +// Almost all printers will be using one per axis. Probes will use one or more of the +// extra connectors. Leave undefined any used for non-endstop and non-probe purposes. +#define USE_XMIN_PLUG +#define USE_YMIN_PLUG +#define USE_ZMIN_PLUG +//#define USE_XMAX_PLUG +//#define USE_YMAX_PLUG +//#define USE_ZMAX_PLUG + +// coarse Endstop Settings +#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors + +#if DISABLED(ENDSTOPPULLUPS) + // fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined + //#define ENDSTOPPULLUP_XMAX + //#define ENDSTOPPULLUP_YMAX + //#define ENDSTOPPULLUP_ZMAX + //#define ENDSTOPPULLUP_XMIN + //#define ENDSTOPPULLUP_YMIN + //#define ENDSTOPPULLUP_ZMIN + //#define ENDSTOPPULLUP_ZMIN_PROBE +#endif + +// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup). +#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 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 probe. + +// 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 + * + * Note that if EEPROM is enabled, saved values will override these. + */ + +/** + * With this option each E stepper can have its own factors for the + * following movement settings. If fewer factors are given than the + * total number of extruders, the last value applies to the rest. + */ +//#define DISTINCT_E_FACTORS + +/** + * Default Axis Steps Per Unit (steps/mm) + * Override with M92 + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] + */ +#define DEFAULT_AXIS_STEPS_PER_UNIT { 78.74, 78.74, 2560, 105 } + +/** + * Default Max Feed Rate (mm/s) + * Override with M203 + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] + */ +#define DEFAULT_MAX_FEEDRATE { 400, 400, 2, 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[, E4]]]] + */ +#define DEFAULT_MAX_ACCELERATION { 5000, 5000, 50, 5000 } + +/** + * 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 2000 // E acceleration for retracts +#define DEFAULT_TRAVEL_ACCELERATION 3000 // X, Y, Z acceleration for travel (non printing) moves + +/** + * Default Jerk (mm/s) + * Override with M205 X Y Z E + * + * "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 + +// +// See http://marlinfw.org/configuration/probes.html +// + +/** + * Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN + * + * Enable this option for a probe connected to the Z Min endstop pin. + */ +//#define Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN + +/** + * Z_MIN_PROBE_ENDSTOP + * + * Enable this option for a probe connected to any pin except Z-Min. + * (By default Marlin assumes the Z-Max endstop pin.) + * To use a custom Z Probe pin, set Z_MIN_PROBE_PIN below. + * + * - The simplest option is to use a free endstop connector. + * - Use 5V for powered (usually inductive) sensors. + * + * - RAMPS 1.3/1.4 boards may use the 5V, GND, and Aux4->D32 pin: + * - For simple switches connect... + * - normally-closed switches to GND and D32. + * - normally-open switches to 5V and D32. + * + * WARNING: Setting the wrong pin may have unexpected and potentially + * disastrous consequences. Use with caution and do your homework. + * + */ +//#define Z_MIN_PROBE_ENDSTOP + +/** + * Probe Type + * + * Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, etc. + * Activate one of these to use Auto Bed Leveling below. + */ + +/** + * The "Manual Probe" provides a means to do "Auto" Bed Leveling without a probe. + * Use G29 repeatedly, adjusting the Z height at each point with movement commands + * or (with LCD_BED_LEVELING) the LCD controller. + */ +//#define PROBE_MANUALLY + +/** + * A Fix-Mounted Probe either doesn't deploy or needs manual deployment. + * (e.g., an inductive probe or a nozzle-based probe-switch.) + */ +//#define FIX_MOUNTED_PROBE + +/** + * Z Servo Probe, such as an endstop switch on a rotating arm. + */ +//#define Z_ENDSTOP_SERVO_NR 0 // Defaults to SERVO 0 connector. +//#define Z_SERVO_ANGLES {70,0} // Z Servo Deploy and Stow angles + +/** + * The BLTouch probe uses a Hall effect sensor and emulates a servo. + */ +//#define BLTOUCH +#if ENABLED(BLTOUCH) + //#define BLTOUCH_DELAY 375 // (ms) Enable and increase if needed +#endif + +/** + * Enable one or more of the following if probing seems unreliable. + * Heaters and/or fans can be disabled during probing to minimize electrical + * noise. A delay can also be added to allow noise and vibration to settle. + * These options are most useful for the BLTouch probe, but may also improve + * readings with inductive probes and piezo sensors. + */ +//#define PROBING_HEATERS_OFF // Turn heaters off when probing +//#define PROBING_FANS_OFF // Turn fans off when probing +//#define DELAY_BEFORE_PROBING 200 // (ms) To prevent vibrations from triggering piezo sensors + +// A probe that is deployed and stowed with a solenoid pin (SOL1_PIN) +//#define SOLENOID_PROBE + +// A sled-mounted probe like those designed by Charles Bell. +//#define Z_PROBE_SLED +//#define SLED_DOCKING_OFFSET 5 // The extra distance the X axis must travel to pickup the sled. 0 should be fine but you can push it further if you'd like. + +// +// For Z_PROBE_ALLEN_KEY see the Delta example configurations. +// + +/** + * Z Probe to nozzle (X,Y) offset, relative to (0, 0). + * X and Y offsets must be integers. + * + * In the following example the X and Y offsets are both positive: + * #define X_PROBE_OFFSET_FROM_EXTRUDER 10 + * #define Y_PROBE_OFFSET_FROM_EXTRUDER 10 + * + * +-- BACK ---+ + * | | + * L | (+) P | R <-- probe (20,20) + * E | | I + * F | (-) N (+) | G <-- nozzle (10,10) + * T | | H + * | (-) | T + * | | + * O-- FRONT --+ + * (0,0) + */ +#define X_PROBE_OFFSET_FROM_EXTRUDER 10 // X offset: -left +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 + +// Speed for the first approach when double-probing (with PROBE_DOUBLE_TOUCH) +#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z + +// Speed for the "accurate" probe of each point +#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2) + +// Use double touch for probing +//#define PROBE_DOUBLE_TOUCH + +/** + * 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 +#define Z_PROBE_OFFSET_RANGE_MIN -20 +#define Z_PROBE_OFFSET_RANGE_MAX 20 + +// Enable the M48 repeatability test to test probe accuracy +//#define Z_MIN_PROBE_REPEATABILITY_TEST + +// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1 +// :{ 0:'Low', 1:'High' } +#define X_ENABLE_ON 0 +#define Y_ENABLE_ON 0 +#define Z_ENABLE_ON 0 +#define E_ENABLE_ON 0 // For all extruders + +// Disables axis stepper immediately when it's not being used. +// 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 +// Warn on display about possibly reduced accuracy +//#define DISABLE_REDUCED_ACCURACY_WARNING + +// @section extruder + +#define DISABLE_E false // For all extruders +#define DISABLE_INACTIVE_EXTRUDER true // Keep only the active extruder enabled. + +// @section machine + +// Invert the stepper direction. Change (or reverse the motor connector) if an axis goes the wrong way. +#define INVERT_X_DIR true +#define INVERT_Y_DIR true +#define INVERT_Z_DIR false + +// Enable this option for Toshiba stepper drivers +//#define CONFIG_STEPPERS_TOSHIBA + +// @section extruder + +// For direct drive extruder v9 set to true, for geared extruder set to false. +#define INVERT_E0_DIR true +#define INVERT_E1_DIR true +#define INVERT_E2_DIR true +#define INVERT_E3_DIR true +#define INVERT_E4_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. + +// Direction of endstops when homing; 1=MAX, -1=MIN +// :[-1,1] +#define X_HOME_DIR -1 +#define Y_HOME_DIR -1 +#define Z_HOME_DIR -1 + +// @section machine + +// The size of the print bed +#define X_BED_SIZE 200 +#define Y_BED_SIZE 200 + +// Travel limits (mm) after homing, corresponding to endstop positions. +#define X_MIN_POS 0 +#define Y_MIN_POS 0 +#define Z_MIN_POS 0 +#define X_MAX_POS X_BED_SIZE +#define Y_MAX_POS Y_BED_SIZE +#define Z_MAX_POS 200 + +// If enabled, axes won't move below MIN_POS in response to movement commands. +#define MIN_SOFTWARE_ENDSTOPS +// If enabled, axes won't move above MAX_POS in response to movement commands. +#define MAX_SOFTWARE_ENDSTOPS + +/** + * Filament Runout Sensor + * A mechanical or opto endstop is used to check for the presence of filament. + * + * RAMPS-based boards use SERVO3_PIN. + * For other boards you may need to define FIL_RUNOUT_PIN. + * By default the firmware assumes HIGH = has filament, LOW = ran out + */ +//#define FILAMENT_RUNOUT_SENSOR +#if ENABLED(FILAMENT_RUNOUT_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 + +//=========================================================================== +//=============================== Bed Leveling ============================== +//=========================================================================== +// @section bedlevel + +/** + * Choose one of the options below to enable G29 Bed Leveling. The parameters + * and behavior of G29 will change depending on your selection. + * + * If using a Probe for Z Homing, enable Z_SAFE_HOMING also! + * + * - AUTO_BED_LEVELING_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. + * + * - AUTO_BED_LEVELING_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. + * + * - AUTO_BED_LEVELING_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. + * + * - AUTO_BED_LEVELING_UBL (Unified Bed Leveling) + * A comprehensive bed leveling system combining the features and benefits + * of other systems. UBL also includes integrated Mesh Generation, Mesh + * Validation and Mesh Editing systems. Currently, UBL is only checked out + * for Cartesian Printers. That said, it was primarily designed to correct + * poor quality Delta Printers. If you feel adventurous and have a Delta, + * please post an issue if something doesn't work correctly. Initially, + * you will need to set a reduced bed size so you have a rectangular area + * to test on. + * + * - MESH_BED_LEVELING + * Probe a grid manually + * The result is a mesh, suitable for large or uneven beds. (See BILINEAR.) + * For machines without a probe, Mesh Bed Leveling provides a method to perform + * leveling in steps so you can manually adjust the Z height at each grid-point. + * With an LCD controller the process is guided step-by-step. + */ +//#define AUTO_BED_LEVELING_3POINT +//#define AUTO_BED_LEVELING_LINEAR +//#define AUTO_BED_LEVELING_BILINEAR +//#define AUTO_BED_LEVELING_UBL +//#define MESH_BED_LEVELING + +/** + * 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(MESH_BED_LEVELING) || ENABLED(AUTO_BED_LEVELING_BILINEAR) || ENABLED(AUTO_BED_LEVELING_UBL) + // 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 + +#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR) + + // Set the number of grid points per dimension. + #define GRID_MAX_POINTS_X 3 + #define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X + + // 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 + + // The Z probe minimum outer margin (to validate G29 parameters). + #define MIN_PROBE_EDGE 10 + + // Probe along the Y axis, advancing X after each column + //#define PROBE_Y_FIRST + + #if ENABLED(AUTO_BED_LEVELING_BILINEAR) + + // Beyond the probed grid, continue the implied tilt? + // Default is to maintain the height of the nearest edge. + //#define EXTRAPOLATE_BEYOND_GRID + + // + // Experimental Subdivision of the grid by Catmull-Rom method. + // Synthesizes intermediate points to produce a more detailed mesh. + // + //#define ABL_BILINEAR_SUBDIVISION + #if ENABLED(ABL_BILINEAR_SUBDIVISION) + // Number of subdivisions between probe points + #define BILINEAR_SUBDIVISIONS 3 + #endif + + #endif + +#elif ENABLED(AUTO_BED_LEVELING_3POINT) + + // 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 + +#elif ENABLED(AUTO_BED_LEVELING_UBL) + + //=========================================================================== + //========================= Unified Bed Leveling ============================ + //=========================================================================== + + #define UBL_MESH_INSET 1 // Mesh inset margin on print area + #define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited. + #define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X + + #define UBL_PROBE_PT_1_X 39 // Probing points for 3-Point leveling of the mesh + #define UBL_PROBE_PT_1_Y 180 + #define UBL_PROBE_PT_2_X 39 + #define UBL_PROBE_PT_2_Y 20 + #define UBL_PROBE_PT_3_X 180 + #define UBL_PROBE_PT_3_Y 20 + + #define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation + #define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle + +#elif ENABLED(MESH_BED_LEVELING) + + //=========================================================================== + //=================================== Mesh ================================== + //=========================================================================== + + #define MESH_INSET 10 // Mesh inset margin on print area + #define GRID_MAX_POINTS_X 3 // Don't use more than 7 points per axis, implementation limited. + #define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X + + //#define MESH_G28_REST_ORIGIN // After homing all axes ('G28' or 'G28 XYZ') rest Z at Z_MIN_POS + +#endif // BED_LEVELING + +/** + * Use the LCD controller for bed leveling + * Requires MESH_BED_LEVELING or PROBE_MANUALLY + */ +//#define LCD_BED_LEVELING + +#if ENABLED(LCD_BED_LEVELING) + #define MBL_Z_STEP 0.025 // Step size while manually probing Z axis. + #define LCD_PROBE_Z_RANGE 4 // Z Range centered on Z_MIN_POS for LCD Z adjustment +#endif + +/** + * 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 + +// The center of the bed is at (X=0, Y=0) +//#define BED_CENTER_AT_0_0 + +// Manually set the home position. Leave these undefined for automatic settings. +// For DELTA this is the top-center of the Cartesian print volume. +//#define MANUAL_X_HOME_POS 0 +//#define MANUAL_Y_HOME_POS 0 +//#define MANUAL_Z_HOME_POS 0 + +// Use "Z Safe Homing" to avoid homing with a Z probe outside the bed area. +// +// With this feature enabled: +// +// - Allow Z homing only after X and Y homing AND stepper drivers still enabled. +// - If stepper drivers time out, it will need X and Y homing again before Z homing. +// - Move the Z probe (or nozzle) to a defined XY point before Z Homing when homing all axes (G28). +// - Prevent Z homing when the Z probe is outside bed area. +// +//#define Z_SAFE_HOMING + +#if ENABLED(Z_SAFE_HOMING) + #define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axis (G28). + #define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axis (G28). +#endif + +// Homing speeds (mm/m) +#define HOMING_FEEDRATE_XY (50*60) +#define HOMING_FEEDRATE_Z (4*60) + +//============================================================================= +//============================= Additional Features =========================== +//============================================================================= + +// @section extras + +// +// EEPROM +// +// The microcontroller can store settings in the EEPROM, e.g. max velocity... +// M500 - stores parameters in EEPROM +// 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 EEPROM_SETTINGS // Enable for M500 and M501 commands +//#define DISABLE_M503 // Saves ~2700 bytes of PROGMEM. Disable for release! +#define EEPROM_CHITCHAT // Give feedback on EEPROM commands. Disable to save PROGMEM. + +// +// Host Keepalive +// +// 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 BUSY_WHILE_HEATING // Some hosts require "busy" messages even during heating + +// +// M100 Free Memory Watcher +// +//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose + +// +// G20/G21 Inch mode support +// +//#define INCH_MODE_SUPPORT + +// +// M149 Set temperature units support +// +//#define TEMPERATURE_UNITS_SUPPORT + +// @section temperature + +// Preheat Constants +#define PREHEAT_1_TEMP_HOTEND 180 +#define PREHEAT_1_TEMP_BED 70 +#define PREHEAT_1_FAN_SPEED 0 // Value from 0 to 255 + +#define PREHEAT_2_TEMP_HOTEND 240 +#define PREHEAT_2_TEMP_BED 110 +#define PREHEAT_2_FAN_SPEED 0 // Value from 0 to 255 + +/** + * Nozzle Park -- EXPERIMENTAL + * + * Park the nozzle at the given XYZ position on idle or G27. + * + * The "P" parameter controls the action applied to the Z axis: + * + * P0 (Default) If Z is below park Z raise the nozzle. + * P1 Raise the nozzle always to Z-park height. + * P2 Raise the nozzle by Z-park amount, limited to Z_MAX_POS. + */ +//#define NOZZLE_PARK_FEATURE + +#if ENABLED(NOZZLE_PARK_FEATURE) + // Specify a park position as { X, Y, Z } + #define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 } +#endif + +/** + * Clean Nozzle Feature -- EXPERIMENTAL + * + * Adds the G12 command to perform a nozzle cleaning process. + * + * Parameters: + * P Pattern + * S Strokes / Repetitions + * T Triangles (P1 only) + * + * Patterns: + * P0 Straight line (default). This process requires a sponge type material + * at a fixed bed location. "S" specifies strokes (i.e. back-forth motions) + * between the start / end points. + * + * P1 Zig-zag pattern between (X0, Y0) and (X1, Y1), "T" specifies the + * number of zig-zag triangles to do. "S" defines the number of strokes. + * Zig-zags are done in whichever is the narrower dimension. + * For example, "G12 P1 S1 T3" will execute: + * + * -- + * | (X0, Y1) | /\ /\ /\ | (X1, Y1) + * | | / \ / \ / \ | + * A | | / \ / \ / \ | + * | | / \ / \ / \ | + * | (X0, Y0) | / \/ \/ \ | (X1, Y0) + * -- +--------------------------------+ + * |________|_________|_________| + * T1 T2 T3 + * + * P2 Circular pattern with middle at NOZZLE_CLEAN_CIRCLE_MIDDLE. + * "R" specifies the radius. "S" specifies the stroke count. + * Before starting, the nozzle moves to NOZZLE_CLEAN_START_POINT. + * + * Caveats: The ending Z should be the same as starting Z. + * Attention: EXPERIMENTAL. G-code arguments may change. + * + */ +//#define NOZZLE_CLEAN_FEATURE + +#if ENABLED(NOZZLE_CLEAN_FEATURE) + // Default number of pattern repetitions + #define NOZZLE_CLEAN_STROKES 12 + + // Default number of triangles + #define NOZZLE_CLEAN_TRIANGLES 3 + + // Specify positions as { X, Y, Z } + #define NOZZLE_CLEAN_START_POINT { 30, 30, (Z_MIN_POS + 1)} + #define NOZZLE_CLEAN_END_POINT {100, 60, (Z_MIN_POS + 1)} + + // Circular pattern radius + #define NOZZLE_CLEAN_CIRCLE_RADIUS 6.5 + // Circular pattern circle fragments number + #define NOZZLE_CLEAN_CIRCLE_FN 10 + // Middle point of circle + #define NOZZLE_CLEAN_CIRCLE_MIDDLE NOZZLE_CLEAN_START_POINT + + // Moves the nozzle to the initial position + #define NOZZLE_CLEAN_GOBACK +#endif + +/** + * Print Job Timer + * + * Automatically start and stop the print job timer on M104/M109/M190. + * + * M104 (hotend, no wait) - high temp = none, low temp = stop timer + * M109 (hotend, wait) - high temp = start timer, low temp = stop timer + * M190 (bed, wait) - high temp = start timer, low temp = none + * + * The timer can also be controlled with the following commands: + * + * M75 - Start the print job timer + * M76 - Pause the print job timer + * M77 - Stop the print job timer + */ +#define PRINTJOB_TIMER_AUTOSTART + +/** + * Print Counter + * + * Track statistical data such as: + * + * - Total print jobs + * - Total successful print jobs + * - Total failed print jobs + * - Total time printing + * + * View the current statistics with M78. + */ +//#define PRINTCOUNTER + +//============================================================================= +//============================= LCD and SD support ============================ +//============================================================================= + +// @section lcd + +/** + * LCD LANGUAGE + * + * Select the language to display on the LCD. These languages are available: + * + * en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr, + * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, + * zh_CN, zh_TW, test + * + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } + */ +#define LCD_LANGUAGE en + +/** + * LCD Character Set + * + * Note: This option is NOT applicable to Graphical Displays. + * + * All character-based LCDs provide ASCII plus one of these + * language extensions: + * + * - JAPANESE ... the most common + * - WESTERN ... with more accented characters + * - CYRILLIC ... for the Russian language + * + * To determine the language extension installed on your controller: + * + * - Compile and upload with LCD_LANGUAGE set to 'test' + * - Click the controller to view the LCD menu + * - The LCD will display Japanese, Western, or Cyrillic text + * + * See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language + * + * :['JAPANESE', 'WESTERN', 'CYRILLIC'] + */ +#define DISPLAY_CHARSET_HD44780 JAPANESE + +/** + * LCD TYPE + * + * Enable ULTRA_LCD for a 16x2, 16x4, 20x2, or 20x4 character-based LCD. + * Enable DOGLCD for a 128x64 (ST7565R) Full Graphical Display. + * (These options will be enabled automatically for most displays.) + * + * IMPORTANT: The U8glib library is required for Full Graphic Display! + * https://github.com/olikraus/U8glib_Arduino + */ +//#define ULTRA_LCD // Character based +//#define DOGLCD // Full graphics display + +/** + * SD CARD + * + * SD Card support is disabled by default. If your controller has an SD slot, + * you must uncomment the following option or it won't work. + * + */ +//#define SDSUPPORT + +/** + * SD CARD: SPI SPEED + * + * Enable one of the following items for a slower SPI transfer speed. + * This may be required to resolve "volume init" errors. + */ +//#define SPI_SPEED SPI_HALF_SPEED +//#define SPI_SPEED SPI_QUARTER_SPEED +//#define SPI_SPEED SPI_EIGHTH_SPEED + +/** + * SD CARD: ENABLE CRC + * + * Use CRC checks and retries on the SD communication. + */ +//#define SD_CHECK_AND_RETRY + +// +// ENCODER SETTINGS +// +// 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 + +// +// 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 + +/** + * Encoder Direction Options + * + * Test your encoder's behavior first with both options disabled. + * + * Reversed Value Edit and Menu Nav? Enable REVERSE_ENCODER_DIRECTION. + * Reversed Menu Navigation only? Enable REVERSE_MENU_DIRECTION. + * Reversed Value Editing only? Enable BOTH options. + */ + +// +// This option reverses the encoder direction everywhere. +// +// Set this option if CLOCKWISE causes values to DECREASE +// +//#define REVERSE_ENCODER_DIRECTION + +// +// This option reverses the encoder direction for navigating LCD menus. +// +// If CLOCKWISE normally moves DOWN this makes it go UP. +// If CLOCKWISE normally moves UP this makes it go DOWN. +// +//#define REVERSE_MENU_DIRECTION + +// +// Individual Axis Homing +// +// Add individual axis homing items (Home X, Home Y, and Home Z) to the LCD menu. +// +//#define INDIVIDUAL_AXIS_HOMING_MENU + +// +// SPEAKER/BUZZER +// +// If you have a speaker that can produce tones, enable it here. +// By default Marlin assumes you have a buzzer with a fixed frequency. +// +//#define SPEAKER + +// +// The duration and frequency for the UI feedback sound. +// Set these to 0 to disable audio feedback in the LCD menus. +// +// Note: Test audio output with the G-Code: +// M300 S P +// +//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100 +//#define LCD_FEEDBACK_FREQUENCY_HZ 1000 + +// +// CONTROLLER TYPE: Standard +// +// Marlin supports a wide variety of controllers. +// Enable one of the following options to specify your controller. +// + +// +// ULTIMAKER Controller. +// +//#define ULTIMAKERCONTROLLER + +// +// ULTIPANEL as seen on Thingiverse. +// +//#define ULTIPANEL + +// +// PanelOne from T3P3 (via RAMPS 1.4 AUX2/AUX3) +// http://reprap.org/wiki/PanelOne +// +//#define PANEL_ONE + +// +// MaKr3d Makr-Panel with graphic controller and SD support. +// http://reprap.org/wiki/MaKr3d_MaKrPanel +// +//#define MAKRPANEL + +// +// ReprapWorld Graphical LCD +// https://reprapworld.com/?products_details&products_id/1218 +// +//#define REPRAPWORLD_GRAPHICAL_LCD + +// +// Activate one of these if you have a Panucatt Devices +// Viki 2.0 or mini Viki with Graphic LCD +// http://panucatt.com +// +//#define VIKI2 +//#define miniVIKI + +// +// Adafruit ST7565 Full Graphic Controller. +// https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/ +// +//#define ELB_FULL_GRAPHIC_CONTROLLER + +// +// RepRapDiscount Smart Controller. +// http://reprap.org/wiki/RepRapDiscount_Smart_Controller +// +// Note: Usually sold with a white PCB. +// +#define REPRAP_DISCOUNT_SMART_CONTROLLER + +// +// GADGETS3D G3D LCD/SD Controller +// http://reprap.org/wiki/RAMPS_1.3/1.4_GADGETS3D_Shield_with_Panel +// +// Note: Usually sold with a blue PCB. +// +//#define G3D_PANEL + +// +// RepRapDiscount FULL GRAPHIC Smart Controller +// http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller +// +//#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER + +// +// MakerLab Mini Panel with graphic +// controller and SD support - http://reprap.org/wiki/Mini_panel +// +//#define MINIPANEL + +// +// RepRapWorld REPRAPWORLD_KEYPAD v1.1 +// http://reprapworld.com/?products_details&products_id=202&cPath=1591_1626 +// +// REPRAPWORLD_KEYPAD_MOVE_STEP sets how much should the robot move when a key +// is pressed, a value of 10.0 means 10mm per click. +// +//#define REPRAPWORLD_KEYPAD +//#define REPRAPWORLD_KEYPAD_MOVE_STEP 1.0 + +// +// RigidBot Panel V1.0 +// http://www.inventapart.com/ +// +//#define RIGIDBOT_PANEL + +// +// BQ LCD Smart Controller shipped by +// default with the BQ Hephestos 2 and Witbox 2. +// +//#define BQ_LCD_SMART_CONTROLLER + +// +// Cartesio UI +// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface +// +//#define CARTESIO_UI + +// +// ANET_10 Controller supported displays. +// +//#define ANET_KEYPAD_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin. + // This LCD is known to be susceptible to electrical interference + // which scrambles the display. Pressing any button clears it up. +//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6 + // A clone of the RepRapDiscount full graphics display but with + // different pins/wiring (see pins_ANET_10.h). + +// +// LCD for Melzi Card with Graphical LCD +// +//#define LCD_FOR_MELZI + +// +// CONTROLLER TYPE: I2C +// +// Note: These controllers require the installation of Arduino's LiquidCrystal_I2C +// library. For more info: https://github.com/kiyoshigawa/LiquidCrystal_I2C +// + +// +// Elefu RA Board Control Panel +// http://www.elefu.com/index.php?route=product/product&product_id=53 +// +//#define RA_CONTROL_PANEL + +// +// Sainsmart YW Robot (LCM1602) LCD Display +// +// Note: This controller requires F.Malpartida's LiquidCrystal_I2C library +// https://bitbucket.org/fmalpartida/new-liquidcrystal/wiki/Home +// +//#define LCD_I2C_SAINSMART_YWROBOT + +// +// Generic LCM1602 LCD adapter +// +//#define LCM1602 + +// +// PANELOLU2 LCD with status LEDs, +// separate encoder and click inputs. +// +// Note: This controller requires Arduino's LiquidTWI2 library v1.2.3 or later. +// For more info: https://github.com/lincomatic/LiquidTWI2 +// +// Note: The PANELOLU2 encoder click input can either be directly connected to +// a pin (if BTN_ENC defined to != -1) or read through I2C (when BTN_ENC == -1). +// +//#define LCD_I2C_PANELOLU2 + +// +// Panucatt VIKI LCD with status LEDs, +// integrated click & L/R/U/D buttons, separate encoder inputs. +// +//#define LCD_I2C_VIKI + +// +// SSD1306 OLED full graphics generic display +// +//#define U8GLIB_SSD1306 + +// +// SAV OLEd LCD module support using either SSD1306 or SH1106 based LCD modules +// +//#define SAV_3DGLCD +#if ENABLED(SAV_3DGLCD) + //#define U8GLIB_SSD1306 + #define U8GLIB_SH1106 +#endif + +// +// CONTROLLER TYPE: Shift register panels +// +// 2 wire Non-latching LCD SR from https://goo.gl/aJJ4sH +// LCD configuration: http://reprap.org/wiki/SAV_3D_LCD +// +//#define SAV_3DLCD + +// +// TinyBoy2 128x64 OLED / Encoder Panel +// +//#define OLED_PANEL_TINYBOY2 + +//============================================================================= +//=============================== Extra Features ============================== +//============================================================================= + +// @section extras + +// Increase the FAN PWM frequency. Removes the PWM noise but increases heating in the FET/Arduino +//#define FAST_PWM_FAN + +// Use software PWM to drive the fan, as for the heaters. This uses a very low frequency +// which is not as annoying as with the hardware PWM. On the other hand, if this frequency +// is too low, you should also increment SOFT_PWM_SCALE. +//#define FAN_SOFT_PWM + +// Incrementing this by 1 will double the software PWM frequency, +// affecting heaters, and the fan if FAN_SOFT_PWM is enabled. +// However, control resolution will be halved for each increment; +// at zero value, there are 128 effective control positions. +#define SOFT_PWM_SCALE 0 + +// If SOFT_PWM_SCALE is set to a value higher than 0, dithering can +// be used to mitigate the associated resolution loss. If enabled, +// some of the PWM cycles are stretched so on average the desired +// duty cycle is attained. +//#define SOFT_PWM_DITHER + +// Temperature status LEDs that display the hotend and bed temperature. +// If all hotends, bed temperature, and target temperature are under 54C +// then the BLUE led is on. Otherwise the RED led is on. (1C hysteresis) +//#define TEMP_STAT_LEDS + +// M240 Triggers a camera by emulating a Canon RC-1 Remote +// Data from: http://www.doc-diy.net/photo/rc-1_hacked/ +//#define PHOTOGRAPH_PIN 23 + +// SkeinForge sends the wrong arc g-codes when using Arc Point as fillet procedure +//#define SF_ARC_FIX + +// Support for the BariCUDA Paste Extruder +//#define BARICUDA + +// Support for BlinkM/CyzRgb +//#define BLINKM + +// Support for PCA9632 PWM LED driver +//#define PCA9632 + +/** + * RGB LED / LED Strip Control + * + * Enable support for an RGB LED connected to 5V digital pins, or + * an RGB Strip connected to MOSFETs controlled by digital pins. + * + * Adds the M150 command to set the LED (or LED strip) color. + * If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of + * luminance values can be set from 0 to 255. + * + * *** CAUTION *** + * LED Strips require a MOFSET Chip between PWM lines and LEDs, + * as the Arduino cannot handle the current the LEDs will require. + * Failure to follow this precaution can destroy your Arduino! + * *** CAUTION *** + * + */ +//#define RGB_LED +//#define RGBW_LED +#if ENABLED(RGB_LED) || ENABLED(RGBW_LED) + #define RGB_LED_R_PIN 34 + #define RGB_LED_G_PIN 43 + #define RGB_LED_B_PIN 35 + #define RGB_LED_W_PIN -1 +#endif + +// Support for Adafruit Neopixel LED driver +//#define NEOPIXEL_RGBW_LED +#if ENABLED(NEOPIXEL_RGBW_LED) + #define NEOPIXEL_PIN 4 // D4 (EXP2-5 on Printrboard) + #define NEOPIXEL_PIXELS 3 + //#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup +#endif + +/** + * Printer Event LEDs + * + * During printing, the LEDs will reflect the printer status: + * + * - Gradually change from blue to violet as the heated bed gets to target temp + * - Gradually change from violet to red as the hotend gets to temperature + * - Change to white to illuminate work surface + * - Change to green once print has finished + * - Turn off after the print has finished and the user has pushed a button + */ +#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_RGBW_LED) + #define PRINTER_EVENT_LEDS +#endif + +/*********************************************************************\ +* R/C SERVO support +* Sponsored by TrinityLabs, Reworked by codexmas +**********************************************************************/ + +// Number of servos +// +// If you select a configuration below, this will receive a default value and does not need to be set manually +// set it manually if you have more servos than extruders and wish to manually control some +// leaving it undefined or defining as 0 will disable the servo subsystem +// If unsure, leave commented / disabled +// +//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command + +// Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle. +// 300ms is a good value but you can try less delay. +// If the servo can't reach the requested position, increase it. +#define SERVO_DELAY 300 + +// Servo deactivation +// +// With this option servos are powered only during movement, then turned off to prevent jitter. +//#define DEACTIVATE_SERVOS_AFTER_MOVE + +/** + * Filament Width Sensor + * + * Measures the filament width in real-time and adjusts + * flow rate to compensate for any irregularities. + * + * Also allows the measured filament diameter to set the + * extrusion rate, so the slicer only has to specify the + * volume. + * + * Only a single extruder is supported at this time. + * + * 34 RAMPS_14 : Analog input 5 on the AUX2 connector + * 81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E) + * 301 RAMBO : Analog input 3 + * + * Note: May require analog pins to be defined for other boards. + */ +//#define FILAMENT_WIDTH_SENSOR + +#define DEFAULT_NOMINAL_FILAMENT_DIA 1.75 // (mm) Diameter of the filament generally used (3.0 or 1.75mm), also used in the slicer. Used to validate sensor reading. + +#if ENABLED(FILAMENT_WIDTH_SENSOR) + #define FILAMENT_SENSOR_EXTRUDER_NUM 0 // Index of the extruder that has the filament sensor (0,1,2,3) + #define MEASUREMENT_DELAY_CM 14 // (cm) The distance from the filament sensor to the melting chamber + + #define MEASURED_UPPER_LIMIT 3.30 // (mm) Upper limit used to validate sensor reading + #define MEASURED_LOWER_LIMIT 1.90 // (mm) Lower limit used to validate sensor reading + #define MAX_MEASUREMENT_DELAY 20 // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM. + + #define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially + + // Display filament width on the LCD status line. Status messages will expire after 5 seconds. + //#define FILAMENT_LCD_DISPLAY +#endif + +/** + * Customize common displays for GT2560 + */ +#if ENABLED(ULTIMAKERCONTROLLER) || ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) || ENABLED(G3D_PANEL) + #define SDSUPPORT // Force SD Card support on for these displays +#elif ENABLED(ULTRA_LCD) && ENABLED(DOGLCD) // No panel, just graphical LCD? + #define LCD_WIDTH 20 // Default is 22. For this Geeetech use 20 +#endif + +#endif // CONFIGURATION_H diff --git a/Marlin/example_configurations/Geeetech/I3_Pro_X-GT2560/Configuration.h b/Marlin/example_configurations/Geeetech/I3_Pro_X-GT2560/Configuration.h index d2cdbd18b..d7e024dce 100644 --- a/Marlin/example_configurations/Geeetech/I3_Pro_X-GT2560/Configuration.h +++ b/Marlin/example_configurations/Geeetech/I3_Pro_X-GT2560/Configuration.h @@ -524,7 +524,6 @@ * Override with M201 * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ - #define DEFAULT_MAX_ACCELERATION { 4000, 4000, 40, 4000 } /** diff --git a/Marlin/pins.h b/Marlin/pins.h index 93aedd3f3..867b5ac25 100644 --- a/Marlin/pins.h +++ b/Marlin/pins.h @@ -192,6 +192,10 @@ #include "pins_SAINSMART_2IN1.h" #elif MB(ZRIB_V20) #include "pins_ZRIB_V20.h" +#elif MB(GT2560_REV_A) + #include "pins_GT2560_REV_A.h" +#elif MB(GT2560_REV_A_PLUS) + #include "pins_GT2560_REV_A_PLUS.h" #else #error "Unknown MOTHERBOARD value set in Configuration.h" #endif diff --git a/Marlin/pins_GT2560_REV_A.h b/Marlin/pins_GT2560_REV_A.h new file mode 100644 index 000000000..cb85c1223 --- /dev/null +++ b/Marlin/pins_GT2560_REV_A.h @@ -0,0 +1,133 @@ +/** + * 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 . + * + */ + +/** + * Geeetech GT2560 Revision A board pin assignments, based on the work of + * George Robles (https://georges3dprinters.com) and + * Richard Smith + */ + +#if !defined(__AVR_ATmega1280__) && !defined(__AVR_ATmega2560__) + #error "Oops! Make sure you have 'Arduino Mega' selected from the 'Tools -> Boards' menu." +#endif + +#define BOARD_NAME "GT2560 Rev.A" +#define DEFAULT_MACHINE_NAME "Prusa i3 Pro B" +#define LARGE_FLASH true + +// +// 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 + +// +// Steppers +// +#define X_STEP_PIN 25 +#define X_DIR_PIN 23 +#define X_ENABLE_PIN 27 + +#define Y_STEP_PIN 31 +#define Y_DIR_PIN 33 +#define Y_ENABLE_PIN 29 + +#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 E1_STEP_PIN 49 +#define E1_DIR_PIN 47 +#define E1_ENABLE_PIN 48 + +// +// Temperature Sensors +// +#define TEMP_0_PIN 8 +#define TEMP_1_PIN 9 +#define TEMP_BED_PIN 10 + +// +// Heaters / Fans +// +#define HEATER_0_PIN 2 +#define HEATER_1_PIN 3 +#define HEATER_BED_PIN 4 +#define FAN_PIN 7 + +// +// Misc. Functions +// +#define SDPOWER -1 +#define SDSS 53 +#define LED_PIN 13 +#define PS_ON_PIN 12 +#define SUICIDE_PIN 54 // Must be enabled at startup to keep power flowing +#define KILL_PIN -1 + +#if ENABLED(ULTRA_LCD) + + #define BEEPER_PIN 18 + + #if ENABLED(NEWPANEL) + + #define LCD_PINS_RS 20 + #define LCD_PINS_ENABLE 17 + #define LCD_PINS_D4 16 + #define LCD_PINS_D5 21 + #define LCD_PINS_D6 5 + #define LCD_PINS_D7 6 + + // Buttons are directly attached + #define BTN_EN1 42 + #define BTN_EN2 40 + #define BTN_ENC 19 + + #define SD_DETECT_PIN 38 + + #else // !NEWPANEL + + #define SHIFT_CLK 38 + #define SHIFT_LD 42 + #define SHIFT_OUT 40 + #define SHIFT_EN 17 + + #define LCD_PINS_RS 16 + #define LCD_PINS_ENABLE 5 + #define LCD_PINS_D4 6 + #define LCD_PINS_D5 21 + #define LCD_PINS_D6 20 + #define LCD_PINS_D7 19 + + #define SD_DETECT_PIN -1 + + #endif // !NEWPANEL + +#endif // ULTRA_LCD diff --git a/Marlin/pins_GT2560_REV_A_PLUS.h b/Marlin/pins_GT2560_REV_A_PLUS.h new file mode 100644 index 000000000..a99a39da8 --- /dev/null +++ b/Marlin/pins_GT2560_REV_A_PLUS.h @@ -0,0 +1,31 @@ +/** + * 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 . + * + */ + +/** + * Geeetech GT2560 Revision A+ board pin assignments + */ + +#include "pins_GT2560_REV_A.h" + +#define BOARD_NAME "GT2560 Rev.A+" + +#define SERVO0_PIN 11 From 7f3406d47b89c053b8db2901cfb7a94975a8f53c Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 10 Aug 2017 15:41:35 -0500 Subject: [PATCH 071/112] Fix Italian string length Addressing #7264 --- Marlin/language_it.h | 20 ++++++++++---------- 1 file changed, 10 insertions(+), 10 deletions(-) diff --git a/Marlin/language_it.h b/Marlin/language_it.h index 532650014..db93a7eb6 100644 --- a/Marlin/language_it.h +++ b/Marlin/language_it.h @@ -56,17 +56,17 @@ #define MSG_HOME_OFFSETS_APPLIED _UxGT("Offset applicato") #define MSG_SET_ORIGIN _UxGT("Imposta Origine") #define MSG_PREHEAT_1 _UxGT("Preriscalda PLA") -#define MSG_PREHEAT_1_N MSG_PREHEAT_1 _UxGT(" ") -#define MSG_PREHEAT_1_ALL MSG_PREHEAT_1 _UxGT(" Tutto") -#define MSG_PREHEAT_1_END MSG_PREHEAT_1 _UxGT(" Ugello") -#define MSG_PREHEAT_1_BEDONLY MSG_PREHEAT_1 _UxGT(" Piatto") -#define MSG_PREHEAT_1_SETTINGS MSG_PREHEAT_1 _UxGT(" conf") +#define MSG_PREHEAT_1_N _UxGT("Prerisc.PLA ") +#define MSG_PREHEAT_1_ALL MSG_PREHEAT_1_N _UxGT("Tutto") +#define MSG_PREHEAT_1_END MSG_PREHEAT_1_N _UxGT("Ugello") +#define MSG_PREHEAT_1_BEDONLY MSG_PREHEAT_1_N _UxGT("Piatto") +#define MSG_PREHEAT_1_SETTINGS MSG_PREHEAT_1_N _UxGT("conf") #define MSG_PREHEAT_2 _UxGT("Preriscalda ABS") -#define MSG_PREHEAT_2_N MSG_PREHEAT_2 _UxGT(" ") -#define MSG_PREHEAT_2_ALL MSG_PREHEAT_2 _UxGT(" Tutto") -#define MSG_PREHEAT_2_END MSG_PREHEAT_2 _UxGT(" Ugello") -#define MSG_PREHEAT_2_BEDONLY MSG_PREHEAT_2 _UxGT(" Piatto") -#define MSG_PREHEAT_2_SETTINGS MSG_PREHEAT_2 _UxGT(" conf") +#define MSG_PREHEAT_2_N _UxGT("Prerisc.ABS ") +#define MSG_PREHEAT_2_ALL MSG_PREHEAT_2_N _UxGT("Tutto") +#define MSG_PREHEAT_2_END MSG_PREHEAT_2_N _UxGT("Ugello") +#define MSG_PREHEAT_2_BEDONLY MSG_PREHEAT_2_N _UxGT("Piatto") +#define MSG_PREHEAT_2_SETTINGS MSG_PREHEAT_2_N _UxGT("conf") #define MSG_COOLDOWN _UxGT("Raffredda") #define MSG_SWITCH_PS_ON _UxGT("Accendi aliment.") #define MSG_SWITCH_PS_OFF _UxGT("Spegni aliment.") From 25a11cd485aabc892bcdc36f83027e03cdb7b27c Mon Sep 17 00:00:00 2001 From: Frederik Kemner Date: Thu, 10 Aug 2017 14:53:04 -0700 Subject: [PATCH 072/112] Use bed size and inset instead of travel limits to define mesh area\n\nAs proposed in #7435 (#7480) --- Marlin/Configuration_adv.h | 16 ++++++++-------- .../AlephObjects/TAZ4/Configuration_adv.h | 16 ++++++++-------- .../Anet/A6/Configuration_adv.h | 16 ++++++++-------- .../Anet/A8/Configuration_adv.h | 16 ++++++++-------- .../BQ/Hephestos/Configuration_adv.h | 16 ++++++++-------- .../BQ/Hephestos_2/Configuration_adv.h | 16 ++++++++-------- .../BQ/WITBOX/Configuration_adv.h | 16 ++++++++-------- .../Cartesio/Configuration_adv.h | 16 ++++++++-------- .../Felix/Configuration_adv.h | 16 ++++++++-------- .../Folger Tech/i3-2020/Configuration_adv.h | 16 ++++++++-------- .../Infitary/i3-M508/Configuration_adv.h | 16 ++++++++-------- .../Malyan/M150/Configuration_adv.h | 16 ++++++++-------- .../RigidBot/Configuration_adv.h | 16 ++++++++-------- .../SCARA/Configuration_adv.h | 16 ++++++++-------- .../TinyBoy2/Configuration_adv.h | 16 ++++++++-------- .../Velleman/K8200/Configuration_adv.h | 16 ++++++++-------- .../Velleman/K8400/Configuration_adv.h | 16 ++++++++-------- .../FLSUN/auto_calibrate/Configuration_adv.h | 16 ++++++++-------- .../delta/FLSUN/kossel_mini/Configuration_adv.h | 16 ++++++++-------- .../delta/generic/Configuration_adv.h | 16 ++++++++-------- .../delta/kossel_mini/Configuration_adv.h | 16 ++++++++-------- .../delta/kossel_pro/Configuration_adv.h | 16 ++++++++-------- .../delta/kossel_xl/Configuration_adv.h | 16 ++++++++-------- .../gCreate/gMax1.5+/Configuration_adv.h | 16 ++++++++-------- .../makibox/Configuration_adv.h | 16 ++++++++-------- .../tvrrug/Round2/Configuration_adv.h | 16 ++++++++-------- .../wt150/Configuration_adv.h | 16 ++++++++-------- 27 files changed, 216 insertions(+), 216 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 43be4998e..fc7865401 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -661,15 +661,15 @@ // Below are the macros that are used to define the borders for the mesh area, // made available here for specialized needs, ie dual extruder setup. #if ENABLED(MESH_BED_LEVELING) - #define MESH_MIN_X (X_MIN_POS + MESH_INSET) - #define MESH_MAX_X (X_MAX_POS - (MESH_INSET)) - #define MESH_MIN_Y (Y_MIN_POS + MESH_INSET) - #define MESH_MAX_Y (Y_MAX_POS - (MESH_INSET)) + #define MESH_MIN_X MESH_INSET + #define MESH_MAX_X (X_BED_SIZE - (MESH_INSET)) + #define MESH_MIN_Y MESH_INSET + #define MESH_MAX_Y (Y_BED_SIZE - (MESH_INSET)) #elif ENABLED(AUTO_BED_LEVELING_UBL) - #define UBL_MESH_MIN_X (X_MIN_POS + UBL_MESH_INSET) - #define UBL_MESH_MAX_X (X_MAX_POS - (UBL_MESH_INSET)) - #define UBL_MESH_MIN_Y (Y_MIN_POS + UBL_MESH_INSET) - #define UBL_MESH_MAX_Y (Y_MAX_POS - (UBL_MESH_INSET)) + #define UBL_MESH_MIN_X UBL_MESH_INSET + #define UBL_MESH_MAX_X (X_BED_SIZE - (UBL_MESH_INSET)) + #define UBL_MESH_MIN_Y UBL_MESH_INSET + #define UBL_MESH_MAX_Y (Y_BED_SIZE - (UBL_MESH_INSET)) // If this is defined, the currently active mesh will be saved in the // current slot on M500. diff --git a/Marlin/example_configurations/AlephObjects/TAZ4/Configuration_adv.h b/Marlin/example_configurations/AlephObjects/TAZ4/Configuration_adv.h index 5511b1187..723d3d12e 100644 --- a/Marlin/example_configurations/AlephObjects/TAZ4/Configuration_adv.h +++ b/Marlin/example_configurations/AlephObjects/TAZ4/Configuration_adv.h @@ -661,15 +661,15 @@ // Below are the macros that are used to define the borders for the mesh area, // made available here for specialized needs, ie dual extruder setup. #if ENABLED(MESH_BED_LEVELING) - #define MESH_MIN_X (X_MIN_POS + MESH_INSET) - #define MESH_MAX_X (X_MAX_POS - (MESH_INSET)) - #define MESH_MIN_Y (Y_MIN_POS + MESH_INSET) - #define MESH_MAX_Y (Y_MAX_POS - (MESH_INSET)) + #define MESH_MIN_X MESH_INSET + #define MESH_MAX_X (X_BED_SIZE - (MESH_INSET)) + #define MESH_MIN_Y MESH_INSET + #define MESH_MAX_Y (Y_BED_SIZE - (MESH_INSET)) #elif ENABLED(AUTO_BED_LEVELING_UBL) - #define UBL_MESH_MIN_X (X_MIN_POS + UBL_MESH_INSET) - #define UBL_MESH_MAX_X (X_MAX_POS - (UBL_MESH_INSET)) - #define UBL_MESH_MIN_Y (Y_MIN_POS + UBL_MESH_INSET) - #define UBL_MESH_MAX_Y (Y_MAX_POS - (UBL_MESH_INSET)) + #define UBL_MESH_MIN_X UBL_MESH_INSET + #define UBL_MESH_MAX_X (X_BED_SIZE - (UBL_MESH_INSET)) + #define UBL_MESH_MIN_Y UBL_MESH_INSET + #define UBL_MESH_MAX_Y (Y_BED_SIZE - (UBL_MESH_INSET)) // If this is defined, the currently active mesh will be saved in the // current slot on M500. diff --git a/Marlin/example_configurations/Anet/A6/Configuration_adv.h b/Marlin/example_configurations/Anet/A6/Configuration_adv.h index 265f54429..24ee3e25c 100644 --- a/Marlin/example_configurations/Anet/A6/Configuration_adv.h +++ b/Marlin/example_configurations/Anet/A6/Configuration_adv.h @@ -661,15 +661,15 @@ // Below are the macros that are used to define the borders for the mesh area, // made available here for specialized needs, ie dual extruder setup. #if ENABLED(MESH_BED_LEVELING) - #define MESH_MIN_X (X_MIN_POS + MESH_INSET) - #define MESH_MAX_X (X_MAX_POS - (MESH_INSET)) - #define MESH_MIN_Y (Y_MIN_POS + MESH_INSET) - #define MESH_MAX_Y (Y_MAX_POS - (MESH_INSET)) + #define MESH_MIN_X MESH_INSET + #define MESH_MAX_X (X_BED_SIZE - (MESH_INSET)) + #define MESH_MIN_Y MESH_INSET + #define MESH_MAX_Y (Y_BED_SIZE - (MESH_INSET)) #elif ENABLED(AUTO_BED_LEVELING_UBL) - #define UBL_MESH_MIN_X (X_MIN_POS + UBL_MESH_INSET) - #define UBL_MESH_MAX_X (X_MAX_POS - (UBL_MESH_INSET)) - #define UBL_MESH_MIN_Y (Y_MIN_POS + UBL_MESH_INSET) - #define UBL_MESH_MAX_Y (Y_MAX_POS - (UBL_MESH_INSET)) + #define UBL_MESH_MIN_X UBL_MESH_INSET + #define UBL_MESH_MAX_X (X_BED_SIZE - (UBL_MESH_INSET)) + #define UBL_MESH_MIN_Y UBL_MESH_INSET + #define UBL_MESH_MAX_Y (Y_BED_SIZE - (UBL_MESH_INSET)) // If this is defined, the currently active mesh will be saved in the // current slot on M500. diff --git a/Marlin/example_configurations/Anet/A8/Configuration_adv.h b/Marlin/example_configurations/Anet/A8/Configuration_adv.h index ee2229416..0ff1fb0d1 100644 --- a/Marlin/example_configurations/Anet/A8/Configuration_adv.h +++ b/Marlin/example_configurations/Anet/A8/Configuration_adv.h @@ -661,15 +661,15 @@ // Below are the macros that are used to define the borders for the mesh area, // made available here for specialized needs, ie dual extruder setup. #if ENABLED(MESH_BED_LEVELING) - #define MESH_MIN_X (X_MIN_POS + MESH_INSET) - #define MESH_MAX_X (X_MAX_POS - (MESH_INSET)) - #define MESH_MIN_Y (Y_MIN_POS + MESH_INSET) - #define MESH_MAX_Y (Y_MAX_POS - (MESH_INSET)) + #define MESH_MIN_X MESH_INSET + #define MESH_MAX_X (X_BED_SIZE - (MESH_INSET)) + #define MESH_MIN_Y MESH_INSET + #define MESH_MAX_Y (Y_BED_SIZE - (MESH_INSET)) #elif ENABLED(AUTO_BED_LEVELING_UBL) - #define UBL_MESH_MIN_X (X_MIN_POS + UBL_MESH_INSET) - #define UBL_MESH_MAX_X (X_MAX_POS - (UBL_MESH_INSET)) - #define UBL_MESH_MIN_Y (Y_MIN_POS + UBL_MESH_INSET) - #define UBL_MESH_MAX_Y (Y_MAX_POS - (UBL_MESH_INSET)) + #define UBL_MESH_MIN_X UBL_MESH_INSET + #define UBL_MESH_MAX_X (X_BED_SIZE - (UBL_MESH_INSET)) + #define UBL_MESH_MIN_Y UBL_MESH_INSET + #define UBL_MESH_MAX_Y (Y_BED_SIZE - (UBL_MESH_INSET)) // If this is defined, the currently active mesh will be saved in the // current slot on M500. diff --git a/Marlin/example_configurations/BQ/Hephestos/Configuration_adv.h b/Marlin/example_configurations/BQ/Hephestos/Configuration_adv.h index 611336851..e2a20f6da 100644 --- a/Marlin/example_configurations/BQ/Hephestos/Configuration_adv.h +++ b/Marlin/example_configurations/BQ/Hephestos/Configuration_adv.h @@ -661,15 +661,15 @@ // Below are the macros that are used to define the borders for the mesh area, // made available here for specialized needs, ie dual extruder setup. #if ENABLED(MESH_BED_LEVELING) - #define MESH_MIN_X (X_MIN_POS + MESH_INSET) - #define MESH_MAX_X (X_MAX_POS - (MESH_INSET)) - #define MESH_MIN_Y (Y_MIN_POS + MESH_INSET) - #define MESH_MAX_Y (Y_MAX_POS - (MESH_INSET)) + #define MESH_MIN_X MESH_INSET + #define MESH_MAX_X (X_BED_SIZE - (MESH_INSET)) + #define MESH_MIN_Y MESH_INSET + #define MESH_MAX_Y (Y_BED_SIZE - (MESH_INSET)) #elif ENABLED(AUTO_BED_LEVELING_UBL) - #define UBL_MESH_MIN_X (X_MIN_POS + UBL_MESH_INSET) - #define UBL_MESH_MAX_X (X_MAX_POS - (UBL_MESH_INSET)) - #define UBL_MESH_MIN_Y (Y_MIN_POS + UBL_MESH_INSET) - #define UBL_MESH_MAX_Y (Y_MAX_POS - (UBL_MESH_INSET)) + #define UBL_MESH_MIN_X UBL_MESH_INSET + #define UBL_MESH_MAX_X (X_BED_SIZE - (UBL_MESH_INSET)) + #define UBL_MESH_MIN_Y UBL_MESH_INSET + #define UBL_MESH_MAX_Y (Y_BED_SIZE - (UBL_MESH_INSET)) // If this is defined, the currently active mesh will be saved in the // current slot on M500. diff --git a/Marlin/example_configurations/BQ/Hephestos_2/Configuration_adv.h b/Marlin/example_configurations/BQ/Hephestos_2/Configuration_adv.h index adde1b841..2e4365a97 100644 --- a/Marlin/example_configurations/BQ/Hephestos_2/Configuration_adv.h +++ b/Marlin/example_configurations/BQ/Hephestos_2/Configuration_adv.h @@ -661,15 +661,15 @@ // Below are the macros that are used to define the borders for the mesh area, // made available here for specialized needs, ie dual extruder setup. #if ENABLED(MESH_BED_LEVELING) - #define MESH_MIN_X (X_MIN_POS + MESH_INSET) - #define MESH_MAX_X (X_MAX_POS - (MESH_INSET)) - #define MESH_MIN_Y (Y_MIN_POS + MESH_INSET) - #define MESH_MAX_Y (Y_MAX_POS - (MESH_INSET)) + #define MESH_MIN_X MESH_INSET + #define MESH_MAX_X (X_BED_SIZE - (MESH_INSET)) + #define MESH_MIN_Y MESH_INSET + #define MESH_MAX_Y (Y_BED_SIZE - (MESH_INSET)) #elif ENABLED(AUTO_BED_LEVELING_UBL) - #define UBL_MESH_MIN_X (X_MIN_POS + UBL_MESH_INSET) - #define UBL_MESH_MAX_X (X_MAX_POS - (UBL_MESH_INSET)) - #define UBL_MESH_MIN_Y (Y_MIN_POS + UBL_MESH_INSET) - #define UBL_MESH_MAX_Y (Y_MAX_POS - (UBL_MESH_INSET)) + #define UBL_MESH_MIN_X UBL_MESH_INSET + #define UBL_MESH_MAX_X (X_BED_SIZE - (UBL_MESH_INSET)) + #define UBL_MESH_MIN_Y UBL_MESH_INSET + #define UBL_MESH_MAX_Y (Y_BED_SIZE - (UBL_MESH_INSET)) // If this is defined, the currently active mesh will be saved in the // current slot on M500. diff --git a/Marlin/example_configurations/BQ/WITBOX/Configuration_adv.h b/Marlin/example_configurations/BQ/WITBOX/Configuration_adv.h index 611336851..e2a20f6da 100644 --- a/Marlin/example_configurations/BQ/WITBOX/Configuration_adv.h +++ b/Marlin/example_configurations/BQ/WITBOX/Configuration_adv.h @@ -661,15 +661,15 @@ // Below are the macros that are used to define the borders for the mesh area, // made available here for specialized needs, ie dual extruder setup. #if ENABLED(MESH_BED_LEVELING) - #define MESH_MIN_X (X_MIN_POS + MESH_INSET) - #define MESH_MAX_X (X_MAX_POS - (MESH_INSET)) - #define MESH_MIN_Y (Y_MIN_POS + MESH_INSET) - #define MESH_MAX_Y (Y_MAX_POS - (MESH_INSET)) + #define MESH_MIN_X MESH_INSET + #define MESH_MAX_X (X_BED_SIZE - (MESH_INSET)) + #define MESH_MIN_Y MESH_INSET + #define MESH_MAX_Y (Y_BED_SIZE - (MESH_INSET)) #elif ENABLED(AUTO_BED_LEVELING_UBL) - #define UBL_MESH_MIN_X (X_MIN_POS + UBL_MESH_INSET) - #define UBL_MESH_MAX_X (X_MAX_POS - (UBL_MESH_INSET)) - #define UBL_MESH_MIN_Y (Y_MIN_POS + UBL_MESH_INSET) - #define UBL_MESH_MAX_Y (Y_MAX_POS - (UBL_MESH_INSET)) + #define UBL_MESH_MIN_X UBL_MESH_INSET + #define UBL_MESH_MAX_X (X_BED_SIZE - (UBL_MESH_INSET)) + #define UBL_MESH_MIN_Y UBL_MESH_INSET + #define UBL_MESH_MAX_Y (Y_BED_SIZE - (UBL_MESH_INSET)) // If this is defined, the currently active mesh will be saved in the // current slot on M500. diff --git a/Marlin/example_configurations/Cartesio/Configuration_adv.h b/Marlin/example_configurations/Cartesio/Configuration_adv.h index f8d170dca..b30fdf2ec 100644 --- a/Marlin/example_configurations/Cartesio/Configuration_adv.h +++ b/Marlin/example_configurations/Cartesio/Configuration_adv.h @@ -661,15 +661,15 @@ // Below are the macros that are used to define the borders for the mesh area, // made available here for specialized needs, ie dual extruder setup. #if ENABLED(MESH_BED_LEVELING) - #define MESH_MIN_X (X_MIN_POS + MESH_INSET) - #define MESH_MAX_X (X_MAX_POS - (MESH_INSET)) - #define MESH_MIN_Y (Y_MIN_POS + MESH_INSET) - #define MESH_MAX_Y (Y_MAX_POS - (MESH_INSET)) + #define MESH_MIN_X MESH_INSET + #define MESH_MAX_X (X_BED_SIZE - (MESH_INSET)) + #define MESH_MIN_Y MESH_INSET + #define MESH_MAX_Y (Y_BED_SIZE - (MESH_INSET)) #elif ENABLED(AUTO_BED_LEVELING_UBL) - #define UBL_MESH_MIN_X (X_MIN_POS + UBL_MESH_INSET) - #define UBL_MESH_MAX_X (X_MAX_POS - (UBL_MESH_INSET)) - #define UBL_MESH_MIN_Y (Y_MIN_POS + UBL_MESH_INSET) - #define UBL_MESH_MAX_Y (Y_MAX_POS - (UBL_MESH_INSET)) + #define UBL_MESH_MIN_X UBL_MESH_INSET + #define UBL_MESH_MAX_X (X_BED_SIZE - (UBL_MESH_INSET)) + #define UBL_MESH_MIN_Y UBL_MESH_INSET + #define UBL_MESH_MAX_Y (Y_BED_SIZE - (UBL_MESH_INSET)) // If this is defined, the currently active mesh will be saved in the // current slot on M500. diff --git a/Marlin/example_configurations/Felix/Configuration_adv.h b/Marlin/example_configurations/Felix/Configuration_adv.h index b954f1ddb..706bf132e 100644 --- a/Marlin/example_configurations/Felix/Configuration_adv.h +++ b/Marlin/example_configurations/Felix/Configuration_adv.h @@ -661,15 +661,15 @@ // Below are the macros that are used to define the borders for the mesh area, // made available here for specialized needs, ie dual extruder setup. #if ENABLED(MESH_BED_LEVELING) - #define MESH_MIN_X (X_MIN_POS + MESH_INSET) - #define MESH_MAX_X (X_MAX_POS - (MESH_INSET)) - #define MESH_MIN_Y (Y_MIN_POS + MESH_INSET) - #define MESH_MAX_Y (Y_MAX_POS - (MESH_INSET)) + #define MESH_MIN_X MESH_INSET + #define MESH_MAX_X (X_BED_SIZE - (MESH_INSET)) + #define MESH_MIN_Y MESH_INSET + #define MESH_MAX_Y (Y_BED_SIZE - (MESH_INSET)) #elif ENABLED(AUTO_BED_LEVELING_UBL) - #define UBL_MESH_MIN_X (X_MIN_POS + UBL_MESH_INSET) - #define UBL_MESH_MAX_X (X_MAX_POS - (UBL_MESH_INSET)) - #define UBL_MESH_MIN_Y (Y_MIN_POS + UBL_MESH_INSET) - #define UBL_MESH_MAX_Y (Y_MAX_POS - (UBL_MESH_INSET)) + #define UBL_MESH_MIN_X UBL_MESH_INSET + #define UBL_MESH_MAX_X (X_BED_SIZE - (UBL_MESH_INSET)) + #define UBL_MESH_MIN_Y UBL_MESH_INSET + #define UBL_MESH_MAX_Y (Y_BED_SIZE - (UBL_MESH_INSET)) // If this is defined, the currently active mesh will be saved in the // current slot on M500. diff --git a/Marlin/example_configurations/Folger Tech/i3-2020/Configuration_adv.h b/Marlin/example_configurations/Folger Tech/i3-2020/Configuration_adv.h index 2bd673901..c8ee383db 100644 --- a/Marlin/example_configurations/Folger Tech/i3-2020/Configuration_adv.h +++ b/Marlin/example_configurations/Folger Tech/i3-2020/Configuration_adv.h @@ -661,15 +661,15 @@ // Below are the macros that are used to define the borders for the mesh area, // made available here for specialized needs, ie dual extruder setup. #if ENABLED(MESH_BED_LEVELING) - #define MESH_MIN_X (X_MIN_POS + MESH_INSET) - #define MESH_MAX_X (X_MAX_POS - (MESH_INSET)) - #define MESH_MIN_Y (Y_MIN_POS + MESH_INSET) - #define MESH_MAX_Y (Y_MAX_POS - (MESH_INSET)) + #define MESH_MIN_X MESH_INSET + #define MESH_MAX_X (X_BED_SIZE - (MESH_INSET)) + #define MESH_MIN_Y MESH_INSET + #define MESH_MAX_Y (Y_BED_SIZE - (MESH_INSET)) #elif ENABLED(AUTO_BED_LEVELING_UBL) - #define UBL_MESH_MIN_X (X_MIN_POS + UBL_MESH_INSET) - #define UBL_MESH_MAX_X (X_MAX_POS - (UBL_MESH_INSET)) - #define UBL_MESH_MIN_Y (Y_MIN_POS + UBL_MESH_INSET) - #define UBL_MESH_MAX_Y (Y_MAX_POS - (UBL_MESH_INSET)) + #define UBL_MESH_MIN_X UBL_MESH_INSET + #define UBL_MESH_MAX_X (X_BED_SIZE - (UBL_MESH_INSET)) + #define UBL_MESH_MIN_Y UBL_MESH_INSET + #define UBL_MESH_MAX_Y (Y_BED_SIZE - (UBL_MESH_INSET)) // If this is defined, the currently active mesh will be saved in the // current slot on M500. diff --git a/Marlin/example_configurations/Infitary/i3-M508/Configuration_adv.h b/Marlin/example_configurations/Infitary/i3-M508/Configuration_adv.h index eb7127285..598f44138 100644 --- a/Marlin/example_configurations/Infitary/i3-M508/Configuration_adv.h +++ b/Marlin/example_configurations/Infitary/i3-M508/Configuration_adv.h @@ -661,15 +661,15 @@ // Below are the macros that are used to define the borders for the mesh area, // made available here for specialized needs, ie dual extruder setup. #if ENABLED(MESH_BED_LEVELING) - #define MESH_MIN_X (X_MIN_POS + MESH_INSET) - #define MESH_MAX_X (X_MAX_POS - (MESH_INSET)) - #define MESH_MIN_Y (Y_MIN_POS + MESH_INSET) - #define MESH_MAX_Y (Y_MAX_POS - (MESH_INSET)) + #define MESH_MIN_X MESH_INSET + #define MESH_MAX_X (X_BED_SIZE - (MESH_INSET)) + #define MESH_MIN_Y MESH_INSET + #define MESH_MAX_Y (Y_BED_SIZE - (MESH_INSET)) #elif ENABLED(AUTO_BED_LEVELING_UBL) - #define UBL_MESH_MIN_X (X_MIN_POS + UBL_MESH_INSET) - #define UBL_MESH_MAX_X (X_MAX_POS - (UBL_MESH_INSET)) - #define UBL_MESH_MIN_Y (Y_MIN_POS + UBL_MESH_INSET) - #define UBL_MESH_MAX_Y (Y_MAX_POS - (UBL_MESH_INSET)) + #define UBL_MESH_MIN_X UBL_MESH_INSET + #define UBL_MESH_MAX_X (X_BED_SIZE - (UBL_MESH_INSET)) + #define UBL_MESH_MIN_Y UBL_MESH_INSET + #define UBL_MESH_MAX_Y (Y_BED_SIZE - (UBL_MESH_INSET)) // If this is defined, the currently active mesh will be saved in the // current slot on M500. diff --git a/Marlin/example_configurations/Malyan/M150/Configuration_adv.h b/Marlin/example_configurations/Malyan/M150/Configuration_adv.h index 11403a7fb..4cd6f6766 100644 --- a/Marlin/example_configurations/Malyan/M150/Configuration_adv.h +++ b/Marlin/example_configurations/Malyan/M150/Configuration_adv.h @@ -661,15 +661,15 @@ // Below are the macros that are used to define the borders for the mesh area, // made available here for specialized needs, ie dual extruder setup. #if ENABLED(MESH_BED_LEVELING) - #define MESH_MIN_X (X_MIN_POS + MESH_INSET) - #define MESH_MAX_X (X_MAX_POS - (MESH_INSET)) - #define MESH_MIN_Y (Y_MIN_POS + MESH_INSET) - #define MESH_MAX_Y (Y_MAX_POS - (MESH_INSET)) + #define MESH_MIN_X MESH_INSET + #define MESH_MAX_X (X_BED_SIZE - (MESH_INSET)) + #define MESH_MIN_Y MESH_INSET + #define MESH_MAX_Y (Y_BED_SIZE - (MESH_INSET)) #elif ENABLED(AUTO_BED_LEVELING_UBL) - #define UBL_MESH_MIN_X (X_MIN_POS + UBL_MESH_INSET) - #define UBL_MESH_MAX_X (X_MAX_POS - (UBL_MESH_INSET)) - #define UBL_MESH_MIN_Y (Y_MIN_POS + UBL_MESH_INSET) - #define UBL_MESH_MAX_Y (Y_MAX_POS - (UBL_MESH_INSET)) + #define UBL_MESH_MIN_X UBL_MESH_INSET + #define UBL_MESH_MAX_X (X_BED_SIZE - (UBL_MESH_INSET)) + #define UBL_MESH_MIN_Y UBL_MESH_INSET + #define UBL_MESH_MAX_Y (Y_BED_SIZE - (UBL_MESH_INSET)) // If this is defined, the currently active mesh will be saved in the // current slot on M500. diff --git a/Marlin/example_configurations/RigidBot/Configuration_adv.h b/Marlin/example_configurations/RigidBot/Configuration_adv.h index 565ac51bf..1bf040696 100644 --- a/Marlin/example_configurations/RigidBot/Configuration_adv.h +++ b/Marlin/example_configurations/RigidBot/Configuration_adv.h @@ -661,15 +661,15 @@ // Below are the macros that are used to define the borders for the mesh area, // made available here for specialized needs, ie dual extruder setup. #if ENABLED(MESH_BED_LEVELING) - #define MESH_MIN_X (X_MIN_POS + MESH_INSET) - #define MESH_MAX_X (X_MAX_POS - (MESH_INSET)) - #define MESH_MIN_Y (Y_MIN_POS + MESH_INSET) - #define MESH_MAX_Y (Y_MAX_POS - (MESH_INSET)) + #define MESH_MIN_X MESH_INSET + #define MESH_MAX_X (X_BED_SIZE - (MESH_INSET)) + #define MESH_MIN_Y MESH_INSET + #define MESH_MAX_Y (Y_BED_SIZE - (MESH_INSET)) #elif ENABLED(AUTO_BED_LEVELING_UBL) - #define UBL_MESH_MIN_X (X_MIN_POS + UBL_MESH_INSET) - #define UBL_MESH_MAX_X (X_MAX_POS - (UBL_MESH_INSET)) - #define UBL_MESH_MIN_Y (Y_MIN_POS + UBL_MESH_INSET) - #define UBL_MESH_MAX_Y (Y_MAX_POS - (UBL_MESH_INSET)) + #define UBL_MESH_MIN_X UBL_MESH_INSET + #define UBL_MESH_MAX_X (X_BED_SIZE - (UBL_MESH_INSET)) + #define UBL_MESH_MIN_Y UBL_MESH_INSET + #define UBL_MESH_MAX_Y (Y_BED_SIZE - (UBL_MESH_INSET)) // If this is defined, the currently active mesh will be saved in the // current slot on M500. diff --git a/Marlin/example_configurations/SCARA/Configuration_adv.h b/Marlin/example_configurations/SCARA/Configuration_adv.h index 09771987b..0c7b8b4e3 100644 --- a/Marlin/example_configurations/SCARA/Configuration_adv.h +++ b/Marlin/example_configurations/SCARA/Configuration_adv.h @@ -661,15 +661,15 @@ // Below are the macros that are used to define the borders for the mesh area, // made available here for specialized needs, ie dual extruder setup. #if ENABLED(MESH_BED_LEVELING) - #define MESH_MIN_X (X_MIN_POS + MESH_INSET) - #define MESH_MAX_X (X_MAX_POS - (MESH_INSET)) - #define MESH_MIN_Y (Y_MIN_POS + MESH_INSET) - #define MESH_MAX_Y (Y_MAX_POS - (MESH_INSET)) + #define MESH_MIN_X MESH_INSET + #define MESH_MAX_X (X_BED_SIZE - (MESH_INSET)) + #define MESH_MIN_Y MESH_INSET + #define MESH_MAX_Y (Y_BED_SIZE - (MESH_INSET)) #elif ENABLED(AUTO_BED_LEVELING_UBL) - #define UBL_MESH_MIN_X (X_MIN_POS + UBL_MESH_INSET) - #define UBL_MESH_MAX_X (X_MAX_POS - (UBL_MESH_INSET)) - #define UBL_MESH_MIN_Y (Y_MIN_POS + UBL_MESH_INSET) - #define UBL_MESH_MAX_Y (Y_MAX_POS - (UBL_MESH_INSET)) + #define UBL_MESH_MIN_X UBL_MESH_INSET + #define UBL_MESH_MAX_X (X_BED_SIZE - (UBL_MESH_INSET)) + #define UBL_MESH_MIN_Y UBL_MESH_INSET + #define UBL_MESH_MAX_Y (Y_BED_SIZE - (UBL_MESH_INSET)) // If this is defined, the currently active mesh will be saved in the // current slot on M500. diff --git a/Marlin/example_configurations/TinyBoy2/Configuration_adv.h b/Marlin/example_configurations/TinyBoy2/Configuration_adv.h index f590111ee..543dcd876 100644 --- a/Marlin/example_configurations/TinyBoy2/Configuration_adv.h +++ b/Marlin/example_configurations/TinyBoy2/Configuration_adv.h @@ -661,15 +661,15 @@ // Below are the macros that are used to define the borders for the mesh area, // made available here for specialized needs, ie dual extruder setup. #if ENABLED(MESH_BED_LEVELING) - #define MESH_MIN_X (X_MIN_POS + MESH_INSET) - #define MESH_MAX_X (X_MAX_POS - (MESH_INSET)) - #define MESH_MIN_Y (Y_MIN_POS + MESH_INSET) - #define MESH_MAX_Y (Y_MAX_POS - (MESH_INSET)) + #define MESH_MIN_X MESH_INSET + #define MESH_MAX_X (X_BED_SIZE - (MESH_INSET)) + #define MESH_MIN_Y MESH_INSET + #define MESH_MAX_Y (Y_BED_SIZE - (MESH_INSET)) #elif ENABLED(AUTO_BED_LEVELING_UBL) - #define UBL_MESH_MIN_X (X_MIN_POS + UBL_MESH_INSET) - #define UBL_MESH_MAX_X (X_MAX_POS - (UBL_MESH_INSET)) - #define UBL_MESH_MIN_Y (Y_MIN_POS + UBL_MESH_INSET) - #define UBL_MESH_MAX_Y (Y_MAX_POS - (UBL_MESH_INSET)) + #define UBL_MESH_MIN_X UBL_MESH_INSET + #define UBL_MESH_MAX_X (X_BED_SIZE - (UBL_MESH_INSET)) + #define UBL_MESH_MIN_Y UBL_MESH_INSET + #define UBL_MESH_MAX_Y (Y_BED_SIZE - (UBL_MESH_INSET)) // If this is defined, the currently active mesh will be saved in the // current slot on M500. diff --git a/Marlin/example_configurations/Velleman/K8200/Configuration_adv.h b/Marlin/example_configurations/Velleman/K8200/Configuration_adv.h index 94f87feed..0960203a6 100644 --- a/Marlin/example_configurations/Velleman/K8200/Configuration_adv.h +++ b/Marlin/example_configurations/Velleman/K8200/Configuration_adv.h @@ -674,15 +674,15 @@ // Below are the macros that are used to define the borders for the mesh area, // made available here for specialized needs, ie dual extruder setup. #if ENABLED(MESH_BED_LEVELING) - #define MESH_MIN_X (X_MIN_POS + MESH_INSET) - #define MESH_MAX_X (X_MAX_POS - (MESH_INSET)) - #define MESH_MIN_Y (Y_MIN_POS + MESH_INSET) - #define MESH_MAX_Y (Y_MAX_POS - (MESH_INSET)) + #define MESH_MIN_X MESH_INSET + #define MESH_MAX_X (X_BED_SIZE - (MESH_INSET)) + #define MESH_MIN_Y MESH_INSET + #define MESH_MAX_Y (Y_BED_SIZE - (MESH_INSET)) #elif ENABLED(AUTO_BED_LEVELING_UBL) - #define UBL_MESH_MIN_X (X_MIN_POS + UBL_MESH_INSET) - #define UBL_MESH_MAX_X (X_MAX_POS - (UBL_MESH_INSET)) - #define UBL_MESH_MIN_Y (Y_MIN_POS + UBL_MESH_INSET) - #define UBL_MESH_MAX_Y (Y_MAX_POS - (UBL_MESH_INSET)) + #define UBL_MESH_MIN_X UBL_MESH_INSET + #define UBL_MESH_MAX_X (X_BED_SIZE - (UBL_MESH_INSET)) + #define UBL_MESH_MIN_Y UBL_MESH_INSET + #define UBL_MESH_MAX_Y (Y_BED_SIZE - (UBL_MESH_INSET)) // If this is defined, the currently active mesh will be saved in the // current slot on M500. diff --git a/Marlin/example_configurations/Velleman/K8400/Configuration_adv.h b/Marlin/example_configurations/Velleman/K8400/Configuration_adv.h index d910ab8ea..7a28615d6 100644 --- a/Marlin/example_configurations/Velleman/K8400/Configuration_adv.h +++ b/Marlin/example_configurations/Velleman/K8400/Configuration_adv.h @@ -661,15 +661,15 @@ // Below are the macros that are used to define the borders for the mesh area, // made available here for specialized needs, ie dual extruder setup. #if ENABLED(MESH_BED_LEVELING) - #define MESH_MIN_X (X_MIN_POS + MESH_INSET) - #define MESH_MAX_X (X_MAX_POS - (MESH_INSET)) - #define MESH_MIN_Y (Y_MIN_POS + MESH_INSET) - #define MESH_MAX_Y (Y_MAX_POS - (MESH_INSET)) + #define MESH_MIN_X MESH_INSET + #define MESH_MAX_X (X_BED_SIZE - (MESH_INSET)) + #define MESH_MIN_Y MESH_INSET + #define MESH_MAX_Y (Y_BED_SIZE - (MESH_INSET)) #elif ENABLED(AUTO_BED_LEVELING_UBL) - #define UBL_MESH_MIN_X (X_MIN_POS + UBL_MESH_INSET) - #define UBL_MESH_MAX_X (X_MAX_POS - (UBL_MESH_INSET)) - #define UBL_MESH_MIN_Y (Y_MIN_POS + UBL_MESH_INSET) - #define UBL_MESH_MAX_Y (Y_MAX_POS - (UBL_MESH_INSET)) + #define UBL_MESH_MIN_X UBL_MESH_INSET + #define UBL_MESH_MAX_X (X_BED_SIZE - (UBL_MESH_INSET)) + #define UBL_MESH_MIN_Y UBL_MESH_INSET + #define UBL_MESH_MAX_Y (Y_BED_SIZE - (UBL_MESH_INSET)) // If this is defined, the currently active mesh will be saved in the // current slot on M500. diff --git a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h index 9f2bba659..7b47e138b 100644 --- a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h +++ b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h @@ -663,15 +663,15 @@ // Below are the macros that are used to define the borders for the mesh area, // made available here for specialized needs, ie dual extruder setup. #if ENABLED(MESH_BED_LEVELING) - #define MESH_MIN_X (X_MIN_POS + MESH_INSET) - #define MESH_MAX_X (X_MAX_POS - (MESH_INSET)) - #define MESH_MIN_Y (Y_MIN_POS + MESH_INSET) - #define MESH_MAX_Y (Y_MAX_POS - (MESH_INSET)) + #define MESH_MIN_X MESH_INSET + #define MESH_MAX_X (X_BED_SIZE - (MESH_INSET)) + #define MESH_MIN_Y MESH_INSET + #define MESH_MAX_Y (Y_BED_SIZE - (MESH_INSET)) #elif ENABLED(AUTO_BED_LEVELING_UBL) - #define UBL_MESH_MIN_X (X_MIN_POS + UBL_MESH_INSET) - #define UBL_MESH_MAX_X (X_MAX_POS - (UBL_MESH_INSET)) - #define UBL_MESH_MIN_Y (Y_MIN_POS + UBL_MESH_INSET) - #define UBL_MESH_MAX_Y (Y_MAX_POS - (UBL_MESH_INSET)) + #define UBL_MESH_MIN_X UBL_MESH_INSET + #define UBL_MESH_MAX_X (X_BED_SIZE - (UBL_MESH_INSET)) + #define UBL_MESH_MIN_Y UBL_MESH_INSET + #define UBL_MESH_MAX_Y (Y_BED_SIZE - (UBL_MESH_INSET)) // If this is defined, the currently active mesh will be saved in the // current slot on M500. diff --git a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h index fdc226633..b48a6f8e6 100644 --- a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h +++ b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h @@ -663,15 +663,15 @@ // Below are the macros that are used to define the borders for the mesh area, // made available here for specialized needs, ie dual extruder setup. #if ENABLED(MESH_BED_LEVELING) - #define MESH_MIN_X (X_MIN_POS + MESH_INSET) - #define MESH_MAX_X (X_MAX_POS - (MESH_INSET)) - #define MESH_MIN_Y (Y_MIN_POS + MESH_INSET) - #define MESH_MAX_Y (Y_MAX_POS - (MESH_INSET)) + #define MESH_MIN_X MESH_INSET + #define MESH_MAX_X (X_BED_SIZE - (MESH_INSET)) + #define MESH_MIN_Y MESH_INSET + #define MESH_MAX_Y (Y_BED_SIZE - (MESH_INSET)) #elif ENABLED(AUTO_BED_LEVELING_UBL) - #define UBL_MESH_MIN_X (X_MIN_POS + UBL_MESH_INSET) - #define UBL_MESH_MAX_X (X_MAX_POS - (UBL_MESH_INSET)) - #define UBL_MESH_MIN_Y (Y_MIN_POS + UBL_MESH_INSET) - #define UBL_MESH_MAX_Y (Y_MAX_POS - (UBL_MESH_INSET)) + #define UBL_MESH_MIN_X UBL_MESH_INSET + #define UBL_MESH_MAX_X (X_BED_SIZE - (UBL_MESH_INSET)) + #define UBL_MESH_MIN_Y UBL_MESH_INSET + #define UBL_MESH_MAX_Y (Y_BED_SIZE - (UBL_MESH_INSET)) // If this is defined, the currently active mesh will be saved in the // current slot on M500. diff --git a/Marlin/example_configurations/delta/generic/Configuration_adv.h b/Marlin/example_configurations/delta/generic/Configuration_adv.h index fdc226633..b48a6f8e6 100644 --- a/Marlin/example_configurations/delta/generic/Configuration_adv.h +++ b/Marlin/example_configurations/delta/generic/Configuration_adv.h @@ -663,15 +663,15 @@ // Below are the macros that are used to define the borders for the mesh area, // made available here for specialized needs, ie dual extruder setup. #if ENABLED(MESH_BED_LEVELING) - #define MESH_MIN_X (X_MIN_POS + MESH_INSET) - #define MESH_MAX_X (X_MAX_POS - (MESH_INSET)) - #define MESH_MIN_Y (Y_MIN_POS + MESH_INSET) - #define MESH_MAX_Y (Y_MAX_POS - (MESH_INSET)) + #define MESH_MIN_X MESH_INSET + #define MESH_MAX_X (X_BED_SIZE - (MESH_INSET)) + #define MESH_MIN_Y MESH_INSET + #define MESH_MAX_Y (Y_BED_SIZE - (MESH_INSET)) #elif ENABLED(AUTO_BED_LEVELING_UBL) - #define UBL_MESH_MIN_X (X_MIN_POS + UBL_MESH_INSET) - #define UBL_MESH_MAX_X (X_MAX_POS - (UBL_MESH_INSET)) - #define UBL_MESH_MIN_Y (Y_MIN_POS + UBL_MESH_INSET) - #define UBL_MESH_MAX_Y (Y_MAX_POS - (UBL_MESH_INSET)) + #define UBL_MESH_MIN_X UBL_MESH_INSET + #define UBL_MESH_MAX_X (X_BED_SIZE - (UBL_MESH_INSET)) + #define UBL_MESH_MIN_Y UBL_MESH_INSET + #define UBL_MESH_MAX_Y (Y_BED_SIZE - (UBL_MESH_INSET)) // If this is defined, the currently active mesh will be saved in the // current slot on M500. diff --git a/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h index fdc226633..b48a6f8e6 100644 --- a/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h @@ -663,15 +663,15 @@ // Below are the macros that are used to define the borders for the mesh area, // made available here for specialized needs, ie dual extruder setup. #if ENABLED(MESH_BED_LEVELING) - #define MESH_MIN_X (X_MIN_POS + MESH_INSET) - #define MESH_MAX_X (X_MAX_POS - (MESH_INSET)) - #define MESH_MIN_Y (Y_MIN_POS + MESH_INSET) - #define MESH_MAX_Y (Y_MAX_POS - (MESH_INSET)) + #define MESH_MIN_X MESH_INSET + #define MESH_MAX_X (X_BED_SIZE - (MESH_INSET)) + #define MESH_MIN_Y MESH_INSET + #define MESH_MAX_Y (Y_BED_SIZE - (MESH_INSET)) #elif ENABLED(AUTO_BED_LEVELING_UBL) - #define UBL_MESH_MIN_X (X_MIN_POS + UBL_MESH_INSET) - #define UBL_MESH_MAX_X (X_MAX_POS - (UBL_MESH_INSET)) - #define UBL_MESH_MIN_Y (Y_MIN_POS + UBL_MESH_INSET) - #define UBL_MESH_MAX_Y (Y_MAX_POS - (UBL_MESH_INSET)) + #define UBL_MESH_MIN_X UBL_MESH_INSET + #define UBL_MESH_MAX_X (X_BED_SIZE - (UBL_MESH_INSET)) + #define UBL_MESH_MIN_Y UBL_MESH_INSET + #define UBL_MESH_MAX_Y (Y_BED_SIZE - (UBL_MESH_INSET)) // If this is defined, the currently active mesh will be saved in the // current slot on M500. diff --git a/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h index c01524728..5cdd4aae7 100644 --- a/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h @@ -668,15 +668,15 @@ // Below are the macros that are used to define the borders for the mesh area, // made available here for specialized needs, ie dual extruder setup. #if ENABLED(MESH_BED_LEVELING) - #define MESH_MIN_X (X_MIN_POS + MESH_INSET) - #define MESH_MAX_X (X_MAX_POS - (MESH_INSET)) - #define MESH_MIN_Y (Y_MIN_POS + MESH_INSET) - #define MESH_MAX_Y (Y_MAX_POS - (MESH_INSET)) + #define MESH_MIN_X MESH_INSET + #define MESH_MAX_X (X_BED_SIZE - (MESH_INSET)) + #define MESH_MIN_Y MESH_INSET + #define MESH_MAX_Y (Y_BED_SIZE - (MESH_INSET)) #elif ENABLED(AUTO_BED_LEVELING_UBL) - #define UBL_MESH_MIN_X (X_MIN_POS + UBL_MESH_INSET) - #define UBL_MESH_MAX_X (X_MAX_POS - (UBL_MESH_INSET)) - #define UBL_MESH_MIN_Y (Y_MIN_POS + UBL_MESH_INSET) - #define UBL_MESH_MAX_Y (Y_MAX_POS - (UBL_MESH_INSET)) + #define UBL_MESH_MIN_X UBL_MESH_INSET + #define UBL_MESH_MAX_X (X_BED_SIZE - (UBL_MESH_INSET)) + #define UBL_MESH_MIN_Y UBL_MESH_INSET + #define UBL_MESH_MAX_Y (Y_BED_SIZE - (UBL_MESH_INSET)) // If this is defined, the currently active mesh will be saved in the // current slot on M500. diff --git a/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h index a41212a88..4816afd25 100644 --- a/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h @@ -663,15 +663,15 @@ // Below are the macros that are used to define the borders for the mesh area, // made available here for specialized needs, ie dual extruder setup. #if ENABLED(MESH_BED_LEVELING) - #define MESH_MIN_X (X_MIN_POS + MESH_INSET) - #define MESH_MAX_X (X_MAX_POS - (MESH_INSET)) - #define MESH_MIN_Y (Y_MIN_POS + MESH_INSET) - #define MESH_MAX_Y (Y_MAX_POS - (MESH_INSET)) + #define MESH_MIN_X MESH_INSET + #define MESH_MAX_X (X_BED_SIZE - (MESH_INSET)) + #define MESH_MIN_Y MESH_INSET + #define MESH_MAX_Y (Y_BED_SIZE - (MESH_INSET)) #elif ENABLED(AUTO_BED_LEVELING_UBL) - #define UBL_MESH_MIN_X (X_MIN_POS + UBL_MESH_INSET) - #define UBL_MESH_MAX_X (X_MAX_POS - (UBL_MESH_INSET)) - #define UBL_MESH_MIN_Y (Y_MIN_POS + UBL_MESH_INSET) - #define UBL_MESH_MAX_Y (Y_MAX_POS - (UBL_MESH_INSET)) + #define UBL_MESH_MIN_X UBL_MESH_INSET + #define UBL_MESH_MAX_X (X_BED_SIZE - (UBL_MESH_INSET)) + #define UBL_MESH_MIN_Y UBL_MESH_INSET + #define UBL_MESH_MAX_Y (Y_BED_SIZE - (UBL_MESH_INSET)) // If this is defined, the currently active mesh will be saved in the // current slot on M500. diff --git a/Marlin/example_configurations/gCreate/gMax1.5+/Configuration_adv.h b/Marlin/example_configurations/gCreate/gMax1.5+/Configuration_adv.h index f32a9354d..54b75428a 100644 --- a/Marlin/example_configurations/gCreate/gMax1.5+/Configuration_adv.h +++ b/Marlin/example_configurations/gCreate/gMax1.5+/Configuration_adv.h @@ -661,15 +661,15 @@ // Below are the macros that are used to define the borders for the mesh area, // made available here for specialized needs, ie dual extruder setup. #if ENABLED(MESH_BED_LEVELING) - #define MESH_MIN_X (X_MIN_POS + MESH_INSET) - #define MESH_MAX_X (X_MAX_POS - (MESH_INSET)) - #define MESH_MIN_Y (Y_MIN_POS + MESH_INSET) - #define MESH_MAX_Y (Y_MAX_POS - (MESH_INSET)) + #define MESH_MIN_X MESH_INSET + #define MESH_MAX_X (X_BED_SIZE - (MESH_INSET)) + #define MESH_MIN_Y MESH_INSET + #define MESH_MAX_Y (Y_BED_SIZE - (MESH_INSET)) #elif ENABLED(AUTO_BED_LEVELING_UBL) - #define UBL_MESH_MIN_X (X_MIN_POS + UBL_MESH_INSET) - #define UBL_MESH_MAX_X (X_MAX_POS - (UBL_MESH_INSET)) - #define UBL_MESH_MIN_Y (Y_MIN_POS + UBL_MESH_INSET) - #define UBL_MESH_MAX_Y (Y_MAX_POS - (UBL_MESH_INSET)) + #define UBL_MESH_MIN_X UBL_MESH_INSET + #define UBL_MESH_MAX_X (X_BED_SIZE - (UBL_MESH_INSET)) + #define UBL_MESH_MIN_Y UBL_MESH_INSET + #define UBL_MESH_MAX_Y (Y_BED_SIZE - (UBL_MESH_INSET)) // If this is defined, the currently active mesh will be saved in the // current slot on M500. diff --git a/Marlin/example_configurations/makibox/Configuration_adv.h b/Marlin/example_configurations/makibox/Configuration_adv.h index 8a568f2f8..82fe99679 100644 --- a/Marlin/example_configurations/makibox/Configuration_adv.h +++ b/Marlin/example_configurations/makibox/Configuration_adv.h @@ -661,15 +661,15 @@ // Below are the macros that are used to define the borders for the mesh area, // made available here for specialized needs, ie dual extruder setup. #if ENABLED(MESH_BED_LEVELING) - #define MESH_MIN_X (X_MIN_POS + MESH_INSET) - #define MESH_MAX_X (X_MAX_POS - (MESH_INSET)) - #define MESH_MIN_Y (Y_MIN_POS + MESH_INSET) - #define MESH_MAX_Y (Y_MAX_POS - (MESH_INSET)) + #define MESH_MIN_X MESH_INSET + #define MESH_MAX_X (X_BED_SIZE - (MESH_INSET)) + #define MESH_MIN_Y MESH_INSET + #define MESH_MAX_Y (Y_BED_SIZE - (MESH_INSET)) #elif ENABLED(AUTO_BED_LEVELING_UBL) - #define UBL_MESH_MIN_X (X_MIN_POS + UBL_MESH_INSET) - #define UBL_MESH_MAX_X (X_MAX_POS - (UBL_MESH_INSET)) - #define UBL_MESH_MIN_Y (Y_MIN_POS + UBL_MESH_INSET) - #define UBL_MESH_MAX_Y (Y_MAX_POS - (UBL_MESH_INSET)) + #define UBL_MESH_MIN_X UBL_MESH_INSET + #define UBL_MESH_MAX_X (X_BED_SIZE - (UBL_MESH_INSET)) + #define UBL_MESH_MIN_Y UBL_MESH_INSET + #define UBL_MESH_MAX_Y (Y_BED_SIZE - (UBL_MESH_INSET)) // If this is defined, the currently active mesh will be saved in the // current slot on M500. diff --git a/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h b/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h index 0f75b95c7..7a61aff1f 100644 --- a/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h +++ b/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h @@ -661,15 +661,15 @@ // Below are the macros that are used to define the borders for the mesh area, // made available here for specialized needs, ie dual extruder setup. #if ENABLED(MESH_BED_LEVELING) - #define MESH_MIN_X (X_MIN_POS + MESH_INSET) - #define MESH_MAX_X (X_MAX_POS - (MESH_INSET)) - #define MESH_MIN_Y (Y_MIN_POS + MESH_INSET) - #define MESH_MAX_Y (Y_MAX_POS - (MESH_INSET)) + #define MESH_MIN_X MESH_INSET + #define MESH_MAX_X (X_BED_SIZE - (MESH_INSET)) + #define MESH_MIN_Y MESH_INSET + #define MESH_MAX_Y (Y_BED_SIZE - (MESH_INSET)) #elif ENABLED(AUTO_BED_LEVELING_UBL) - #define UBL_MESH_MIN_X (X_MIN_POS + UBL_MESH_INSET) - #define UBL_MESH_MAX_X (X_MAX_POS - (UBL_MESH_INSET)) - #define UBL_MESH_MIN_Y (Y_MIN_POS + UBL_MESH_INSET) - #define UBL_MESH_MAX_Y (Y_MAX_POS - (UBL_MESH_INSET)) + #define UBL_MESH_MIN_X UBL_MESH_INSET + #define UBL_MESH_MAX_X (X_BED_SIZE - (UBL_MESH_INSET)) + #define UBL_MESH_MIN_Y UBL_MESH_INSET + #define UBL_MESH_MAX_Y (Y_BED_SIZE - (UBL_MESH_INSET)) // If this is defined, the currently active mesh will be saved in the // current slot on M500. diff --git a/Marlin/example_configurations/wt150/Configuration_adv.h b/Marlin/example_configurations/wt150/Configuration_adv.h index 3501c7157..bed6afd6b 100644 --- a/Marlin/example_configurations/wt150/Configuration_adv.h +++ b/Marlin/example_configurations/wt150/Configuration_adv.h @@ -661,15 +661,15 @@ // Below are the macros that are used to define the borders for the mesh area, // made available here for specialized needs, ie dual extruder setup. #if ENABLED(MESH_BED_LEVELING) - #define MESH_MIN_X (X_MIN_POS + MESH_INSET) - #define MESH_MAX_X (X_MAX_POS - (MESH_INSET)) - #define MESH_MIN_Y (Y_MIN_POS + MESH_INSET) - #define MESH_MAX_Y (Y_MAX_POS - (MESH_INSET)) + #define MESH_MIN_X MESH_INSET + #define MESH_MAX_X (X_BED_SIZE - (MESH_INSET)) + #define MESH_MIN_Y MESH_INSET + #define MESH_MAX_Y (Y_BED_SIZE - (MESH_INSET)) #elif ENABLED(AUTO_BED_LEVELING_UBL) - #define UBL_MESH_MIN_X (X_MIN_POS + UBL_MESH_INSET) - #define UBL_MESH_MAX_X (X_MAX_POS - (UBL_MESH_INSET)) - #define UBL_MESH_MIN_Y (Y_MIN_POS + UBL_MESH_INSET) - #define UBL_MESH_MAX_Y (Y_MAX_POS - (UBL_MESH_INSET)) + #define UBL_MESH_MIN_X UBL_MESH_INSET + #define UBL_MESH_MAX_X (X_BED_SIZE - (UBL_MESH_INSET)) + #define UBL_MESH_MIN_Y UBL_MESH_INSET + #define UBL_MESH_MAX_Y (Y_BED_SIZE - (UBL_MESH_INSET)) // If this is defined, the currently active mesh will be saved in the // current slot on M500. From 35d5a7bdff674b17c8094373ea4a80fc24850a64 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 9 Aug 2017 12:31:18 -0500 Subject: [PATCH 073/112] Tweak CR-10 config/pins --- Marlin/example_configurations/Creality/CR-10/Configuration.h | 2 +- Marlin/pins_MELZI_CREALITY.h | 2 +- Marlin/pins_MELZI_MAKR3D.h | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/Marlin/example_configurations/Creality/CR-10/Configuration.h b/Marlin/example_configurations/Creality/CR-10/Configuration.h index b4817e4ae..53e703b81 100644 --- a/Marlin/example_configurations/Creality/CR-10/Configuration.h +++ b/Marlin/example_configurations/Creality/CR-10/Configuration.h @@ -74,7 +74,7 @@ // User-specified version info of this build to display in [Pronterface, etc] terminal window during // startup. Implementation of an idea by Prof Braino to inform user that any changes made to this // build by the user have been successfully uploaded into firmware. -#define STRING_CONFIG_H_AUTHOR "(none, default config)" // Who made the changes. +#define STRING_CONFIG_H_AUTHOR "(Creality CR-10)" // Who made the changes. #define SHOW_BOOTSCREEN #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 diff --git a/Marlin/pins_MELZI_CREALITY.h b/Marlin/pins_MELZI_CREALITY.h index d08bba1c3..d66f589fe 100644 --- a/Marlin/pins_MELZI_CREALITY.h +++ b/Marlin/pins_MELZI_CREALITY.h @@ -24,7 +24,7 @@ * Melzi (Creality) pin assignments */ -#define BOARD_NAME "Melzi Creality" +#define BOARD_NAME "Melzi (Creality)" #ifdef __AVR_ATmega1284P__ #define LARGE_FLASH true diff --git a/Marlin/pins_MELZI_MAKR3D.h b/Marlin/pins_MELZI_MAKR3D.h index 83deb884c..bd86f59c0 100644 --- a/Marlin/pins_MELZI_MAKR3D.h +++ b/Marlin/pins_MELZI_MAKR3D.h @@ -24,7 +24,7 @@ * Melzi with ATmega1284 (MaKr3d version) pin assignments */ -#define BOARD_NAME "Melzi ATmega1284" +#define BOARD_NAME "Melzi (ATmega1284)" #ifdef __AVR_ATmega1284P__ #define LARGE_FLASH true From 9d95b1b4df0fcdd853b83ca2e065c0d626e6887a Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 6 Aug 2017 23:29:35 -0500 Subject: [PATCH 074/112] Tweak Conditionals_post.h --- Marlin/Conditionals_post.h | 20 +++++++++----------- 1 file changed, 9 insertions(+), 11 deletions(-) diff --git a/Marlin/Conditionals_post.h b/Marlin/Conditionals_post.h index 7d4a4a457..e3878ecb9 100644 --- a/Marlin/Conditionals_post.h +++ b/Marlin/Conditionals_post.h @@ -681,16 +681,6 @@ #endif #define WRITE_FAN_N(n, v) WRITE_FAN##n(v) - - /** - * Heater & Fan Pausing - */ - #if FAN_COUNT == 0 - #undef PROBING_FANS_OFF - #endif - #define QUIET_PROBING (HAS_BED_PROBE && (ENABLED(PROBING_HEATERS_OFF) || ENABLED(PROBING_FANS_OFF) || DELAY_BEFORE_PROBING > 0)) - #define HEATER_IDLE_HANDLER (ENABLED(ADVANCED_PAUSE_FEATURE) || ENABLED(PROBING_HEATERS_OFF)) - /** * Servos and probes */ @@ -702,7 +692,6 @@ #endif #define PROBE_PIN_CONFIGURED (HAS_Z_MIN_PROBE_PIN || (HAS_Z_MIN && ENABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN))) - #define HAS_BED_PROBE (PROBE_SELECTED && PROBE_PIN_CONFIGURED && DISABLED(PROBE_MANUALLY)) #if ENABLED(Z_PROBE_ALLEN_KEY) @@ -743,6 +732,15 @@ #define Z_PROBE_OFFSET_FROM_EXTRUDER 0 #endif + /** + * Heater & Fan Pausing + */ + #if FAN_COUNT == 0 + #undef PROBING_FANS_OFF + #endif + #define QUIET_PROBING (HAS_BED_PROBE && (ENABLED(PROBING_HEATERS_OFF) || ENABLED(PROBING_FANS_OFF) || DELAY_BEFORE_PROBING > 0)) + #define HEATER_IDLE_HANDLER (ENABLED(ADVANCED_PAUSE_FEATURE) || ENABLED(PROBING_HEATERS_OFF)) + /** * Delta radius/rod trimmers/angle trimmers */ From 0938c62b4826e62549f0f86818fd8d4c8e94d228 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 9 Aug 2017 12:31:00 -0500 Subject: [PATCH 075/112] Neater position_is_reachable call --- Marlin/Marlin_main.cpp | 9 +++++---- 1 file changed, 5 insertions(+), 4 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 185dfb413..f9db4f49b 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -2359,10 +2359,11 @@ static void clean_up_after_endstop_or_probe_move() { const float nx = lx - (X_PROBE_OFFSET_FROM_EXTRUDER), ny = ly - (Y_PROBE_OFFSET_FROM_EXTRUDER); - if (printable) { - if (!position_is_reachable_by_probe_xy(lx, ly)) return NAN; - } - else if (!position_is_reachable_xy(nx, ny)) return NAN; + if (printable + ? !position_is_reachable_xy(nx, ny) + : !position_is_reachable_by_probe_xy(lx, ly) + ) return NAN; + const float old_feedrate_mm_s = feedrate_mm_s; From f54e0fc90f5bc12d665c5d877b73c95bf76e582f Mon Sep 17 00:00:00 2001 From: Thomas Moore Date: Wed, 2 Aug 2017 22:52:40 -0500 Subject: [PATCH 076/112] Prevent damage if DELTA_HEIGHT is incorrect --- Marlin/Marlin_main.cpp | 212 +++++++++++++++++++++++++---------------- Marlin/endstops.cpp | 10 +- Marlin/language_en.h | 17 +++- Marlin/ultralcd.cpp | 18 +++- 4 files changed, 166 insertions(+), 91 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 185dfb413..c56325810 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -1409,6 +1409,9 @@ bool get_target_extruder_from_command(const uint16_t code) { soft_endstop_max[axis] = base_max_pos(axis) + offs; } } + #elif ENABLED(DELTA) + soft_endstop_min[axis] = base_min_pos(axis) + (axis == Z_AXIS ? 0 : offs); + soft_endstop_max[axis] = base_max_pos(axis) + offs; #else soft_endstop_min[axis] = base_min_pos(axis) + offs; soft_endstop_max[axis] = base_max_pos(axis) + offs; @@ -1806,13 +1809,9 @@ static void clean_up_after_endstop_or_probe_move() { } #endif - float z_dest = LOGICAL_Z_POSITION(z_raise); + float z_dest = z_raise; if (zprobe_zoffset < 0) z_dest -= zprobe_zoffset; - #if ENABLED(DELTA) - z_dest -= home_offset[Z_AXIS]; // Account for delta height adjustment - #endif - if (z_dest > current_position[Z_AXIS]) do_blocking_move_to_z(z_dest); } @@ -2106,7 +2105,7 @@ static void clean_up_after_endstop_or_probe_move() { safe_delay(BLTOUCH_DELAY); } - void set_bltouch_deployed(const bool deploy) { + bool set_bltouch_deployed(const bool deploy) { if (deploy && TEST_BLTOUCH()) { // If BL-Touch says it's triggered bltouch_command(BLTOUCH_RESET); // try to reset it. bltouch_command(BLTOUCH_DEPLOY); // Also needs to deploy and stow to @@ -2118,6 +2117,7 @@ static void clean_up_after_endstop_or_probe_move() { SERIAL_ERROR_START(); SERIAL_ERRORLNPGM(MSG_STOP_BLTOUCH); stop(); // punt! + return true; } } @@ -2130,6 +2130,8 @@ static void clean_up_after_endstop_or_probe_move() { SERIAL_EOL(); } #endif + + return false; } #endif // BLTOUCH @@ -2149,23 +2151,7 @@ static void clean_up_after_endstop_or_probe_move() { // Make room for probe do_probe_raise(_Z_CLEARANCE_DEPLOY_PROBE); - // When deploying make sure BLTOUCH is not already triggered - #if ENABLED(BLTOUCH) - if (deploy && TEST_BLTOUCH()) { // If BL-Touch says it's triggered - bltouch_command(BLTOUCH_RESET); // try to reset it. - bltouch_command(BLTOUCH_DEPLOY); // Also needs to deploy and stow to - bltouch_command(BLTOUCH_STOW); // clear the triggered condition. - safe_delay(1500); // wait for internal self test to complete - // measured completion time was 0.65 seconds - // after reset, deploy & stow sequence - if (TEST_BLTOUCH()) { // If it still claims to be triggered... - SERIAL_ERROR_START(); - SERIAL_ERRORLNPGM(MSG_STOP_BLTOUCH); - stop(); // punt! - return true; - } - } - #elif ENABLED(Z_PROBE_SLED) || ENABLED(Z_PROBE_ALLEN_KEY) + #if ENABLED(Z_PROBE_SLED) || ENABLED(Z_PROBE_ALLEN_KEY) #if ENABLED(Z_PROBE_SLED) #define _AUE_ARGS true, false, false #else @@ -2236,14 +2222,14 @@ static void clean_up_after_endstop_or_probe_move() { return false; } - static void do_probe_move(float z, float fr_mm_m) { + static bool 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); + if (set_bltouch_deployed(true)) return true; #endif #if QUIET_PROBING @@ -2251,15 +2237,24 @@ static void clean_up_after_endstop_or_probe_move() { #endif // Move down until probe triggered - do_blocking_move_to_z(LOGICAL_Z_POSITION(z), MMM_TO_MMS(fr_mm_m)); + do_blocking_move_to_z(z, MMM_TO_MMS(fr_mm_m)); + + // Check to see if the probe was triggered + const bool probe_triggered = TEST(Endstops::endstop_hit_bits, + #ifdef Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN + Z_MIN + #else + Z_MIN_PROBE + #endif + ); #if QUIET_PROBING probing_pause(false); #endif - // Retract BLTouch immediately after a probe + // Retract BLTouch immediately after a probe if it was triggered #if ENABLED(BLTOUCH) - set_bltouch_deployed(false); + if (probe_triggered && set_bltouch_deployed(false)) return true; #endif // Clear endstop flags @@ -2274,11 +2269,13 @@ static void clean_up_after_endstop_or_probe_move() { #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) DEBUG_POS("<<< do_probe_move", current_position); #endif + + return !probe_triggered; } // Do a single Z probe and return with current_position[Z_AXIS] // at the height where the probe triggered. - static float run_z_probe() { + static float run_z_probe(bool printable=true) { #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) DEBUG_POS(">>> run_z_probe", current_position); @@ -2290,34 +2287,33 @@ static void clean_up_after_endstop_or_probe_move() { #if ENABLED(PROBE_DOUBLE_TOUCH) // Do a first probe at the fast speed - do_probe_move(-(Z_MAX_LENGTH) - 10, Z_PROBE_SPEED_FAST); + if (do_probe_move(-10, Z_PROBE_SPEED_FAST)) return NAN; #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)); + // move up to make clearance for the probe + do_blocking_move_to_z(current_position[Z_AXIS] + Z_CLEARANCE_BETWEEN_PROBES, MMM_TO_MMS(Z_PROBE_SPEED_FAST)); #else // 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); + float z = Z_CLEARANCE_DEPLOY_PROBE; if (zprobe_zoffset < 0) z -= zprobe_zoffset; - #if ENABLED(DELTA) - z -= home_offset[Z_AXIS]; // Account for delta height adjustment - #endif - - if (z < current_position[Z_AXIS]) - do_blocking_move_to_z(z, MMM_TO_MMS(Z_PROBE_SPEED_FAST)); + if (z < current_position[Z_AXIS]) { + // If we don't make it to the z position (i.e. the probe triggered), move up to make clearance for the probe + if (!do_probe_move(z, Z_PROBE_SPEED_FAST)) + do_blocking_move_to_z(current_position[Z_AXIS] + Z_CLEARANCE_BETWEEN_PROBES, MMM_TO_MMS(Z_PROBE_SPEED_FAST)); + } #endif // move down slowly to find bed - do_probe_move(-(Z_MAX_LENGTH) - 10, Z_PROBE_SPEED_SLOW); + if (do_probe_move(-10 + (printable ? 0 : -(Z_MAX_LENGTH)), Z_PROBE_SPEED_SLOW)) return NAN; #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) DEBUG_POS("<<< run_z_probe", current_position); @@ -2330,6 +2326,7 @@ static void clean_up_after_endstop_or_probe_move() { SERIAL_ECHOLNPAIR(" Discrepancy:", first_probe_z - current_position[Z_AXIS]); } #endif + return RAW_CURRENT_POSITION(Z) + zprobe_zoffset #if ENABLED(DELTA) + home_offset[Z_AXIS] // Account for delta height adjustment @@ -2371,22 +2368,31 @@ static void clean_up_after_endstop_or_probe_move() { do_blocking_move_to_z(delta_clip_start_height); #endif - // Ensure a minimum height before moving the probe - do_probe_raise(Z_CLEARANCE_BETWEEN_PROBES); + #if HAS_SOFTWARE_ENDSTOPS + // Store the status of the soft endstops and disable if we're probing a non-printable location + static bool enable_soft_endstops = soft_endstops_enabled; + if (!printable) soft_endstops_enabled = false; + #endif feedrate_mm_s = XY_PROBE_FEEDRATE_MM_S; // Move the probe to the given XY do_blocking_move_to_xy(nx, ny); - if (DEPLOY_PROBE()) return NAN; + float measured_z = NAN; + if (!DEPLOY_PROBE()) { + measured_z = run_z_probe(printable); - const float measured_z = run_z_probe(); + if (!stow) + do_blocking_move_to_z(current_position[Z_AXIS] + Z_CLEARANCE_BETWEEN_PROBES, MMM_TO_MMS(Z_PROBE_SPEED_FAST)); + else + if (STOW_PROBE()) measured_z = NAN; + } - if (!stow) - do_probe_raise(Z_CLEARANCE_BETWEEN_PROBES); - else - if (STOW_PROBE()) return NAN; + #if HAS_SOFTWARE_ENDSTOPS + // Restore the soft endstop status + soft_endstops_enabled = enable_soft_endstops; + #endif if (verbose_level > 2) { SERIAL_PROTOCOLPGM("Bed X: "); @@ -3752,7 +3758,7 @@ inline void gcode_G4() { * 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() { + inline bool home_delta() { #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) DEBUG_POS(">>> home_delta", current_position); #endif @@ -3761,10 +3767,23 @@ inline void gcode_G4() { 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); + current_position[X_AXIS] = current_position[Y_AXIS] = current_position[Z_AXIS] = (DELTA_HEIGHT + home_offset[Z_AXIS] + 10); feedrate_mm_s = homing_feedrate(X_AXIS); line_to_current_position(); stepper.synchronize(); + + // If an endstop was not hit, then damage can occur if homing is continued. + // This can occur if the delta height (DELTA_HEIGHT + home_offset[Z_AXIS]) is + // not set correctly. + if (!(TEST(Endstops::endstop_hit_bits, X_MAX) || + TEST(Endstops::endstop_hit_bits, Y_MAX) || + TEST(Endstops::endstop_hit_bits, Z_MAX))) { + LCD_MESSAGEPGM(MSG_ERR_HOMING_FAILED); + SERIAL_ERROR_START(); + SERIAL_ERRORLNPGM(MSG_ERR_HOMING_FAILED); + return false; + } + endstops.hit_on_purpose(); // clear endstop hit flags // At least one carriage has reached the top. @@ -3784,6 +3803,8 @@ inline void gcode_G4() { #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) DEBUG_POS("<<< home_delta", current_position); #endif + + return true; } #endif // DELTA @@ -4105,6 +4126,20 @@ void home_all_axes() { gcode_G28(true); } #endif +#if HAS_BED_PROBE + + static bool nan_error(const float v) { + const bool is_nan = isnan(v); + if (is_nan) { + LCD_MESSAGEPGM(MSG_ERR_PROBING_FAILED); + SERIAL_ERROR_START(); + SERIAL_ERRORLNPGM(MSG_ERR_PROBING_FAILED); + } + return is_nan; + } + +#endif // HAS_BED_PROBE + #if ENABLED(MESH_BED_LEVELING) // Save 130 bytes with non-duplication of PSTR @@ -4648,7 +4683,7 @@ void home_all_axes() { gcode_G28(true); } // Deploy the probe. Probe will raise if needed. if (DEPLOY_PROBE()) { planner.abl_enabled = abl_should_enable; - return; + goto FAIL; } #endif @@ -4864,7 +4899,7 @@ void home_all_axes() { gcode_G28(true); } #endif // AUTO_BED_LEVELING_3POINT #else // !PROBE_MANUALLY - + { const bool stow_probe_after_each = parser.boolval('E'); #if ABL_GRID @@ -4909,9 +4944,9 @@ void home_all_axes() { gcode_G28(true); } measured_z = faux ? 0.001 * random(-100, 101) : probe_pt(xProbe, yProbe, stow_probe_after_each, verbose_level); - if (isnan(measured_z)) { + if (nan_error(measured_z)) { planner.abl_enabled = abl_should_enable; - return; + goto FAIL; } #if ENABLED(AUTO_BED_LEVELING_LINEAR) @@ -4945,9 +4980,9 @@ void home_all_axes() { gcode_G28(true); } xProbe = LOGICAL_X_POSITION(points[i].x); yProbe = LOGICAL_Y_POSITION(points[i].y); measured_z = faux ? 0.001 * random(-100, 101) : probe_pt(xProbe, yProbe, stow_probe_after_each, verbose_level); - if (isnan(measured_z)) { + if (nan_error(measured_z)) { planner.abl_enabled = abl_should_enable; - return; + goto FAIL; } points[i].z = measured_z; } @@ -4970,9 +5005,9 @@ void home_all_axes() { gcode_G28(true); } // Raise to _Z_CLEARANCE_DEPLOY_PROBE. Stow the probe. if (STOW_PROBE()) { planner.abl_enabled = abl_should_enable; - return; + goto FAIL; } - + } #endif // !PROBE_MANUALLY // @@ -4985,9 +5020,6 @@ void home_all_axes() { gcode_G28(true); } // return or loop before this point. // - // Restore state after probing - if (!faux) clean_up_after_endstop_or_probe_move(); - #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) DEBUG_POS("> probing complete", current_position); #endif @@ -5192,6 +5224,14 @@ void home_all_axes() { gcode_G28(true); } stepper.synchronize(); #endif + // Auto Bed Leveling is complete! Enable if possible. + planner.abl_enabled = dryrun ? abl_should_enable : true; + + FAIL: + + // Restore state after probing + if (!faux) clean_up_after_endstop_or_probe_move(); + #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("<<< gcode_G29"); #endif @@ -5200,9 +5240,6 @@ void home_all_axes() { gcode_G28(true); } 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(); } @@ -5235,7 +5272,7 @@ void home_all_axes() { gcode_G28(true); } const float measured_z = probe_pt(xpos, ypos, parser.boolval('S', true), 1); - if (!isnan(measured_z)) { + if (!nan_error(measured_z)) { SERIAL_PROTOCOLPAIR("Bed X: ", FIXFLOAT(xpos)); SERIAL_PROTOCOLPAIR(" Y: ", FIXFLOAT(ypos)); SERIAL_PROTOCOLLNPAIR(" Z: ", FIXFLOAT(measured_z)); @@ -5399,9 +5436,9 @@ void home_all_axes() { gcode_G28(true); } tool_change(0, 0, true); #endif setup_for_endstop_or_probe_move(); - DEPLOY_PROBE(); endstops.enable(true); - home_delta(); + if (!home_delta()) + return; endstops.not_homing(); // print settings @@ -5415,7 +5452,11 @@ void home_all_axes() { gcode_G28(true); } print_G33_settings(!_1p_calibration, _7p_calibration && towers_set); #if DISABLED(PROBE_MANUALLY) - home_offset[Z_AXIS] -= probe_pt(dx, dy, stow_after_each, 1, false); // 1st probe to set height + const float measured_z = probe_pt(dx, dy, stow_after_each, 1, false); // 1st probe to set height + if (nan_error(measured_z)) + goto FAIL; + else + home_offset[Z_AXIS] -= measured_z; #endif do { @@ -5433,6 +5474,7 @@ void home_all_axes() { gcode_G28(true); } z_at_pt[0] += lcd_probe_pt(0, 0); #else z_at_pt[0] += probe_pt(dx, dy, stow_after_each, 1, false); + if (nan_error(z_at_pt[0])) goto FAIL; #endif } if (_7p_calibration) { // probe extra center points @@ -5441,7 +5483,8 @@ void home_all_axes() { gcode_G28(true); } #if ENABLED(PROBE_MANUALLY) z_at_pt[0] += lcd_probe_pt(cos(a) * r, sin(a) * r); #else - z_at_pt[0] += probe_pt(cos(a) * r + dx, sin(a) * r + dy, stow_after_each, 1, false); + z_at_pt[0] += probe_pt(cos(a) * r + dx, sin(a) * r + dy, stow_after_each, 1); + if (nan_error(z_at_pt[0])) goto FAIL; #endif } z_at_pt[0] /= float(_7p_double_circle ? 7 : probe_points); @@ -5461,7 +5504,8 @@ void home_all_axes() { gcode_G28(true); } #if ENABLED(PROBE_MANUALLY) z_at_pt[axis] += lcd_probe_pt(cos(a) * r, sin(a) * r); #else - z_at_pt[axis] += probe_pt(cos(a) * r + dx, sin(a) * r + dy, stow_after_each, 1, false); + z_at_pt[axis] += probe_pt(cos(a) * r + dx, sin(a) * r + dy, stow_after_each, 1); + if (nan_error(z_at_pt[axis])) goto FAIL; #endif } zig_zag = !zig_zag; @@ -5661,6 +5705,8 @@ void home_all_axes() { gcode_G28(true); } } while ((zero_std_dev < test_precision && zero_std_dev > calibration_precision && iterations < 31) || iterations <= force_iterations); + FAIL: + #if ENABLED(DELTA_HOME_TO_SAFE_ZONE) do_blocking_move_to_z(delta_clip_start_height); #endif @@ -6979,14 +7025,14 @@ inline void gcode_M42() { setup_for_endstop_or_probe_move(); + double mean = 0.0, sigma = 0.0, min = 99999.9, max = -99999.9, sample_set[n_samples]; + // Move to the first point, deploy, and probe const float t = probe_pt(X_probe_location, Y_probe_location, stow_probe_after_each, verbose_level); - if (isnan(t)) return; + if (nan_error(t)) goto FAIL; randomSeed(millis()); - 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) { const int dir = (random(0, 10) > 5.0) ? -1 : 1; // clockwise or counter clockwise @@ -7058,6 +7104,7 @@ inline void gcode_M42() { // Probe a single point sample_set[n] = probe_pt(X_probe_location, Y_probe_location, stow_probe_after_each, 0); + if (nan_error(sample_set[n])) goto FAIL; /** * Get the current mean for the data points we have so far @@ -7103,7 +7150,7 @@ inline void gcode_M42() { } // End of probe loop - if (STOW_PROBE()) return; + if (STOW_PROBE()) goto FAIL; SERIAL_PROTOCOLPGM("Finished!"); SERIAL_EOL(); @@ -7125,6 +7172,8 @@ inline void gcode_M42() { SERIAL_EOL(); SERIAL_EOL(); + FAIL: + clean_up_after_endstop_or_probe_move(); // Re-enable bed level correction if it had been on @@ -11452,19 +11501,22 @@ void ok_to_send() { // DELTA_PRINTABLE_RADIUS from center of bed, but delta // now enforces is_position_reachable for X/Y regardless // of HAS_SOFTWARE_ENDSTOPS, so that enforcement would be - // redundant here. Probably should #ifdef out the X/Y - // axis clamps here for delta and just leave the Z clamp. + // redundant here. void clamp_to_software_endstops(float target[XYZ]) { if (!soft_endstops_enabled) return; #if ENABLED(MIN_SOFTWARE_ENDSTOPS) - NOLESS(target[X_AXIS], soft_endstop_min[X_AXIS]); - NOLESS(target[Y_AXIS], soft_endstop_min[Y_AXIS]); + #if DISABLED(DELTA) + NOLESS(target[X_AXIS], soft_endstop_min[X_AXIS]); + NOLESS(target[Y_AXIS], soft_endstop_min[Y_AXIS]); + #endif 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]); + #if DISABLED(DELTA) + NOMORE(target[X_AXIS], soft_endstop_max[X_AXIS]); + NOMORE(target[Y_AXIS], soft_endstop_max[Y_AXIS]); + #endif NOMORE(target[Z_AXIS], soft_endstop_max[Z_AXIS]); #endif } diff --git a/Marlin/endstops.cpp b/Marlin/endstops.cpp index 32541b675..8ff6c7668 100644 --- a/Marlin/endstops.cpp +++ b/Marlin/endstops.cpp @@ -247,7 +247,7 @@ 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_HIT(AXIS, MINMAX) SBI(endstop_hit_bits, _ENDSTOP(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))) @@ -257,7 +257,7 @@ void Endstops::update() { #define UPDATE_ENDSTOP(AXIS,MINMAX) do { \ UPDATE_ENDSTOP_BIT(AXIS, MINMAX); \ if (TEST_ENDSTOP(_ENDSTOP(AXIS, MINMAX)) && stepper.current_block->steps[_AXIS(AXIS)] > 0) { \ - _ENDSTOP_HIT(AXIS); \ + _ENDSTOP_HIT(AXIS, MINMAX); \ stepper.endstop_triggered(_AXIS(AXIS)); \ } \ } while(0) @@ -267,9 +267,9 @@ void Endstops::update() { if (G38_move) { UPDATE_ENDSTOP_BIT(Z, MIN_PROBE); if (TEST_ENDSTOP(_ENDSTOP(Z, MIN_PROBE))) { - if (stepper.current_block->steps[_AXIS(X)] > 0) { _ENDSTOP_HIT(X); stepper.endstop_triggered(_AXIS(X)); } - else if (stepper.current_block->steps[_AXIS(Y)] > 0) { _ENDSTOP_HIT(Y); stepper.endstop_triggered(_AXIS(Y)); } - else if (stepper.current_block->steps[_AXIS(Z)] > 0) { _ENDSTOP_HIT(Z); stepper.endstop_triggered(_AXIS(Z)); } + if (stepper.current_block->steps[_AXIS(X)] > 0) { _ENDSTOP_HIT(X, MIN); stepper.endstop_triggered(_AXIS(X)); } + else if (stepper.current_block->steps[_AXIS(Y)] > 0) { _ENDSTOP_HIT(Y, MIN); stepper.endstop_triggered(_AXIS(Y)); } + else if (stepper.current_block->steps[_AXIS(Z)] > 0) { _ENDSTOP_HIT(Z, MIN); stepper.endstop_triggered(_AXIS(Z)); } G38_endstop_hit = true; } } diff --git a/Marlin/language_en.h b/Marlin/language_en.h index 5da9d9648..52d9aa49e 100644 --- a/Marlin/language_en.h +++ b/Marlin/language_en.h @@ -717,7 +717,7 @@ #define MSG_DELTA_CALIBRATE_CENTER _UxGT("Calibrate Center") #endif #ifndef MSG_DELTA_SETTINGS - #define MSG_DELTA_SETTINGS _UxGT("Show Delta Settings") + #define MSG_DELTA_SETTINGS _UxGT("Delta Settings") #endif #ifndef MSG_DELTA_AUTO_CALIBRATE #define MSG_DELTA_AUTO_CALIBRATE _UxGT("Auto Calibration") @@ -725,6 +725,15 @@ #ifndef MSG_DELTA_HEIGHT_CALIBRATE #define MSG_DELTA_HEIGHT_CALIBRATE _UxGT("Set Delta Height") #endif +#ifndef MSG_DELTA_DIAG_ROG + #define MSG_DELTA_DIAG_ROG _UxGT("Diag Rod") +#endif +#ifndef MSG_DELTA_HEIGHT + #define MSG_DELTA_HEIGHT _UxGT("Height") +#endif +#ifndef MSG_DELTA_RADIUS + #define MSG_DELTA_RADIUS _UxGT("Radius") +#endif #ifndef MSG_INFO_MENU #define MSG_INFO_MENU _UxGT("About Printer") #endif @@ -840,6 +849,12 @@ #ifndef MSG_FILAMENT_CHANGE_NOZZLE #define MSG_FILAMENT_CHANGE_NOZZLE _UxGT(" Nozzle: ") #endif +#ifndef MSG_ERR_HOMING_FAILED + #define MSG_ERR_HOMING_FAILED _UxGT("Homing failed") +#endif +#ifndef MSG_ERR_PROBING_FAILED + #define MSG_ERR_PROBING_FAILED _UxGT("Probing failed") +#endif // // Filament Change screens show up to 3 lines on a 4-line display diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index 8de1e0129..499530c48 100644 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -2537,15 +2537,23 @@ void kill_screen(const char* lcd_msg) { void _goto_tower_z() { _man_probe_pt(cos(RADIANS( 90)) * delta_calibration_radius, sin(RADIANS( 90)) * delta_calibration_radius); } void _goto_center() { _man_probe_pt(0,0); } - void lcd_delta_G33_settings() { + static float _delta_height = DELTA_HEIGHT; + void _lcd_set_delta_height() { + home_offset[Z_AXIS] = _delta_height - DELTA_HEIGHT; + update_software_endstops(Z_AXIS); + } + + void lcd_delta_settings() { START_MENU(); MENU_BACK(MSG_DELTA_CALIBRATE); - float delta_height = DELTA_HEIGHT + home_offset[Z_AXIS], Tz = 0.00; - MENU_ITEM_EDIT(float52, "Height", &delta_height, delta_height, delta_height); + float Tz = 0.00; + MENU_ITEM_EDIT(float52, MSG_DELTA_DIAG_ROG, &delta_diagonal_rod, DELTA_DIAGONAL_ROD - 5.0, DELTA_DIAGONAL_ROD + 5.0); + _delta_height = DELTA_HEIGHT + home_offset[Z_AXIS]; + MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float52, MSG_DELTA_HEIGHT, &_delta_height, _delta_height - 10.0, _delta_height + 10.0, _lcd_set_delta_height); MENU_ITEM_EDIT(float43, "Ex", &endstop_adj[A_AXIS], -5.0, 5.0); MENU_ITEM_EDIT(float43, "Ey", &endstop_adj[B_AXIS], -5.0, 5.0); MENU_ITEM_EDIT(float43, "Ez", &endstop_adj[C_AXIS], -5.0, 5.0); - MENU_ITEM_EDIT(float52, "Radius", &delta_radius, DELTA_RADIUS - 5.0, DELTA_RADIUS + 5.0); + MENU_ITEM_EDIT(float52, MSG_DELTA_RADIUS, &delta_radius, DELTA_RADIUS - 5.0, DELTA_RADIUS + 5.0); MENU_ITEM_EDIT(float43, "Tx", &delta_tower_angle_trim[A_AXIS], -5.0, 5.0); MENU_ITEM_EDIT(float43, "Ty", &delta_tower_angle_trim[B_AXIS], -5.0, 5.0); MENU_ITEM_EDIT(float43, "Tz", &Tz, -5.0, 5.0); @@ -2556,7 +2564,7 @@ void kill_screen(const char* lcd_msg) { START_MENU(); MENU_BACK(MSG_MAIN); #if ENABLED(DELTA_AUTO_CALIBRATION) - MENU_ITEM(submenu, MSG_DELTA_SETTINGS, lcd_delta_G33_settings); + MENU_ITEM(submenu, MSG_DELTA_SETTINGS, lcd_delta_settings); MENU_ITEM(gcode, MSG_DELTA_AUTO_CALIBRATE, PSTR("G33")); MENU_ITEM(gcode, MSG_DELTA_HEIGHT_CALIBRATE, PSTR("G33 P1")); #if ENABLED(EEPROM_SETTINGS) From 6bd63d27b50f417b65abc83a95dd9dff639344b5 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 11 Aug 2017 16:39:55 -0500 Subject: [PATCH 077/112] Updates to G29 for probe error handling --- Marlin/Marlin_main.cpp | 364 ++++++++++++++++++++--------------------- 1 file changed, 182 insertions(+), 182 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index c56325810..5c505263d 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -2222,7 +2222,14 @@ static void clean_up_after_endstop_or_probe_move() { return false; } - static bool do_probe_move(float z, float fr_mm_m) { + /** + * @brief Used by run_z_probe to do a single Z probe move. + * + * @param z Z destination + * @param fr_mm_s Feedrate in mm/s + * @return true to indicate an error + */ + static bool do_probe_move(const float z, const float fr_mm_m) { #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) DEBUG_POS(">>> do_probe_move", current_position); #endif @@ -2241,7 +2248,7 @@ static void clean_up_after_endstop_or_probe_move() { // Check to see if the probe was triggered const bool probe_triggered = TEST(Endstops::endstop_hit_bits, - #ifdef Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN + #if ENABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) Z_MIN #else Z_MIN_PROBE @@ -2273,9 +2280,14 @@ static void clean_up_after_endstop_or_probe_move() { return !probe_triggered; } - // Do a single Z probe and return with current_position[Z_AXIS] - // at the height where the probe triggered. - static float run_z_probe(bool printable=true) { + /** + * @details Used by probe_pt to do a single Z probe. + * Leaves current_position[Z_AXIS] at the height where the probe triggered. + * + * @param short_move Flag for a shorter probe move towards the bed + * @return The raw Z position where the probe was triggered + */ + static float run_z_probe(const bool short_move=true) { #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) DEBUG_POS(">>> run_z_probe", current_position); @@ -2313,7 +2325,7 @@ static void clean_up_after_endstop_or_probe_move() { #endif // move down slowly to find bed - if (do_probe_move(-10 + (printable ? 0 : -(Z_MAX_LENGTH)), Z_PROBE_SPEED_SLOW)) return NAN; + if (do_probe_move(-10 + (short_move ? 0 : -(Z_MAX_LENGTH)), Z_PROBE_SPEED_SLOW)) return NAN; #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) DEBUG_POS("<<< run_z_probe", current_position); @@ -2410,6 +2422,12 @@ static void clean_up_after_endstop_or_probe_move() { feedrate_mm_s = old_feedrate_mm_s; + if (isnan(measured_z)) { + LCD_MESSAGEPGM(MSG_ERR_PROBING_FAILED); + SERIAL_ERROR_START(); + SERIAL_ERRORLNPGM(MSG_ERR_PROBING_FAILED); + } + return measured_z; } @@ -3775,9 +3793,7 @@ inline void gcode_G4() { // If an endstop was not hit, then damage can occur if homing is continued. // This can occur if the delta height (DELTA_HEIGHT + home_offset[Z_AXIS]) is // not set correctly. - if (!(TEST(Endstops::endstop_hit_bits, X_MAX) || - TEST(Endstops::endstop_hit_bits, Y_MAX) || - TEST(Endstops::endstop_hit_bits, Z_MAX))) { + if (!(Endstops::endstop_hit_bits & (_BV(X_MAX) | _BV(Y_MAX) | _BV(Z_MAX)))) { LCD_MESSAGEPGM(MSG_ERR_HOMING_FAILED); SERIAL_ERROR_START(); SERIAL_ERRORLNPGM(MSG_ERR_HOMING_FAILED); @@ -4126,20 +4142,6 @@ void home_all_axes() { gcode_G28(true); } #endif -#if HAS_BED_PROBE - - static bool nan_error(const float v) { - const bool is_nan = isnan(v); - if (is_nan) { - LCD_MESSAGEPGM(MSG_ERR_PROBING_FAILED); - SERIAL_ERROR_START(); - SERIAL_ERRORLNPGM(MSG_ERR_PROBING_FAILED); - } - return is_nan; - } - -#endif // HAS_BED_PROBE - #if ENABLED(MESH_BED_LEVELING) // Save 130 bytes with non-duplication of PSTR @@ -4675,18 +4677,16 @@ void home_all_axes() { gcode_G28(true); } SYNC_PLAN_POSITION_KINEMATIC(); } - if (!faux) setup_for_endstop_or_probe_move(); - - //xProbe = yProbe = measured_z = 0; - #if HAS_BED_PROBE // Deploy the probe. Probe will raise if needed. if (DEPLOY_PROBE()) { planner.abl_enabled = abl_should_enable; - goto FAIL; + return; } #endif + if (!faux) setup_for_endstop_or_probe_move(); + #if ENABLED(AUTO_BED_LEVELING_BILINEAR) #if ENABLED(PROBE_MANUALLY) @@ -4907,7 +4907,7 @@ void home_all_axes() { gcode_G28(true); } 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++) { + for (uint8_t PR_OUTER_VAR = 0; PR_OUTER_VAR < PR_OUTER_END && !isnan(measured_z); PR_OUTER_VAR++) { int8_t inStart, inStop, inInc; @@ -4944,9 +4944,9 @@ void home_all_axes() { gcode_G28(true); } measured_z = faux ? 0.001 * random(-100, 101) : probe_pt(xProbe, yProbe, stow_probe_after_each, verbose_level); - if (nan_error(measured_z)) { + if (isnan(measured_z)) { planner.abl_enabled = abl_should_enable; - goto FAIL; + break; } #if ENABLED(AUTO_BED_LEVELING_LINEAR) @@ -4980,14 +4980,14 @@ void home_all_axes() { gcode_G28(true); } xProbe = LOGICAL_X_POSITION(points[i].x); yProbe = LOGICAL_Y_POSITION(points[i].y); measured_z = faux ? 0.001 * random(-100, 101) : probe_pt(xProbe, yProbe, stow_probe_after_each, verbose_level); - if (nan_error(measured_z)) { + if (isnan(measured_z)) { planner.abl_enabled = abl_should_enable; - goto FAIL; + break; } points[i].z = measured_z; } - if (!dryrun) { + if (!dryrun && !isnan(measured_z)) { vector_3 planeNormal = vector_3::cross(points[0] - points[1], points[2] - points[1]).get_normal(); if (planeNormal.z < 0) { planeNormal.x *= -1; @@ -5005,7 +5005,7 @@ void home_all_axes() { gcode_G28(true); } // Raise to _Z_CLEARANCE_DEPLOY_PROBE. Stow the probe. if (STOW_PROBE()) { planner.abl_enabled = abl_should_enable; - goto FAIL; + measured_z = NAN; } } #endif // !PROBE_MANUALLY @@ -5032,114 +5032,91 @@ void home_all_axes() { gcode_G28(true); } #endif // Calculate leveling, print reports, correct the position - #if ENABLED(AUTO_BED_LEVELING_BILINEAR) + if (!isnan(measured_z)) { + #if ENABLED(AUTO_BED_LEVELING_BILINEAR) - if (!dryrun) extrapolate_unprobed_bed_level(); - print_bilinear_leveling_grid(); + if (!dryrun) extrapolate_unprobed_bed_level(); + print_bilinear_leveling_grid(); - refresh_bed_level(); + refresh_bed_level(); - #if ENABLED(ABL_BILINEAR_SUBDIVISION) - bed_level_virt_print(); - #endif + #if ENABLED(ABL_BILINEAR_SUBDIVISION) + bed_level_virt_print(); + #endif - #elif ENABLED(AUTO_BED_LEVELING_LINEAR) + #elif ENABLED(AUTO_BED_LEVELING_LINEAR) - // For LINEAR leveling calculate matrix, print reports, correct the position + // For LINEAR leveling calculate matrix, print reports, correct the position - /** - * solve the plane equation ax + by + d = z - * A is the matrix with rows [x y 1] for all the probed points - * B is the vector of the Z positions - * the normal vector to the plane is formed by the coefficients of the - * plane equation in the standard form, which is Vx*x+Vy*y+Vz*z+d = 0 - * so Vx = -a Vy = -b Vz = 1 (we want the vector facing towards positive Z - */ - float plane_equation_coefficients[3]; - - finish_incremental_LSF(&lsf_results); - plane_equation_coefficients[0] = -lsf_results.A; // We should be able to eliminate the '-' on these three lines and down below - plane_equation_coefficients[1] = -lsf_results.B; // but that is not yet tested. - plane_equation_coefficients[2] = -lsf_results.D; - - 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); + /** + * solve the plane equation ax + by + d = z + * A is the matrix with rows [x y 1] for all the probed points + * B is the vector of the Z positions + * the normal vector to the plane is formed by the coefficients of the + * plane equation in the standard form, which is Vx*x+Vy*y+Vz*z+d = 0 + * so Vx = -a Vy = -b Vz = 1 (we want the vector facing towards positive Z + */ + float plane_equation_coefficients[3]; + + finish_incremental_LSF(&lsf_results); + plane_equation_coefficients[0] = -lsf_results.A; // We should be able to eliminate the '-' on these three lines and down below + plane_equation_coefficients[1] = -lsf_results.B; // but that is not yet tested. + plane_equation_coefficients[2] = -lsf_results.D; + + 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(); + } } - } - // 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) // We can eliminate the '-' here and up above - ); + // 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) // We can eliminate the '-' here and up above + ); - // 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)"); - - float min_diff = 999; - - 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(); + // Show the Topography map if enabled + if (do_topography_map) { - if (verbose_level > 3) { - SERIAL_PROTOCOLLNPGM("\nCorrected Bed Height vs. Bed Topology:"); + 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; 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 x_tmp = eqnAMatrix[ind + 0 * abl2], + 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); - float diff = eqnBVector[ind] - z_tmp - min_diff; + NOMORE(min_diff, eqnBVector[ind] - z_tmp); + if (diff >= 0.0) - SERIAL_PROTOCOLPGM(" +"); - // Include + for column alignment + SERIAL_PROTOCOLPGM(" +"); // Include + for column alignment else SERIAL_PROTOCOLCHAR(' '); SERIAL_PROTOCOL_F(diff, 5); @@ -5147,87 +5124,110 @@ void home_all_axes() { gcode_G28(true); } SERIAL_EOL(); } // yy SERIAL_EOL(); - } - } //do_topography_map - #endif // AUTO_BED_LEVELING_LINEAR + 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 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); + + 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 - #if ABL_PLANAR + #endif // AUTO_BED_LEVELING_LINEAR - // For LINEAR and 3POINT leveling correct the current position + #if ABL_PLANAR - if (verbose_level > 0) - planner.bed_level_matrix.debug(PSTR("\n\nBed Level Correction Matrix:")); + // For LINEAR and 3POINT leveling correct the current position - if (!dryrun) { - // - // Correct the current XYZ position based on the tilted plane. - // + if (verbose_level > 0) + planner.bed_level_matrix.debug(PSTR("\n\nBed Level Correction Matrix:")); - #if ENABLED(DEBUG_LEVELING_FEATURE) - if (DEBUGGING(LEVELING)) DEBUG_POS("G29 uncorrected XYZ", current_position); - #endif + if (!dryrun) { + // + // Correct the current XYZ position based on the tilted plane. + // - float converted[XYZ]; - COPY(converted, current_position); + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (DEBUGGING(LEVELING)) DEBUG_POS("G29 uncorrected XYZ", current_position); + #endif - planner.abl_enabled = true; - planner.unapply_leveling(converted); // use conversion machinery - planner.abl_enabled = false; + float converted[XYZ]; + COPY(converted, current_position); + + planner.abl_enabled = true; + planner.unapply_leveling(converted); // use conversion machinery + planner.abl_enabled = false; + + // 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)) + ) { + const float simple_z = current_position[Z_AXIS] - measured_z; + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (DEBUGGING(LEVELING)) { + SERIAL_ECHOPAIR("Z from Probe:", simple_z); + SERIAL_ECHOPAIR(" Matrix:", converted[Z_AXIS]); + SERIAL_ECHOLNPAIR(" Discrepancy:", simple_z - converted[Z_AXIS]); + } + #endif + converted[Z_AXIS] = simple_z; + } + + // The rotated XY and corrected Z are now current_position + COPY(current_position, converted); - // 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)) - ) { - const float simple_z = current_position[Z_AXIS] - measured_z; #if ENABLED(DEBUG_LEVELING_FEATURE) - if (DEBUGGING(LEVELING)) { - SERIAL_ECHOPAIR("Z from Probe:", simple_z); - SERIAL_ECHOPAIR(" Matrix:", converted[Z_AXIS]); - SERIAL_ECHOLNPAIR(" Discrepancy:", simple_z - converted[Z_AXIS]); - } + if (DEBUGGING(LEVELING)) DEBUG_POS("G29 corrected XYZ", current_position); #endif - converted[Z_AXIS] = simple_z; } - // The rotated XY and corrected Z are now current_position - COPY(current_position, converted); + #elif ENABLED(AUTO_BED_LEVELING_BILINEAR) - #if ENABLED(DEBUG_LEVELING_FEATURE) - if (DEBUGGING(LEVELING)) DEBUG_POS("G29 corrected XYZ", current_position); - #endif - } + if (!dryrun) { + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPAIR("G29 uncorrected Z:", current_position[Z_AXIS]); + #endif - #elif ENABLED(AUTO_BED_LEVELING_BILINEAR) + // 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 (!dryrun) { - #if ENABLED(DEBUG_LEVELING_FEATURE) - if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPAIR("G29 uncorrected Z:", current_position[Z_AXIS]); - #endif + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPAIR(" corrected 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); + #endif // ABL_PLANAR + #ifdef Z_PROBE_END_SCRIPT #if ENABLED(DEBUG_LEVELING_FEATURE) - if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPAIR(" corrected Z:", current_position[Z_AXIS]); + if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPAIR("Z Probe End Script: ", Z_PROBE_END_SCRIPT); #endif - } - - #endif // ABL_PLANAR - - #ifdef Z_PROBE_END_SCRIPT - #if ENABLED(DEBUG_LEVELING_FEATURE) - if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPAIR("Z Probe End Script: ", Z_PROBE_END_SCRIPT); + enqueue_and_echo_commands_P(PSTR(Z_PROBE_END_SCRIPT)); + stepper.synchronize(); #endif - enqueue_and_echo_commands_P(PSTR(Z_PROBE_END_SCRIPT)); - stepper.synchronize(); - #endif - - // Auto Bed Leveling is complete! Enable if possible. - planner.abl_enabled = dryrun ? abl_should_enable : true; - FAIL: + // Auto Bed Leveling is complete! Enable if possible. + planner.abl_enabled = dryrun ? abl_should_enable : true; + } // !isnan(measured_z) // Restore state after probing if (!faux) clean_up_after_endstop_or_probe_move(); @@ -5272,7 +5272,7 @@ void home_all_axes() { gcode_G28(true); } const float measured_z = probe_pt(xpos, ypos, parser.boolval('S', true), 1); - if (!nan_error(measured_z)) { + if (!isnan(measured_z)) { SERIAL_PROTOCOLPAIR("Bed X: ", FIXFLOAT(xpos)); SERIAL_PROTOCOLPAIR(" Y: ", FIXFLOAT(ypos)); SERIAL_PROTOCOLLNPAIR(" Z: ", FIXFLOAT(measured_z)); From 75e6ead5fd627a9029d79d7a708a2baf146e5076 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 11 Aug 2017 16:48:01 -0500 Subject: [PATCH 078/112] Eliminate goto in gcode_G33 --- Marlin/Marlin_main.cpp | 43 +++++++++++++++++++++++++----------------- 1 file changed, 26 insertions(+), 17 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 5c505263d..981ba84e5 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -5355,6 +5355,21 @@ void home_all_axes() { gcode_G28(true); } } } + void G33_cleanup( + #if HOTENDS > 1 + const uint8_t old_tool_index + #endif + ) { + #if ENABLED(DELTA_HOME_TO_SAFE_ZONE) + do_blocking_move_to_z(delta_clip_start_height); + #endif + STOW_PROBE(); + clean_up_after_endstop_or_probe_move(); + #if HOTENDS > 1 + tool_change(old_tool_index, 0, true); + #endif + } + inline void gcode_G33() { const int8_t probe_points = parser.intval('P', DELTA_CALIBRATION_DEFAULT_POINTS); @@ -5431,10 +5446,15 @@ void home_all_axes() { gcode_G28(true); } #if HAS_LEVELING reset_bed_level(); // After calibration bed-level data is no longer valid #endif + #if HOTENDS > 1 const uint8_t old_tool_index = active_extruder; tool_change(0, 0, true); + #define G33_CLEANUP() G33_cleanup(old_tool_index) + #else + #define G33_CLEANUP() G33_cleanup() #endif + setup_for_endstop_or_probe_move(); endstops.enable(true); if (!home_delta()) @@ -5453,10 +5473,8 @@ void home_all_axes() { gcode_G28(true); } #if DISABLED(PROBE_MANUALLY) const float measured_z = probe_pt(dx, dy, stow_after_each, 1, false); // 1st probe to set height - if (nan_error(measured_z)) - goto FAIL; - else - home_offset[Z_AXIS] -= measured_z; + if (isnan(measured_z)) return G33_CLEANUP(); + home_offset[Z_AXIS] -= measured_z; #endif do { @@ -5474,7 +5492,7 @@ void home_all_axes() { gcode_G28(true); } z_at_pt[0] += lcd_probe_pt(0, 0); #else z_at_pt[0] += probe_pt(dx, dy, stow_after_each, 1, false); - if (nan_error(z_at_pt[0])) goto FAIL; + if (isnan(z_at_pt[0])) return G33_CLEANUP(); #endif } if (_7p_calibration) { // probe extra center points @@ -5484,7 +5502,7 @@ void home_all_axes() { gcode_G28(true); } z_at_pt[0] += lcd_probe_pt(cos(a) * r, sin(a) * r); #else z_at_pt[0] += probe_pt(cos(a) * r + dx, sin(a) * r + dy, stow_after_each, 1); - if (nan_error(z_at_pt[0])) goto FAIL; + if (isnan(z_at_pt[0])) return G33_CLEANUP(); #endif } z_at_pt[0] /= float(_7p_double_circle ? 7 : probe_points); @@ -5505,7 +5523,7 @@ void home_all_axes() { gcode_G28(true); } z_at_pt[axis] += lcd_probe_pt(cos(a) * r, sin(a) * r); #else z_at_pt[axis] += probe_pt(cos(a) * r + dx, sin(a) * r + dy, stow_after_each, 1); - if (nan_error(z_at_pt[axis])) goto FAIL; + if (isnan(z_at_pt[axis])) return G33_CLEANUP(); #endif } zig_zag = !zig_zag; @@ -5705,16 +5723,7 @@ void home_all_axes() { gcode_G28(true); } } while ((zero_std_dev < test_precision && zero_std_dev > calibration_precision && iterations < 31) || iterations <= force_iterations); - FAIL: - - #if ENABLED(DELTA_HOME_TO_SAFE_ZONE) - do_blocking_move_to_z(delta_clip_start_height); - #endif - STOW_PROBE(); - clean_up_after_endstop_or_probe_move(); - #if HOTENDS > 1 - tool_change(old_tool_index, 0, true); - #endif + G33_CLEANUP(); } #endif // DELTA_AUTO_CALIBRATION From ac76101ec328fe9314a229a1bb94e01bbd87a3fb Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 11 Aug 2017 16:59:32 -0500 Subject: [PATCH 079/112] Eliminate goto in gcode_M48 --- Marlin/Marlin_main.cpp | 248 +++++++++++++++++++++-------------------- 1 file changed, 126 insertions(+), 122 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 981ba84e5..a94d778be 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -7038,151 +7038,155 @@ inline void gcode_M42() { // Move to the first point, deploy, and probe const float t = probe_pt(X_probe_location, Y_probe_location, stow_probe_after_each, verbose_level); - if (nan_error(t)) goto FAIL; - - randomSeed(millis()); - - for (uint8_t n = 0; n < n_samples; n++) { - if (n_legs) { - const int dir = (random(0, 10) > 5.0) ? -1 : 1; // clockwise or counter clockwise - float angle = random(0.0, 360.0); - const float radius = random( - #if ENABLED(DELTA) - 0.1250000000 * (DELTA_PROBEABLE_RADIUS), - 0.3333333333 * (DELTA_PROBEABLE_RADIUS) - #else - 5.0, 0.125 * min(X_BED_SIZE, Y_BED_SIZE) - #endif - ); - - if (verbose_level > 3) { - SERIAL_ECHOPAIR("Starting radius: ", radius); - SERIAL_ECHOPAIR(" angle: ", angle); - SERIAL_ECHOPGM(" Direction: "); - if (dir > 0) SERIAL_ECHOPGM("Counter-"); - SERIAL_ECHOLNPGM("Clockwise"); - } + bool probing_good = !isnan(t); + + if (probing_good) { + randomSeed(millis()); + + for (uint8_t n = 0; n < n_samples; n++) { + if (n_legs) { + const int dir = (random(0, 10) > 5.0) ? -1 : 1; // clockwise or counter clockwise + float angle = random(0.0, 360.0); + const float radius = random( + #if ENABLED(DELTA) + 0.1250000000 * (DELTA_PROBEABLE_RADIUS), + 0.3333333333 * (DELTA_PROBEABLE_RADIUS) + #else + 5.0, 0.125 * min(X_BED_SIZE, Y_BED_SIZE) + #endif + ); - for (uint8_t l = 0; l < n_legs - 1; l++) { - double delta_angle; + if (verbose_level > 3) { + SERIAL_ECHOPAIR("Starting radius: ", radius); + SERIAL_ECHOPAIR(" angle: ", angle); + SERIAL_ECHOPGM(" Direction: "); + if (dir > 0) SERIAL_ECHOPGM("Counter-"); + SERIAL_ECHOLNPGM("Clockwise"); + } - if (schizoid_flag) - // The points of a 5 point star are 72 degrees apart. We need to - // skip a point and go to the next one on the star. - delta_angle = dir * 2.0 * 72.0; + for (uint8_t l = 0; l < n_legs - 1; l++) { + double delta_angle; - else - // If we do this line, we are just trying to move further - // around the circle. - delta_angle = dir * (float) random(25, 45); + if (schizoid_flag) + // The points of a 5 point star are 72 degrees apart. We need to + // skip a point and go to the next one on the star. + delta_angle = dir * 2.0 * 72.0; - angle += delta_angle; + else + // If we do this line, we are just trying to move further + // around the circle. + delta_angle = dir * (float) random(25, 45); - while (angle > 360.0) // We probably do not need to keep the angle between 0 and 2*PI, but the - angle -= 360.0; // Arduino documentation says the trig functions should not be given values - while (angle < 0.0) // outside of this range. It looks like they behave correctly with - angle += 360.0; // numbers outside of the range, but just to be safe we clamp them. + angle += delta_angle; - X_current = X_probe_location - (X_PROBE_OFFSET_FROM_EXTRUDER) + cos(RADIANS(angle)) * radius; - Y_current = Y_probe_location - (Y_PROBE_OFFSET_FROM_EXTRUDER) + sin(RADIANS(angle)) * radius; + while (angle > 360.0) // We probably do not need to keep the angle between 0 and 2*PI, but the + angle -= 360.0; // Arduino documentation says the trig functions should not be given values + while (angle < 0.0) // outside of this range. It looks like they behave correctly with + angle += 360.0; // numbers outside of the range, but just to be safe we clamp them. - #if DISABLED(DELTA) - X_current = constrain(X_current, X_MIN_POS, X_MAX_POS); - Y_current = constrain(Y_current, Y_MIN_POS, Y_MAX_POS); - #else - // If we have gone out too far, we can do a simple fix and scale the numbers - // back in closer to the origin. - while (!position_is_reachable_by_probe_xy(X_current, Y_current)) { - X_current *= 0.8; - Y_current *= 0.8; - if (verbose_level > 3) { - SERIAL_ECHOPAIR("Pulling point towards center:", X_current); - SERIAL_ECHOLNPAIR(", ", Y_current); + X_current = X_probe_location - (X_PROBE_OFFSET_FROM_EXTRUDER) + cos(RADIANS(angle)) * radius; + Y_current = Y_probe_location - (Y_PROBE_OFFSET_FROM_EXTRUDER) + sin(RADIANS(angle)) * radius; + + #if DISABLED(DELTA) + X_current = constrain(X_current, X_MIN_POS, X_MAX_POS); + Y_current = constrain(Y_current, Y_MIN_POS, Y_MAX_POS); + #else + // If we have gone out too far, we can do a simple fix and scale the numbers + // back in closer to the origin. + while (!position_is_reachable_by_probe_xy(X_current, Y_current)) { + X_current *= 0.8; + Y_current *= 0.8; + if (verbose_level > 3) { + SERIAL_ECHOPAIR("Pulling point towards center:", X_current); + SERIAL_ECHOLNPAIR(", ", Y_current); + } } + #endif + if (verbose_level > 3) { + SERIAL_PROTOCOLPGM("Going to:"); + SERIAL_ECHOPAIR(" X", X_current); + SERIAL_ECHOPAIR(" Y", Y_current); + SERIAL_ECHOLNPAIR(" Z", current_position[Z_AXIS]); } - #endif - if (verbose_level > 3) { - SERIAL_PROTOCOLPGM("Going to:"); - SERIAL_ECHOPAIR(" X", X_current); - SERIAL_ECHOPAIR(" Y", Y_current); - SERIAL_ECHOLNPAIR(" Z", current_position[Z_AXIS]); - } - do_blocking_move_to_xy(X_current, Y_current); - } // n_legs loop - } // n_legs + 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, 0); - if (nan_error(sample_set[n])) goto FAIL; + // Probe a single point + 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 - */ - double sum = 0.0; - for (uint8_t j = 0; j <= n; j++) sum += sample_set[j]; - mean = sum / (n + 1); + // Break the loop if the probe fails + probing_good = !isnan(sample_set[n]); + if (!probing_good) break; - NOMORE(min, sample_set[n]); - NOLESS(max, sample_set[n]); + /** + * Get the current mean for the data points we have so far + */ + double sum = 0.0; + for (uint8_t j = 0; j <= n; j++) sum += sample_set[j]; + mean = sum / (n + 1); - /** - * Now, use that mean to calculate the standard deviation for the - * data points we have so far - */ - sum = 0.0; - for (uint8_t j = 0; j <= n; j++) - sum += sq(sample_set[j] - mean); + NOMORE(min, sample_set[n]); + NOLESS(max, sample_set[n]); - sigma = SQRT(sum / (n + 1)); - if (verbose_level > 0) { - if (verbose_level > 1) { - SERIAL_PROTOCOL(n + 1); - SERIAL_PROTOCOLPGM(" of "); - SERIAL_PROTOCOL((int)n_samples); - SERIAL_PROTOCOLPGM(": z: "); - SERIAL_PROTOCOL_F(sample_set[n], 3); - if (verbose_level > 2) { - SERIAL_PROTOCOLPGM(" mean: "); - 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); + /** + * Now, use that mean to calculate the standard deviation for the + * data points we have so far + */ + sum = 0.0; + for (uint8_t j = 0; j <= n; j++) + sum += sq(sample_set[j] - mean); + + sigma = SQRT(sum / (n + 1)); + if (verbose_level > 0) { + if (verbose_level > 1) { + SERIAL_PROTOCOL(n + 1); + SERIAL_PROTOCOLPGM(" of "); + SERIAL_PROTOCOL((int)n_samples); + SERIAL_PROTOCOLPGM(": z: "); + SERIAL_PROTOCOL_F(sample_set[n], 3); + if (verbose_level > 2) { + SERIAL_PROTOCOLPGM(" mean: "); + 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(); } - SERIAL_EOL(); } - } - } // End of probe loop + } // n_samples loop + } - if (STOW_PROBE()) goto FAIL; + STOW_PROBE(); - SERIAL_PROTOCOLPGM("Finished!"); - SERIAL_EOL(); + if (probing_good) { + SERIAL_PROTOCOLLNPGM("Finished!"); + + 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(); + } - 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_PROTOCOLPGM("Standard Deviation: "); + SERIAL_PROTOCOL_F(sigma, 6); + SERIAL_EOL(); SERIAL_EOL(); } - SERIAL_PROTOCOLPGM("Standard Deviation: "); - SERIAL_PROTOCOL_F(sigma, 6); - SERIAL_EOL(); - SERIAL_EOL(); - - FAIL: - clean_up_after_endstop_or_probe_move(); // Re-enable bed level correction if it had been on From 75e6f72c89d9a2afc232b5097ced3f5d8b9a3df1 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 9 Aug 2017 13:23:14 -0500 Subject: [PATCH 080/112] Fix hexadecimal number formatting --- Marlin/Sd2Card.cpp | 28 ++++++++--------- Marlin/Sd2Card.h | 22 ++++++------- Marlin/SdBaseFile.cpp | 14 ++++----- Marlin/SdBaseFile.h | 26 ++++++++-------- Marlin/SdFatStructs.h | 72 +++++++++++++++++++++---------------------- Marlin/SdInfo.h | 52 +++++++++++++++---------------- Marlin/SdVolume.cpp | 20 ++++++------ Marlin/SdVolume.h | 2 +- Marlin/pca9632.cpp | 2 +- Marlin/softspi.h | 6 ++-- 10 files changed, 122 insertions(+), 122 deletions(-) diff --git a/Marlin/Sd2Card.cpp b/Marlin/Sd2Card.cpp index 74de29b9d..ce07846f1 100644 --- a/Marlin/Sd2Card.cpp +++ b/Marlin/Sd2Card.cpp @@ -55,7 +55,7 @@ //------------------------------------------------------------------------------ /** SPI receive a byte */ static uint8_t spiRec() { - SPDR = 0XFF; + SPDR = 0xFF; while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ } return SPDR; } @@ -64,11 +64,11 @@ static inline __attribute__((always_inline)) void spiRead(uint8_t* buf, uint16_t nbyte) { if (nbyte-- == 0) return; - SPDR = 0XFF; + SPDR = 0xFF; for (uint16_t i = 0; i < nbyte; i++) { while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ } buf[i] = SPDR; - SPDR = 0XFF; + SPDR = 0xFF; } while (!TEST(SPSR, SPIF)) { /* Intentionally left empty */ } buf[nbyte] = SPDR; @@ -103,7 +103,7 @@ uint8_t data = 0; // no interrupts during byte receive - about 8 us cli(); - // output pin high - like sending 0XFF + // output pin high - like sending 0xFF WRITE(SPI_MOSI_PIN, HIGH); for (uint8_t i = 0; i < 8; i++) { @@ -137,7 +137,7 @@ for (uint8_t i = 0; i < 8; i++) { WRITE(SPI_SCK_PIN, LOW); - WRITE(SPI_MOSI_PIN, data & 0X80); + WRITE(SPI_MOSI_PIN, data & 0x80); data <<= 1; @@ -177,16 +177,16 @@ uint8_t Sd2Card::cardCommand(uint8_t cmd, uint32_t arg) { for (int8_t s = 24; s >= 0; s -= 8) spiSend(arg >> s); // send CRC - uint8_t crc = 0XFF; - if (cmd == CMD0) crc = 0X95; // correct crc for CMD0 with arg 0 - if (cmd == CMD8) crc = 0X87; // correct crc for CMD8 with arg 0X1AA + uint8_t crc = 0xFF; + if (cmd == CMD0) crc = 0x95; // correct crc for CMD0 with arg 0 + if (cmd == CMD8) crc = 0x87; // correct crc for CMD8 with arg 0x1AA spiSend(crc); // skip stuff byte for stop read if (cmd == CMD12) spiRec(); // wait for response - for (uint8_t i = 0; ((status_ = spiRec()) & 0X80) && i != 0XFF; i++) { /* Intentionally left empty */ } + for (uint8_t i = 0; ((status_ = spiRec()) & 0x80) && i != 0xFF; i++) { /* Intentionally left empty */ } return status_; } //------------------------------------------------------------------------------ @@ -329,7 +329,7 @@ bool Sd2Card::init(uint8_t sckRateID, uint8_t chipSelectPin) { #endif // SOFTWARE_SPI // must supply min of 74 clock cycles with CS high. - for (uint8_t i = 0; i < 10; i++) spiSend(0XFF); + for (uint8_t i = 0; i < 10; i++) spiSend(0xFF); // command to go idle in SPI mode while ((status_ = cardCommand(CMD0, 0)) != R1_IDLE_STATE) { @@ -345,14 +345,14 @@ bool Sd2Card::init(uint8_t sckRateID, uint8_t chipSelectPin) { else { // only need last byte of r7 response for (uint8_t i = 0; i < 4; i++) status_ = spiRec(); - if (status_ != 0XAA) { + if (status_ != 0xAA) { error(SD_CARD_ERROR_CMD8); goto fail; } type(SD_CARD_TYPE_SD2); } // initialize card and send host supports SDHC if SD2 - arg = type() == SD_CARD_TYPE_SD2 ? 0X40000000 : 0; + arg = type() == SD_CARD_TYPE_SD2 ? 0x40000000 : 0; while ((status_ = cardAcmd(ACMD41, arg)) != R1_READY_STATE) { // check for timeout @@ -367,7 +367,7 @@ bool Sd2Card::init(uint8_t sckRateID, uint8_t chipSelectPin) { error(SD_CARD_ERROR_CMD58); goto fail; } - if ((spiRec() & 0XC0) == 0XC0) type(SD_CARD_TYPE_SDHC); + if ((spiRec() & 0xC0) == 0xC0) type(SD_CARD_TYPE_SDHC); // discard rest of ocr - contains allowed voltage range for (uint8_t i = 0; i < 3; i++) spiRec(); } @@ -473,7 +473,7 @@ static const uint16_t crctab[] PROGMEM = { static uint16_t CRC_CCITT(const uint8_t* data, size_t n) { uint16_t crc = 0; for (size_t i = 0; i < n; i++) { - crc = pgm_read_word(&crctab[(crc >> 8 ^ data[i]) & 0XFF]) ^ (crc << 8); + crc = pgm_read_word(&crctab[(crc >> 8 ^ data[i]) & 0xFF]) ^ (crc << 8); } return crc; } diff --git a/Marlin/Sd2Card.h b/Marlin/Sd2Card.h index f91958ac0..1fbd52747 100644 --- a/Marlin/Sd2Card.h +++ b/Marlin/Sd2Card.h @@ -92,27 +92,27 @@ uint8_t const SD_CARD_ERROR_ERASE_TIMEOUT = 0XE; /** card returned an error token instead of read data */ uint8_t const SD_CARD_ERROR_READ = 0XF; /** read CID or CSD failed */ -uint8_t const SD_CARD_ERROR_READ_REG = 0X10; +uint8_t const SD_CARD_ERROR_READ_REG = 0x10; /** timeout while waiting for start of read data */ -uint8_t const SD_CARD_ERROR_READ_TIMEOUT = 0X11; +uint8_t const SD_CARD_ERROR_READ_TIMEOUT = 0x11; /** card did not accept STOP_TRAN_TOKEN */ -uint8_t const SD_CARD_ERROR_STOP_TRAN = 0X12; +uint8_t const SD_CARD_ERROR_STOP_TRAN = 0x12; /** card returned an error token as a response to a write operation */ -uint8_t const SD_CARD_ERROR_WRITE = 0X13; +uint8_t const SD_CARD_ERROR_WRITE = 0x13; /** attempt to write protected block zero */ -uint8_t const SD_CARD_ERROR_WRITE_BLOCK_ZERO = 0X14; // REMOVE - not used +uint8_t const SD_CARD_ERROR_WRITE_BLOCK_ZERO = 0x14; // REMOVE - not used /** card did not go ready for a multiple block write */ -uint8_t const SD_CARD_ERROR_WRITE_MULTIPLE = 0X15; +uint8_t const SD_CARD_ERROR_WRITE_MULTIPLE = 0x15; /** card returned an error to a CMD13 status check after a write */ -uint8_t const SD_CARD_ERROR_WRITE_PROGRAMMING = 0X16; +uint8_t const SD_CARD_ERROR_WRITE_PROGRAMMING = 0x16; /** timeout occurred during write programming */ -uint8_t const SD_CARD_ERROR_WRITE_TIMEOUT = 0X17; +uint8_t const SD_CARD_ERROR_WRITE_TIMEOUT = 0x17; /** incorrect rate selected */ -uint8_t const SD_CARD_ERROR_SCK_RATE = 0X18; +uint8_t const SD_CARD_ERROR_SCK_RATE = 0x18; /** init() not called */ -uint8_t const SD_CARD_ERROR_INIT_NOT_CALLED = 0X19; +uint8_t const SD_CARD_ERROR_INIT_NOT_CALLED = 0x19; /** crc check error */ -uint8_t const SD_CARD_ERROR_CRC = 0X20; +uint8_t const SD_CARD_ERROR_CRC = 0x20; //------------------------------------------------------------------------------ // card types /** Standard capacity V1 SD card */ diff --git a/Marlin/SdBaseFile.cpp b/Marlin/SdBaseFile.cpp index 97b4fa00f..0dc165cd6 100644 --- a/Marlin/SdBaseFile.cpp +++ b/Marlin/SdBaseFile.cpp @@ -57,7 +57,7 @@ bool SdBaseFile::addCluster() { bool SdBaseFile::addDirCluster() { uint32_t block; // max folder size - if (fileSize_ / sizeof(dir_t) >= 0XFFFF) goto fail; + if (fileSize_ / sizeof(dir_t) >= 0xFFFF) goto fail; if (!addCluster()) goto fail; if (!vol_->cacheFlush()) goto fail; @@ -510,7 +510,7 @@ bool SdBaseFile::mkdir(SdBaseFile* parent, const uint8_t dname[11]) { d.firstClusterHigh = 0; } else { - d.firstClusterLow = parent->firstCluster_ & 0XFFFF; + d.firstClusterLow = parent->firstCluster_ & 0xFFFF; d.firstClusterHigh = parent->firstCluster_ >> 16; } // copy '..' to block @@ -1063,7 +1063,7 @@ int16_t SdBaseFile::read(void* buf, uint16_t nbyte) { // amount left to read toRead = nbyte; while (toRead > 0) { - offset = curPosition_ & 0X1FF; // offset in block + offset = curPosition_ & 0x1FF; // offset in block if (type_ == FAT_FILE_TYPE_ROOT_FIXED) { block = vol_->rootDirStart() + (curPosition_ >> 9); } @@ -1120,7 +1120,7 @@ fail: int8_t SdBaseFile::readDir(dir_t* dir, char* longFilename) { int16_t n; // if not a directory file or miss-positioned return an error - if (!isDir() || (0X1F & curPosition_)) return -1; + if (!isDir() || (0x1F & curPosition_)) return -1; //If we have a longFilename buffer, mark it as invalid. If we find a long filename it will be filled automaticly. if (longFilename != NULL) longFilename[0] = '\0'; @@ -1513,7 +1513,7 @@ bool SdBaseFile::sync() { if (!isDir()) d->fileSize = fileSize_; // update first cluster fields - d->firstClusterLow = firstCluster_ & 0XFFFF; + d->firstClusterLow = firstCluster_ & 0xFFFF; d->firstClusterHigh = firstCluster_ >> 16; // set modify time if user supplied a callback date/time function @@ -1738,7 +1738,7 @@ int16_t SdBaseFile::write(const void* buf, uint16_t nbyte) { while (nToWrite > 0) { uint8_t blockOfCluster = vol_->blockOfCluster(curPosition_); - uint16_t blockOffset = curPosition_ & 0X1FF; + uint16_t blockOffset = curPosition_ & 0x1FF; if (blockOfCluster == 0 && blockOffset == 0) { // start of new cluster if (curCluster_ == 0) { @@ -1774,7 +1774,7 @@ int16_t SdBaseFile::write(const void* buf, uint16_t nbyte) { // full block - don't need to use cache if (vol_->cacheBlockNumber() == block) { // invalidate cache if block is in cache - vol_->cacheSetBlockNumber(0XFFFFFFFF, false); + vol_->cacheSetBlockNumber(0xFFFFFFFF, false); } if (!vol_->writeBlock(block, src)) goto fail; } diff --git a/Marlin/SdBaseFile.h b/Marlin/SdBaseFile.h index 02ab70543..02daa7b7f 100644 --- a/Marlin/SdBaseFile.h +++ b/Marlin/SdBaseFile.h @@ -54,11 +54,11 @@ struct filepos_t { // use the gnu style oflag in open() /** open() oflag for reading */ -uint8_t const O_READ = 0X01; +uint8_t const O_READ = 0x01; /** open() oflag - same as O_IN */ uint8_t const O_RDONLY = O_READ; /** open() oflag for write */ -uint8_t const O_WRITE = 0X02; +uint8_t const O_WRITE = 0x02; /** open() oflag - same as O_WRITE */ uint8_t const O_WRONLY = O_WRITE; /** open() oflag for reading and writing */ @@ -66,17 +66,17 @@ uint8_t const O_RDWR = (O_READ | O_WRITE); /** open() oflag mask for access modes */ uint8_t const O_ACCMODE = (O_READ | O_WRITE); /** The file offset shall be set to the end of the file prior to each write. */ -uint8_t const O_APPEND = 0X04; +uint8_t const O_APPEND = 0x04; /** synchronous writes - call sync() after each write */ -uint8_t const O_SYNC = 0X08; +uint8_t const O_SYNC = 0x08; /** truncate the file to zero length */ -uint8_t const O_TRUNC = 0X10; +uint8_t const O_TRUNC = 0x10; /** set the initial position at the end of the file */ -uint8_t const O_AT_END = 0X20; +uint8_t const O_AT_END = 0x20; /** create the file if nonexistent */ -uint8_t const O_CREAT = 0X40; +uint8_t const O_CREAT = 0x40; /** If O_CREAT and O_EXCL are set, open() shall fail if the file exists */ -uint8_t const O_EXCL = 0X80; +uint8_t const O_EXCL = 0x80; // SdBaseFile class static and const definitions // flags for ls() @@ -141,7 +141,7 @@ static inline uint8_t FAT_MONTH(uint16_t fatDate) { * \return Extracted day [1,31] */ static inline uint8_t FAT_DAY(uint16_t fatDate) { - return fatDate & 0X1F; + return fatDate & 0x1F; } /** time field for FAT directory entry * \param[in] hour [0,23] @@ -167,7 +167,7 @@ static inline uint8_t FAT_HOUR(uint16_t fatTime) { * \return Extracted minute [0,59] */ static inline uint8_t FAT_MINUTE(uint16_t fatTime) { - return (fatTime >> 5) & 0X3F; + return (fatTime >> 5) & 0x3F; } /** second part of FAT directory time field * Note second/2 is stored in packed time. @@ -177,7 +177,7 @@ static inline uint8_t FAT_MINUTE(uint16_t fatTime) { * \return Extracted second [0,58] */ static inline uint8_t FAT_SECOND(uint16_t fatTime) { - return 2 * (fatTime & 0X1F); + return 2 * (fatTime & 0x1F); } /** Default date for file timestamps is 1 Jan 2000 */ uint16_t const FAT_DEFAULT_DATE = ((2000 - 1980) << 9) | (1 << 5) | 1; @@ -338,10 +338,10 @@ class SdBaseFile { // data time callback function static void (*dateTime_)(uint16_t* date, uint16_t* time); // bits defined in flags_ - // should be 0X0F + // should be 0x0F static uint8_t const F_OFLAG = (O_ACCMODE | O_APPEND | O_SYNC); // sync of directory entry required - static uint8_t const F_FILE_DIR_DIRTY = 0X80; + static uint8_t const F_FILE_DIR_DIRTY = 0x80; // private data uint8_t flags_; // See above for definition of flags_ bits diff --git a/Marlin/SdFatStructs.h b/Marlin/SdFatStructs.h index 3e78aa292..52c815d76 100644 --- a/Marlin/SdFatStructs.h +++ b/Marlin/SdFatStructs.h @@ -43,11 +43,11 @@ */ //------------------------------------------------------------------------------ /** Value for byte 510 of boot block or MBR */ -uint8_t const BOOTSIG0 = 0X55; +uint8_t const BOOTSIG0 = 0x55; /** Value for byte 511 of boot block or MBR */ -uint8_t const BOOTSIG1 = 0XAA; +uint8_t const BOOTSIG1 = 0xAA; /** Value for bootSignature field int FAT/FAT32 boot sector */ -uint8_t const EXTENDED_BOOT_SIG = 0X29; +uint8_t const EXTENDED_BOOT_SIG = 0x29; //------------------------------------------------------------------------------ /** * \struct partitionTable @@ -59,8 +59,8 @@ uint8_t const EXTENDED_BOOT_SIG = 0X29; struct partitionTable { /** * Boot Indicator . Indicates whether the volume is the active - * partition. Legal values include: 0X00. Do not use for booting. - * 0X80 Active partition. + * partition. Legal values include: 0x00. Do not use for booting. + * 0x80 Active partition. */ uint8_t boot; /** @@ -126,9 +126,9 @@ struct masterBootRecord { uint16_t usuallyZero; /** Partition tables. */ part_t part[4]; - /** First MBR signature byte. Must be 0X55 */ + /** First MBR signature byte. Must be 0x55 */ uint8_t mbrSig0; - /** Second MBR signature byte. Must be 0XAA */ + /** Second MBR signature byte. Must be 0xAA */ uint8_t mbrSig1; } PACKED; /** Type name for masterBootRecord */ @@ -234,7 +234,7 @@ struct fat_boot { uint8_t driveNumber; /** used by Windows NT - should be zero for FAT */ uint8_t reserved1; - /** 0X29 if next three fields are valid */ + /** 0x29 if next three fields are valid */ uint8_t bootSignature; /** * A random serial number created when formatting a disk, @@ -254,9 +254,9 @@ struct fat_boot { char fileSystemType[8]; /** X86 boot code */ uint8_t bootCode[448]; - /** must be 0X55 */ + /** must be 0x55 */ uint8_t bootSectorSig0; - /** must be 0XAA */ + /** must be 0xAA */ uint8_t bootSectorSig1; } PACKED; /** Type name for FAT Boot Sector */ @@ -389,7 +389,7 @@ struct fat32_boot { uint8_t driveNumber; /** used by Windows NT - should be zero for FAT */ uint8_t reserved1; - /** 0X29 if next three fields are valid */ + /** 0x29 if next three fields are valid */ uint8_t bootSignature; /** * A random serial number created when formatting a disk, @@ -408,9 +408,9 @@ struct fat32_boot { char fileSystemType[8]; /** X86 boot code */ uint8_t bootCode[420]; - /** must be 0X55 */ + /** must be 0x55 */ uint8_t bootSectorSig0; - /** must be 0XAA */ + /** must be 0xAA */ uint8_t bootSectorSig1; } PACKED; /** Type name for FAT32 Boot Sector */ @@ -427,11 +427,11 @@ uint32_t const FSINFO_STRUCT_SIG = 0x61417272; * */ struct fat32_fsinfo { - /** must be 0X52, 0X52, 0X61, 0X41 */ + /** must be 0x52, 0x52, 0x61, 0x41 */ uint32_t leadSignature; /** must be zero */ uint8_t reserved1[480]; - /** must be 0X72, 0X72, 0X41, 0X61 */ + /** must be 0x72, 0x72, 0x41, 0x61 */ uint32_t structSignature; /** * Contains the last known free cluster count on the volume. @@ -450,7 +450,7 @@ struct fat32_fsinfo { uint32_t nextFree; /** must be zero */ uint8_t reserved2[12]; - /** must be 0X00, 0X00, 0X55, 0XAA */ + /** must be 0x00, 0x00, 0x55, 0xAA */ uint8_t tailSignature[4]; } PACKED; /** Type name for FAT32 FSINFO Sector */ @@ -458,19 +458,19 @@ typedef struct fat32_fsinfo fat32_fsinfo_t; //------------------------------------------------------------------------------ // End Of Chain values for FAT entries /** FAT12 end of chain value used by Microsoft. */ -uint16_t const FAT12EOC = 0XFFF; +uint16_t const FAT12EOC = 0xFFF; /** Minimum value for FAT12 EOC. Use to test for EOC. */ -uint16_t const FAT12EOC_MIN = 0XFF8; +uint16_t const FAT12EOC_MIN = 0xFF8; /** FAT16 end of chain value used by Microsoft. */ -uint16_t const FAT16EOC = 0XFFFF; +uint16_t const FAT16EOC = 0xFFFF; /** Minimum value for FAT16 EOC. Use to test for EOC. */ -uint16_t const FAT16EOC_MIN = 0XFFF8; +uint16_t const FAT16EOC_MIN = 0xFFF8; /** FAT32 end of chain value used by Microsoft. */ -uint32_t const FAT32EOC = 0X0FFFFFFF; +uint32_t const FAT32EOC = 0x0FFFFFFF; /** Minimum value for FAT32 EOC. Use to test for EOC. */ -uint32_t const FAT32EOC_MIN = 0X0FFFFFF8; +uint32_t const FAT32EOC_MIN = 0x0FFFFFF8; /** Mask a for FAT32 entry. Entries are 28 bits. */ -uint32_t const FAT32MASK = 0X0FFFFFFF; +uint32_t const FAT32MASK = 0x0FFFFFFF; //------------------------------------------------------------------------------ /** * \struct directoryEntry @@ -590,31 +590,31 @@ struct directoryVFATEntry { typedef struct directoryEntry dir_t; /** Type name for directoryVFATEntry */ typedef struct directoryVFATEntry vfat_t; -/** escape for name[0] = 0XE5 */ -uint8_t const DIR_NAME_0XE5 = 0X05; +/** escape for name[0] = 0xE5 */ +uint8_t const DIR_NAME_0xE5 = 0x05; /** name[0] value for entry that is free after being "deleted" */ -uint8_t const DIR_NAME_DELETED = 0XE5; +uint8_t const DIR_NAME_DELETED = 0xE5; /** name[0] value for entry that is free and no allocated entries follow */ -uint8_t const DIR_NAME_FREE = 0X00; +uint8_t const DIR_NAME_FREE = 0x00; /** file is read-only */ -uint8_t const DIR_ATT_READ_ONLY = 0X01; +uint8_t const DIR_ATT_READ_ONLY = 0x01; /** File should hidden in directory listings */ -uint8_t const DIR_ATT_HIDDEN = 0X02; +uint8_t const DIR_ATT_HIDDEN = 0x02; /** Entry is for a system file */ -uint8_t const DIR_ATT_SYSTEM = 0X04; +uint8_t const DIR_ATT_SYSTEM = 0x04; /** Directory entry contains the volume label */ -uint8_t const DIR_ATT_VOLUME_ID = 0X08; +uint8_t const DIR_ATT_VOLUME_ID = 0x08; /** Entry is for a directory */ -uint8_t const DIR_ATT_DIRECTORY = 0X10; +uint8_t const DIR_ATT_DIRECTORY = 0x10; /** Old DOS archive bit for backup support */ -uint8_t const DIR_ATT_ARCHIVE = 0X20; +uint8_t const DIR_ATT_ARCHIVE = 0x20; /** Test value for long name entry. Test is (d->attributes & DIR_ATT_LONG_NAME_MASK) == DIR_ATT_LONG_NAME. */ -uint8_t const DIR_ATT_LONG_NAME = 0X0F; +uint8_t const DIR_ATT_LONG_NAME = 0x0F; /** Test mask for long name entry */ -uint8_t const DIR_ATT_LONG_NAME_MASK = 0X3F; +uint8_t const DIR_ATT_LONG_NAME_MASK = 0x3F; /** defined attribute bits */ -uint8_t const DIR_ATT_DEFINED_BITS = 0X3F; +uint8_t const DIR_ATT_DEFINED_BITS = 0x3F; /** Directory entry is part of a long name * \param[in] dir Pointer to a directory entry. * diff --git a/Marlin/SdInfo.h b/Marlin/SdInfo.h index f4b36b7ae..88b465690 100644 --- a/Marlin/SdInfo.h +++ b/Marlin/SdInfo.h @@ -45,59 +45,59 @@ //------------------------------------------------------------------------------ // SD card commands /** GO_IDLE_STATE - init card in spi mode if CS low */ -uint8_t const CMD0 = 0X00; +uint8_t const CMD0 = 0x00; /** SEND_IF_COND - verify SD Memory Card interface operating condition.*/ -uint8_t const CMD8 = 0X08; +uint8_t const CMD8 = 0x08; /** SEND_CSD - read the Card Specific Data (CSD register) */ -uint8_t const CMD9 = 0X09; +uint8_t const CMD9 = 0x09; /** SEND_CID - read the card identification information (CID register) */ -uint8_t const CMD10 = 0X0A; +uint8_t const CMD10 = 0x0A; /** STOP_TRANSMISSION - end multiple block read sequence */ -uint8_t const CMD12 = 0X0C; +uint8_t const CMD12 = 0x0C; /** SEND_STATUS - read the card status register */ -uint8_t const CMD13 = 0X0D; +uint8_t const CMD13 = 0x0D; /** READ_SINGLE_BLOCK - read a single data block from the card */ -uint8_t const CMD17 = 0X11; +uint8_t const CMD17 = 0x11; /** READ_MULTIPLE_BLOCK - read a multiple data blocks from the card */ -uint8_t const CMD18 = 0X12; +uint8_t const CMD18 = 0x12; /** WRITE_BLOCK - write a single data block to the card */ -uint8_t const CMD24 = 0X18; +uint8_t const CMD24 = 0x18; /** WRITE_MULTIPLE_BLOCK - write blocks of data until a STOP_TRANSMISSION */ -uint8_t const CMD25 = 0X19; +uint8_t const CMD25 = 0x19; /** ERASE_WR_BLK_START - sets the address of the first block to be erased */ -uint8_t const CMD32 = 0X20; +uint8_t const CMD32 = 0x20; /** ERASE_WR_BLK_END - sets the address of the last block of the continuous range to be erased*/ -uint8_t const CMD33 = 0X21; +uint8_t const CMD33 = 0x21; /** ERASE - erase all previously selected blocks */ -uint8_t const CMD38 = 0X26; +uint8_t const CMD38 = 0x26; /** APP_CMD - escape for application specific command */ -uint8_t const CMD55 = 0X37; +uint8_t const CMD55 = 0x37; /** READ_OCR - read the OCR register of a card */ -uint8_t const CMD58 = 0X3A; +uint8_t const CMD58 = 0x3A; /** SET_WR_BLK_ERASE_COUNT - Set the number of write blocks to be pre-erased before writing */ -uint8_t const ACMD23 = 0X17; +uint8_t const ACMD23 = 0x17; /** SD_SEND_OP_COMD - Sends host capacity support information and activates the card's initialization process */ -uint8_t const ACMD41 = 0X29; +uint8_t const ACMD41 = 0x29; //------------------------------------------------------------------------------ /** status for card in the ready state */ -uint8_t const R1_READY_STATE = 0X00; +uint8_t const R1_READY_STATE = 0x00; /** status for card in the idle state */ -uint8_t const R1_IDLE_STATE = 0X01; +uint8_t const R1_IDLE_STATE = 0x01; /** status bit for illegal command */ -uint8_t const R1_ILLEGAL_COMMAND = 0X04; +uint8_t const R1_ILLEGAL_COMMAND = 0x04; /** start data token for read or write single block*/ -uint8_t const DATA_START_BLOCK = 0XFE; +uint8_t const DATA_START_BLOCK = 0xFE; /** stop token for write multiple blocks*/ -uint8_t const STOP_TRAN_TOKEN = 0XFD; +uint8_t const STOP_TRAN_TOKEN = 0xFD; /** start data token for write multiple blocks*/ -uint8_t const WRITE_MULTIPLE_TOKEN = 0XFC; +uint8_t const WRITE_MULTIPLE_TOKEN = 0xFC; /** mask for data response tokens after a write block operation */ -uint8_t const DATA_RES_MASK = 0X1F; +uint8_t const DATA_RES_MASK = 0x1F; /** write data accepted token */ -uint8_t const DATA_RES_ACCEPTED = 0X05; +uint8_t const DATA_RES_ACCEPTED = 0x05; //------------------------------------------------------------------------------ /** Card IDentification (CID) register */ typedef struct CID { @@ -203,7 +203,7 @@ typedef struct CSDV2 { unsigned char reserved1 : 6; unsigned char csd_ver : 2; // byte 1 - /** fixed to 0X0E */ + /** fixed to 0x0E */ unsigned char taac; // byte 2 /** fixed to 0 */ diff --git a/Marlin/SdVolume.cpp b/Marlin/SdVolume.cpp index 4166c0661..701b116c2 100644 --- a/Marlin/SdVolume.cpp +++ b/Marlin/SdVolume.cpp @@ -167,7 +167,7 @@ bool SdVolume::fatGet(uint32_t cluster, uint32_t* value) { index += index >> 1; lba = fatStartBlock_ + (index >> 9); if (!cacheRawBlock(lba, CACHE_FOR_READ)) goto fail; - index &= 0X1FF; + index &= 0x1FF; uint16_t tmp = cacheBuffer_.data[index]; index++; if (index == 512) { @@ -175,7 +175,7 @@ bool SdVolume::fatGet(uint32_t cluster, uint32_t* value) { index = 0; } tmp |= cacheBuffer_.data[index] << 8; - *value = cluster & 1 ? tmp >> 4 : tmp & 0XFFF; + *value = cluster & 1 ? tmp >> 4 : tmp & 0xFFF; return true; } if (fatType_ == 16) { @@ -191,10 +191,10 @@ bool SdVolume::fatGet(uint32_t cluster, uint32_t* value) { if (!cacheRawBlock(lba, CACHE_FOR_READ)) goto fail; } if (fatType_ == 16) { - *value = cacheBuffer_.fat16[cluster & 0XFF]; + *value = cacheBuffer_.fat16[cluster & 0xFF]; } else { - *value = cacheBuffer_.fat32[cluster & 0X7F] & FAT32MASK; + *value = cacheBuffer_.fat32[cluster & 0x7F] & FAT32MASK; } return true; fail: @@ -217,7 +217,7 @@ bool SdVolume::fatPut(uint32_t cluster, uint32_t value) { if (!cacheRawBlock(lba, CACHE_FOR_WRITE)) goto fail; // mirror second FAT if (fatCount_ > 1) cacheMirrorBlock_ = lba + blocksPerFat_; - index &= 0X1FF; + index &= 0x1FF; uint8_t tmp = value; if (cluster & 1) { tmp = (cacheBuffer_.data[index] & 0XF) | tmp << 4; @@ -233,7 +233,7 @@ bool SdVolume::fatPut(uint32_t cluster, uint32_t value) { } tmp = value >> 4; if (!(cluster & 1)) { - tmp = ((cacheBuffer_.data[index] & 0XF0)) | tmp >> 4; + tmp = ((cacheBuffer_.data[index] & 0xF0)) | tmp >> 4; } cacheBuffer_.data[index] = tmp; return true; @@ -250,10 +250,10 @@ bool SdVolume::fatPut(uint32_t cluster, uint32_t value) { if (!cacheRawBlock(lba, CACHE_FOR_WRITE)) goto fail; // store entry if (fatType_ == 16) { - cacheBuffer_.fat16[cluster & 0XFF] = value; + cacheBuffer_.fat16[cluster & 0xFF] = value; } else { - cacheBuffer_.fat32[cluster & 0X7F] = value; + cacheBuffer_.fat32[cluster & 0x7F] = value; } // mirror second FAT if (fatCount_ > 1) cacheMirrorBlock_ = lba + blocksPerFat_; @@ -344,7 +344,7 @@ bool SdVolume::init(Sd2Card* dev, uint8_t part) { allocSearchStart_ = 2; cacheDirty_ = 0; // cacheFlush() will write block if true cacheMirrorBlock_ = 0; - cacheBlockNumber_ = 0XFFFFFFFF; + cacheBlockNumber_ = 0xFFFFFFFF; // if part == 0 assume super floppy with FAT boot sector in block zero // if part > 0 assume mbr volume with partition table @@ -352,7 +352,7 @@ bool SdVolume::init(Sd2Card* dev, uint8_t part) { if (part > 4)goto fail; if (!cacheRawBlock(volumeStartBlock, CACHE_FOR_READ)) goto fail; part_t* p = &cacheBuffer_.mbr.part[part - 1]; - if ((p->boot & 0X7F) != 0 || + if ((p->boot & 0x7F) != 0 || p->totalSectors < 100 || p->firstSector == 0) { // not a valid partition diff --git a/Marlin/SdVolume.h b/Marlin/SdVolume.h index 990248d6a..3041a6dfb 100644 --- a/Marlin/SdVolume.h +++ b/Marlin/SdVolume.h @@ -76,7 +76,7 @@ class SdVolume { */ cache_t* cacheClear() { if (!cacheFlush()) return 0; - cacheBlockNumber_ = 0XFFFFFFFF; + cacheBlockNumber_ = 0xFFFFFFFF; return &cacheBuffer_; } /** Initialize a FAT volume. Try partition one first then try super diff --git a/Marlin/pca9632.cpp b/Marlin/pca9632.cpp index fe0647639..37f7bd7df 100644 --- a/Marlin/pca9632.cpp +++ b/Marlin/pca9632.cpp @@ -45,7 +45,7 @@ #define PCA9632_PWM3 0x05 #define PCA9632_GRPPWM 0x06 #define PCA9632_GRPFREQ 0x07 -#define PCA9632_LEDOUT 0X08 +#define PCA9632_LEDOUT 0x08 #define PCA9632_SUBADR1 0x09 #define PCA9632_SUBADR2 0x0A #define PCA9632_SUBADR3 0x0B diff --git a/Marlin/softspi.h b/Marlin/softspi.h index 24ee33fed..3b77e443b 100644 --- a/Marlin/softspi.h +++ b/Marlin/softspi.h @@ -455,7 +455,7 @@ void badPinCheck(uint8_t pin) { static inline __attribute__((always_inline)) void fastBitWriteSafe(volatile uint8_t* address, uint8_t bit, bool level) { uint8_t oldSREG; - if (address > (uint8_t*)0X5F) { + if (address > (uint8_t*)0x5F) { oldSREG = SREG; cli(); } @@ -464,7 +464,7 @@ void fastBitWriteSafe(volatile uint8_t* address, uint8_t bit, bool level) { } else { *address &= ~(1 << bit); } - if (address > (uint8_t*)0X5F) { + if (address > (uint8_t*)0x5F) { SREG = oldSREG; } } @@ -488,7 +488,7 @@ bool fastDigitalRead(uint8_t pin) { static inline __attribute__((always_inline)) void fastDigitalToggle(uint8_t pin) { badPinCheck(pin); - if (pinMap[pin].pin > (uint8_t*)0X5F) { + if (pinMap[pin].pin > (uint8_t*)0x5F) { // must write bit to high address port *pinMap[pin].pin = 1 << pinMap[pin].bit; } else { From 8fd58cd6dca91412dec589dcfb85fa6f29d5429f Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 11 Aug 2017 15:55:07 -0500 Subject: [PATCH 081/112] Patch goto labels for consistency --- Marlin/Sd2Card.cpp | 76 +++++------ Marlin/SdBaseFile.cpp | 288 +++++++++++++++++++++--------------------- Marlin/SdVolume.cpp | 76 +++++------ 3 files changed, 220 insertions(+), 220 deletions(-) diff --git a/Marlin/Sd2Card.cpp b/Marlin/Sd2Card.cpp index ce07846f1..2afe9a8b4 100644 --- a/Marlin/Sd2Card.cpp +++ b/Marlin/Sd2Card.cpp @@ -244,7 +244,7 @@ void Sd2Card::chipSelectLow() { */ bool Sd2Card::erase(uint32_t firstBlock, uint32_t lastBlock) { csd_t csd; - if (!readCSD(&csd)) goto fail; + if (!readCSD(&csd)) goto FAIL; // check for single block erase if (!csd.v1.erase_blk_en) { // erase size mask @@ -252,7 +252,7 @@ bool Sd2Card::erase(uint32_t firstBlock, uint32_t lastBlock) { if ((firstBlock & m) != 0 || ((lastBlock + 1) & m) != 0) { // error card can't erase specified area error(SD_CARD_ERROR_ERASE_SINGLE_BLOCK); - goto fail; + goto FAIL; } } if (type_ != SD_CARD_TYPE_SDHC) { @@ -263,15 +263,15 @@ bool Sd2Card::erase(uint32_t firstBlock, uint32_t lastBlock) { || cardCommand(CMD33, lastBlock) || cardCommand(CMD38, 0)) { error(SD_CARD_ERROR_ERASE); - goto fail; + goto FAIL; } if (!waitNotBusy(SD_ERASE_TIMEOUT)) { error(SD_CARD_ERROR_ERASE_TIMEOUT); - goto fail; + goto FAIL; } chipSelectHigh(); return true; -fail: + FAIL: chipSelectHigh(); return false; } @@ -335,7 +335,7 @@ bool Sd2Card::init(uint8_t sckRateID, uint8_t chipSelectPin) { while ((status_ = cardCommand(CMD0, 0)) != R1_IDLE_STATE) { if (((uint16_t)millis() - t0) > SD_INIT_TIMEOUT) { error(SD_CARD_ERROR_CMD0); - goto fail; + goto FAIL; } } // check SD version @@ -347,7 +347,7 @@ bool Sd2Card::init(uint8_t sckRateID, uint8_t chipSelectPin) { for (uint8_t i = 0; i < 4; i++) status_ = spiRec(); if (status_ != 0xAA) { error(SD_CARD_ERROR_CMD8); - goto fail; + goto FAIL; } type(SD_CARD_TYPE_SD2); } @@ -358,14 +358,14 @@ bool Sd2Card::init(uint8_t sckRateID, uint8_t chipSelectPin) { // check for timeout if (((uint16_t)millis() - t0) > SD_INIT_TIMEOUT) { error(SD_CARD_ERROR_ACMD41); - goto fail; + goto FAIL; } } // if SD2 read OCR register to check for SDHC card if (type() == SD_CARD_TYPE_SD2) { if (cardCommand(CMD58, 0)) { error(SD_CARD_ERROR_CMD58); - goto fail; + goto FAIL; } if ((spiRec() & 0xC0) == 0xC0) type(SD_CARD_TYPE_SDHC); // discard rest of ocr - contains allowed voltage range @@ -380,7 +380,7 @@ bool Sd2Card::init(uint8_t sckRateID, uint8_t chipSelectPin) { return true; #endif // SOFTWARE_SPI -fail: + FAIL: chipSelectHigh(); return false; } @@ -486,12 +486,12 @@ bool Sd2Card::readData(uint8_t* dst, uint16_t count) { while ((status_ = spiRec()) == 0XFF) { if (((uint16_t)millis() - t0) > SD_READ_TIMEOUT) { error(SD_CARD_ERROR_READ_TIMEOUT); - goto fail; + goto FAIL; } } if (status_ != DATA_START_BLOCK) { error(SD_CARD_ERROR_READ); - goto fail; + goto FAIL; } // transfer data spiRead(dst, count); @@ -503,7 +503,7 @@ bool Sd2Card::readData(uint8_t* dst, uint16_t count) { recvCrc |= spiRec(); if (calcCrc != recvCrc) { error(SD_CARD_ERROR_CRC); - goto fail; + goto FAIL; } } #else @@ -515,7 +515,7 @@ bool Sd2Card::readData(uint8_t* dst, uint16_t count) { // Send an additional dummy byte, required by Toshiba Flash Air SD Card spiSend(0XFF); return true; -fail: + FAIL: chipSelectHigh(); // Send an additional dummy byte, required by Toshiba Flash Air SD Card spiSend(0XFF); @@ -527,10 +527,10 @@ bool Sd2Card::readRegister(uint8_t cmd, void* buf) { uint8_t* dst = reinterpret_cast(buf); if (cardCommand(cmd, 0)) { error(SD_CARD_ERROR_READ_REG); - goto fail; + goto FAIL; } return readData(dst, 16); -fail: + FAIL: chipSelectHigh(); return false; } @@ -549,11 +549,11 @@ bool Sd2Card::readStart(uint32_t blockNumber) { if (type() != SD_CARD_TYPE_SDHC) blockNumber <<= 9; if (cardCommand(CMD18, blockNumber)) { error(SD_CARD_ERROR_CMD18); - goto fail; + goto FAIL; } chipSelectHigh(); return true; -fail: + FAIL: chipSelectHigh(); return false; } @@ -567,11 +567,11 @@ bool Sd2Card::readStop() { chipSelectLow(); if (cardCommand(CMD12, 0)) { error(SD_CARD_ERROR_CMD12); - goto fail; + goto FAIL; } chipSelectHigh(); return true; -fail: + FAIL: chipSelectHigh(); return false; } @@ -601,10 +601,10 @@ bool Sd2Card::setSckRate(uint8_t sckRateID) { bool Sd2Card::waitNotBusy(uint16_t timeoutMillis) { uint16_t t0 = millis(); while (spiRec() != 0XFF) { - if (((uint16_t)millis() - t0) >= timeoutMillis) goto fail; + if (((uint16_t)millis() - t0) >= timeoutMillis) goto FAIL; } return true; -fail: + FAIL: return false; } //------------------------------------------------------------------------------ @@ -621,23 +621,23 @@ bool Sd2Card::writeBlock(uint32_t blockNumber, const uint8_t* src) { if (type() != SD_CARD_TYPE_SDHC) blockNumber <<= 9; if (cardCommand(CMD24, blockNumber)) { error(SD_CARD_ERROR_CMD24); - goto fail; + goto FAIL; } - if (!writeData(DATA_START_BLOCK, src)) goto fail; + if (!writeData(DATA_START_BLOCK, src)) goto FAIL; // wait for flash programming to complete if (!waitNotBusy(SD_WRITE_TIMEOUT)) { error(SD_CARD_ERROR_WRITE_TIMEOUT); - goto fail; + goto FAIL; } // response is r2 so get and check two bytes for nonzero if (cardCommand(CMD13, 0) || spiRec()) { error(SD_CARD_ERROR_WRITE_PROGRAMMING); - goto fail; + goto FAIL; } chipSelectHigh(); return true; -fail: + FAIL: chipSelectHigh(); return false; } @@ -650,11 +650,11 @@ fail: bool Sd2Card::writeData(const uint8_t* src) { chipSelectLow(); // wait for previous write to finish - if (!waitNotBusy(SD_WRITE_TIMEOUT)) goto fail; - if (!writeData(WRITE_MULTIPLE_TOKEN, src)) goto fail; + if (!waitNotBusy(SD_WRITE_TIMEOUT)) goto FAIL; + if (!writeData(WRITE_MULTIPLE_TOKEN, src)) goto FAIL; chipSelectHigh(); return true; -fail: + FAIL: error(SD_CARD_ERROR_WRITE_MULTIPLE); chipSelectHigh(); return false; @@ -670,10 +670,10 @@ bool Sd2Card::writeData(uint8_t token, const uint8_t* src) { status_ = spiRec(); if ((status_ & DATA_RES_MASK) != DATA_RES_ACCEPTED) { error(SD_CARD_ERROR_WRITE); - goto fail; + goto FAIL; } return true; -fail: + FAIL: chipSelectHigh(); return false; } @@ -693,17 +693,17 @@ bool Sd2Card::writeStart(uint32_t blockNumber, uint32_t eraseCount) { // send pre-erase count if (cardAcmd(ACMD23, eraseCount)) { error(SD_CARD_ERROR_ACMD23); - goto fail; + goto FAIL; } // use address if not SDHC card if (type() != SD_CARD_TYPE_SDHC) blockNumber <<= 9; if (cardCommand(CMD25, blockNumber)) { error(SD_CARD_ERROR_CMD25); - goto fail; + goto FAIL; } chipSelectHigh(); return true; -fail: + FAIL: chipSelectHigh(); return false; } @@ -715,12 +715,12 @@ fail: */ bool Sd2Card::writeStop() { chipSelectLow(); - if (!waitNotBusy(SD_WRITE_TIMEOUT)) goto fail; + if (!waitNotBusy(SD_WRITE_TIMEOUT)) goto FAIL; spiSend(STOP_TRAN_TOKEN); - if (!waitNotBusy(SD_WRITE_TIMEOUT)) goto fail; + if (!waitNotBusy(SD_WRITE_TIMEOUT)) goto FAIL; chipSelectHigh(); return true; -fail: + FAIL: error(SD_CARD_ERROR_STOP_TRAN); chipSelectHigh(); return false; diff --git a/Marlin/SdBaseFile.cpp b/Marlin/SdBaseFile.cpp index 0dc165cd6..95fc2b62b 100644 --- a/Marlin/SdBaseFile.cpp +++ b/Marlin/SdBaseFile.cpp @@ -39,7 +39,7 @@ void (*SdBaseFile::dateTime_)(uint16_t* date, uint16_t* time) = 0; //------------------------------------------------------------------------------ // add a cluster to a file bool SdBaseFile::addCluster() { - if (!vol_->allocContiguous(1, &curCluster_)) goto fail; + if (!vol_->allocContiguous(1, &curCluster_)) goto FAIL; // if first cluster of file link to directory entry if (firstCluster_ == 0) { @@ -48,7 +48,7 @@ bool SdBaseFile::addCluster() { } return true; - fail: + FAIL: return false; } //------------------------------------------------------------------------------ @@ -57,10 +57,10 @@ bool SdBaseFile::addCluster() { bool SdBaseFile::addDirCluster() { uint32_t block; // max folder size - if (fileSize_ / sizeof(dir_t) >= 0xFFFF) goto fail; + if (fileSize_ / sizeof(dir_t) >= 0xFFFF) goto FAIL; - if (!addCluster()) goto fail; - if (!vol_->cacheFlush()) goto fail; + if (!addCluster()) goto FAIL; + if (!vol_->cacheFlush()) goto FAIL; block = vol_->clusterStartBlock(curCluster_); @@ -72,21 +72,21 @@ bool SdBaseFile::addDirCluster() { // zero rest of cluster for (uint8_t i = 1; i < vol_->blocksPerCluster_; i++) { - if (!vol_->writeBlock(block + i, vol_->cacheBuffer_.data)) goto fail; + if (!vol_->writeBlock(block + i, vol_->cacheBuffer_.data)) goto FAIL; } // Increase directory file size by cluster size fileSize_ += 512UL << vol_->clusterSizeShift_; return true; -fail: + FAIL: return false; } //------------------------------------------------------------------------------ // cache a file's directory entry // return pointer to cached entry or null for failure dir_t* SdBaseFile::cacheDirEntry(uint8_t action) { - if (!vol_->cacheRawBlock(dirBlock_, action)) goto fail; + if (!vol_->cacheRawBlock(dirBlock_, action)) goto FAIL; return vol_->cache()->dir + dirIndex_; -fail: + FAIL: return 0; } //------------------------------------------------------------------------------ @@ -115,16 +115,16 @@ bool SdBaseFile::close() { */ bool SdBaseFile::contiguousRange(uint32_t* bgnBlock, uint32_t* endBlock) { // error if no blocks - if (firstCluster_ == 0) goto fail; + if (firstCluster_ == 0) goto FAIL; for (uint32_t c = firstCluster_; ; c++) { uint32_t next; - if (!vol_->fatGet(c, &next)) goto fail; + if (!vol_->fatGet(c, &next)) goto FAIL; // check for contiguous if (next != (c + 1)) { // error if not end of chain - if (!vol_->isEOC(next)) goto fail; + if (!vol_->isEOC(next)) goto FAIL; *bgnBlock = vol_->clusterStartBlock(firstCluster_); *endBlock = vol_->clusterStartBlock(c) + vol_->blocksPerCluster_ - 1; @@ -132,7 +132,7 @@ bool SdBaseFile::contiguousRange(uint32_t* bgnBlock, uint32_t* endBlock) { } } -fail: + FAIL: return false; } //------------------------------------------------------------------------------ @@ -157,8 +157,8 @@ bool SdBaseFile::createContiguous(SdBaseFile* dirFile, const char* path, uint32_t size) { uint32_t count; // don't allow zero length file - if (size == 0) goto fail; - if (!open(dirFile, path, O_CREAT | O_EXCL | O_RDWR)) goto fail; + if (size == 0) goto FAIL; + if (!open(dirFile, path, O_CREAT | O_EXCL | O_RDWR)) goto FAIL; // calculate number of clusters needed count = ((size - 1) >> (vol_->clusterSizeShift_ + 9)) + 1; @@ -166,7 +166,7 @@ bool SdBaseFile::createContiguous(SdBaseFile* dirFile, // allocate clusters if (!vol_->allocContiguous(count, &firstCluster_)) { remove(); - goto fail; + goto FAIL; } fileSize_ = size; @@ -174,7 +174,7 @@ bool SdBaseFile::createContiguous(SdBaseFile* dirFile, flags_ |= F_FILE_DIR_DIRTY; return sync(); -fail: + FAIL: return false; } //------------------------------------------------------------------------------ @@ -188,16 +188,16 @@ fail: bool SdBaseFile::dirEntry(dir_t* dir) { dir_t* p; // make sure fields on SD are correct - if (!sync()) goto fail; + if (!sync()) goto FAIL; // read entry p = cacheDirEntry(SdVolume::CACHE_FOR_READ); - if (!p) goto fail; + if (!p) goto FAIL; // copy to caller's struct memcpy(dir, p, sizeof(dir_t)); return true; -fail: + FAIL: return false; } //------------------------------------------------------------------------------ @@ -395,7 +395,7 @@ bool SdBaseFile::make83Name(const char* str, uint8_t* name, const char** ptr) { while (*str != '\0' && *str != '/') { c = *str++; if (c == '.') { - if (n == 10) goto fail; // only one dot allowed + if (n == 10) goto FAIL; // only one dot allowed n = 10; // max index for full 8.3 name i = 8; // place for extension } @@ -403,9 +403,9 @@ bool SdBaseFile::make83Name(const char* str, uint8_t* name, const char** ptr) { // illegal FAT characters PGM_P p = PSTR("|<>^+=?/[];,*\"\\"); uint8_t b; - while ((b = pgm_read_byte(p++))) if (b == c) goto fail; + while ((b = pgm_read_byte(p++))) if (b == c) goto FAIL; // check size and only allow ASCII printable characters - if (i > n || c < 0x21 || c == 0x7F) goto fail; + if (i > n || c < 0x21 || c == 0x7F) goto FAIL; // only upper case allowed in 8.3 names - convert lower to upper name[i++] = (c < 'a' || c > 'z') ? (c) : (c + ('A' - 'a')); } @@ -413,7 +413,7 @@ bool SdBaseFile::make83Name(const char* str, uint8_t* name, const char** ptr) { *ptr = str; // must have a file name, extension is optional return name[0] != ' '; -fail: + FAIL: return false; } //------------------------------------------------------------------------------ @@ -437,22 +437,22 @@ bool SdBaseFile::mkdir(SdBaseFile* parent, const char* path, bool pFlag) { SdBaseFile* sub = &dir1; SdBaseFile* start = parent; - if (!parent || isOpen()) goto fail; + if (!parent || isOpen()) goto FAIL; if (*path == '/') { while (*path == '/') path++; if (!parent->isRoot()) { - if (!dir2.openRoot(parent->vol_)) goto fail; + if (!dir2.openRoot(parent->vol_)) goto FAIL; parent = &dir2; } } while (1) { - if (!make83Name(path, dname, &path)) goto fail; + if (!make83Name(path, dname, &path)) goto FAIL; while (*path == '/') path++; if (!*path) break; if (!sub->open(parent, dname, O_READ)) { if (!pFlag || !sub->mkdir(parent, dname)) { - goto fail; + goto FAIL; } } if (parent != start) parent->close(); @@ -460,7 +460,7 @@ bool SdBaseFile::mkdir(SdBaseFile* parent, const char* path, bool pFlag) { sub = parent != &dir1 ? &dir1 : &dir2; } return mkdir(parent, dname); -fail: + FAIL: return false; } //------------------------------------------------------------------------------ @@ -469,24 +469,24 @@ bool SdBaseFile::mkdir(SdBaseFile* parent, const uint8_t dname[11]) { dir_t d; dir_t* p; - if (!parent->isDir()) goto fail; + if (!parent->isDir()) goto FAIL; // create a normal file - if (!open(parent, dname, O_CREAT | O_EXCL | O_RDWR)) goto fail; + if (!open(parent, dname, O_CREAT | O_EXCL | O_RDWR)) goto FAIL; // convert file to directory flags_ = O_READ; type_ = FAT_FILE_TYPE_SUBDIR; // allocate and zero first cluster - if (!addDirCluster())goto fail; + if (!addDirCluster())goto FAIL; // force entry to SD - if (!sync()) goto fail; + if (!sync()) goto FAIL; // cache entry - should already be in cache due to sync() call p = cacheDirEntry(SdVolume::CACHE_FOR_WRITE); - if (!p) goto fail; + if (!p) goto FAIL; // change directory entry attribute p->attributes = DIR_ATT_DIRECTORY; @@ -498,7 +498,7 @@ bool SdBaseFile::mkdir(SdBaseFile* parent, const uint8_t dname[11]) { // cache block for '.' and '..' block = vol_->clusterStartBlock(firstCluster_); - if (!vol_->cacheRawBlock(block, SdVolume::CACHE_FOR_WRITE)) goto fail; + if (!vol_->cacheRawBlock(block, SdVolume::CACHE_FOR_WRITE)) goto FAIL; // copy '.' to block memcpy(&vol_->cache()->dir[0], &d, sizeof(d)); @@ -518,7 +518,7 @@ bool SdBaseFile::mkdir(SdBaseFile* parent, const uint8_t dname[11]) { // write first block return vol_->cacheFlush(); -fail: + FAIL: return false; } //------------------------------------------------------------------------------ @@ -592,29 +592,29 @@ bool SdBaseFile::open(SdBaseFile* dirFile, const char* path, uint8_t oflag) { SdBaseFile* parent = dirFile; SdBaseFile* sub = &dir1; - if (!dirFile) goto fail; + if (!dirFile) goto FAIL; // error if already open - if (isOpen()) goto fail; + if (isOpen()) goto FAIL; if (*path == '/') { while (*path == '/') path++; if (!dirFile->isRoot()) { - if (!dir2.openRoot(dirFile->vol_)) goto fail; + if (!dir2.openRoot(dirFile->vol_)) goto FAIL; parent = &dir2; } } while (1) { - if (!make83Name(path, dname, &path)) goto fail; + if (!make83Name(path, dname, &path)) goto FAIL; while (*path == '/') path++; if (!*path) break; - if (!sub->open(parent, dname, O_READ)) goto fail; + if (!sub->open(parent, dname, O_READ)) goto FAIL; if (parent != dirFile) parent->close(); parent = sub; sub = parent != &dir1 ? &dir1 : &dir2; } return open(parent, dname, oflag); -fail: + FAIL: return false; } //------------------------------------------------------------------------------ @@ -634,7 +634,7 @@ bool SdBaseFile::open(SdBaseFile* dirFile, while (dirFile->curPosition_ < dirFile->fileSize_) { index = 0XF & (dirFile->curPosition_ >> 5); p = dirFile->readDirCache(); - if (!p) goto fail; + if (!p) goto FAIL; if (p->name[0] == DIR_NAME_FREE || p->name[0] == DIR_NAME_DELETED) { // remember first empty slot @@ -653,21 +653,21 @@ bool SdBaseFile::open(SdBaseFile* dirFile, } if (fileFound) { // don't open existing file if O_EXCL - if (oflag & O_EXCL) goto fail; + if (oflag & O_EXCL) goto FAIL; } else { // don't create unless O_CREAT and O_WRITE - if (!(oflag & O_CREAT) || !(oflag & O_WRITE)) goto fail; + if (!(oflag & O_CREAT) || !(oflag & O_WRITE)) goto FAIL; if (emptyFound) { index = dirIndex_; p = cacheDirEntry(SdVolume::CACHE_FOR_WRITE); - if (!p) goto fail; + if (!p) goto FAIL; } else { - if (dirFile->type_ == FAT_FILE_TYPE_ROOT_FIXED) goto fail; + if (dirFile->type_ == FAT_FILE_TYPE_ROOT_FIXED) goto FAIL; // add and zero cluster for dirFile - first cluster is in cache for write - if (!dirFile->addDirCluster()) goto fail; + if (!dirFile->addDirCluster()) goto FAIL; // use first entry in cluster p = dirFile->vol_->cache()->dir; @@ -692,11 +692,11 @@ bool SdBaseFile::open(SdBaseFile* dirFile, p->lastWriteTime = p->creationTime; // write entry to SD - if (!dirFile->vol_->cacheFlush()) goto fail; + if (!dirFile->vol_->cacheFlush()) goto FAIL; } // open entry in cache return openCachedEntry(index, oflag); -fail: + FAIL: return false; } //------------------------------------------------------------------------------ @@ -719,26 +719,26 @@ bool SdBaseFile::open(SdBaseFile* dirFile, uint16_t index, uint8_t oflag) { vol_ = dirFile->vol_; // error if already open - if (isOpen() || !dirFile) goto fail; + if (isOpen() || !dirFile) goto FAIL; // don't open existing file if O_EXCL - user call error - if (oflag & O_EXCL) goto fail; + if (oflag & O_EXCL) goto FAIL; // seek to location of entry - if (!dirFile->seekSet(32 * index)) goto fail; + if (!dirFile->seekSet(32 * index)) goto FAIL; // read entry into cache p = dirFile->readDirCache(); - if (!p) goto fail; + if (!p) goto FAIL; // error if empty slot or '.' or '..' if (p->name[0] == DIR_NAME_FREE || p->name[0] == DIR_NAME_DELETED || p->name[0] == '.') { - goto fail; + goto FAIL; } // open cached entry return openCachedEntry(index & 0XF, oflag); -fail: + FAIL: return false; } //------------------------------------------------------------------------------ @@ -749,7 +749,7 @@ bool SdBaseFile::openCachedEntry(uint8_t dirIndex, uint8_t oflag) { // write or truncate is an error for a directory or read-only file if (p->attributes & (DIR_ATT_READ_ONLY | DIR_ATT_DIRECTORY)) { - if (oflag & (O_WRITE | O_TRUNC)) goto fail; + if (oflag & (O_WRITE | O_TRUNC)) goto FAIL; } // remember location of directory entry on SD dirBlock_ = vol_->cacheBlockNumber(); @@ -765,11 +765,11 @@ bool SdBaseFile::openCachedEntry(uint8_t dirIndex, uint8_t oflag) { type_ = FAT_FILE_TYPE_NORMAL; } else if (DIR_IS_SUBDIR(p)) { - if (!vol_->chainSize(firstCluster_, &fileSize_)) goto fail; + if (!vol_->chainSize(firstCluster_, &fileSize_)) goto FAIL; type_ = FAT_FILE_TYPE_SUBDIR; } else { - goto fail; + goto FAIL; } // save open flags for read/write flags_ = oflag & F_OFLAG; @@ -779,7 +779,7 @@ bool SdBaseFile::openCachedEntry(uint8_t dirIndex, uint8_t oflag) { curPosition_ = 0; if ((oflag & O_TRUNC) && !truncate(0)) return false; return oflag & O_AT_END ? seekEnd(0) : true; -fail: + FAIL: type_ = FAT_FILE_TYPE_CLOSED; return false; } @@ -799,10 +799,10 @@ bool SdBaseFile::openNext(SdBaseFile* dirFile, uint8_t oflag) { dir_t* p; uint8_t index; - if (!dirFile) goto fail; + if (!dirFile) goto FAIL; // error if already open - if (isOpen()) goto fail; + if (isOpen()) goto FAIL; vol_ = dirFile->vol_; @@ -811,10 +811,10 @@ bool SdBaseFile::openNext(SdBaseFile* dirFile, uint8_t oflag) { // read entry into cache p = dirFile->readDirCache(); - if (!p) goto fail; + if (!p) goto FAIL; // done if last entry - if (p->name[0] == DIR_NAME_FREE) goto fail; + if (p->name[0] == DIR_NAME_FREE) goto FAIL; // skip empty slot or '.' or '..' if (p->name[0] == DIR_NAME_DELETED || p->name[0] == '.') { @@ -825,7 +825,7 @@ bool SdBaseFile::openNext(SdBaseFile* dirFile, uint8_t oflag) { return openCachedEntry(index, oflag); } } -fail: + FAIL: return false; } //------------------------------------------------------------------------------ @@ -844,14 +844,14 @@ bool SdBaseFile::openParent(SdBaseFile* dir) { uint32_t cluster; uint32_t lbn; // error if already open or dir is root or dir is not a directory - if (isOpen() || !dir || dir->isRoot() || !dir->isDir()) goto fail; + if (isOpen() || !dir || dir->isRoot() || !dir->isDir()) goto FAIL; vol_ = dir->vol_; // position to '..' - if (!dir->seekSet(32)) goto fail; + if (!dir->seekSet(32)) goto FAIL; // read '..' entry - if (dir->read(&entry, sizeof(entry)) != 32) goto fail; + if (dir->read(&entry, sizeof(entry)) != 32) goto FAIL; // verify it is '..' - if (entry.name[0] != '.' || entry.name[1] != '.') goto fail; + if (entry.name[0] != '.' || entry.name[1] != '.') goto FAIL; // start cluster for '..' cluster = entry.firstClusterLow; cluster |= (uint32_t)entry.firstClusterHigh << 16; @@ -860,27 +860,27 @@ bool SdBaseFile::openParent(SdBaseFile* dir) { lbn = vol_->clusterStartBlock(cluster); // first block of parent dir if (!vol_->cacheRawBlock(lbn, SdVolume::CACHE_FOR_READ)) { - goto fail; + goto FAIL; } p = &vol_->cacheBuffer_.dir[1]; // verify name for '../..' - if (p->name[0] != '.' || p->name[1] != '.') goto fail; + if (p->name[0] != '.' || p->name[1] != '.') goto FAIL; // '..' is pointer to first cluster of parent. open '../..' to find parent if (p->firstClusterHigh == 0 && p->firstClusterLow == 0) { - if (!file.openRoot(dir->volume())) goto fail; + if (!file.openRoot(dir->volume())) goto FAIL; } else if (!file.openCachedEntry(1, O_READ)) { - goto fail; + goto FAIL; } // search for parent in '../..' do { - if (file.readDir(&entry, NULL) != 32) goto fail; + if (file.readDir(&entry, NULL) != 32) goto FAIL; c = entry.firstClusterLow; c |= (uint32_t)entry.firstClusterHigh << 16; } while (c != cluster); // open parent return open(&file, file.curPosition() / 32 - 1, O_READ); -fail: + FAIL: return false; } //------------------------------------------------------------------------------ @@ -895,7 +895,7 @@ fail: */ bool SdBaseFile::openRoot(SdVolume* vol) { // error if file is already open - if (isOpen()) goto fail; + if (isOpen()) goto FAIL; if (vol->fatType() == 16 || (FAT12_SUPPORT && vol->fatType() == 12)) { type_ = FAT_FILE_TYPE_ROOT_FIXED; @@ -905,7 +905,7 @@ bool SdBaseFile::openRoot(SdVolume* vol) { else if (vol->fatType() == 32) { type_ = FAT_FILE_TYPE_ROOT32; firstCluster_ = vol->rootDirStart(); - if (!vol->chainSize(firstCluster_, &fileSize_)) goto fail; + if (!vol->chainSize(firstCluster_, &fileSize_)) goto FAIL; } else { // volume is not initialized, invalid, or FAT12 without support @@ -923,7 +923,7 @@ bool SdBaseFile::openRoot(SdVolume* vol) { dirBlock_ = 0; dirIndex_ = 0; return true; -fail: + FAIL: return false; } //------------------------------------------------------------------------------ @@ -1055,7 +1055,7 @@ int16_t SdBaseFile::read(void* buf, uint16_t nbyte) { uint32_t block; // raw device block number // error if not open or write only - if (!isOpen() || !(flags_ & O_READ)) goto fail; + if (!isOpen() || !(flags_ & O_READ)) goto FAIL; // max bytes left in file NOMORE(nbyte, fileSize_ - curPosition_); @@ -1077,7 +1077,7 @@ int16_t SdBaseFile::read(void* buf, uint16_t nbyte) { } else { // get next cluster from FAT - if (!vol_->fatGet(curCluster_, &curCluster_)) goto fail; + if (!vol_->fatGet(curCluster_, &curCluster_)) goto FAIL; } } block = vol_->clusterStartBlock(curCluster_) + blockOfCluster; @@ -1089,11 +1089,11 @@ int16_t SdBaseFile::read(void* buf, uint16_t nbyte) { // no buffering needed if n == 512 if (n == 512 && block != vol_->cacheBlockNumber()) { - if (!vol_->readBlock(block, dst)) goto fail; + if (!vol_->readBlock(block, dst)) goto FAIL; } else { // read block to cache and copy data to caller - if (!vol_->cacheRawBlock(block, SdVolume::CACHE_FOR_READ)) goto fail; + if (!vol_->cacheRawBlock(block, SdVolume::CACHE_FOR_READ)) goto FAIL; uint8_t* src = vol_->cache()->data + offset; memcpy(dst, src, n); } @@ -1102,7 +1102,7 @@ int16_t SdBaseFile::read(void* buf, uint16_t nbyte) { toRead -= n; } return nbyte; -fail: + FAIL: return -1; } @@ -1161,20 +1161,20 @@ int8_t SdBaseFile::readDir(dir_t* dir, char* longFilename) { dir_t* SdBaseFile::readDirCache() { uint8_t i; // error if not directory - if (!isDir()) goto fail; + if (!isDir()) goto FAIL; // index of entry in cache i = (curPosition_ >> 5) & 0XF; // use read to locate and cache block - if (read() < 0) goto fail; + if (read() < 0) goto FAIL; // advance to next entry curPosition_ += 31; // return pointer to entry return vol_->cache()->dir + i; -fail: + FAIL: return 0; } //------------------------------------------------------------------------------ @@ -1194,11 +1194,11 @@ fail: bool SdBaseFile::remove() { dir_t* d; // free any clusters - will fail if read-only or directory - if (!truncate(0)) goto fail; + if (!truncate(0)) goto FAIL; // cache directory entry d = cacheDirEntry(SdVolume::CACHE_FOR_WRITE); - if (!d) goto fail; + if (!d) goto FAIL; // mark entry deleted d->name[0] = DIR_NAME_DELETED; @@ -1209,7 +1209,7 @@ bool SdBaseFile::remove() { // write entry to SD return vol_->cacheFlush(); return true; -fail: + FAIL: return false; } //------------------------------------------------------------------------------ @@ -1232,9 +1232,9 @@ fail: */ bool SdBaseFile::remove(SdBaseFile* dirFile, const char* path) { SdBaseFile file; - if (!file.open(dirFile, path, O_WRITE)) goto fail; + if (!file.open(dirFile, path, O_WRITE)) goto FAIL; return file.remove(); -fail: + FAIL: // can't set iostate - static function return false; } @@ -1256,15 +1256,15 @@ bool SdBaseFile::rename(SdBaseFile* dirFile, const char* newPath) { dir_t* d; // must be an open file or subdirectory - if (!(isFile() || isSubDir())) goto fail; + if (!(isFile() || isSubDir())) goto FAIL; // can't move file - if (vol_ != dirFile->vol_) goto fail; + if (vol_ != dirFile->vol_) goto FAIL; // sync() and cache directory entry sync(); d = cacheDirEntry(SdVolume::CACHE_FOR_WRITE); - if (!d) goto fail; + if (!d) goto FAIL; // save directory entry memcpy(&entry, d, sizeof(entry)); @@ -1295,7 +1295,7 @@ bool SdBaseFile::rename(SdBaseFile* dirFile, const char* newPath) { // cache new directory entry d = cacheDirEntry(SdVolume::CACHE_FOR_WRITE); - if (!d) goto fail; + if (!d) goto FAIL; // copy all but name field to new directory entry memcpy(&d->attributes, &entry.attributes, sizeof(entry) - sizeof(d->name)); @@ -1304,27 +1304,27 @@ bool SdBaseFile::rename(SdBaseFile* dirFile, const char* newPath) { if (dirCluster) { // get new dot dot uint32_t block = vol_->clusterStartBlock(dirCluster); - if (!vol_->cacheRawBlock(block, SdVolume::CACHE_FOR_READ)) goto fail; + if (!vol_->cacheRawBlock(block, SdVolume::CACHE_FOR_READ)) goto FAIL; memcpy(&entry, &vol_->cache()->dir[1], sizeof(entry)); // free unused cluster - if (!vol_->freeChain(dirCluster)) goto fail; + if (!vol_->freeChain(dirCluster)) goto FAIL; // store new dot dot block = vol_->clusterStartBlock(firstCluster_); - if (!vol_->cacheRawBlock(block, SdVolume::CACHE_FOR_WRITE)) goto fail; + if (!vol_->cacheRawBlock(block, SdVolume::CACHE_FOR_WRITE)) goto FAIL; memcpy(&vol_->cache()->dir[1], &entry, sizeof(entry)); } return vol_->cacheFlush(); restore: d = cacheDirEntry(SdVolume::CACHE_FOR_WRITE); - if (!d) goto fail; + if (!d) goto FAIL; // restore entry d->name[0] = entry.name[0]; vol_->cacheFlush(); -fail: + FAIL: return false; } //------------------------------------------------------------------------------ @@ -1345,26 +1345,26 @@ fail: */ bool SdBaseFile::rmdir() { // must be open subdirectory - if (!isSubDir()) goto fail; + if (!isSubDir()) goto FAIL; rewind(); // make sure directory is empty while (curPosition_ < fileSize_) { dir_t* p = readDirCache(); - if (!p) goto fail; + if (!p) goto FAIL; // done if past last used entry if (p->name[0] == DIR_NAME_FREE) break; // skip empty slot, '.' or '..' if (p->name[0] == DIR_NAME_DELETED || p->name[0] == '.') continue; // error not empty - if (DIR_IS_FILE_OR_SUBDIR(p)) goto fail; + if (DIR_IS_FILE_OR_SUBDIR(p)) goto FAIL; } // convert empty directory to normal file for remove type_ = FAT_FILE_TYPE_NORMAL; flags_ |= O_WRITE; return remove(); -fail: + FAIL: return false; } //------------------------------------------------------------------------------ @@ -1392,7 +1392,7 @@ bool SdBaseFile::rmRfStar() { index = curPosition_ / 32; dir_t* p = readDirCache(); - if (!p) goto fail; + if (!p) goto FAIL; // done if past last entry if (p->name[0] == DIR_NAME_FREE) break; @@ -1403,27 +1403,27 @@ bool SdBaseFile::rmRfStar() { // skip if part of long file name or volume label in root if (!DIR_IS_FILE_OR_SUBDIR(p)) continue; - if (!f.open(this, index, O_READ)) goto fail; + if (!f.open(this, index, O_READ)) goto FAIL; if (f.isSubDir()) { // recursively delete - if (!f.rmRfStar()) goto fail; + if (!f.rmRfStar()) goto FAIL; } else { // ignore read-only f.flags_ |= O_WRITE; - if (!f.remove()) goto fail; + if (!f.remove()) goto FAIL; } // position to next entry if required if (curPosition_ != (32 * (index + 1))) { - if (!seekSet(32 * (index + 1))) goto fail; + if (!seekSet(32 * (index + 1))) goto FAIL; } } // don't try to delete root if (!isRoot()) { - if (!rmdir()) goto fail; + if (!rmdir()) goto FAIL; } return true; -fail: + FAIL: return false; } //------------------------------------------------------------------------------ @@ -1451,7 +1451,7 @@ bool SdBaseFile::seekSet(uint32_t pos) { uint32_t nCur; uint32_t nNew; // error if file not open or seek past end of file - if (!isOpen() || pos > fileSize_) goto fail; + if (!isOpen() || pos > fileSize_) goto FAIL; if (type_ == FAT_FILE_TYPE_ROOT_FIXED) { curPosition_ = pos; @@ -1476,14 +1476,14 @@ bool SdBaseFile::seekSet(uint32_t pos) { nNew -= nCur; } while (nNew--) { - if (!vol_->fatGet(curCluster_, &curCluster_)) goto fail; + if (!vol_->fatGet(curCluster_, &curCluster_)) goto FAIL; } curPosition_ = pos; done: return true; -fail: + FAIL: return false; } //------------------------------------------------------------------------------ @@ -1502,12 +1502,12 @@ void SdBaseFile::setpos(filepos_t* pos) { */ bool SdBaseFile::sync() { // only allow open files and directories - if (!isOpen()) goto fail; + if (!isOpen()) goto FAIL; if (flags_ & F_FILE_DIR_DIRTY) { dir_t* d = cacheDirEntry(SdVolume::CACHE_FOR_WRITE); // check for deleted by another open file object - if (!d || d->name[0] == DIR_NAME_DELETED) goto fail; + if (!d || d->name[0] == DIR_NAME_DELETED) goto FAIL; // do not set filesize for dir files if (!isDir()) d->fileSize = fileSize_; @@ -1526,7 +1526,7 @@ bool SdBaseFile::sync() { } return vol_->cacheFlush(); -fail: + FAIL: writeError = true; return false; } @@ -1547,13 +1547,13 @@ bool SdBaseFile::timestamp(SdBaseFile* file) { dir_t dir; // get timestamps - if (!file->dirEntry(&dir)) goto fail; + if (!file->dirEntry(&dir)) goto FAIL; // update directory fields - if (!sync()) goto fail; + if (!sync()) goto FAIL; d = cacheDirEntry(SdVolume::CACHE_FOR_WRITE); - if (!d) goto fail; + if (!d) goto FAIL; // copy timestamps d->lastAccessDate = dir.lastAccessDate; @@ -1566,7 +1566,7 @@ bool SdBaseFile::timestamp(SdBaseFile* file) { // write back entry return vol_->cacheFlush(); -fail: + FAIL: return false; } //------------------------------------------------------------------------------ @@ -1619,13 +1619,13 @@ bool SdBaseFile::timestamp(uint8_t flags, uint16_t year, uint8_t month, || hour > 23 || minute > 59 || second > 59) { - goto fail; + goto FAIL; } // update directory entry - if (!sync()) goto fail; + if (!sync()) goto FAIL; d = cacheDirEntry(SdVolume::CACHE_FOR_WRITE); - if (!d) goto fail; + if (!d) goto FAIL; dirDate = FAT_DATE(year, month, day); dirTime = FAT_TIME(hour, minute, second); @@ -1643,7 +1643,7 @@ bool SdBaseFile::timestamp(uint8_t flags, uint16_t year, uint8_t month, d->lastWriteTime = dirTime; } return vol_->cacheFlush(); -fail: + FAIL: return false; } //------------------------------------------------------------------------------ @@ -1661,10 +1661,10 @@ fail: bool SdBaseFile::truncate(uint32_t length) { uint32_t newPos; // error if not a normal file or read-only - if (!isFile() || !(flags_ & O_WRITE)) goto fail; + if (!isFile() || !(flags_ & O_WRITE)) goto FAIL; // error if length is greater than current size - if (length > fileSize_) goto fail; + if (length > fileSize_) goto FAIL; // fileSize and length are zero - nothing to do if (fileSize_ == 0) return true; @@ -1673,23 +1673,23 @@ bool SdBaseFile::truncate(uint32_t length) { newPos = curPosition_ > length ? length : curPosition_; // position to last cluster in truncated file - if (!seekSet(length)) goto fail; + if (!seekSet(length)) goto FAIL; if (length == 0) { // free all clusters - if (!vol_->freeChain(firstCluster_)) goto fail; + if (!vol_->freeChain(firstCluster_)) goto FAIL; firstCluster_ = 0; } else { uint32_t toFree; - if (!vol_->fatGet(curCluster_, &toFree)) goto fail; + if (!vol_->fatGet(curCluster_, &toFree)) goto FAIL; if (!vol_->isEOC(toFree)) { // free extra clusters - if (!vol_->freeChain(toFree)) goto fail; + if (!vol_->freeChain(toFree)) goto FAIL; // current cluster is end of chain - if (!vol_->fatPutEOC(curCluster_)) goto fail; + if (!vol_->fatPutEOC(curCluster_)) goto FAIL; } } fileSize_ = length; @@ -1697,12 +1697,12 @@ bool SdBaseFile::truncate(uint32_t length) { // need to update directory entry flags_ |= F_FILE_DIR_DIRTY; - if (!sync()) goto fail; + if (!sync()) goto FAIL; // set file to correct position return seekSet(newPos); -fail: + FAIL: return false; } //------------------------------------------------------------------------------ @@ -1729,11 +1729,11 @@ int16_t SdBaseFile::write(const void* buf, uint16_t nbyte) { uint16_t nToWrite = nbyte; // error if not a normal file or is read-only - if (!isFile() || !(flags_ & O_WRITE)) goto fail; + if (!isFile() || !(flags_ & O_WRITE)) goto FAIL; // seek to end of file if append flag if ((flags_ & O_APPEND) && curPosition_ != fileSize_) { - if (!seekEnd()) goto fail; + if (!seekEnd()) goto FAIL; } while (nToWrite > 0) { @@ -1744,7 +1744,7 @@ int16_t SdBaseFile::write(const void* buf, uint16_t nbyte) { if (curCluster_ == 0) { if (firstCluster_ == 0) { // allocate first cluster of file - if (!addCluster()) goto fail; + if (!addCluster()) goto FAIL; } else { curCluster_ = firstCluster_; @@ -1752,10 +1752,10 @@ int16_t SdBaseFile::write(const void* buf, uint16_t nbyte) { } else { uint32_t next; - if (!vol_->fatGet(curCluster_, &next)) goto fail; + if (!vol_->fatGet(curCluster_, &next)) goto FAIL; if (vol_->isEOC(next)) { // add cluster if at end of chain - if (!addCluster()) goto fail; + if (!addCluster()) goto FAIL; } else { curCluster_ = next; @@ -1776,18 +1776,18 @@ int16_t SdBaseFile::write(const void* buf, uint16_t nbyte) { // invalidate cache if block is in cache vol_->cacheSetBlockNumber(0xFFFFFFFF, false); } - if (!vol_->writeBlock(block, src)) goto fail; + if (!vol_->writeBlock(block, src)) goto FAIL; } else { if (blockOffset == 0 && curPosition_ >= fileSize_) { // start of new block don't need to read into cache - if (!vol_->cacheFlush()) goto fail; + if (!vol_->cacheFlush()) goto FAIL; // set cache dirty and SD address of block vol_->cacheSetBlockNumber(block, true); } else { // rewrite part of block - if (!vol_->cacheRawBlock(block, SdVolume::CACHE_FOR_WRITE)) goto fail; + if (!vol_->cacheRawBlock(block, SdVolume::CACHE_FOR_WRITE)) goto FAIL; } uint8_t* dst = vol_->cache()->data + blockOffset; memcpy(dst, src, n); @@ -1807,11 +1807,11 @@ int16_t SdBaseFile::write(const void* buf, uint16_t nbyte) { } if (flags_ & O_SYNC) { - if (!sync()) goto fail; + if (!sync()) goto FAIL; } return nbyte; -fail: + FAIL: // return for write error writeError = true; return -1; diff --git a/Marlin/SdVolume.cpp b/Marlin/SdVolume.cpp index 701b116c2..4093cb5e0 100644 --- a/Marlin/SdVolume.cpp +++ b/Marlin/SdVolume.cpp @@ -73,14 +73,14 @@ bool SdVolume::allocContiguous(uint32_t count, uint32_t* curCluster) { // search the FAT for free clusters for (uint32_t n = 0;; n++, endCluster++) { // can't find space checked all clusters - if (n >= clusterCount_) goto fail; + if (n >= clusterCount_) goto FAIL; // past end - start from beginning of FAT if (endCluster > fatEnd) { bgnCluster = endCluster = 2; } uint32_t f; - if (!fatGet(endCluster, &f)) goto fail; + if (!fatGet(endCluster, &f)) goto FAIL; if (f != 0) { // cluster in use try next cluster as bgnCluster @@ -92,16 +92,16 @@ bool SdVolume::allocContiguous(uint32_t count, uint32_t* curCluster) { } } // mark end of chain - if (!fatPutEOC(endCluster)) goto fail; + if (!fatPutEOC(endCluster)) goto FAIL; // link clusters while (endCluster > bgnCluster) { - if (!fatPut(endCluster - 1, endCluster)) goto fail; + if (!fatPut(endCluster - 1, endCluster)) goto FAIL; endCluster--; } if (*curCluster != 0) { // connect chains - if (!fatPut(*curCluster, bgnCluster)) goto fail; + if (!fatPut(*curCluster, bgnCluster)) goto FAIL; } // return first cluster number to caller *curCluster = bgnCluster; @@ -110,38 +110,38 @@ bool SdVolume::allocContiguous(uint32_t count, uint32_t* curCluster) { if (setStart) allocSearchStart_ = bgnCluster + 1; return true; -fail: + FAIL: return false; } //------------------------------------------------------------------------------ bool SdVolume::cacheFlush() { if (cacheDirty_) { if (!sdCard_->writeBlock(cacheBlockNumber_, cacheBuffer_.data)) { - goto fail; + goto FAIL; } // mirror FAT tables if (cacheMirrorBlock_) { if (!sdCard_->writeBlock(cacheMirrorBlock_, cacheBuffer_.data)) { - goto fail; + goto FAIL; } cacheMirrorBlock_ = 0; } cacheDirty_ = 0; } return true; -fail: + FAIL: return false; } //------------------------------------------------------------------------------ bool SdVolume::cacheRawBlock(uint32_t blockNumber, bool dirty) { if (cacheBlockNumber_ != blockNumber) { - if (!cacheFlush()) goto fail; - if (!sdCard_->readBlock(blockNumber, cacheBuffer_.data)) goto fail; + if (!cacheFlush()) goto FAIL; + if (!sdCard_->readBlock(blockNumber, cacheBuffer_.data)) goto FAIL; cacheBlockNumber_ = blockNumber; } if (dirty) cacheDirty_ = true; return true; -fail: + FAIL: return false; } //------------------------------------------------------------------------------ @@ -149,29 +149,29 @@ fail: bool SdVolume::chainSize(uint32_t cluster, uint32_t* size) { uint32_t s = 0; do { - if (!fatGet(cluster, &cluster)) goto fail; + if (!fatGet(cluster, &cluster)) goto FAIL; s += 512UL << clusterSizeShift_; } while (!isEOC(cluster)); *size = s; return true; -fail: + FAIL: return false; } //------------------------------------------------------------------------------ // Fetch a FAT entry bool SdVolume::fatGet(uint32_t cluster, uint32_t* value) { uint32_t lba; - if (cluster > (clusterCount_ + 1)) goto fail; + if (cluster > (clusterCount_ + 1)) goto FAIL; if (FAT12_SUPPORT && fatType_ == 12) { uint16_t index = cluster; index += index >> 1; lba = fatStartBlock_ + (index >> 9); - if (!cacheRawBlock(lba, CACHE_FOR_READ)) goto fail; + if (!cacheRawBlock(lba, CACHE_FOR_READ)) goto FAIL; index &= 0x1FF; uint16_t tmp = cacheBuffer_.data[index]; index++; if (index == 512) { - if (!cacheRawBlock(lba + 1, CACHE_FOR_READ)) goto fail; + if (!cacheRawBlock(lba + 1, CACHE_FOR_READ)) goto FAIL; index = 0; } tmp |= cacheBuffer_.data[index] << 8; @@ -185,10 +185,10 @@ bool SdVolume::fatGet(uint32_t cluster, uint32_t* value) { lba = fatStartBlock_ + (cluster >> 7); } else { - goto fail; + goto FAIL; } if (lba != cacheBlockNumber_) { - if (!cacheRawBlock(lba, CACHE_FOR_READ)) goto fail; + if (!cacheRawBlock(lba, CACHE_FOR_READ)) goto FAIL; } if (fatType_ == 16) { *value = cacheBuffer_.fat16[cluster & 0xFF]; @@ -197,7 +197,7 @@ bool SdVolume::fatGet(uint32_t cluster, uint32_t* value) { *value = cacheBuffer_.fat32[cluster & 0x7F] & FAT32MASK; } return true; -fail: + FAIL: return false; } //------------------------------------------------------------------------------ @@ -205,16 +205,16 @@ fail: bool SdVolume::fatPut(uint32_t cluster, uint32_t value) { uint32_t lba; // error if reserved cluster - if (cluster < 2) goto fail; + if (cluster < 2) goto FAIL; // error if not in FAT - if (cluster > (clusterCount_ + 1)) goto fail; + if (cluster > (clusterCount_ + 1)) goto FAIL; if (FAT12_SUPPORT && fatType_ == 12) { uint16_t index = cluster; index += index >> 1; lba = fatStartBlock_ + (index >> 9); - if (!cacheRawBlock(lba, CACHE_FOR_WRITE)) goto fail; + if (!cacheRawBlock(lba, CACHE_FOR_WRITE)) goto FAIL; // mirror second FAT if (fatCount_ > 1) cacheMirrorBlock_ = lba + blocksPerFat_; index &= 0x1FF; @@ -227,7 +227,7 @@ bool SdVolume::fatPut(uint32_t cluster, uint32_t value) { if (index == 512) { lba++; index = 0; - if (!cacheRawBlock(lba, CACHE_FOR_WRITE)) goto fail; + if (!cacheRawBlock(lba, CACHE_FOR_WRITE)) goto FAIL; // mirror second FAT if (fatCount_ > 1) cacheMirrorBlock_ = lba + blocksPerFat_; } @@ -245,9 +245,9 @@ bool SdVolume::fatPut(uint32_t cluster, uint32_t value) { lba = fatStartBlock_ + (cluster >> 7); } else { - goto fail; + goto FAIL; } - if (!cacheRawBlock(lba, CACHE_FOR_WRITE)) goto fail; + if (!cacheRawBlock(lba, CACHE_FOR_WRITE)) goto FAIL; // store entry if (fatType_ == 16) { cacheBuffer_.fat16[cluster & 0xFF] = value; @@ -258,7 +258,7 @@ bool SdVolume::fatPut(uint32_t cluster, uint32_t value) { // mirror second FAT if (fatCount_ > 1) cacheMirrorBlock_ = lba + blocksPerFat_; return true; -fail: + FAIL: return false; } //------------------------------------------------------------------------------ @@ -270,16 +270,16 @@ bool SdVolume::freeChain(uint32_t cluster) { allocSearchStart_ = 2; do { - if (!fatGet(cluster, &next)) goto fail; + if (!fatGet(cluster, &next)) goto FAIL; // free cluster - if (!fatPut(cluster, 0)) goto fail; + if (!fatPut(cluster, 0)) goto FAIL; cluster = next; } while (!isEOC(cluster)); return true; -fail: + FAIL: return false; } //------------------------------------------------------------------------------ @@ -349,25 +349,25 @@ bool SdVolume::init(Sd2Card* dev, uint8_t part) { // if part == 0 assume super floppy with FAT boot sector in block zero // if part > 0 assume mbr volume with partition table if (part) { - if (part > 4)goto fail; - if (!cacheRawBlock(volumeStartBlock, CACHE_FOR_READ)) goto fail; + if (part > 4)goto FAIL; + if (!cacheRawBlock(volumeStartBlock, CACHE_FOR_READ)) goto FAIL; part_t* p = &cacheBuffer_.mbr.part[part - 1]; if ((p->boot & 0x7F) != 0 || p->totalSectors < 100 || p->firstSector == 0) { // not a valid partition - goto fail; + goto FAIL; } volumeStartBlock = p->firstSector; } - if (!cacheRawBlock(volumeStartBlock, CACHE_FOR_READ)) goto fail; + if (!cacheRawBlock(volumeStartBlock, CACHE_FOR_READ)) goto FAIL; fbs = &cacheBuffer_.fbs32; if (fbs->bytesPerSector != 512 || fbs->fatCount == 0 || fbs->reservedSectorCount == 0 || fbs->sectorsPerCluster == 0) { // not valid FAT volume - goto fail; + goto FAIL; } fatCount_ = fbs->fatCount; blocksPerCluster_ = fbs->sectorsPerCluster; @@ -375,7 +375,7 @@ bool SdVolume::init(Sd2Card* dev, uint8_t part) { clusterSizeShift_ = 0; while (blocksPerCluster_ != _BV(clusterSizeShift_)) { // error if not power of 2 - if (clusterSizeShift_++ > 7) goto fail; + if (clusterSizeShift_++ > 7) goto FAIL; } blocksPerFat_ = fbs->sectorsPerFat16 ? fbs->sectorsPerFat16 : fbs->sectorsPerFat32; @@ -404,7 +404,7 @@ bool SdVolume::init(Sd2Card* dev, uint8_t part) { // FAT type is determined by cluster count if (clusterCount_ < 4085) { fatType_ = 12; - if (!FAT12_SUPPORT) goto fail; + if (!FAT12_SUPPORT) goto FAIL; } else if (clusterCount_ < 65525) { fatType_ = 16; @@ -414,7 +414,7 @@ bool SdVolume::init(Sd2Card* dev, uint8_t part) { fatType_ = 32; } return true; -fail: + FAIL: return false; } #endif From 3be9c19f12fbc7eeb8d9b49bbf034c114c406434 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 14 Aug 2017 19:49:14 -0500 Subject: [PATCH 082/112] Hold on move axis screens --- Marlin/ultralcd.cpp | 13 +++++++++---- 1 file changed, 9 insertions(+), 4 deletions(-) diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index 8de1e0129..baefcf97f 100644 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -2720,11 +2720,16 @@ void kill_screen(const char* lcd_msg) { screenFunc_t _manual_move_func_ptr; - void lcd_move_menu_10mm() { move_menu_scale = 10.0; lcd_goto_screen(_manual_move_func_ptr); } - void lcd_move_menu_1mm() { move_menu_scale = 1.0; lcd_goto_screen(_manual_move_func_ptr); } - void lcd_move_menu_01mm() { move_menu_scale = 0.1; lcd_goto_screen(_manual_move_func_ptr); } + void _goto_manual_move(const float scale) { + defer_return_to_status = true; + move_menu_scale = scale; + lcd_goto_screen(_manual_move_func_ptr); + } + void lcd_move_menu_10mm() { _goto_manual_move(10.0); } + void lcd_move_menu_1mm() { _goto_manual_move( 1.0); } + void lcd_move_menu_01mm() { _goto_manual_move( 0.1); } - void _lcd_move_distance_menu(AxisEnum axis, screenFunc_t func) { + void _lcd_move_distance_menu(const AxisEnum axis, const screenFunc_t func) { _manual_move_func_ptr = func; START_MENU(); if (LCD_HEIGHT >= 4) { From 96ae53cf41fc0f6f6003fc1a5e2a2ddac4f3ac4f Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 14 Aug 2017 23:52:23 -0500 Subject: [PATCH 083/112] Use MOVE_SERVO macro where possible --- Marlin/Marlin_main.cpp | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index f9db4f49b..04e5716b2 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -2102,7 +2102,7 @@ static void clean_up_after_endstop_or_probe_move() { #if ENABLED(BLTOUCH) void bltouch_command(int angle) { - servo[Z_ENDSTOP_SERVO_NR].move(angle); // Give the BL-Touch the command and wait + MOVE_SERVO(Z_ENDSTOP_SERVO_NR, angle); // Give the BL-Touch the command and wait safe_delay(BLTOUCH_DELAY); } @@ -2206,7 +2206,7 @@ static void clean_up_after_endstop_or_probe_move() { #elif HAS_Z_SERVO_ENDSTOP && DISABLED(BLTOUCH) - servo[Z_ENDSTOP_SERVO_NR].move(z_servo_angle[deploy ? 0 : 1]); + MOVE_SERVO(Z_ENDSTOP_SERVO_NR, z_servo_angle[deploy ? 0 : 1]); #elif ENABLED(Z_PROBE_ALLEN_KEY) @@ -6663,7 +6663,7 @@ inline void gcode_M42() { SERIAL_ERROR_START(); SERIAL_ERRORLNPGM("Z_ENDSTOP_SERVO_NR not setup"); - #else + #else // HAS_Z_SERVO_ENDSTOP const uint8_t probe_index = parser.byteval('P', Z_ENDSTOP_SERVO_NR); @@ -6711,10 +6711,10 @@ inline void gcode_M42() { SET_INPUT_PULLUP(PROBE_TEST_PIN); bool deploy_state, stow_state; for (uint8_t i = 0; i < 4; i++) { - servo[probe_index].move(z_servo_angle[0]); //deploy + MOVE_SERVO(probe_index, z_servo_angle[0]); //deploy safe_delay(500); deploy_state = READ(PROBE_TEST_PIN); - servo[probe_index].move(z_servo_angle[1]); //stow + MOVE_SERVO(probe_index, z_servo_angle[1]); //stow safe_delay(500); stow_state = READ(PROBE_TEST_PIN); } @@ -6738,7 +6738,7 @@ inline void gcode_M42() { } else { // measure active signal length - servo[probe_index].move(z_servo_angle[0]); // deploy + MOVE_SERVO(probe_index, z_servo_angle[0]); // deploy safe_delay(500); SERIAL_PROTOCOLLNPGM("please trigger probe"); uint16_t probe_counter = 0; @@ -6763,7 +6763,7 @@ inline void gcode_M42() { else SERIAL_PROTOCOLLNPGM("noise detected - please re-run test"); // less than 2mS pulse - servo[probe_index].move(z_servo_angle[1]); //stow + MOVE_SERVO(probe_index, z_servo_angle[1]); //stow } // pulse detected From e9c72978c71c92c996842d93683c895c3dc11787 Mon Sep 17 00:00:00 2001 From: GMagician Date: Fri, 11 Aug 2017 23:21:39 +0200 Subject: [PATCH 084/112] Implement SERVO_DELAY as array This modify give SERVO_DELAY x servo basis --- .travis.yml | 1 + Marlin/Conditionals_LCD.h | 2 +- Marlin/Configuration.h | 2 +- .../example_configurations/AlephObjects/TAZ4/Configuration.h | 2 +- .../example_configurations/AliExpress/CL-260/Configuration.h | 2 +- Marlin/example_configurations/Anet/A6/Configuration.h | 2 +- Marlin/example_configurations/Anet/A8/Configuration.h | 2 +- Marlin/example_configurations/BQ/Hephestos/Configuration.h | 2 +- Marlin/example_configurations/BQ/Hephestos_2/Configuration.h | 2 +- Marlin/example_configurations/BQ/WITBOX/Configuration.h | 2 +- Marlin/example_configurations/Cartesio/Configuration.h | 2 +- Marlin/example_configurations/Creality/CR-10/Configuration.h | 2 +- Marlin/example_configurations/Felix/Configuration.h | 2 +- Marlin/example_configurations/Felix/DUAL/Configuration.h | 2 +- Marlin/example_configurations/Geeetech/GT2560/Configuration.h | 2 +- .../Geeetech/I3_Pro_X-GT2560/Configuration.h | 2 +- .../example_configurations/Infitary/i3-M508/Configuration.h | 2 +- Marlin/example_configurations/Malyan/M150/Configuration.h | 2 +- .../RepRapWorld/Megatronics/Configuration.h | 2 +- Marlin/example_configurations/RigidBot/Configuration.h | 2 +- Marlin/example_configurations/SCARA/Configuration.h | 2 +- Marlin/example_configurations/TinyBoy2/Configuration.h | 2 +- Marlin/example_configurations/Velleman/K8200/Configuration.h | 2 +- Marlin/example_configurations/Velleman/K8400/Configuration.h | 2 +- .../Velleman/K8400/Dual-head/Configuration.h | 2 +- Marlin/example_configurations/adafruit/ST7565/Configuration.h | 2 +- .../delta/FLSUN/auto_calibrate/Configuration.h | 2 +- .../delta/FLSUN/kossel_mini/Configuration.h | 2 +- Marlin/example_configurations/delta/generic/Configuration.h | 2 +- .../example_configurations/delta/kossel_mini/Configuration.h | 2 +- .../example_configurations/delta/kossel_pro/Configuration.h | 2 +- Marlin/example_configurations/delta/kossel_xl/Configuration.h | 2 +- .../example_configurations/gCreate/gMax1.5+/Configuration.h | 2 +- Marlin/example_configurations/makibox/Configuration.h | 2 +- Marlin/example_configurations/tvrrug/Round2/Configuration.h | 2 +- Marlin/example_configurations/wt150/Configuration.h | 2 +- Marlin/servo.cpp | 4 +++- 37 files changed, 39 insertions(+), 36 deletions(-) diff --git a/.travis.yml b/.travis.yml index 2b1a1a773..b3461a932 100644 --- a/.travis.yml +++ b/.travis.yml @@ -114,6 +114,7 @@ script: # - restore_configs - opt_enable NUM_SERVOS Z_ENDSTOP_SERVO_NR Z_SERVO_ANGLES DEACTIVATE_SERVOS_AFTER_MOVE + - opt_set NUM_SERVOS 1 - opt_enable AUTO_BED_LEVELING_3POINT DEBUG_LEVELING_FEATURE EEPROM_SETTINGS EEPROM_CHITCHAT - opt_enable_adv EXTENDED_CAPABILITIES_REPORT AUTO_REPORT_TEMPERATURES AUTOTEMP G38_PROBE_TARGET - build_marlin diff --git a/Marlin/Conditionals_LCD.h b/Marlin/Conditionals_LCD.h index 914ef51a6..d36931662 100644 --- a/Marlin/Conditionals_LCD.h +++ b/Marlin/Conditionals_LCD.h @@ -377,7 +377,7 @@ #endif #undef DEACTIVATE_SERVOS_AFTER_MOVE #undef SERVO_DELAY - #define SERVO_DELAY 50 + #define SERVO_DELAY { 50 } #ifndef BLTOUCH_DELAY #define BLTOUCH_DELAY 375 #endif diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 12d394fc3..f061b9c0f 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -1595,7 +1595,7 @@ // Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle. // 300ms is a good value but you can try less delay. // If the servo can't reach the requested position, increase it. -#define SERVO_DELAY 300 +#define SERVO_DELAY { 300 } // Servo deactivation // diff --git a/Marlin/example_configurations/AlephObjects/TAZ4/Configuration.h b/Marlin/example_configurations/AlephObjects/TAZ4/Configuration.h index ce9250eb9..52f64e984 100644 --- a/Marlin/example_configurations/AlephObjects/TAZ4/Configuration.h +++ b/Marlin/example_configurations/AlephObjects/TAZ4/Configuration.h @@ -1615,7 +1615,7 @@ // Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle. // 300ms is a good value but you can try less delay. // If the servo can't reach the requested position, increase it. -#define SERVO_DELAY 300 +#define SERVO_DELAY { 300 } // Servo deactivation // diff --git a/Marlin/example_configurations/AliExpress/CL-260/Configuration.h b/Marlin/example_configurations/AliExpress/CL-260/Configuration.h index 5cbd95adf..a81224d9a 100644 --- a/Marlin/example_configurations/AliExpress/CL-260/Configuration.h +++ b/Marlin/example_configurations/AliExpress/CL-260/Configuration.h @@ -1595,7 +1595,7 @@ // Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle. // 300ms is a good value but you can try less delay. // If the servo can't reach the requested position, increase it. -#define SERVO_DELAY 300 +#define SERVO_DELAY { 300 } // Servo deactivation // diff --git a/Marlin/example_configurations/Anet/A6/Configuration.h b/Marlin/example_configurations/Anet/A6/Configuration.h index 319826393..f090b8392 100644 --- a/Marlin/example_configurations/Anet/A6/Configuration.h +++ b/Marlin/example_configurations/Anet/A6/Configuration.h @@ -1754,7 +1754,7 @@ // Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle. // 300ms is a good value but you can try less delay. // If the servo can't reach the requested position, increase it. -#define SERVO_DELAY 300 +#define SERVO_DELAY { 300 } // Servo deactivation // diff --git a/Marlin/example_configurations/Anet/A8/Configuration.h b/Marlin/example_configurations/Anet/A8/Configuration.h index 537a90468..cd8ce118a 100644 --- a/Marlin/example_configurations/Anet/A8/Configuration.h +++ b/Marlin/example_configurations/Anet/A8/Configuration.h @@ -1603,7 +1603,7 @@ // Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle. // 300ms is a good value but you can try less delay. // If the servo can't reach the requested position, increase it. -#define SERVO_DELAY 300 +#define SERVO_DELAY { 300 } // Servo deactivation // diff --git a/Marlin/example_configurations/BQ/Hephestos/Configuration.h b/Marlin/example_configurations/BQ/Hephestos/Configuration.h index fd956dcdf..c4998aeff 100644 --- a/Marlin/example_configurations/BQ/Hephestos/Configuration.h +++ b/Marlin/example_configurations/BQ/Hephestos/Configuration.h @@ -1586,7 +1586,7 @@ // Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle. // 300ms is a good value but you can try less delay. // If the servo can't reach the requested position, increase it. -#define SERVO_DELAY 300 +#define SERVO_DELAY { 300 } // Servo deactivation // diff --git a/Marlin/example_configurations/BQ/Hephestos_2/Configuration.h b/Marlin/example_configurations/BQ/Hephestos_2/Configuration.h index fdba13b24..dacdfcf05 100644 --- a/Marlin/example_configurations/BQ/Hephestos_2/Configuration.h +++ b/Marlin/example_configurations/BQ/Hephestos_2/Configuration.h @@ -1596,7 +1596,7 @@ // Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle. // 300ms is a good value but you can try less delay. // If the servo can't reach the requested position, increase it. -#define SERVO_DELAY 300 +#define SERVO_DELAY { 300 } // Servo deactivation // diff --git a/Marlin/example_configurations/BQ/WITBOX/Configuration.h b/Marlin/example_configurations/BQ/WITBOX/Configuration.h index b8fbc1266..0b814b17a 100644 --- a/Marlin/example_configurations/BQ/WITBOX/Configuration.h +++ b/Marlin/example_configurations/BQ/WITBOX/Configuration.h @@ -1586,7 +1586,7 @@ // Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle. // 300ms is a good value but you can try less delay. // If the servo can't reach the requested position, increase it. -#define SERVO_DELAY 300 +#define SERVO_DELAY { 300 } // Servo deactivation // diff --git a/Marlin/example_configurations/Cartesio/Configuration.h b/Marlin/example_configurations/Cartesio/Configuration.h index 9360232d6..3b4e6c521 100644 --- a/Marlin/example_configurations/Cartesio/Configuration.h +++ b/Marlin/example_configurations/Cartesio/Configuration.h @@ -1594,7 +1594,7 @@ // Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle. // 300ms is a good value but you can try less delay. // If the servo can't reach the requested position, increase it. -#define SERVO_DELAY 300 +#define SERVO_DELAY { 300 } // Servo deactivation // diff --git a/Marlin/example_configurations/Creality/CR-10/Configuration.h b/Marlin/example_configurations/Creality/CR-10/Configuration.h index 53e703b81..efd28a8b2 100644 --- a/Marlin/example_configurations/Creality/CR-10/Configuration.h +++ b/Marlin/example_configurations/Creality/CR-10/Configuration.h @@ -1607,7 +1607,7 @@ // Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle. // 300ms is a good value but you can try less delay. // If the servo can't reach the requested position, increase it. -#define SERVO_DELAY 300 +#define SERVO_DELAY { 300 } // Servo deactivation // diff --git a/Marlin/example_configurations/Felix/Configuration.h b/Marlin/example_configurations/Felix/Configuration.h index 5b99d6dba..49af65921 100644 --- a/Marlin/example_configurations/Felix/Configuration.h +++ b/Marlin/example_configurations/Felix/Configuration.h @@ -1577,7 +1577,7 @@ // Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle. // 300ms is a good value but you can try less delay. // If the servo can't reach the requested position, increase it. -#define SERVO_DELAY 300 +#define SERVO_DELAY { 300 } // Servo deactivation // diff --git a/Marlin/example_configurations/Felix/DUAL/Configuration.h b/Marlin/example_configurations/Felix/DUAL/Configuration.h index eeaaf0e7f..ae36182bf 100644 --- a/Marlin/example_configurations/Felix/DUAL/Configuration.h +++ b/Marlin/example_configurations/Felix/DUAL/Configuration.h @@ -1577,7 +1577,7 @@ // Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle. // 300ms is a good value but you can try less delay. // If the servo can't reach the requested position, increase it. -#define SERVO_DELAY 300 +#define SERVO_DELAY { 300 } // Servo deactivation // diff --git a/Marlin/example_configurations/Geeetech/GT2560/Configuration.h b/Marlin/example_configurations/Geeetech/GT2560/Configuration.h index 6cbc46bc0..2d95f5221 100644 --- a/Marlin/example_configurations/Geeetech/GT2560/Configuration.h +++ b/Marlin/example_configurations/Geeetech/GT2560/Configuration.h @@ -1610,7 +1610,7 @@ // Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle. // 300ms is a good value but you can try less delay. // If the servo can't reach the requested position, increase it. -#define SERVO_DELAY 300 +#define SERVO_DELAY { 300 } // Servo deactivation // diff --git a/Marlin/example_configurations/Geeetech/I3_Pro_X-GT2560/Configuration.h b/Marlin/example_configurations/Geeetech/I3_Pro_X-GT2560/Configuration.h index d7e024dce..86731fee9 100644 --- a/Marlin/example_configurations/Geeetech/I3_Pro_X-GT2560/Configuration.h +++ b/Marlin/example_configurations/Geeetech/I3_Pro_X-GT2560/Configuration.h @@ -1595,7 +1595,7 @@ // Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle. // 300ms is a good value but you can try less delay. // If the servo can't reach the requested position, increase it. -#define SERVO_DELAY 300 +#define SERVO_DELAY { 300 } // Servo deactivation // diff --git a/Marlin/example_configurations/Infitary/i3-M508/Configuration.h b/Marlin/example_configurations/Infitary/i3-M508/Configuration.h index 872870a76..de23a4ca7 100644 --- a/Marlin/example_configurations/Infitary/i3-M508/Configuration.h +++ b/Marlin/example_configurations/Infitary/i3-M508/Configuration.h @@ -1599,7 +1599,7 @@ // Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle. // 300ms is a good value but you can try less delay. // If the servo can't reach the requested position, increase it. -#define SERVO_DELAY 300 +#define SERVO_DELAY { 300 } // Servo deactivation // diff --git a/Marlin/example_configurations/Malyan/M150/Configuration.h b/Marlin/example_configurations/Malyan/M150/Configuration.h index 501738266..23162888f 100644 --- a/Marlin/example_configurations/Malyan/M150/Configuration.h +++ b/Marlin/example_configurations/Malyan/M150/Configuration.h @@ -1623,7 +1623,7 @@ // Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle. // 300ms is a good value but you can try less delay. // If the servo can't reach the requested position, increase it. -#define SERVO_DELAY 300 +#define SERVO_DELAY { 300 } // Servo deactivation // diff --git a/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h b/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h index 0f575a8fc..b4b895f64 100644 --- a/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h +++ b/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h @@ -1595,7 +1595,7 @@ // Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle. // 300ms is a good value but you can try less delay. // If the servo can't reach the requested position, increase it. -#define SERVO_DELAY 300 +#define SERVO_DELAY { 300 } // Servo deactivation // diff --git a/Marlin/example_configurations/RigidBot/Configuration.h b/Marlin/example_configurations/RigidBot/Configuration.h index ea744e8e8..152cf61aa 100644 --- a/Marlin/example_configurations/RigidBot/Configuration.h +++ b/Marlin/example_configurations/RigidBot/Configuration.h @@ -1595,7 +1595,7 @@ // Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle. // 300ms is a good value but you can try less delay. // If the servo can't reach the requested position, increase it. -#define SERVO_DELAY 300 +#define SERVO_DELAY { 300 } // Servo deactivation // diff --git a/Marlin/example_configurations/SCARA/Configuration.h b/Marlin/example_configurations/SCARA/Configuration.h index aa5dcdac6..a457c2d35 100644 --- a/Marlin/example_configurations/SCARA/Configuration.h +++ b/Marlin/example_configurations/SCARA/Configuration.h @@ -1607,7 +1607,7 @@ // Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle. // 300ms is a good value but you can try less delay. // If the servo can't reach the requested position, increase it. -#define SERVO_DELAY 300 +#define SERVO_DELAY { 300 } // Servo deactivation // diff --git a/Marlin/example_configurations/TinyBoy2/Configuration.h b/Marlin/example_configurations/TinyBoy2/Configuration.h index 480ba0a7a..1453e0656 100644 --- a/Marlin/example_configurations/TinyBoy2/Configuration.h +++ b/Marlin/example_configurations/TinyBoy2/Configuration.h @@ -1651,7 +1651,7 @@ // Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle. // 300ms is a good value but you can try less delay. // If the servo can't reach the requested position, increase it. -#define SERVO_DELAY 300 +#define SERVO_DELAY { 300 } // Servo deactivation // diff --git a/Marlin/example_configurations/Velleman/K8200/Configuration.h b/Marlin/example_configurations/Velleman/K8200/Configuration.h index 959713d3d..cd39af033 100644 --- a/Marlin/example_configurations/Velleman/K8200/Configuration.h +++ b/Marlin/example_configurations/Velleman/K8200/Configuration.h @@ -1629,7 +1629,7 @@ // Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle. // 300ms is a good value but you can try less delay. // If the servo can't reach the requested position, increase it. -#define SERVO_DELAY 300 +#define SERVO_DELAY { 300 } // Servo deactivation // diff --git a/Marlin/example_configurations/Velleman/K8400/Configuration.h b/Marlin/example_configurations/Velleman/K8400/Configuration.h index 48ed7f53f..33914e41d 100644 --- a/Marlin/example_configurations/Velleman/K8400/Configuration.h +++ b/Marlin/example_configurations/Velleman/K8400/Configuration.h @@ -1595,7 +1595,7 @@ // Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle. // 300ms is a good value but you can try less delay. // If the servo can't reach the requested position, increase it. -#define SERVO_DELAY 300 +#define SERVO_DELAY { 300 } // Servo deactivation // diff --git a/Marlin/example_configurations/Velleman/K8400/Dual-head/Configuration.h b/Marlin/example_configurations/Velleman/K8400/Dual-head/Configuration.h index 1c24b7217..94bca1fc0 100644 --- a/Marlin/example_configurations/Velleman/K8400/Dual-head/Configuration.h +++ b/Marlin/example_configurations/Velleman/K8400/Dual-head/Configuration.h @@ -1595,7 +1595,7 @@ // Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle. // 300ms is a good value but you can try less delay. // If the servo can't reach the requested position, increase it. -#define SERVO_DELAY 300 +#define SERVO_DELAY { 300 } // Servo deactivation // diff --git a/Marlin/example_configurations/adafruit/ST7565/Configuration.h b/Marlin/example_configurations/adafruit/ST7565/Configuration.h index 4c99ee2f1..9a4a60a42 100644 --- a/Marlin/example_configurations/adafruit/ST7565/Configuration.h +++ b/Marlin/example_configurations/adafruit/ST7565/Configuration.h @@ -1595,7 +1595,7 @@ // Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle. // 300ms is a good value but you can try less delay. // If the servo can't reach the requested position, increase it. -#define SERVO_DELAY 300 +#define SERVO_DELAY { 300 } // Servo deactivation // diff --git a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h index 643d2e2ee..8c2947a25 100644 --- a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h +++ b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h @@ -1723,7 +1723,7 @@ // Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle. // 300ms is a good value but you can try less delay. // If the servo can't reach the requested position, increase it. -#define SERVO_DELAY 300 +#define SERVO_DELAY { 300 } // Servo deactivation // diff --git a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h index 82de18e31..c0718640a 100644 --- a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h +++ b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h @@ -1716,7 +1716,7 @@ // Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle. // 300ms is a good value but you can try less delay. // If the servo can't reach the requested position, increase it. -#define SERVO_DELAY 300 +#define SERVO_DELAY { 300 } // Servo deactivation // diff --git a/Marlin/example_configurations/delta/generic/Configuration.h b/Marlin/example_configurations/delta/generic/Configuration.h index ce2b8ceec..63d53eec1 100644 --- a/Marlin/example_configurations/delta/generic/Configuration.h +++ b/Marlin/example_configurations/delta/generic/Configuration.h @@ -1711,7 +1711,7 @@ // Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle. // 300ms is a good value but you can try less delay. // If the servo can't reach the requested position, increase it. -#define SERVO_DELAY 300 +#define SERVO_DELAY { 300 } // Servo deactivation // diff --git a/Marlin/example_configurations/delta/kossel_mini/Configuration.h b/Marlin/example_configurations/delta/kossel_mini/Configuration.h index 75c03f697..f1d39ef72 100644 --- a/Marlin/example_configurations/delta/kossel_mini/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_mini/Configuration.h @@ -1714,7 +1714,7 @@ // Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle. // 300ms is a good value but you can try less delay. // If the servo can't reach the requested position, increase it. -#define SERVO_DELAY 300 +#define SERVO_DELAY { 300 } // Servo deactivation // diff --git a/Marlin/example_configurations/delta/kossel_pro/Configuration.h b/Marlin/example_configurations/delta/kossel_pro/Configuration.h index 259c923d0..95a8be324 100644 --- a/Marlin/example_configurations/delta/kossel_pro/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_pro/Configuration.h @@ -1714,7 +1714,7 @@ // Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle. // 300ms is a good value but you can try less delay. // If the servo can't reach the requested position, increase it. -#define SERVO_DELAY 300 +#define SERVO_DELAY { 300 } // Servo deactivation // diff --git a/Marlin/example_configurations/delta/kossel_xl/Configuration.h b/Marlin/example_configurations/delta/kossel_xl/Configuration.h index 4231be068..2bda92c26 100644 --- a/Marlin/example_configurations/delta/kossel_xl/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_xl/Configuration.h @@ -1723,7 +1723,7 @@ // Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle. // 300ms is a good value but you can try less delay. // If the servo can't reach the requested position, increase it. -#define SERVO_DELAY 300 +#define SERVO_DELAY { 300 } // Servo deactivation // diff --git a/Marlin/example_configurations/gCreate/gMax1.5+/Configuration.h b/Marlin/example_configurations/gCreate/gMax1.5+/Configuration.h index a870e8da8..ed98ed508 100644 --- a/Marlin/example_configurations/gCreate/gMax1.5+/Configuration.h +++ b/Marlin/example_configurations/gCreate/gMax1.5+/Configuration.h @@ -1609,7 +1609,7 @@ // Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle. // 300ms is a good value but you can try less delay. // If the servo can't reach the requested position, increase it. -#define SERVO_DELAY 300 +#define SERVO_DELAY { 300 } // Servo deactivation // diff --git a/Marlin/example_configurations/makibox/Configuration.h b/Marlin/example_configurations/makibox/Configuration.h index 02f33df03..a552a7727 100644 --- a/Marlin/example_configurations/makibox/Configuration.h +++ b/Marlin/example_configurations/makibox/Configuration.h @@ -1598,7 +1598,7 @@ // Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle. // 300ms is a good value but you can try less delay. // If the servo can't reach the requested position, increase it. -#define SERVO_DELAY 300 +#define SERVO_DELAY { 300 } // Servo deactivation // diff --git a/Marlin/example_configurations/tvrrug/Round2/Configuration.h b/Marlin/example_configurations/tvrrug/Round2/Configuration.h index 8212beb07..26a59a205 100644 --- a/Marlin/example_configurations/tvrrug/Round2/Configuration.h +++ b/Marlin/example_configurations/tvrrug/Round2/Configuration.h @@ -1590,7 +1590,7 @@ // Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle. // 300ms is a good value but you can try less delay. // If the servo can't reach the requested position, increase it. -#define SERVO_DELAY 300 +#define SERVO_DELAY { 300 } // Servo deactivation // diff --git a/Marlin/example_configurations/wt150/Configuration.h b/Marlin/example_configurations/wt150/Configuration.h index 2c468a942..db6dac6cf 100644 --- a/Marlin/example_configurations/wt150/Configuration.h +++ b/Marlin/example_configurations/wt150/Configuration.h @@ -1600,7 +1600,7 @@ // Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle. // 300ms is a good value but you can try less delay. // If the servo can't reach the requested position, increase it. -#define SERVO_DELAY 300 +#define SERVO_DELAY { 300 } // Servo deactivation // diff --git a/Marlin/servo.cpp b/Marlin/servo.cpp index 74feb5c61..d6b7b700f 100644 --- a/Marlin/servo.cpp +++ b/Marlin/servo.cpp @@ -308,9 +308,11 @@ int Servo::readMicroseconds() { bool Servo::attached() { return servo_info[this->servoIndex].Pin.isActive; } void Servo::move(int value) { + constexpr uint16_t servo_delay[] = SERVO_DELAY; + static_assert(COUNT(servo_delay) == NUM_SERVOS, "SERVO_DELAY must be an array NUM_SERVOS long."); if (this->attach(0) >= 0) { this->write(value); - delay(SERVO_DELAY); + delay(servo_delay[this->servoIndex]); #if ENABLED(DEACTIVATE_SERVOS_AFTER_MOVE) this->detach(); #endif From be5ca3421543a3c88b2141b1ee45e9f1600292c4 Mon Sep 17 00:00:00 2001 From: Roxy-3D Date: Tue, 15 Aug 2017 17:04:52 -0500 Subject: [PATCH 085/112] Allow G29 to work correctly even if nozzle is off the mesh. (#7512) * work around previous regressions... --- Marlin/ubl_G29.cpp | 13 +++++-------- 1 file changed, 5 insertions(+), 8 deletions(-) diff --git a/Marlin/ubl_G29.cpp b/Marlin/ubl_G29.cpp index bc645fb2c..2bdc14a69 100644 --- a/Marlin/ubl_G29.cpp +++ b/Marlin/ubl_G29.cpp @@ -1132,15 +1132,12 @@ SERIAL_PROTOCOLLNPGM("Both X & Y locations must be specified.\n"); err_flag = true; } - if (!WITHIN(RAW_X_POSITION(g29_x_pos), X_MIN_BED, X_MAX_BED)) { - SERIAL_PROTOCOLLNPGM("Invalid X location specified.\n"); - err_flag = true; - } - if (!WITHIN(RAW_Y_POSITION(g29_y_pos), Y_MIN_BED, Y_MAX_BED)) { - SERIAL_PROTOCOLLNPGM("Invalid Y location specified.\n"); - err_flag = true; - } + if (!WITHIN(RAW_X_POSITION(g29_x_pos), X_MIN_BED, X_MAX_BED)) // if X & Y are not valid, use center of the bed values + g29_x_pos = (X_MIN_BED + X_MAX_BED) / 2.0; + + if (!WITHIN(RAW_Y_POSITION(g29_y_pos), Y_MIN_BED, Y_MAX_BED)) // if X & Y are not valid, use center of the bed values + g29_y_pos = (Y_MIN_BED + Y_MAX_BED) / 2.0; if (err_flag) return UBL_ERR; From f1843211e67143d6e9a220789938bdaa7f8a1a41 Mon Sep 17 00:00:00 2001 From: cdedwards Date: Tue, 15 Aug 2017 17:04:53 -0600 Subject: [PATCH 086/112] Fix for G26 spam output while heating, G26 will continuously spam the heater states instead of printing it out every 5000ms. --- Marlin/G26_Mesh_Validation_Tool.cpp | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/Marlin/G26_Mesh_Validation_Tool.cpp b/Marlin/G26_Mesh_Validation_Tool.cpp index a0e17fe76..ffcad389f 100644 --- a/Marlin/G26_Mesh_Validation_Tool.cpp +++ b/Marlin/G26_Mesh_Validation_Tool.cpp @@ -785,9 +785,10 @@ if (ubl_lcd_clicked()) return exit_from_g26(); #endif - if (PENDING(millis(), next)) { + if (ELAPSED(millis(), next)) { next = millis() + 5000UL; print_heaterstates(); + SERIAL_EOL(); } idle(); } @@ -806,9 +807,10 @@ if (ubl_lcd_clicked()) return exit_from_g26(); #endif - if (PENDING(millis(), next)) { + if (ELAPSED(millis(), next)) { next = millis() + 5000UL; print_heaterstates(); + SERIAL_EOL(); } idle(); } From ab2ac1af713724113f8fc09ca8afd338e3f4e153 Mon Sep 17 00:00:00 2001 From: Tannoo Date: Tue, 15 Aug 2017 20:01:11 -0600 Subject: [PATCH 087/112] UBL_LCD_storage_corrections (#7517) Correcting the storage selection. Also EEPROM error handling on the LCD. --- Marlin/ultralcd.cpp | 21 ++++++++++++++++----- 1 file changed, 16 insertions(+), 5 deletions(-) diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index 23b807e3b..9704dfcac 100644 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -2118,18 +2118,22 @@ void kill_screen(const char* lcd_msg) { * UBL Load Mesh Command */ void _lcd_ubl_load_mesh_cmd() { - char UBL_LCD_GCODE[8]; + char UBL_LCD_GCODE[25]; sprintf_P(UBL_LCD_GCODE, PSTR("G29 L%i"), ubl_storage_slot); enqueue_and_echo_command(UBL_LCD_GCODE); + sprintf_P(UBL_LCD_GCODE, PSTR("M117 Map %i loaded."), ubl_storage_slot); + enqueue_and_echo_command(UBL_LCD_GCODE); } /** * UBL Save Mesh Command */ void _lcd_ubl_save_mesh_cmd() { - char UBL_LCD_GCODE[8]; + char UBL_LCD_GCODE[25]; sprintf_P(UBL_LCD_GCODE, PSTR("G29 S%i"), ubl_storage_slot); enqueue_and_echo_command(UBL_LCD_GCODE); + sprintf_P(UBL_LCD_GCODE, PSTR("M117 Map %i saved."), ubl_storage_slot); + enqueue_and_echo_command(UBL_LCD_GCODE); } /** @@ -2141,11 +2145,18 @@ void kill_screen(const char* lcd_msg) { * Save Bed Mesh */ void _lcd_ubl_storage_mesh() { + int16_t a = settings.calc_num_meshes(); START_MENU(); MENU_BACK(MSG_UBL_LEVEL_BED); - MENU_ITEM_EDIT(int3, MSG_UBL_STORAGE_SLOT, &ubl_storage_slot, 0, 9); - MENU_ITEM(function, MSG_UBL_LOAD_MESH, _lcd_ubl_load_mesh_cmd); - MENU_ITEM(function, MSG_UBL_SAVE_MESH, _lcd_ubl_save_mesh_cmd); + if (!WITHIN(ubl_storage_slot, 0, a - 1)) { + STATIC_ITEM("No storage"); + STATIC_ITEM("Initialize EEPROM"); + } + else { + MENU_ITEM_EDIT(int3, MSG_UBL_STORAGE_SLOT, &ubl_storage_slot, 0, a - 1); + MENU_ITEM(function, MSG_UBL_LOAD_MESH, _lcd_ubl_load_mesh_cmd); + MENU_ITEM(function, MSG_UBL_SAVE_MESH, _lcd_ubl_save_mesh_cmd); + } END_MENU(); } From 257b693ab0dbdeaf798567c7c6c6fe6210db7f19 Mon Sep 17 00:00:00 2001 From: Thomas Moore Date: Tue, 15 Aug 2017 22:57:13 -0500 Subject: [PATCH 088/112] Advanced pause fixes (#7518) * Disallow filament change while paused * Use kinematic movemements in pause_print and resume_print --- Marlin/Marlin_main.cpp | 48 +++++++++++++++--------------------------- Marlin/cardreader.h | 2 ++ Marlin/ultralcd.cpp | 2 +- 3 files changed, 20 insertions(+), 32 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index f2d6d47f2..b2d609e63 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -6192,32 +6192,25 @@ inline void gcode_M17() { lcd_advanced_pause_show_message(ADVANCED_PAUSE_MESSAGE_INIT); #endif } - stepper.synchronize(); // Save current position + stepper.synchronize(); COPY(resume_position, current_position); - set_destination_to_current(); if (retract) { // Initial retract before move to filament change position + set_destination_to_current(); destination[E_AXIS] += retract; RUNPLAN(PAUSE_PARK_RETRACT_FEEDRATE); + stepper.synchronize(); } // Lift Z axis - if (z_lift > 0) { - destination[Z_AXIS] += z_lift; - NOMORE(destination[Z_AXIS], Z_MAX_POS); - RUNPLAN(PAUSE_PARK_Z_FEEDRATE); - } + if (z_lift > 0) + do_blocking_move_to_z(current_position[Z_AXIS] + z_lift, PAUSE_PARK_Z_FEEDRATE); // Move XY axes to filament exchange position - destination[X_AXIS] = x_pos; - destination[Y_AXIS] = y_pos; - - clamp_to_software_endstops(destination); - RUNPLAN(PAUSE_PARK_XY_FEEDRATE); - stepper.synchronize(); + do_blocking_move_to_xy(x_pos, y_pos, PAUSE_PARK_XY_FEEDRATE); if (unload_length != 0) { if (show_lcd) { @@ -6228,6 +6221,7 @@ inline void gcode_M17() { } // Unload filament + set_destination_to_current(); destination[E_AXIS] += unload_length; RUNPLAN(FILAMENT_CHANGE_UNLOAD_FEEDRATE); stepper.synchronize(); @@ -6355,7 +6349,6 @@ inline void gcode_M17() { // Load filament destination[E_AXIS] += load_length; - RUNPLAN(FILAMENT_CHANGE_LOAD_FEEDRATE); stepper.synchronize(); } @@ -6398,18 +6391,9 @@ inline void gcode_M17() { destination[E_AXIS] = current_position[E_AXIS] = resume_position[E_AXIS]; planner.set_e_position_mm(current_position[E_AXIS]); - #if IS_KINEMATIC - // Move XYZ to starting position - planner.buffer_line_kinematic(resume_position, PAUSE_PARK_XY_FEEDRATE, active_extruder); - #else - // Move XY to starting position, then Z - destination[X_AXIS] = resume_position[X_AXIS]; - destination[Y_AXIS] = resume_position[Y_AXIS]; - RUNPLAN(PAUSE_PARK_XY_FEEDRATE); - destination[Z_AXIS] = resume_position[Z_AXIS]; - RUNPLAN(PAUSE_PARK_Z_FEEDRATE); - #endif - stepper.synchronize(); + // Move XY to starting position, then Z + do_blocking_move_to_xy(resume_position[X_AXIS], resume_position[Y_AXIS], PAUSE_PARK_XY_FEEDRATE); + do_blocking_move_to_z(resume_position[Z_AXIS], PAUSE_PARK_Z_FEEDRATE); #if ENABLED(FILAMENT_RUNOUT_SENSOR) filament_ran_out = false; @@ -8292,14 +8276,14 @@ inline void gcode_M121() { endstops.enable_globally(false); } // Initial retract before move to filament change position const float retract = parser.seen('L') ? parser.value_axis_units(E_AXIS) : 0 - #if defined(PAUSE_PARK_RETRACT_LENGTH) && PAUSE_PARK_RETRACT_LENGTH > 0 + #ifdef PAUSE_PARK_RETRACT_LENGTH - (PAUSE_PARK_RETRACT_LENGTH) #endif ; // Lift Z axis const float z_lift = parser.linearval('Z') - #if PAUSE_PARK_Z_ADD > 0 + #ifdef PAUSE_PARK_Z_ADD + PAUSE_PARK_Z_ADD #endif ; @@ -8322,7 +8306,9 @@ inline void gcode_M121() { endstops.enable_globally(false); } #endif ; - const bool job_running = print_job_timer.isRunning(); + #if DISABLED(SDSUPPORT) + const bool job_running = print_job_timer.isRunning(); + #endif if (pause_print(retract, z_lift, x_pos, y_pos)) { #if DISABLED(SDSUPPORT) @@ -9642,14 +9628,14 @@ inline void gcode_M502() { // Initial retract before move to filament change position const float retract = parser.seen('E') ? parser.value_axis_units(E_AXIS) : 0 - #if defined(PAUSE_PARK_RETRACT_LENGTH) && PAUSE_PARK_RETRACT_LENGTH > 0 + #ifdef PAUSE_PARK_RETRACT_LENGTH - (PAUSE_PARK_RETRACT_LENGTH) #endif ; // Lift Z axis const float z_lift = parser.linearval('Z', 0 - #if defined(PAUSE_PARK_Z_ADD) && PAUSE_PARK_Z_ADD > 0 + #ifdef PAUSE_PARK_Z_ADD + PAUSE_PARK_Z_ADD #endif ); diff --git a/Marlin/cardreader.h b/Marlin/cardreader.h index ca2968273..c9bea6036 100644 --- a/Marlin/cardreader.h +++ b/Marlin/cardreader.h @@ -167,6 +167,7 @@ private: extern CardReader card; #define IS_SD_PRINTING (card.sdprinting) +#define IS_SD_FILE_OPEN (card.isFileOpen()) #if PIN_EXISTS(SD_DETECT) #if ENABLED(SD_DETECT_INVERTED) @@ -182,6 +183,7 @@ extern CardReader card; #else #define IS_SD_PRINTING (false) +#define IS_SD_FILE_OPEN (false) #endif // SDSUPPORT diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index 9704dfcac..c29c661a3 100644 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -2425,7 +2425,7 @@ void kill_screen(const char* lcd_msg) { // Change filament // #if ENABLED(ADVANCED_PAUSE_FEATURE) - if (!thermalManager.tooColdToExtrude(active_extruder) && !IS_SD_PRINTING) + if (!thermalManager.tooColdToExtrude(active_extruder) && !IS_SD_FILE_OPEN) MENU_ITEM(function, MSG_FILAMENTCHANGE, lcd_enqueue_filament_change); #endif From 30887feae3fdab912c7355c353a4926c3b0ae7ad Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 23 Jul 2017 18:47:11 -0500 Subject: [PATCH 089/112] Tweak some formatting in ABL G29 --- Marlin/Marlin_main.cpp | 22 +++++++++++----------- 1 file changed, 11 insertions(+), 11 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index b2d609e63..e77b7d0e6 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -2786,7 +2786,7 @@ static void clean_up_after_endstop_or_probe_move() { int bilinear_grid_spacing_virt[2] = { 0 }; float bilinear_grid_factor_virt[2] = { 0 }; - static void bed_level_virt_print() { + static void print_bilinear_leveling_grid_virt() { SERIAL_ECHOLNPGM("Subdivided with CATMULL ROM Leveling Grid:"); print_2d_array(ABL_GRID_POINTS_VIRT_X, ABL_GRID_POINTS_VIRT_Y, 5, [](const uint8_t ix, const uint8_t iy) { return z_values_virt[ix][iy]; } @@ -5042,7 +5042,7 @@ void home_all_axes() { gcode_G28(true); } refresh_bed_level(); #if ENABLED(ABL_BILINEAR_SUBDIVISION) - bed_level_virt_print(); + print_bilinear_leveling_grid_virt(); #endif #elif ENABLED(AUTO_BED_LEVELING_LINEAR) @@ -9314,18 +9314,18 @@ void quickstop_stepper() { if (parser.seen('V')) { #if ABL_PLANAR planner.bed_level_matrix.debug(PSTR("Bed Level Correction Matrix:")); - #elif ENABLED(AUTO_BED_LEVELING_BILINEAR) + #else if (leveling_is_valid()) { - print_bilinear_leveling_grid(); - #if ENABLED(ABL_BILINEAR_SUBDIVISION) - bed_level_virt_print(); + #if ENABLED(AUTO_BED_LEVELING_BILINEAR) + print_bilinear_leveling_grid(); + #if ENABLED(ABL_BILINEAR_SUBDIVISION) + print_bilinear_leveling_grid_virt(); + #endif + #elif ENABLED(MESH_BED_LEVELING) + SERIAL_ECHOLNPGM("Mesh Bed Level data:"); + mbl_mesh_report(); #endif } - #elif ENABLED(MESH_BED_LEVELING) - if (leveling_is_valid()) { - SERIAL_ECHOLNPGM("Mesh Bed Level data:"); - mbl_mesh_report(); - } #endif } From 0a18fb735e4d2608a03a0f13b4bb1e9d71ea10ee Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 16 Aug 2017 02:28:11 -0500 Subject: [PATCH 090/112] Use "PSU" label to fit on screen --- Marlin/language_el.h | 2 +- Marlin/language_en.h | 2 +- Marlin/language_nl.h | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/Marlin/language_el.h b/Marlin/language_el.h index af23ede57..62e95646a 100644 --- a/Marlin/language_el.h +++ b/Marlin/language_el.h @@ -199,7 +199,7 @@ #endif #define MSG_INFO_MIN_TEMP _UxGT("Min Temp") #define MSG_INFO_MAX_TEMP _UxGT("Max Temp") -#define MSG_INFO_PSU _UxGT("Power Supply") +#define MSG_INFO_PSU _UxGT("PSU") #define MSG_FILAMENT_CHANGE_HEADER _UxGT("CHANGE FILAMENT") #define MSG_FILAMENT_CHANGE_OPTION_EXTRUDE _UxGT("Extrude more") diff --git a/Marlin/language_en.h b/Marlin/language_en.h index 52d9aa49e..b702ecdbb 100644 --- a/Marlin/language_en.h +++ b/Marlin/language_en.h @@ -820,7 +820,7 @@ #define MSG_INFO_MAX_TEMP _UxGT("Max Temp") #endif #ifndef MSG_INFO_PSU - #define MSG_INFO_PSU _UxGT("Power Supply") + #define MSG_INFO_PSU _UxGT("PSU") #endif #ifndef MSG_DRIVE_STRENGTH #define MSG_DRIVE_STRENGTH _UxGT("Drive Strength") diff --git a/Marlin/language_nl.h b/Marlin/language_nl.h index 27274aaca..c1df0c80b 100644 --- a/Marlin/language_nl.h +++ b/Marlin/language_nl.h @@ -220,7 +220,7 @@ #define MSG_INFO_MIN_TEMP _UxGT("Min Temp") #define MSG_INFO_MAX_TEMP _UxGT("Max Temp") -#define MSG_INFO_PSU _UxGT("Power Supply") //accepted English term in Dutch +#define MSG_INFO_PSU _UxGT("PSU") //accepted English term in Dutch #define MSG_DRIVE_STRENGTH _UxGT("Motorstroom") #define MSG_DAC_PERCENT _UxGT("Driver %") //accepted English term in Dutch From a1878cd1c0194205a4b5d9cf12cd169043e5dff5 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 16 Aug 2017 02:27:50 -0500 Subject: [PATCH 091/112] Add "Level Corners" menu option --- Marlin/Conditionals_post.h | 7 ++ Marlin/Configuration.h | 1 + .../AlephObjects/TAZ4/Configuration.h | 1 + .../AliExpress/CL-260/Configuration.h | 1 + .../Anet/A6/Configuration.h | 1 + .../Anet/A8/Configuration.h | 1 + .../BQ/Hephestos/Configuration.h | 1 + .../BQ/Hephestos_2/Configuration.h | 1 + .../BQ/WITBOX/Configuration.h | 1 + .../Cartesio/Configuration.h | 1 + .../Creality/CR-10/Configuration.h | 1 + .../Felix/Configuration.h | 1 + .../Felix/DUAL/Configuration.h | 1 + .../Folger Tech/i3-2020/Configuration.h | 1 + .../Geeetech/GT2560/Configuration.h | 1 + .../Geeetech/I3_Pro_X-GT2560/Configuration.h | 1 + .../Infitary/i3-M508/Configuration.h | 1 + .../Malyan/M150/Configuration.h | 1 + .../RepRapWorld/Megatronics/Configuration.h | 1 + .../RigidBot/Configuration.h | 1 + .../SCARA/Configuration.h | 1 + .../TinyBoy2/Configuration.h | 1 + .../Velleman/K8200/Configuration.h | 1 + .../Velleman/K8400/Configuration.h | 1 + .../Velleman/K8400/Dual-head/Configuration.h | 1 + .../adafruit/ST7565/Configuration.h | 1 + .../FLSUN/auto_calibrate/Configuration.h | 1 + .../delta/FLSUN/kossel_mini/Configuration.h | 1 + .../delta/generic/Configuration.h | 1 + .../delta/kossel_mini/Configuration.h | 1 + .../delta/kossel_pro/Configuration.h | 1 + .../delta/kossel_xl/Configuration.h | 1 + .../gCreate/gMax1.5+/Configuration.h | 1 + .../makibox/Configuration.h | 1 + .../tvrrug/Round2/Configuration.h | 1 + .../wt150/Configuration.h | 1 + Marlin/language_en.h | 6 ++ Marlin/ultralcd.cpp | 78 +++++++++++++++++-- 38 files changed, 118 insertions(+), 8 deletions(-) diff --git a/Marlin/Conditionals_post.h b/Marlin/Conditionals_post.h index e3878ecb9..ca38296b3 100644 --- a/Marlin/Conditionals_post.h +++ b/Marlin/Conditionals_post.h @@ -89,6 +89,13 @@ #define IS_KINEMATIC (ENABLED(DELTA) || IS_SCARA) #define IS_CARTESIAN !IS_KINEMATIC + /** + * No adjustable bed on non-cartesians + */ + #if IS_KINEMATIC + #undef LEVEL_BED_CORNERS + #endif + /** * SCARA cannot use SLOWDOWN and requires QUICKHOME */ diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 12d394fc3..340f67dc8 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -940,6 +940,7 @@ #if ENABLED(LCD_BED_LEVELING) #define MBL_Z_STEP 0.025 // Step size while manually probing Z axis. #define LCD_PROBE_Z_RANGE 4 // Z Range centered on Z_MIN_POS for LCD Z adjustment + #define LEVEL_BED_CORNERS // Add an option to move between corners #endif /** diff --git a/Marlin/example_configurations/AlephObjects/TAZ4/Configuration.h b/Marlin/example_configurations/AlephObjects/TAZ4/Configuration.h index ce9250eb9..c7ddc5163 100644 --- a/Marlin/example_configurations/AlephObjects/TAZ4/Configuration.h +++ b/Marlin/example_configurations/AlephObjects/TAZ4/Configuration.h @@ -960,6 +960,7 @@ #if ENABLED(LCD_BED_LEVELING) #define MBL_Z_STEP 0.025 // Step size while manually probing Z axis. #define LCD_PROBE_Z_RANGE 4 // Z Range centered on Z_MIN_POS for LCD Z adjustment + #define LEVEL_BED_CORNERS // Add an option to move between corners #endif /** diff --git a/Marlin/example_configurations/AliExpress/CL-260/Configuration.h b/Marlin/example_configurations/AliExpress/CL-260/Configuration.h index 5cbd95adf..097a78b10 100644 --- a/Marlin/example_configurations/AliExpress/CL-260/Configuration.h +++ b/Marlin/example_configurations/AliExpress/CL-260/Configuration.h @@ -940,6 +940,7 @@ #if ENABLED(LCD_BED_LEVELING) #define MBL_Z_STEP 0.025 // Step size while manually probing Z axis. #define LCD_PROBE_Z_RANGE 4 // Z Range centered on Z_MIN_POS for LCD Z adjustment + #define LEVEL_BED_CORNERS // Add an option to move between corners #endif /** diff --git a/Marlin/example_configurations/Anet/A6/Configuration.h b/Marlin/example_configurations/Anet/A6/Configuration.h index 319826393..f94d783fa 100644 --- a/Marlin/example_configurations/Anet/A6/Configuration.h +++ b/Marlin/example_configurations/Anet/A6/Configuration.h @@ -1083,6 +1083,7 @@ #if ENABLED(LCD_BED_LEVELING) #define MBL_Z_STEP 0.025 // Step size while manually probing Z axis. #define LCD_PROBE_Z_RANGE 4 // Z Range centered on Z_MIN_POS for LCD Z adjustment + #define LEVEL_BED_CORNERS // Add an option to move between corners #endif /** diff --git a/Marlin/example_configurations/Anet/A8/Configuration.h b/Marlin/example_configurations/Anet/A8/Configuration.h index 537a90468..0d03b6301 100644 --- a/Marlin/example_configurations/Anet/A8/Configuration.h +++ b/Marlin/example_configurations/Anet/A8/Configuration.h @@ -946,6 +946,7 @@ #if ENABLED(LCD_BED_LEVELING) #define MBL_Z_STEP 0.025 // Step size while manually probing Z axis. #define LCD_PROBE_Z_RANGE 4 // Z Range centered on Z_MIN_POS for LCD Z adjustment + #define LEVEL_BED_CORNERS // Add an option to move between corners #endif /** diff --git a/Marlin/example_configurations/BQ/Hephestos/Configuration.h b/Marlin/example_configurations/BQ/Hephestos/Configuration.h index fd956dcdf..c544996bc 100644 --- a/Marlin/example_configurations/BQ/Hephestos/Configuration.h +++ b/Marlin/example_configurations/BQ/Hephestos/Configuration.h @@ -931,6 +931,7 @@ #if ENABLED(LCD_BED_LEVELING) #define MBL_Z_STEP 0.025 // Step size while manually probing Z axis. #define LCD_PROBE_Z_RANGE 4 // Z Range centered on Z_MIN_POS for LCD Z adjustment + #define LEVEL_BED_CORNERS // Add an option to move between corners #endif /** diff --git a/Marlin/example_configurations/BQ/Hephestos_2/Configuration.h b/Marlin/example_configurations/BQ/Hephestos_2/Configuration.h index fdba13b24..b4d0bb45f 100644 --- a/Marlin/example_configurations/BQ/Hephestos_2/Configuration.h +++ b/Marlin/example_configurations/BQ/Hephestos_2/Configuration.h @@ -941,6 +941,7 @@ #if ENABLED(LCD_BED_LEVELING) #define MBL_Z_STEP 0.025 // Step size while manually probing Z axis. #define LCD_PROBE_Z_RANGE 4 // Z Range centered on Z_MIN_POS for LCD Z adjustment + #define LEVEL_BED_CORNERS // Add an option to move between corners #endif /** diff --git a/Marlin/example_configurations/BQ/WITBOX/Configuration.h b/Marlin/example_configurations/BQ/WITBOX/Configuration.h index b8fbc1266..be954db5f 100644 --- a/Marlin/example_configurations/BQ/WITBOX/Configuration.h +++ b/Marlin/example_configurations/BQ/WITBOX/Configuration.h @@ -931,6 +931,7 @@ #if ENABLED(LCD_BED_LEVELING) #define MBL_Z_STEP 0.025 // Step size while manually probing Z axis. #define LCD_PROBE_Z_RANGE 4 // Z Range centered on Z_MIN_POS for LCD Z adjustment + #define LEVEL_BED_CORNERS // Add an option to move between corners #endif /** diff --git a/Marlin/example_configurations/Cartesio/Configuration.h b/Marlin/example_configurations/Cartesio/Configuration.h index 9360232d6..6e59b16a6 100644 --- a/Marlin/example_configurations/Cartesio/Configuration.h +++ b/Marlin/example_configurations/Cartesio/Configuration.h @@ -939,6 +939,7 @@ #if ENABLED(LCD_BED_LEVELING) #define MBL_Z_STEP 0.025 // Step size while manually probing Z axis. #define LCD_PROBE_Z_RANGE 4 // Z Range centered on Z_MIN_POS for LCD Z adjustment + #define LEVEL_BED_CORNERS // Add an option to move between corners #endif /** diff --git a/Marlin/example_configurations/Creality/CR-10/Configuration.h b/Marlin/example_configurations/Creality/CR-10/Configuration.h index 53e703b81..a35a6be4e 100644 --- a/Marlin/example_configurations/Creality/CR-10/Configuration.h +++ b/Marlin/example_configurations/Creality/CR-10/Configuration.h @@ -950,6 +950,7 @@ #if ENABLED(LCD_BED_LEVELING) #define MBL_Z_STEP 0.025 // Step size while manually probing Z axis. #define LCD_PROBE_Z_RANGE 4 // Z Range centered on Z_MIN_POS for LCD Z adjustment + #define LEVEL_BED_CORNERS // Add an option to move between corners #endif /** diff --git a/Marlin/example_configurations/Felix/Configuration.h b/Marlin/example_configurations/Felix/Configuration.h index 5b99d6dba..b916aa985 100644 --- a/Marlin/example_configurations/Felix/Configuration.h +++ b/Marlin/example_configurations/Felix/Configuration.h @@ -922,6 +922,7 @@ #if ENABLED(LCD_BED_LEVELING) #define MBL_Z_STEP 0.025 // Step size while manually probing Z axis. #define LCD_PROBE_Z_RANGE 4 // Z Range centered on Z_MIN_POS for LCD Z adjustment + #define LEVEL_BED_CORNERS // Add an option to move between corners #endif /** diff --git a/Marlin/example_configurations/Felix/DUAL/Configuration.h b/Marlin/example_configurations/Felix/DUAL/Configuration.h index eeaaf0e7f..dc122e877 100644 --- a/Marlin/example_configurations/Felix/DUAL/Configuration.h +++ b/Marlin/example_configurations/Felix/DUAL/Configuration.h @@ -922,6 +922,7 @@ #if ENABLED(LCD_BED_LEVELING) #define MBL_Z_STEP 0.025 // Step size while manually probing Z axis. #define LCD_PROBE_Z_RANGE 4 // Z Range centered on Z_MIN_POS for LCD Z adjustment + #define LEVEL_BED_CORNERS // Add an option to move between corners #endif /** diff --git a/Marlin/example_configurations/Folger Tech/i3-2020/Configuration.h b/Marlin/example_configurations/Folger Tech/i3-2020/Configuration.h index b0a875840..8fac72668 100644 --- a/Marlin/example_configurations/Folger Tech/i3-2020/Configuration.h +++ b/Marlin/example_configurations/Folger Tech/i3-2020/Configuration.h @@ -945,6 +945,7 @@ #if ENABLED(LCD_BED_LEVELING) #define MBL_Z_STEP 0.025 // Step size while manually probing Z axis. #define LCD_PROBE_Z_RANGE 4 // Z Range centered on Z_MIN_POS for LCD Z adjustment + #define LEVEL_BED_CORNERS // Add an option to move between corners #endif /** diff --git a/Marlin/example_configurations/Geeetech/GT2560/Configuration.h b/Marlin/example_configurations/Geeetech/GT2560/Configuration.h index 6cbc46bc0..c896359ff 100644 --- a/Marlin/example_configurations/Geeetech/GT2560/Configuration.h +++ b/Marlin/example_configurations/Geeetech/GT2560/Configuration.h @@ -955,6 +955,7 @@ #if ENABLED(LCD_BED_LEVELING) #define MBL_Z_STEP 0.025 // Step size while manually probing Z axis. #define LCD_PROBE_Z_RANGE 4 // Z Range centered on Z_MIN_POS for LCD Z adjustment + #define LEVEL_BED_CORNERS // Add an option to move between corners #endif /** diff --git a/Marlin/example_configurations/Geeetech/I3_Pro_X-GT2560/Configuration.h b/Marlin/example_configurations/Geeetech/I3_Pro_X-GT2560/Configuration.h index d7e024dce..f44de66dd 100644 --- a/Marlin/example_configurations/Geeetech/I3_Pro_X-GT2560/Configuration.h +++ b/Marlin/example_configurations/Geeetech/I3_Pro_X-GT2560/Configuration.h @@ -940,6 +940,7 @@ #if ENABLED(LCD_BED_LEVELING) #define MBL_Z_STEP 0.025 // Step size while manually probing Z axis. #define LCD_PROBE_Z_RANGE 4 // Z Range centered on Z_MIN_POS for LCD Z adjustment + #define LEVEL_BED_CORNERS // Add an option to move between corners #endif /** diff --git a/Marlin/example_configurations/Infitary/i3-M508/Configuration.h b/Marlin/example_configurations/Infitary/i3-M508/Configuration.h index 872870a76..5f214be3c 100644 --- a/Marlin/example_configurations/Infitary/i3-M508/Configuration.h +++ b/Marlin/example_configurations/Infitary/i3-M508/Configuration.h @@ -944,6 +944,7 @@ #if ENABLED(LCD_BED_LEVELING) #define MBL_Z_STEP 0.025 // Step size while manually probing Z axis. #define LCD_PROBE_Z_RANGE 4 // Z Range centered on Z_MIN_POS for LCD Z adjustment + #define LEVEL_BED_CORNERS // Add an option to move between corners #endif /** diff --git a/Marlin/example_configurations/Malyan/M150/Configuration.h b/Marlin/example_configurations/Malyan/M150/Configuration.h index 501738266..63eb4a3de 100644 --- a/Marlin/example_configurations/Malyan/M150/Configuration.h +++ b/Marlin/example_configurations/Malyan/M150/Configuration.h @@ -968,6 +968,7 @@ #if ENABLED(LCD_BED_LEVELING) #define MBL_Z_STEP 0.025 // Step size while manually probing Z axis. #define LCD_PROBE_Z_RANGE 4 // Z Range centered on Z_MIN_POS for LCD Z adjustment + #define LEVEL_BED_CORNERS // Add an option to move between corners #endif /** diff --git a/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h b/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h index 0f575a8fc..c52f0a76b 100644 --- a/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h +++ b/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h @@ -940,6 +940,7 @@ #if ENABLED(LCD_BED_LEVELING) #define MBL_Z_STEP 0.025 // Step size while manually probing Z axis. #define LCD_PROBE_Z_RANGE 4 // Z Range centered on Z_MIN_POS for LCD Z adjustment + #define LEVEL_BED_CORNERS // Add an option to move between corners #endif /** diff --git a/Marlin/example_configurations/RigidBot/Configuration.h b/Marlin/example_configurations/RigidBot/Configuration.h index ea744e8e8..98df154af 100644 --- a/Marlin/example_configurations/RigidBot/Configuration.h +++ b/Marlin/example_configurations/RigidBot/Configuration.h @@ -938,6 +938,7 @@ #if ENABLED(LCD_BED_LEVELING) #define MBL_Z_STEP 0.025 // Step size while manually probing Z axis. #define LCD_PROBE_Z_RANGE 4 // Z Range centered on Z_MIN_POS for LCD Z adjustment + #define LEVEL_BED_CORNERS // Add an option to move between corners #endif /** diff --git a/Marlin/example_configurations/SCARA/Configuration.h b/Marlin/example_configurations/SCARA/Configuration.h index aa5dcdac6..b9b67a3a7 100644 --- a/Marlin/example_configurations/SCARA/Configuration.h +++ b/Marlin/example_configurations/SCARA/Configuration.h @@ -952,6 +952,7 @@ #if ENABLED(LCD_BED_LEVELING) #define MBL_Z_STEP 0.025 // Step size while manually probing Z axis. #define LCD_PROBE_Z_RANGE 4 // Z Range centered on Z_MIN_POS for LCD Z adjustment + #define LEVEL_BED_CORNERS // Add an option to move between corners #endif /** diff --git a/Marlin/example_configurations/TinyBoy2/Configuration.h b/Marlin/example_configurations/TinyBoy2/Configuration.h index 480ba0a7a..e7dae6db4 100644 --- a/Marlin/example_configurations/TinyBoy2/Configuration.h +++ b/Marlin/example_configurations/TinyBoy2/Configuration.h @@ -996,6 +996,7 @@ #if ENABLED(LCD_BED_LEVELING) #define MBL_Z_STEP 0.025 // Step size while manually probing Z axis. #define LCD_PROBE_Z_RANGE 4 // Z Range centered on Z_MIN_POS for LCD Z adjustment + #define LEVEL_BED_CORNERS // Add an option to move between corners #endif /** diff --git a/Marlin/example_configurations/Velleman/K8200/Configuration.h b/Marlin/example_configurations/Velleman/K8200/Configuration.h index 959713d3d..2226b058d 100644 --- a/Marlin/example_configurations/Velleman/K8200/Configuration.h +++ b/Marlin/example_configurations/Velleman/K8200/Configuration.h @@ -969,6 +969,7 @@ #if ENABLED(LCD_BED_LEVELING) #define MBL_Z_STEP 0.025 // Step size while manually probing Z axis. #define LCD_PROBE_Z_RANGE 4 // Z Range centered on Z_MIN_POS for LCD Z adjustment + #define LEVEL_BED_CORNERS // Add an option to move between corners #endif /** diff --git a/Marlin/example_configurations/Velleman/K8400/Configuration.h b/Marlin/example_configurations/Velleman/K8400/Configuration.h index 48ed7f53f..4fd5dd8f4 100644 --- a/Marlin/example_configurations/Velleman/K8400/Configuration.h +++ b/Marlin/example_configurations/Velleman/K8400/Configuration.h @@ -940,6 +940,7 @@ #if ENABLED(LCD_BED_LEVELING) #define MBL_Z_STEP 0.025 // Step size while manually probing Z axis. #define LCD_PROBE_Z_RANGE 4 // Z Range centered on Z_MIN_POS for LCD Z adjustment + #define LEVEL_BED_CORNERS // Add an option to move between corners #endif /** diff --git a/Marlin/example_configurations/Velleman/K8400/Dual-head/Configuration.h b/Marlin/example_configurations/Velleman/K8400/Dual-head/Configuration.h index 1c24b7217..ad15c2cbc 100644 --- a/Marlin/example_configurations/Velleman/K8400/Dual-head/Configuration.h +++ b/Marlin/example_configurations/Velleman/K8400/Dual-head/Configuration.h @@ -940,6 +940,7 @@ #if ENABLED(LCD_BED_LEVELING) #define MBL_Z_STEP 0.025 // Step size while manually probing Z axis. #define LCD_PROBE_Z_RANGE 4 // Z Range centered on Z_MIN_POS for LCD Z adjustment + #define LEVEL_BED_CORNERS // Add an option to move between corners #endif /** diff --git a/Marlin/example_configurations/adafruit/ST7565/Configuration.h b/Marlin/example_configurations/adafruit/ST7565/Configuration.h index 4c99ee2f1..698febfef 100644 --- a/Marlin/example_configurations/adafruit/ST7565/Configuration.h +++ b/Marlin/example_configurations/adafruit/ST7565/Configuration.h @@ -940,6 +940,7 @@ #if ENABLED(LCD_BED_LEVELING) #define MBL_Z_STEP 0.025 // Step size while manually probing Z axis. #define LCD_PROBE_Z_RANGE 4 // Z Range centered on Z_MIN_POS for LCD Z adjustment + #define LEVEL_BED_CORNERS // Add an option to move between corners #endif /** diff --git a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h index 643d2e2ee..52115928b 100644 --- a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h +++ b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h @@ -1068,6 +1068,7 @@ #if ENABLED(LCD_BED_LEVELING) #define MBL_Z_STEP 0.025 // Step size while manually probing Z axis. #define LCD_PROBE_Z_RANGE 4 // Z Range centered on Z_MIN_POS for LCD Z adjustment + #define LEVEL_BED_CORNERS // Add an option to move between corners #endif /** diff --git a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h index 82de18e31..66f8d835d 100644 --- a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h +++ b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h @@ -1062,6 +1062,7 @@ #if ENABLED(LCD_BED_LEVELING) #define MBL_Z_STEP 0.025 // Step size while manually probing Z axis. #define LCD_PROBE_Z_RANGE 4 // Z Range centered on Z_MIN_POS for LCD Z adjustment + #define LEVEL_BED_CORNERS // Add an option to move between corners #endif /** diff --git a/Marlin/example_configurations/delta/generic/Configuration.h b/Marlin/example_configurations/delta/generic/Configuration.h index ce2b8ceec..5b3aff5ad 100644 --- a/Marlin/example_configurations/delta/generic/Configuration.h +++ b/Marlin/example_configurations/delta/generic/Configuration.h @@ -1057,6 +1057,7 @@ #if ENABLED(LCD_BED_LEVELING) #define MBL_Z_STEP 0.025 // Step size while manually probing Z axis. #define LCD_PROBE_Z_RANGE 4 // Z Range centered on Z_MIN_POS for LCD Z adjustment + #define LEVEL_BED_CORNERS // Add an option to move between corners #endif /** diff --git a/Marlin/example_configurations/delta/kossel_mini/Configuration.h b/Marlin/example_configurations/delta/kossel_mini/Configuration.h index 75c03f697..e912cc439 100644 --- a/Marlin/example_configurations/delta/kossel_mini/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_mini/Configuration.h @@ -1060,6 +1060,7 @@ #if ENABLED(LCD_BED_LEVELING) #define MBL_Z_STEP 0.025 // Step size while manually probing Z axis. #define LCD_PROBE_Z_RANGE 4 // Z Range centered on Z_MIN_POS for LCD Z adjustment + #define LEVEL_BED_CORNERS // Add an option to move between corners #endif /** diff --git a/Marlin/example_configurations/delta/kossel_pro/Configuration.h b/Marlin/example_configurations/delta/kossel_pro/Configuration.h index 259c923d0..e1d33834d 100644 --- a/Marlin/example_configurations/delta/kossel_pro/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_pro/Configuration.h @@ -1060,6 +1060,7 @@ #if ENABLED(LCD_BED_LEVELING) #define MBL_Z_STEP 0.025 // Step size while manually probing Z axis. #define LCD_PROBE_Z_RANGE 4 // Z Range centered on Z_MIN_POS for LCD Z adjustment + #define LEVEL_BED_CORNERS // Add an option to move between corners #endif /** diff --git a/Marlin/example_configurations/delta/kossel_xl/Configuration.h b/Marlin/example_configurations/delta/kossel_xl/Configuration.h index 4231be068..a4528e4ab 100644 --- a/Marlin/example_configurations/delta/kossel_xl/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_xl/Configuration.h @@ -1069,6 +1069,7 @@ #if ENABLED(LCD_BED_LEVELING) #define MBL_Z_STEP 0.025 // Step size while manually probing Z axis. #define LCD_PROBE_Z_RANGE 4 // Z Range centered on Z_MIN_POS for LCD Z adjustment + #define LEVEL_BED_CORNERS // Add an option to move between corners #endif /** diff --git a/Marlin/example_configurations/gCreate/gMax1.5+/Configuration.h b/Marlin/example_configurations/gCreate/gMax1.5+/Configuration.h index a870e8da8..f2b340750 100644 --- a/Marlin/example_configurations/gCreate/gMax1.5+/Configuration.h +++ b/Marlin/example_configurations/gCreate/gMax1.5+/Configuration.h @@ -954,6 +954,7 @@ #if ENABLED(LCD_BED_LEVELING) #define MBL_Z_STEP 0.025 // Step size while manually probing Z axis. #define LCD_PROBE_Z_RANGE 4 // Z Range centered on Z_MIN_POS for LCD Z adjustment + #define LEVEL_BED_CORNERS // Add an option to move between corners #endif /** diff --git a/Marlin/example_configurations/makibox/Configuration.h b/Marlin/example_configurations/makibox/Configuration.h index 02f33df03..3533805ee 100644 --- a/Marlin/example_configurations/makibox/Configuration.h +++ b/Marlin/example_configurations/makibox/Configuration.h @@ -943,6 +943,7 @@ #if ENABLED(LCD_BED_LEVELING) #define MBL_Z_STEP 0.025 // Step size while manually probing Z axis. #define LCD_PROBE_Z_RANGE 4 // Z Range centered on Z_MIN_POS for LCD Z adjustment + #define LEVEL_BED_CORNERS // Add an option to move between corners #endif /** diff --git a/Marlin/example_configurations/tvrrug/Round2/Configuration.h b/Marlin/example_configurations/tvrrug/Round2/Configuration.h index 8212beb07..00095874d 100644 --- a/Marlin/example_configurations/tvrrug/Round2/Configuration.h +++ b/Marlin/example_configurations/tvrrug/Round2/Configuration.h @@ -935,6 +935,7 @@ #if ENABLED(LCD_BED_LEVELING) #define MBL_Z_STEP 0.025 // Step size while manually probing Z axis. #define LCD_PROBE_Z_RANGE 4 // Z Range centered on Z_MIN_POS for LCD Z adjustment + #define LEVEL_BED_CORNERS // Add an option to move between corners #endif /** diff --git a/Marlin/example_configurations/wt150/Configuration.h b/Marlin/example_configurations/wt150/Configuration.h index 2c468a942..d5e3cc9f4 100644 --- a/Marlin/example_configurations/wt150/Configuration.h +++ b/Marlin/example_configurations/wt150/Configuration.h @@ -945,6 +945,7 @@ #if ENABLED(LCD_BED_LEVELING) #define MBL_Z_STEP 0.025 // Step size while manually probing Z axis. #define LCD_PROBE_Z_RANGE 4 // Z Range centered on Z_MIN_POS for LCD Z adjustment + #define LEVEL_BED_CORNERS // Add an option to move between corners #endif /** diff --git a/Marlin/language_en.h b/Marlin/language_en.h index b702ecdbb..5e878ca76 100644 --- a/Marlin/language_en.h +++ b/Marlin/language_en.h @@ -156,6 +156,12 @@ #ifndef MSG_LEVEL_BED #define MSG_LEVEL_BED _UxGT("Level bed") #endif +#ifndef MSG_LEVEL_CORNERS + #define MSG_LEVEL_CORNERS _UxGT("Level corners") +#endif +#ifndef MSG_NEXT_CORNER + #define MSG_NEXT_CORNER _UxGT("Next corner") +#endif #ifndef MSG_EDITING_STOPPED #define MSG_EDITING_STOPPED _UxGT("Mesh Editing Stopped") #endif diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index c29c661a3..3176e4374 100644 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -546,6 +546,11 @@ uint16_t max_display_update_time = 0; lcd_return_to_status(); } + void lcd_goto_previous_menu_no_defer() { + defer_return_to_status = false; + lcd_goto_previous_menu(); + } + #endif // ULTIPANEL /** @@ -971,7 +976,7 @@ void kill_screen(const char* lcd_msg) { #if ENABLED(BABYSTEPPING) void _lcd_babystep(const AxisEnum axis, const char* msg) { - if (lcd_clicked) { defer_return_to_status = false; return lcd_goto_previous_menu(); } + if (lcd_clicked) { return lcd_goto_previous_menu_no_defer(); } ENCODER_DIRECTION_NORMAL(); if (encoderPosition) { const int16_t babystep_increment = (int32_t)encoderPosition * (BABYSTEP_MULTIPLICATOR); @@ -994,7 +999,7 @@ void kill_screen(const char* lcd_msg) { #if ENABLED(BABYSTEP_ZPROBE_OFFSET) void lcd_babystep_zoffset() { - if (lcd_clicked) { defer_return_to_status = false; return lcd_goto_previous_menu(); } + if (lcd_clicked) { return lcd_goto_previous_menu_no_defer(); } defer_return_to_status = true; ENCODER_DIRECTION_NORMAL(); if (encoderPosition) { @@ -1545,7 +1550,52 @@ void kill_screen(const char* lcd_msg) { static void lcd_refresh_zprobe_zoffset() { refresh_zprobe_zoffset(); } #endif -#if ENABLED(LCD_BED_LEVELING) + + #if ENABLED(LEVEL_BED_CORNERS) + + /** + * Level corners, starting in the front-left corner. + */ + static int8_t bed_corner; + void _lcd_goto_next_corner() { + line_to_z(LOGICAL_Z_POSITION(4.0)); + switch (bed_corner) { + case 0: + current_position[X_AXIS] = X_MIN_BED + 10; + current_position[Y_AXIS] = Y_MIN_BED + 10; + break; + case 1: + current_position[X_AXIS] = X_MAX_BED - 10; + break; + case 2: + current_position[Y_AXIS] = Y_MAX_BED - 10; + break; + case 3: + current_position[X_AXIS] = X_MIN_BED + 10; + break; + } + planner.buffer_line_kinematic(current_position, MMM_TO_MMS(manual_feedrate_mm_m[X_AXIS]), active_extruder); + line_to_z(LOGICAL_Z_POSITION(0.0)); + if (++bed_corner > 3) bed_corner = 0; + } + + void _lcd_corner_submenu() { + START_MENU(); + MENU_ITEM(function, MSG_NEXT_CORNER, _lcd_goto_next_corner); + MENU_ITEM(function, MSG_BACK, lcd_goto_previous_menu_no_defer); + END_MENU(); + } + + void _lcd_level_bed_corners() { + defer_return_to_status = true; + lcd_goto_screen(_lcd_corner_submenu); + bed_corner = 0; + _lcd_goto_next_corner(); + } + + #endif // LEVEL_BED_CORNERS + + #if ENABLED(LCD_BED_LEVELING) /** * @@ -1788,10 +1838,11 @@ void kill_screen(const char* lcd_msg) { * << Prepare * Auto Home (if homing needed) * Leveling On/Off (if data exists, and homed) - * Level Bed * Fade Height: --- (Req: ENABLE_LEVELING_FADE_HEIGHT) * Mesh Z Offset: --- (Req: MESH_BED_LEVELING) * Z Probe Offset: --- (Req: HAS_BED_PROBE, Opt: BABYSTEP_ZPROBE_OFFSET) + * Level Bed > + * Level Corners > (if homed) * Load Settings (Req: EEPROM_SETTINGS) * Save Settings (Req: EEPROM_SETTINGS) */ @@ -1826,6 +1877,12 @@ void kill_screen(const char* lcd_msg) { MENU_ITEM(submenu, MSG_LEVEL_BED, _lcd_level_bed_continue); + #if ENABLED(LEVEL_BED_CORNERS) + // Move to the next corner for leveling + if (axis_homed[X_AXIS] && axis_homed[Y_AXIS] && axis_homed[Z_AXIS]) + MENU_ITEM(function, MSG_LEVEL_CORNERS, _lcd_level_bed_corners); + #endif + #if ENABLED(EEPROM_SETTINGS) MENU_ITEM(function, MSG_LOAD_EEPROM, lcd_load_settings); MENU_ITEM(function, MSG_STORE_EEPROM, lcd_store_settings); @@ -2404,8 +2461,14 @@ void kill_screen(const char* lcd_msg) { if (!g29_in_progress) #endif MENU_ITEM(submenu, MSG_BED_LEVELING, lcd_bed_leveling); - #elif PLANNER_LEVELING - MENU_ITEM(gcode, MSG_BED_LEVELING, PSTR("G28\nG29")); + #else + #if PLANNER_LEVELING + MENU_ITEM(gcode, MSG_BED_LEVELING, PSTR("G28\nG29")); + #endif + #if ENABLED(LEVEL_BED_CORNERS) + if (axis_homed[X_AXIS] && axis_homed[Y_AXIS] && axis_homed[Z_AXIS]) + MENU_ITEM(function, MSG_LEVEL_CORNERS, _lcd_level_bed_corners); + #endif #endif #if HAS_M206_COMMAND @@ -2538,8 +2601,7 @@ void kill_screen(const char* lcd_msg) { wait_for_user = true; while (wait_for_user) idle(); KEEPALIVE_STATE(IN_HANDLER); - defer_return_to_status = false; - lcd_goto_previous_menu(); + lcd_goto_previous_menu_no_defer(); return current_position[Z_AXIS]; } From b33739d49334327c65545760aadde6e94c79109b Mon Sep 17 00:00:00 2001 From: Tannoo Date: Wed, 16 Aug 2017 08:49:04 -0600 Subject: [PATCH 092/112] UBL_Language_Update (#7520) * UBL_Language_Update Translatable strings * Use slightly better wording... * Use slightly better wording... --- Marlin/language_en.h | 9 +++++++++ Marlin/ultralcd.cpp | 8 ++++---- 2 files changed, 13 insertions(+), 4 deletions(-) diff --git a/Marlin/language_en.h b/Marlin/language_en.h index 52d9aa49e..05509fb9c 100644 --- a/Marlin/language_en.h +++ b/Marlin/language_en.h @@ -328,6 +328,15 @@ #ifndef MSG_UBL_SAVE_MESH #define MSG_UBL_SAVE_MESH _UxGT("Save Bed Mesh") #endif +#ifndef MSG_MESH_LOADED + #define MSG_MESH_LOADED _UxGT("Mesh %i loaded") +#endif +#ifndef MSG_MESH_SAVED + #define MSG_MESH_SAVED _UxGT("Mesh %i saved") +#endif +#ifndef MSG_NO_STORAGE + #define MSG_NO_STORAGE _UxGT("No storage") +#endif #ifndef MSG_UBL_SAVE_ERROR #define MSG_UBL_SAVE_ERROR _UxGT("Err: UBL Save") #endif diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index c29c661a3..352d68aa4 100644 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -2121,7 +2121,7 @@ void kill_screen(const char* lcd_msg) { char UBL_LCD_GCODE[25]; sprintf_P(UBL_LCD_GCODE, PSTR("G29 L%i"), ubl_storage_slot); enqueue_and_echo_command(UBL_LCD_GCODE); - sprintf_P(UBL_LCD_GCODE, PSTR("M117 Map %i loaded."), ubl_storage_slot); + sprintf_P(UBL_LCD_GCODE, PSTR("M117 " MSG_MESH_LOADED "."), ubl_storage_slot); enqueue_and_echo_command(UBL_LCD_GCODE); } @@ -2132,7 +2132,7 @@ void kill_screen(const char* lcd_msg) { char UBL_LCD_GCODE[25]; sprintf_P(UBL_LCD_GCODE, PSTR("G29 S%i"), ubl_storage_slot); enqueue_and_echo_command(UBL_LCD_GCODE); - sprintf_P(UBL_LCD_GCODE, PSTR("M117 Map %i saved."), ubl_storage_slot); + sprintf_P(UBL_LCD_GCODE, PSTR("M117 " MSG_MESH_SAVED "."), ubl_storage_slot); enqueue_and_echo_command(UBL_LCD_GCODE); } @@ -2149,8 +2149,8 @@ void kill_screen(const char* lcd_msg) { START_MENU(); MENU_BACK(MSG_UBL_LEVEL_BED); if (!WITHIN(ubl_storage_slot, 0, a - 1)) { - STATIC_ITEM("No storage"); - STATIC_ITEM("Initialize EEPROM"); + STATIC_ITEM(MSG_NO_STORAGE); + STATIC_ITEM(MSG_INIT_EEPROM); } else { MENU_ITEM_EDIT(int3, MSG_UBL_STORAGE_SLOT, &ubl_storage_slot, 0, a - 1); From 5fa61c0ad32b086bc52f9847e5c85d07d16e963f Mon Sep 17 00:00:00 2001 From: MTrab Date: Sun, 13 Aug 2017 12:55:11 +0200 Subject: [PATCH 093/112] Add Anet 1.0 to Platformio.ini Added env:anet10 to platformio.ini for easy compile and upload to this board --- Marlin/pins_GT2560_REV_A.h | 14 +++++++------- Marlin/pins_GT2560_REV_A_PLUS.h | 6 +++--- platformio.ini | 7 +++++++ 3 files changed, 17 insertions(+), 10 deletions(-) diff --git a/Marlin/pins_GT2560_REV_A.h b/Marlin/pins_GT2560_REV_A.h index cb85c1223..0c420cfaa 100644 --- a/Marlin/pins_GT2560_REV_A.h +++ b/Marlin/pins_GT2560_REV_A.h @@ -19,13 +19,13 @@ * along with this program. If not, see . * */ - + /** - * Geeetech GT2560 Revision A board pin assignments, based on the work of - * George Robles (https://georges3dprinters.com) and + * Geeetech GT2560 Revision A board pin assignments, based on the work of + * George Robles (https://georges3dprinters.com) and * Richard Smith - */ - + */ + #if !defined(__AVR_ATmega1280__) && !defined(__AVR_ATmega2560__) #error "Oops! Make sure you have 'Arduino Mega' selected from the 'Tools -> Boards' menu." #endif @@ -96,7 +96,7 @@ #define BEEPER_PIN 18 - #if ENABLED(NEWPANEL) + #if ENABLED(NEWPANEL) #define LCD_PINS_RS 20 #define LCD_PINS_ENABLE 17 @@ -109,7 +109,7 @@ #define BTN_EN1 42 #define BTN_EN2 40 #define BTN_ENC 19 - + #define SD_DETECT_PIN 38 #else // !NEWPANEL diff --git a/Marlin/pins_GT2560_REV_A_PLUS.h b/Marlin/pins_GT2560_REV_A_PLUS.h index a99a39da8..b722c04fd 100644 --- a/Marlin/pins_GT2560_REV_A_PLUS.h +++ b/Marlin/pins_GT2560_REV_A_PLUS.h @@ -19,13 +19,13 @@ * along with this program. If not, see . * */ - + /** * Geeetech GT2560 Revision A+ board pin assignments - */ + */ #include "pins_GT2560_REV_A.h" #define BOARD_NAME "GT2560 Rev.A+" -#define SERVO0_PIN 11 +#define SERVO0_PIN 11 diff --git a/platformio.ini b/platformio.ini index 50137628e..3b05bc566 100644 --- a/platformio.ini +++ b/platformio.ini @@ -67,3 +67,10 @@ board = reprap_rambo build_flags = -I $BUILDSRC_DIR board_f_cpu = 16000000L lib_deps = ${common.lib_deps} + +[env:anet10] +platform = atmelavr +framework = arduino +board = sanguino_atmega1284p +upload_speed = 57600 +lib_deps = ${common.lib_deps} From 6772e33ef6ca0b26a16685e3cae1c561990733df Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 16 Aug 2017 00:59:30 -0500 Subject: [PATCH 094/112] Use [XY]_CENTER for error correction Followup to #7512 --- Marlin/ubl_G29.cpp | 8 +++----- 1 file changed, 3 insertions(+), 5 deletions(-) diff --git a/Marlin/ubl_G29.cpp b/Marlin/ubl_G29.cpp index 2bdc14a69..4c10c41cf 100644 --- a/Marlin/ubl_G29.cpp +++ b/Marlin/ubl_G29.cpp @@ -1133,11 +1133,9 @@ err_flag = true; } - if (!WITHIN(RAW_X_POSITION(g29_x_pos), X_MIN_BED, X_MAX_BED)) // if X & Y are not valid, use center of the bed values - g29_x_pos = (X_MIN_BED + X_MAX_BED) / 2.0; - - if (!WITHIN(RAW_Y_POSITION(g29_y_pos), Y_MIN_BED, Y_MAX_BED)) // if X & Y are not valid, use center of the bed values - g29_y_pos = (Y_MIN_BED + Y_MAX_BED) / 2.0; + // If X or Y are not valid, use center of the bed values + if (!WITHIN(RAW_X_POSITION(g29_x_pos), X_MIN_BED, X_MAX_BED)) g29_x_pos = LOGICAL_X_POSITION(X_CENTER); + if (!WITHIN(RAW_Y_POSITION(g29_y_pos), Y_MIN_BED, Y_MAX_BED)) g29_y_pos = LOGICAL_Y_POSITION(Y_CENTER); if (err_flag) return UBL_ERR; From 4817b39d9816e6ee11354753f16fcdcf56664536 Mon Sep 17 00:00:00 2001 From: Vben Date: Sun, 13 Aug 2017 23:35:59 +0200 Subject: [PATCH 095/112] Added new feature for AutoParking Extruder (APE) --- Marlin/Conditionals_post.h | 10 + Marlin/Configuration.h | 15 ++ Marlin/Marlin_main.cpp | 191 ++++++++++++++++-- Marlin/SanityCheck.h | 28 +++ Marlin/configuration_store.cpp | 2 +- .../AlephObjects/TAZ4/Configuration.h | 15 ++ .../AliExpress/CL-260/Configuration.h | 15 ++ .../Anet/A6/Configuration.h | 15 ++ .../Anet/A8/Configuration.h | 15 ++ .../BQ/Hephestos/Configuration.h | 15 ++ .../BQ/Hephestos_2/Configuration.h | 15 ++ .../BQ/WITBOX/Configuration.h | 15 ++ .../Cartesio/Configuration.h | 15 ++ .../Creality/CR-10/Configuration.h | 15 ++ .../Felix/Configuration.h | 15 ++ .../Felix/DUAL/Configuration.h | 15 ++ .../Folger Tech/i3-2020/Configuration.h | 15 ++ .../Geeetech/GT2560/Configuration.h | 15 ++ .../Geeetech/I3_Pro_X-GT2560/Configuration.h | 15 ++ .../Infitary/i3-M508/Configuration.h | 15 ++ .../Malyan/M150/Configuration.h | 15 ++ .../RepRapWorld/Megatronics/Configuration.h | 15 ++ .../RigidBot/Configuration.h | 15 ++ .../SCARA/Configuration.h | 15 ++ .../TinyBoy2/Configuration.h | 15 ++ .../Velleman/K8200/Configuration.h | 15 ++ .../Velleman/K8400/Configuration.h | 15 ++ .../Velleman/K8400/Dual-head/Configuration.h | 15 ++ .../adafruit/ST7565/Configuration.h | 15 ++ .../FLSUN/auto_calibrate/Configuration.h | 15 ++ .../delta/FLSUN/kossel_mini/Configuration.h | 15 ++ .../delta/generic/Configuration.h | 15 ++ .../delta/kossel_mini/Configuration.h | 15 ++ .../delta/kossel_pro/Configuration.h | 15 ++ .../delta/kossel_xl/Configuration.h | 15 ++ .../gCreate/gMax1.5+/Configuration.h | 15 ++ .../makibox/Configuration.h | 15 ++ .../tvrrug/Round2/Configuration.h | 15 ++ .../wt150/Configuration.h | 15 ++ 39 files changed, 734 insertions(+), 22 deletions(-) diff --git a/Marlin/Conditionals_post.h b/Marlin/Conditionals_post.h index ca38296b3..a98985373 100644 --- a/Marlin/Conditionals_post.h +++ b/Marlin/Conditionals_post.h @@ -906,4 +906,14 @@ #undef PROBE_MANUALLY #endif + // Parking Extruder + #if ENABLED(PARKING_EXTRUDER) + #ifndef PARKING_EXTRUDER_GRAB_DISTANCE + #define PARKING_EXTRUDER_GRAB_DISTANCE 0 + #endif + #ifndef PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE + #define PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE HIGH + #endif + #endif + #endif // CONDITIONALS_POST_H diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index a1278ff50..66085fbcc 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -175,6 +175,21 @@ //#define HOTEND_OFFSET_Z { 0.0, 0.0 } #endif +/** + * Two separate X-carriages with extruders that connect to a moving part + * via a magnetic docking mechanism. Requires SOL1_PIN and SOL2_PIN. + */ +//#define PARKING_EXTRUDER +#if ENABLED(PARKING_EXTRUDER) + #define PARKING_EXTRUDER_SOLENOIDS_INVERT // If enabled, the solenoid not magnetized with applied voltage + #define PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE LOW // LOW or HIGH pin signal energizes the coil + #define PARKING_EXTRUDER_SOLENOIDS_DELAY 250 // Delay (ms) for magnetic field. No delay if 0 or not defined. + #define PARKING_EXTRUDER_PARKING_X { -78, 184 } // X positions for parking the extruders + #define PARKING_EXTRUDER_GRAB_DISTANCE 1 // mm to move beyond the parking point to grab the extruder + #define PARKING_EXTRUDER_SECURITY_RAISE 5 // Z-raise before parking + #define HOTEND_OFFSET_Z { 0.0, 1.3 } // Z-offsets of the two hotends. The first must be 0. +#endif + /** * "Mixing Extruder" * - Adds a new code, M165, to set the current mix factors. diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index baa1082ef..b25cf0097 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -3494,6 +3494,12 @@ inline void gcode_G0_G1( #endif // ARC_SUPPORT +void dwell(millis_t time) { + refresh_cmd_timeout(); + time += previous_cmd_ms; + while (PENDING(millis(), time)) idle(); +} + /** * G4: Dwell S or P */ @@ -3504,12 +3510,10 @@ inline void gcode_G4() { if (parser.seenval('S')) dwell_ms = parser.value_millis_from_seconds(); // seconds to wait stepper.synchronize(); - refresh_cmd_timeout(); - dwell_ms += previous_cmd_ms; // keep track of when we started waiting if (!lcd_hasstatus()) LCD_MESSAGEPGM(MSG_DWELL); - while (PENDING(millis(), dwell_ms)) idle(); + dwell(dwell_ms); } #if ENABLED(BEZIER_CURVE_SUPPORT) @@ -4083,7 +4087,13 @@ inline void gcode_G28(const bool always_home_all) { // Restore the active tool after homing #if HOTENDS > 1 - tool_change(old_tool_index, 0, true); + tool_change(old_tool_index, 0, + #if ENABLED(PARKING_EXTRUDER) + false // fetch the previous toolhead + #else + true + #endif + ); #endif lcd_refresh(); @@ -6017,16 +6027,10 @@ inline void gcode_G92() { */ // Wait for spindle to come up to speed - inline void delay_for_power_up() { - refresh_cmd_timeout(); - while (PENDING(millis(), SPINDLE_LASER_POWERUP_DELAY + previous_cmd_ms)) idle(); - } + inline void delay_for_power_up() { dwell(SPINDLE_LASER_POWERUP_DELAY); } // Wait for spindle to stop turning - inline void delay_for_power_down() { - refresh_cmd_timeout(); - while (PENDING(millis(), SPINDLE_LASER_POWERDOWN_DELAY + previous_cmd_ms + 1)) idle(); - } + inline void delay_for_power_down() { dwell(SPINDLE_LASER_POWERDOWN_DELAY); } /** * ocr_val_mode() is used for debugging and to get the points needed to compute the RPM vs ocr_val line @@ -8697,7 +8701,7 @@ inline void gcode_M211() { if (parser.seenval('X')) hotend_offset[X_AXIS][target_extruder] = parser.value_linear_units(); if (parser.seenval('Y')) hotend_offset[Y_AXIS][target_extruder] = parser.value_linear_units(); - #if ENABLED(DUAL_X_CARRIAGE) || ENABLED(SWITCHING_NOZZLE) + #if ENABLED(DUAL_X_CARRIAGE) || ENABLED(SWITCHING_NOZZLE) || ENABLED(PARKING_EXTRUDER) if (parser.seenval('Z')) hotend_offset[Z_AXIS][target_extruder] = parser.value_linear_units(); #endif @@ -8708,7 +8712,7 @@ inline void gcode_M211() { SERIAL_ECHO(hotend_offset[X_AXIS][e]); SERIAL_CHAR(','); SERIAL_ECHO(hotend_offset[Y_AXIS][e]); - #if ENABLED(DUAL_X_CARRIAGE) || ENABLED(SWITCHING_NOZZLE) + #if ENABLED(DUAL_X_CARRIAGE) || ENABLED(SWITCHING_NOZZLE) || ENABLED(PARKING_EXTRUDER) SERIAL_CHAR(','); SERIAL_ECHO(hotend_offset[Z_AXIS][e]); #endif @@ -10244,6 +10248,29 @@ inline void invalid_extruder_error(const uint8_t e) { SERIAL_ECHOLN(MSG_INVALID_EXTRUDER); } +#if ENABLED(PARKING_EXTRUDER) + + #if ENABLED(PARKING_EXTRUDER_SOLENOIDS_INVERT) + #define PE_MAGNET_ON_STATE !PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE + #else + #define PE_MAGNET_ON_STATE PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE + #endif + + void pe_set_magnet(const uint8_t extruder_num, const uint8_t state) { + switch (extruder_num) { + case 1: OUT_WRITE(SOL1_PIN, state); break; + default: OUT_WRITE(SOL0_PIN, state); break; + } + #if PARKING_EXTRUDER_SOLENOIDS_DELAY > 0 + dwell(PARKING_EXTRUDER_SOLENOIDS_DELAY); + #endif + } + + inline void pe_activate_magnet(const uint8_t extruder_num) { pe_set_magnet(extruder_num, PE_MAGNET_ON_STATE); } + inline void pe_deactivate_magnet(const uint8_t extruder_num) { pe_set_magnet(extruder_num, !PE_MAGNET_ON_STATE); } + +#endif // PARKING_EXTRUDER + /** * Perform a tool-change, which may result in moving the * previous tool out of the way and the new tool into place. @@ -10271,8 +10298,10 @@ void tool_change(const uint8_t tmp_extruder, const float fr_mm_s/*=0.0*/, bool n if (tmp_extruder != active_extruder) { if (!no_move && axis_unhomed_error()) { - SERIAL_ECHOLNPGM("No move on toolchange"); no_move = true; + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("No move on toolchange"); + #endif } // Save current position to destination, for use later @@ -10382,8 +10411,118 @@ void tool_change(const uint8_t tmp_extruder, const float fr_mm_s/*=0.0*/, bool n #endif // No extra case for HAS_ABL in DUAL_X_CARRIAGE. Does that mean they don't work together? + #else // !DUAL_X_CARRIAGE + #if ENABLED(PARKING_EXTRUDER) // Dual Parking extruder + const float z_diff = hotend_offset[Z_AXIS][active_extruder] - hotend_offset[Z_AXIS][tmp_extruder]; + float z_raise = 0; + if (!no_move) { + + const float parkingposx[] = PARKING_EXTRUDER_PARKING_X, + midpos = ((parkingposx[1] - parkingposx[0])/2) + parkingposx[0] + hotend_offset[X_AXIS][active_extruder], + grabpos = parkingposx[tmp_extruder] + hotend_offset[X_AXIS][active_extruder] + + (tmp_extruder == 0 ? -(PARKING_EXTRUDER_GRAB_DISTANCE) : PARKING_EXTRUDER_GRAB_DISTANCE); + /** + * Steps: + * 1. raise Z-Axis to have enough clearance + * 2. move to park poition of old extruder + * 3. disengage magnetc field, wait for delay + * 4. move near new extruder + * 5. engage magnetic field for new extruder + * 6. move to parking incl. offset of new extruder + * 7. lower Z-Axis + */ + + // STEP 1 + #if ENABLED(DEBUG_LEVELING_FEATURE) + SERIAL_ECHOLNPGM("Starting Autopark"); + if (DEBUGGING(LEVELING)) DEBUG_POS("current position:", current_position); + #endif + z_raise = PARKING_EXTRUDER_SECURITY_RAISE; + current_position[Z_AXIS] += z_raise; + #if ENABLED(DEBUG_LEVELING_FEATURE) + SERIAL_ECHOLNPGM("(1) Raise Z-Axis "); + if (DEBUGGING(LEVELING)) DEBUG_POS("Moving to Raised Z-Position", current_position); + #endif + planner.buffer_line_kinematic(current_position, planner.max_feedrate_mm_s[Z_AXIS], active_extruder); + stepper.synchronize(); + + // STEP 2 + current_position[X_AXIS] = parkingposx[active_extruder] + hotend_offset[X_AXIS][active_extruder]; + #if ENABLED(DEBUG_LEVELING_FEATURE) + SERIAL_ECHOLNPAIR("(2) Park extruder ", active_extruder); + if (DEBUGGING(LEVELING)) DEBUG_POS("Moving ParkPos", current_position); + #endif + planner.buffer_line_kinematic(current_position, planner.max_feedrate_mm_s[X_AXIS], active_extruder); + stepper.synchronize(); + + // STEP 3 + #if ENABLED(DEBUG_LEVELING_FEATURE) + SERIAL_ECHOLNPGM("(3) Disengage magnet "); + #endif + pe_deactivate_magnet(active_extruder); + + // STEP 4 + #if ENABLED(DEBUG_LEVELING_FEATURE) + SERIAL_ECHOLNPGM("(4) Move to position near new extruder"); + #endif + current_position[X_AXIS] += (active_extruder == 0 ? 10 : -10); // move 10mm away from parked extruder + + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (DEBUGGING(LEVELING)) DEBUG_POS("Moving away from parked extruder", current_position); + #endif + planner.buffer_line_kinematic(current_position, planner.max_feedrate_mm_s[X_AXIS], active_extruder); + stepper.synchronize(); + + // STEP 5 + #if ENABLED(DEBUG_LEVELING_FEATURE) + SERIAL_ECHOLNPGM("(5) Engage magnetic field"); + #endif + + #if ENABLED(PARKING_EXTRUDER_SOLENOIDS_INVERT) + pe_activate_magnet(active_extruder); //just save power for inverted magnets + #endif + pe_activate_magnet(tmp_extruder); + + // STEP 6 + current_position[X_AXIS] = grabpos + (tmp_extruder == 0 ? (+10) : (-10)); + planner.buffer_line_kinematic(current_position, planner.max_feedrate_mm_s[X_AXIS], active_extruder); + current_position[X_AXIS] = grabpos; + #if ENABLED(DEBUG_LEVELING_FEATURE) + SERIAL_ECHOLNPAIR("(6) Unpark extruder ", tmp_extruder); + if (DEBUGGING(LEVELING)) DEBUG_POS("Move UnparkPos", current_position); + #endif + planner.buffer_line_kinematic(current_position, planner.max_feedrate_mm_s[X_AXIS]/2, active_extruder); + stepper.synchronize(); + + // Step 7 + current_position[X_AXIS] = midpos - hotend_offset[X_AXIS][tmp_extruder]; + #if ENABLED(DEBUG_LEVELING_FEATURE) + SERIAL_ECHOLNPGM("(7) Move midway between hotends"); + if (DEBUGGING(LEVELING)) DEBUG_POS("Move midway to new extruder", current_position); + #endif + planner.buffer_line_kinematic(current_position, planner.max_feedrate_mm_s[X_AXIS], active_extruder); + stepper.synchronize(); + #if ENABLED(DEBUG_LEVELING_FEATURE) + SERIAL_ECHOLNPGM("Autopark done."); + #endif + } + else { // nomove == true + // Only engage magnetic field for new extruder + pe_activate_magnet(tmp_extruder); + #if ENABLED(PARKING_EXTRUDER_SOLENOIDS_INVERT) + pe_activate_magnet(active_extruder); // Just save power for inverted magnets + #endif + } + current_position[Z_AXIS] -= hotend_offset[Z_AXIS][tmp_extruder] - hotend_offset[Z_AXIS][active_extruder]; // Apply Zoffset + + #if ENABLED(DEBUG_LEVELING_FEATURE) + if (DEBUGGING(LEVELING)) DEBUG_POS("Applying Z-offset", current_position); + #endif + + #endif // dualParking extruder + #if ENABLED(SWITCHING_NOZZLE) #define DONT_SWITCH (SWITCHING_EXTRUDER_SERVO_NR == SWITCHING_NOZZLE_SERVO_NR) // <0 if the new nozzle is higher, >0 if lower. A bigger raise when lower. @@ -10487,7 +10626,7 @@ void tool_change(const uint8_t tmp_extruder, const float fr_mm_s/*=0.0*/, bool n // The newly-selected extruder XY is actually at... current_position[X_AXIS] += xydiff[X_AXIS]; current_position[Y_AXIS] += xydiff[Y_AXIS]; - #if HAS_WORKSPACE_OFFSET || ENABLED(DUAL_X_CARRIAGE) + #if HAS_WORKSPACE_OFFSET || ENABLED(DUAL_X_CARRIAGE) || ENABLED(PARKING_EXTRUDER) for (uint8_t i = X_AXIS; i <= Y_AXIS; i++) { #if HAS_POSITION_SHIFT position_shift[i] += xydiff[i]; @@ -10529,7 +10668,7 @@ void tool_change(const uint8_t tmp_extruder, const float fr_mm_s/*=0.0*/, bool n stepper.synchronize(); - #if ENABLED(EXT_SOLENOID) + #if ENABLED(EXT_SOLENOID) && !ENABLED(PARKING_EXTRUDER) disable_all_solenoids(); enable_solenoid_on_active_extruder(); #endif // EXT_SOLENOID @@ -10684,11 +10823,11 @@ void process_next_command() { #endif // CNC_WORKSPACE_PLANES #if ENABLED(INCH_MODE_SUPPORT) - case 20: //G20: Inch Mode + case 20: // G20: Inch Mode gcode_G20(); break; - case 21: //G21: MM Mode + case 21: // G21: MM Mode gcode_G21(); break; #endif // INCH_MODE_SUPPORT @@ -10835,7 +10974,7 @@ void process_next_command() { #endif #if ENABLED(SDCARD_SORT_ALPHA) && ENABLED(SDSORT_GCODE) - case 34: //M34 - Set SD card sorting options + case 34: // M34: Set SD card sorting options gcode_M34(); break; #endif // SDCARD_SORT_ALPHA && SDSORT_GCODE @@ -11085,7 +11224,7 @@ void process_next_command() { case 204: // M204: Set acceleration gcode_M204(); break; - case 205: //M205: Set advanced settings + case 205: // M205: Set advanced settings gcode_M205(); break; @@ -13352,6 +13491,16 @@ void setup() { #if ENABLED(SWITCHING_NOZZLE) move_nozzle_servo(0); // Initialize nozzle servo #endif + + #if ENABLED(PARKING_EXTRUDER) + #if ENABLED(PARKING_EXTRUDER_SOLENOIDS_INVERT) + pe_activate_magnet(0); + pe_activate_magnet(1); + #else + pe_deactivate_magnet(0); + pe_deactivate_magnet(1); + #endif + #endif } /** diff --git a/Marlin/SanityCheck.h b/Marlin/SanityCheck.h index 6bb86b8a7..57128d3f1 100644 --- a/Marlin/SanityCheck.h +++ b/Marlin/SanityCheck.h @@ -416,6 +416,34 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE && Y_MAX_LENGTH >= Y_BED_SIZE, #endif #endif +/** + * Parking Extruder requirements + */ +#if ENABLED(PARKING_EXTRUDER) + #if ENABLED(DUAL_X_CARRIAGE) + #error "PARKING_EXTRUDER and DUAL_X_CARRIAGE are incompatible." + #elif ENABLED(SINGLENOZZLE) + #error "PARKING_EXTRUDER and SINGLENOZZLE are incompatible." + #elif ENABLED(EXT_SOLENOID) + #error "PARKING_EXTRUDER and EXT_SOLENOID are incompatible. (Pins are used twice.)" + #elif EXTRUDERS != 2 + #error "PARKING_EXTRUDER requires exactly 2 EXTRUDERS." + #elif !PIN_EXISTS(SOL0) || !PIN_EXISTS(SOL1) + #error "PARKING_EXTRUDER requires SOL0_PIN and SOL1_PIN." + #elif !defined(PARKING_EXTRUDER_PARKING_X) + #error "PARKING_EXTRUDER requires PARKING_EXTRUDER_PARKING_X." + #elif !defined(PARKING_EXTRUDER_SECURITY_RAISE) + #error "PARKING_EXTRUDER requires PARKING_EXTRUDER_SECURITY_RAISE." + #elif PARKING_EXTRUDER_SECURITY_RAISE < 0 + #error "PARKING_EXTRUDER_SECURITY_RAISE must be 0 or higher." + #elif !defined(PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE) || !WITHIN(PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE, LOW, HIGH) + #error "PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE must be defined as HIGH or LOW." + #elif !defined(PARKING_EXTRUDER_SOLENOIDS_DELAY) || !WITHIN(PARKING_EXTRUDER_SOLENOIDS_DELAY, 0, 2000) + #error "PARKING_EXTRUDER_SOLENOIDS_DELAY must be between 0 and 2000 (ms)." + #endif +#endif + + /** * Limited number of servos */ diff --git a/Marlin/configuration_store.cpp b/Marlin/configuration_store.cpp index aa34f9633..06e6bfea6 100644 --- a/Marlin/configuration_store.cpp +++ b/Marlin/configuration_store.cpp @@ -1563,7 +1563,7 @@ void MarlinSettings::reset() { SERIAL_ECHOPAIR(" M218 T", (int)e); SERIAL_ECHOPAIR(" X", LINEAR_UNIT(hotend_offset[X_AXIS][e])); SERIAL_ECHOPAIR(" Y", LINEAR_UNIT(hotend_offset[Y_AXIS][e])); - #if ENABLED(DUAL_X_CARRIAGE) || ENABLED(SWITCHING_NOZZLE) + #if ENABLED(DUAL_X_CARRIAGE) || ENABLED(SWITCHING_NOZZLE) ||ENABLED(PARKING_EXTRUDER) SERIAL_ECHOPAIR(" Z", LINEAR_UNIT(hotend_offset[Z_AXIS][e])); #endif SERIAL_EOL(); diff --git a/Marlin/example_configurations/AlephObjects/TAZ4/Configuration.h b/Marlin/example_configurations/AlephObjects/TAZ4/Configuration.h index f492a4e42..b556c7d0f 100644 --- a/Marlin/example_configurations/AlephObjects/TAZ4/Configuration.h +++ b/Marlin/example_configurations/AlephObjects/TAZ4/Configuration.h @@ -175,6 +175,21 @@ //#define HOTEND_OFFSET_Z { 0.0, 0.0 } #endif +/** + * Two separate X-carriages with extruders that connect to a moving part + * via a magnetic docking mechanism. Requires SOL1_PIN and SOL2_PIN. + */ +//#define PARKING_EXTRUDER +#if ENABLED(PARKING_EXTRUDER) + #define PARKING_EXTRUDER_SOLENOIDS_INVERT // If enabled, the solenoid is NOT magnetized with applied voltage + #define PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE LOW // LOW or HIGH pin signal energizes the coil + #define PARKING_EXTRUDER_SOLENOIDS_DELAY 250 // Delay (ms) for magnetic field. No delay if 0 or not defined. + #define PARKING_EXTRUDER_PARKING_X { -78, 184 } // X positions for parking the extruders + #define PARKING_EXTRUDER_GRAB_DISTANCE 1 // mm to move beyond the parking point to grab the extruder + #define PARKING_EXTRUDER_SECURITY_RAISE 5 // Z-raise before parking + #define HOTEND_OFFSET_Z { 0.0, 1.3 } // Z-offsets of the two hotends. The first must be 0. +#endif + /** * "Mixing Extruder" * - Adds a new code, M165, to set the current mix factors. diff --git a/Marlin/example_configurations/AliExpress/CL-260/Configuration.h b/Marlin/example_configurations/AliExpress/CL-260/Configuration.h index 4a4c3b987..d38a1b531 100644 --- a/Marlin/example_configurations/AliExpress/CL-260/Configuration.h +++ b/Marlin/example_configurations/AliExpress/CL-260/Configuration.h @@ -175,6 +175,21 @@ //#define HOTEND_OFFSET_Z { 0.0, 0.0 } #endif +/** + * Two separate X-carriages with extruders that connect to a moving part + * via a magnetic docking mechanism. Requires SOL1_PIN and SOL2_PIN. + */ +//#define PARKING_EXTRUDER +#if ENABLED(PARKING_EXTRUDER) + #define PARKING_EXTRUDER_SOLENOIDS_INVERT // If enabled, the solenoid is NOT magnetized with applied voltage + #define PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE LOW // LOW or HIGH pin signal energizes the coil + #define PARKING_EXTRUDER_SOLENOIDS_DELAY 250 // Delay (ms) for magnetic field. No delay if 0 or not defined. + #define PARKING_EXTRUDER_PARKING_X { -78, 184 } // X positions for parking the extruders + #define PARKING_EXTRUDER_GRAB_DISTANCE 1 // mm to move beyond the parking point to grab the extruder + #define PARKING_EXTRUDER_SECURITY_RAISE 5 // Z-raise before parking + #define HOTEND_OFFSET_Z { 0.0, 1.3 } // Z-offsets of the two hotends. The first must be 0. +#endif + /** * "Mixing Extruder" * - Adds a new code, M165, to set the current mix factors. diff --git a/Marlin/example_configurations/Anet/A6/Configuration.h b/Marlin/example_configurations/Anet/A6/Configuration.h index 09ed6f28e..daf4829a8 100644 --- a/Marlin/example_configurations/Anet/A6/Configuration.h +++ b/Marlin/example_configurations/Anet/A6/Configuration.h @@ -175,6 +175,21 @@ //#define HOTEND_OFFSET_Z { 0.0, 0.0 } #endif +/** + * Two separate X-carriages with extruders that connect to a moving part + * via a magnetic docking mechanism. Requires SOL1_PIN and SOL2_PIN. + */ +//#define PARKING_EXTRUDER +#if ENABLED(PARKING_EXTRUDER) + #define PARKING_EXTRUDER_SOLENOIDS_INVERT // If enabled, the solenoid is NOT magnetized with applied voltage + #define PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE LOW // LOW or HIGH pin signal energizes the coil + #define PARKING_EXTRUDER_SOLENOIDS_DELAY 250 // Delay (ms) for magnetic field. No delay if 0 or not defined. + #define PARKING_EXTRUDER_PARKING_X { -78, 184 } // X positions for parking the extruders + #define PARKING_EXTRUDER_GRAB_DISTANCE 1 // mm to move beyond the parking point to grab the extruder + #define PARKING_EXTRUDER_SECURITY_RAISE 5 // Z-raise before parking + #define HOTEND_OFFSET_Z { 0.0, 1.3 } // Z-offsets of the two hotends. The first must be 0. +#endif + /** * "Mixing Extruder" * - Adds a new code, M165, to set the current mix factors. diff --git a/Marlin/example_configurations/Anet/A8/Configuration.h b/Marlin/example_configurations/Anet/A8/Configuration.h index b8b0576db..f112b7413 100644 --- a/Marlin/example_configurations/Anet/A8/Configuration.h +++ b/Marlin/example_configurations/Anet/A8/Configuration.h @@ -175,6 +175,21 @@ //#define HOTEND_OFFSET_Z { 0.0, 0.0 } #endif +/** + * Two separate X-carriages with extruders that connect to a moving part + * via a magnetic docking mechanism. Requires SOL1_PIN and SOL2_PIN. + */ +//#define PARKING_EXTRUDER +#if ENABLED(PARKING_EXTRUDER) + #define PARKING_EXTRUDER_SOLENOIDS_INVERT // If enabled, the solenoid is NOT magnetized with applied voltage + #define PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE LOW // LOW or HIGH pin signal energizes the coil + #define PARKING_EXTRUDER_SOLENOIDS_DELAY 250 // Delay (ms) for magnetic field. No delay if 0 or not defined. + #define PARKING_EXTRUDER_PARKING_X { -78, 184 } // X positions for parking the extruders + #define PARKING_EXTRUDER_GRAB_DISTANCE 1 // mm to move beyond the parking point to grab the extruder + #define PARKING_EXTRUDER_SECURITY_RAISE 5 // Z-raise before parking + #define HOTEND_OFFSET_Z { 0.0, 1.3 } // Z-offsets of the two hotends. The first must be 0. +#endif + /** * "Mixing Extruder" * - Adds a new code, M165, to set the current mix factors. diff --git a/Marlin/example_configurations/BQ/Hephestos/Configuration.h b/Marlin/example_configurations/BQ/Hephestos/Configuration.h index 17490db8c..0b6b5980d 100644 --- a/Marlin/example_configurations/BQ/Hephestos/Configuration.h +++ b/Marlin/example_configurations/BQ/Hephestos/Configuration.h @@ -178,6 +178,21 @@ //#define HOTEND_OFFSET_Z { 0.0, 0.0 } #endif +/** + * Two separate X-carriages with extruders that connect to a moving part + * via a magnetic docking mechanism. Requires SOL1_PIN and SOL2_PIN. + */ +//#define PARKING_EXTRUDER +#if ENABLED(PARKING_EXTRUDER) + #define PARKING_EXTRUDER_SOLENOIDS_INVERT // If enabled, the solenoid is NOT magnetized with applied voltage + #define PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE LOW // LOW or HIGH pin signal energizes the coil + #define PARKING_EXTRUDER_SOLENOIDS_DELAY 250 // Delay (ms) for magnetic field. No delay if 0 or not defined. + #define PARKING_EXTRUDER_PARKING_X { -78, 184 } // X positions for parking the extruders + #define PARKING_EXTRUDER_GRAB_DISTANCE 1 // mm to move beyond the parking point to grab the extruder + #define PARKING_EXTRUDER_SECURITY_RAISE 5 // Z-raise before parking + #define HOTEND_OFFSET_Z { 0.0, 1.3 } // Z-offsets of the two hotends. The first must be 0. +#endif + /** * "Mixing Extruder" * - Adds a new code, M165, to set the current mix factors. diff --git a/Marlin/example_configurations/BQ/Hephestos_2/Configuration.h b/Marlin/example_configurations/BQ/Hephestos_2/Configuration.h index 1abacba01..a7b4650f9 100644 --- a/Marlin/example_configurations/BQ/Hephestos_2/Configuration.h +++ b/Marlin/example_configurations/BQ/Hephestos_2/Configuration.h @@ -174,6 +174,21 @@ //#define HOTEND_OFFSET_Z { 0.0, 0.0 } #endif +/** + * Two separate X-carriages with extruders that connect to a moving part + * via a magnetic docking mechanism. Requires SOL1_PIN and SOL2_PIN. + */ +//#define PARKING_EXTRUDER +#if ENABLED(PARKING_EXTRUDER) + #define PARKING_EXTRUDER_SOLENOIDS_INVERT // If enabled, the solenoid is NOT magnetized with applied voltage + #define PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE LOW // LOW or HIGH pin signal energizes the coil + #define PARKING_EXTRUDER_SOLENOIDS_DELAY 250 // Delay (ms) for magnetic field. No delay if 0 or not defined. + #define PARKING_EXTRUDER_PARKING_X { -78, 184 } // X positions for parking the extruders + #define PARKING_EXTRUDER_GRAB_DISTANCE 1 // mm to move beyond the parking point to grab the extruder + #define PARKING_EXTRUDER_SECURITY_RAISE 5 // Z-raise before parking + #define HOTEND_OFFSET_Z { 0.0, 1.3 } // Z-offsets of the two hotends. The first must be 0. +#endif + /** * "Mixing Extruder" * - Adds a new code, M165, to set the current mix factors. diff --git a/Marlin/example_configurations/BQ/WITBOX/Configuration.h b/Marlin/example_configurations/BQ/WITBOX/Configuration.h index c50016681..3ada39ed1 100644 --- a/Marlin/example_configurations/BQ/WITBOX/Configuration.h +++ b/Marlin/example_configurations/BQ/WITBOX/Configuration.h @@ -178,6 +178,21 @@ //#define HOTEND_OFFSET_Z { 0.0, 0.0 } #endif +/** + * Two separate X-carriages with extruders that connect to a moving part + * via a magnetic docking mechanism. Requires SOL1_PIN and SOL2_PIN. + */ +//#define PARKING_EXTRUDER +#if ENABLED(PARKING_EXTRUDER) + #define PARKING_EXTRUDER_SOLENOIDS_INVERT // If enabled, the solenoid is NOT magnetized with applied voltage + #define PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE LOW // LOW or HIGH pin signal energizes the coil + #define PARKING_EXTRUDER_SOLENOIDS_DELAY 250 // Delay (ms) for magnetic field. No delay if 0 or not defined. + #define PARKING_EXTRUDER_PARKING_X { -78, 184 } // X positions for parking the extruders + #define PARKING_EXTRUDER_GRAB_DISTANCE 1 // mm to move beyond the parking point to grab the extruder + #define PARKING_EXTRUDER_SECURITY_RAISE 5 // Z-raise before parking + #define HOTEND_OFFSET_Z { 0.0, 1.3 } // Z-offsets of the two hotends. The first must be 0. +#endif + /** * "Mixing Extruder" * - Adds a new code, M165, to set the current mix factors. diff --git a/Marlin/example_configurations/Cartesio/Configuration.h b/Marlin/example_configurations/Cartesio/Configuration.h index 9d941f069..7024a8ae6 100644 --- a/Marlin/example_configurations/Cartesio/Configuration.h +++ b/Marlin/example_configurations/Cartesio/Configuration.h @@ -176,6 +176,21 @@ //#define HOTEND_OFFSET_Z { 0.0, 0.0 } #endif +/** + * Two separate X-carriages with extruders that connect to a moving part + * via a magnetic docking mechanism. Requires SOL1_PIN and SOL2_PIN. + */ +//#define PARKING_EXTRUDER +#if ENABLED(PARKING_EXTRUDER) + #define PARKING_EXTRUDER_SOLENOIDS_INVERT // If enabled, the solenoid is NOT magnetized with applied voltage + #define PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE LOW // LOW or HIGH pin signal energizes the coil + #define PARKING_EXTRUDER_SOLENOIDS_DELAY 250 // Delay (ms) for magnetic field. No delay if 0 or not defined. + #define PARKING_EXTRUDER_PARKING_X { -78, 184 } // X positions for parking the extruders + #define PARKING_EXTRUDER_GRAB_DISTANCE 1 // mm to move beyond the parking point to grab the extruder + #define PARKING_EXTRUDER_SECURITY_RAISE 5 // Z-raise before parking + #define HOTEND_OFFSET_Z { 0.0, 1.3 } // Z-offsets of the two hotends. The first must be 0. +#endif + /** * "Mixing Extruder" * - Adds a new code, M165, to set the current mix factors. diff --git a/Marlin/example_configurations/Creality/CR-10/Configuration.h b/Marlin/example_configurations/Creality/CR-10/Configuration.h index ea713953e..a19df6c91 100644 --- a/Marlin/example_configurations/Creality/CR-10/Configuration.h +++ b/Marlin/example_configurations/Creality/CR-10/Configuration.h @@ -175,6 +175,21 @@ //#define HOTEND_OFFSET_Z { 0.0, 0.0 } #endif +/** + * Two separate X-carriages with extruders that connect to a moving part + * via a magnetic docking mechanism. Requires SOL1_PIN and SOL2_PIN. + */ +//#define PARKING_EXTRUDER +#if ENABLED(PARKING_EXTRUDER) + #define PARKING_EXTRUDER_SOLENOIDS_INVERT // If enabled, the solenoid is NOT magnetized with applied voltage + #define PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE LOW // LOW or HIGH pin signal energizes the coil + #define PARKING_EXTRUDER_SOLENOIDS_DELAY 250 // Delay (ms) for magnetic field. No delay if 0 or not defined. + #define PARKING_EXTRUDER_PARKING_X { -78, 184 } // X positions for parking the extruders + #define PARKING_EXTRUDER_GRAB_DISTANCE 1 // mm to move beyond the parking point to grab the extruder + #define PARKING_EXTRUDER_SECURITY_RAISE 5 // Z-raise before parking + #define HOTEND_OFFSET_Z { 0.0, 1.3 } // Z-offsets of the two hotends. The first must be 0. +#endif + /** * "Mixing Extruder" * - Adds a new code, M165, to set the current mix factors. diff --git a/Marlin/example_configurations/Felix/Configuration.h b/Marlin/example_configurations/Felix/Configuration.h index 34dfb1870..ce6226258 100644 --- a/Marlin/example_configurations/Felix/Configuration.h +++ b/Marlin/example_configurations/Felix/Configuration.h @@ -175,6 +175,21 @@ //#define HOTEND_OFFSET_Z { 0.0, 0.0 } #endif +/** + * Two separate X-carriages with extruders that connect to a moving part + * via a magnetic docking mechanism. Requires SOL1_PIN and SOL2_PIN. + */ +//#define PARKING_EXTRUDER +#if ENABLED(PARKING_EXTRUDER) + #define PARKING_EXTRUDER_SOLENOIDS_INVERT // If enabled, the solenoid is NOT magnetized with applied voltage + #define PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE LOW // LOW or HIGH pin signal energizes the coil + #define PARKING_EXTRUDER_SOLENOIDS_DELAY 250 // Delay (ms) for magnetic field. No delay if 0 or not defined. + #define PARKING_EXTRUDER_PARKING_X { -78, 184 } // X positions for parking the extruders + #define PARKING_EXTRUDER_GRAB_DISTANCE 1 // mm to move beyond the parking point to grab the extruder + #define PARKING_EXTRUDER_SECURITY_RAISE 5 // Z-raise before parking + #define HOTEND_OFFSET_Z { 0.0, 1.3 } // Z-offsets of the two hotends. The first must be 0. +#endif + /** * "Mixing Extruder" * - Adds a new code, M165, to set the current mix factors. diff --git a/Marlin/example_configurations/Felix/DUAL/Configuration.h b/Marlin/example_configurations/Felix/DUAL/Configuration.h index 5a15d28be..4df92ec4f 100644 --- a/Marlin/example_configurations/Felix/DUAL/Configuration.h +++ b/Marlin/example_configurations/Felix/DUAL/Configuration.h @@ -175,6 +175,21 @@ //#define HOTEND_OFFSET_Z { 0.0, 0.0 } #endif +/** + * Two separate X-carriages with extruders that connect to a moving part + * via a magnetic docking mechanism. Requires SOL1_PIN and SOL2_PIN. + */ +//#define PARKING_EXTRUDER +#if ENABLED(PARKING_EXTRUDER) + #define PARKING_EXTRUDER_SOLENOIDS_INVERT // If enabled, the solenoid is NOT magnetized with applied voltage + #define PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE LOW // LOW or HIGH pin signal energizes the coil + #define PARKING_EXTRUDER_SOLENOIDS_DELAY 250 // Delay (ms) for magnetic field. No delay if 0 or not defined. + #define PARKING_EXTRUDER_PARKING_X { -78, 184 } // X positions for parking the extruders + #define PARKING_EXTRUDER_GRAB_DISTANCE 1 // mm to move beyond the parking point to grab the extruder + #define PARKING_EXTRUDER_SECURITY_RAISE 5 // Z-raise before parking + #define HOTEND_OFFSET_Z { 0.0, 1.3 } // Z-offsets of the two hotends. The first must be 0. +#endif + /** * "Mixing Extruder" * - Adds a new code, M165, to set the current mix factors. diff --git a/Marlin/example_configurations/Folger Tech/i3-2020/Configuration.h b/Marlin/example_configurations/Folger Tech/i3-2020/Configuration.h index 8fac72668..21d0b12fb 100644 --- a/Marlin/example_configurations/Folger Tech/i3-2020/Configuration.h +++ b/Marlin/example_configurations/Folger Tech/i3-2020/Configuration.h @@ -175,6 +175,21 @@ //#define HOTEND_OFFSET_Z { 0.0, 0.0 } #endif +/** + * Two separate X-carriages with extruders that connect to a moving part + * via a magnetic docking mechanism. Requires SOL1_PIN and SOL2_PIN. + */ +//#define PARKING_EXTRUDER +#if ENABLED(PARKING_EXTRUDER) + #define PARKING_EXTRUDER_SOLENOIDS_INVERT // If enabled, the solenoid is NOT magnetized with applied voltage + #define PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE LOW // LOW or HIGH pin signal energizes the coil + #define PARKING_EXTRUDER_SOLENOIDS_DELAY 250 // Delay (ms) for magnetic field. No delay if 0 or not defined. + #define PARKING_EXTRUDER_PARKING_X { -78, 184 } // X positions for parking the extruders + #define PARKING_EXTRUDER_GRAB_DISTANCE 1 // mm to move beyond the parking point to grab the extruder + #define PARKING_EXTRUDER_SECURITY_RAISE 5 // Z-raise before parking + #define HOTEND_OFFSET_Z { 0.0, 1.3 } // Z-offsets of the two hotends. The first must be 0. +#endif + /** * "Mixing Extruder" * - Adds a new code, M165, to set the current mix factors. diff --git a/Marlin/example_configurations/Geeetech/GT2560/Configuration.h b/Marlin/example_configurations/Geeetech/GT2560/Configuration.h index 36f13ffa9..fa750794d 100644 --- a/Marlin/example_configurations/Geeetech/GT2560/Configuration.h +++ b/Marlin/example_configurations/Geeetech/GT2560/Configuration.h @@ -175,6 +175,21 @@ //#define HOTEND_OFFSET_Z { 0.0, 0.0 } #endif +/** + * Two separate X-carriages with extruders that connect to a moving part + * via a magnetic docking mechanism. Requires SOL1_PIN and SOL2_PIN. + */ +//#define PARKING_EXTRUDER +#if ENABLED(PARKING_EXTRUDER) + #define PARKING_EXTRUDER_SOLENOIDS_INVERT // If enabled, the solenoid is NOT magnetized with applied voltage + #define PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE LOW // LOW or HIGH pin signal energizes the coil + #define PARKING_EXTRUDER_SOLENOIDS_DELAY 250 // Delay (ms) for magnetic field. No delay if 0 or not defined. + #define PARKING_EXTRUDER_PARKING_X { -78, 184 } // X positions for parking the extruders + #define PARKING_EXTRUDER_GRAB_DISTANCE 1 // mm to move beyond the parking point to grab the extruder + #define PARKING_EXTRUDER_SECURITY_RAISE 5 // Z-raise before parking + #define HOTEND_OFFSET_Z { 0.0, 1.3 } // Z-offsets of the two hotends. The first must be 0. +#endif + /** * "Mixing Extruder" * - Adds a new code, M165, to set the current mix factors. diff --git a/Marlin/example_configurations/Geeetech/I3_Pro_X-GT2560/Configuration.h b/Marlin/example_configurations/Geeetech/I3_Pro_X-GT2560/Configuration.h index bcb20c702..2f6983668 100644 --- a/Marlin/example_configurations/Geeetech/I3_Pro_X-GT2560/Configuration.h +++ b/Marlin/example_configurations/Geeetech/I3_Pro_X-GT2560/Configuration.h @@ -175,6 +175,21 @@ //#define HOTEND_OFFSET_Z { 0.0, 0.0 } #endif +/** + * Two separate X-carriages with extruders that connect to a moving part + * via a magnetic docking mechanism. Requires SOL1_PIN and SOL2_PIN. + */ +//#define PARKING_EXTRUDER +#if ENABLED(PARKING_EXTRUDER) + #define PARKING_EXTRUDER_SOLENOIDS_INVERT // If enabled, the solenoid is NOT magnetized with applied voltage + #define PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE LOW // LOW or HIGH pin signal energizes the coil + #define PARKING_EXTRUDER_SOLENOIDS_DELAY 250 // Delay (ms) for magnetic field. No delay if 0 or not defined. + #define PARKING_EXTRUDER_PARKING_X { -78, 184 } // X positions for parking the extruders + #define PARKING_EXTRUDER_GRAB_DISTANCE 1 // mm to move beyond the parking point to grab the extruder + #define PARKING_EXTRUDER_SECURITY_RAISE 5 // Z-raise before parking + #define HOTEND_OFFSET_Z { 0.0, 1.3 } // Z-offsets of the two hotends. The first must be 0. +#endif + /** * "Mixing Extruder" * - Adds a new code, M165, to set the current mix factors. diff --git a/Marlin/example_configurations/Infitary/i3-M508/Configuration.h b/Marlin/example_configurations/Infitary/i3-M508/Configuration.h index 61abf7b8e..875daa064 100644 --- a/Marlin/example_configurations/Infitary/i3-M508/Configuration.h +++ b/Marlin/example_configurations/Infitary/i3-M508/Configuration.h @@ -175,6 +175,21 @@ //#define HOTEND_OFFSET_Z { 0.0, 0.0 } #endif +/** + * Two separate X-carriages with extruders that connect to a moving part + * via a magnetic docking mechanism. Requires SOL1_PIN and SOL2_PIN. + */ +//#define PARKING_EXTRUDER +#if ENABLED(PARKING_EXTRUDER) + #define PARKING_EXTRUDER_SOLENOIDS_INVERT // If enabled, the solenoid is NOT magnetized with applied voltage + #define PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE LOW // LOW or HIGH pin signal energizes the coil + #define PARKING_EXTRUDER_SOLENOIDS_DELAY 250 // Delay (ms) for magnetic field. No delay if 0 or not defined. + #define PARKING_EXTRUDER_PARKING_X { -78, 184 } // X positions for parking the extruders + #define PARKING_EXTRUDER_GRAB_DISTANCE 1 // mm to move beyond the parking point to grab the extruder + #define PARKING_EXTRUDER_SECURITY_RAISE 5 // Z-raise before parking + #define HOTEND_OFFSET_Z { 0.0, 1.3 } // Z-offsets of the two hotends. The first must be 0. +#endif + /** * "Mixing Extruder" * - Adds a new code, M165, to set the current mix factors. diff --git a/Marlin/example_configurations/Malyan/M150/Configuration.h b/Marlin/example_configurations/Malyan/M150/Configuration.h index 62dd22ec3..a51b477d1 100644 --- a/Marlin/example_configurations/Malyan/M150/Configuration.h +++ b/Marlin/example_configurations/Malyan/M150/Configuration.h @@ -180,6 +180,21 @@ //#define HOTEND_OFFSET_Z { 0.0, 0.0 } #endif +/** + * Two separate X-carriages with extruders that connect to a moving part + * via a magnetic docking mechanism. Requires SOL1_PIN and SOL2_PIN. + */ +//#define PARKING_EXTRUDER +#if ENABLED(PARKING_EXTRUDER) + #define PARKING_EXTRUDER_SOLENOIDS_INVERT // If enabled, the solenoid is NOT magnetized with applied voltage + #define PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE LOW // LOW or HIGH pin signal energizes the coil + #define PARKING_EXTRUDER_SOLENOIDS_DELAY 250 // Delay (ms) for magnetic field. No delay if 0 or not defined. + #define PARKING_EXTRUDER_PARKING_X { -78, 184 } // X positions for parking the extruders + #define PARKING_EXTRUDER_GRAB_DISTANCE 1 // mm to move beyond the parking point to grab the extruder + #define PARKING_EXTRUDER_SECURITY_RAISE 5 // Z-raise before parking + #define HOTEND_OFFSET_Z { 0.0, 1.3 } // Z-offsets of the two hotends. The first must be 0. +#endif + /** * "Mixing Extruder" * - Adds a new code, M165, to set the current mix factors. diff --git a/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h b/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h index 1934b6fe8..8a98c92f6 100644 --- a/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h +++ b/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h @@ -175,6 +175,21 @@ //#define HOTEND_OFFSET_Z { 0.0, 0.0 } #endif +/** + * Two separate X-carriages with extruders that connect to a moving part + * via a magnetic docking mechanism. Requires SOL1_PIN and SOL2_PIN. + */ +//#define PARKING_EXTRUDER +#if ENABLED(PARKING_EXTRUDER) + #define PARKING_EXTRUDER_SOLENOIDS_INVERT // If enabled, the solenoid is NOT magnetized with applied voltage + #define PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE LOW // LOW or HIGH pin signal energizes the coil + #define PARKING_EXTRUDER_SOLENOIDS_DELAY 250 // Delay (ms) for magnetic field. No delay if 0 or not defined. + #define PARKING_EXTRUDER_PARKING_X { -78, 184 } // X positions for parking the extruders + #define PARKING_EXTRUDER_GRAB_DISTANCE 1 // mm to move beyond the parking point to grab the extruder + #define PARKING_EXTRUDER_SECURITY_RAISE 5 // Z-raise before parking + #define HOTEND_OFFSET_Z { 0.0, 1.3 } // Z-offsets of the two hotends. The first must be 0. +#endif + /** * "Mixing Extruder" * - Adds a new code, M165, to set the current mix factors. diff --git a/Marlin/example_configurations/RigidBot/Configuration.h b/Marlin/example_configurations/RigidBot/Configuration.h index e4be6edd2..74985a443 100644 --- a/Marlin/example_configurations/RigidBot/Configuration.h +++ b/Marlin/example_configurations/RigidBot/Configuration.h @@ -178,6 +178,21 @@ //#define HOTEND_OFFSET_Z { 0.0, 0.0 } #endif +/** + * Two separate X-carriages with extruders that connect to a moving part + * via a magnetic docking mechanism. Requires SOL1_PIN and SOL2_PIN. + */ +//#define PARKING_EXTRUDER +#if ENABLED(PARKING_EXTRUDER) + #define PARKING_EXTRUDER_SOLENOIDS_INVERT // If enabled, the solenoid is NOT magnetized with applied voltage + #define PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE LOW // LOW or HIGH pin signal energizes the coil + #define PARKING_EXTRUDER_SOLENOIDS_DELAY 250 // Delay (ms) for magnetic field. No delay if 0 or not defined. + #define PARKING_EXTRUDER_PARKING_X { -78, 184 } // X positions for parking the extruders + #define PARKING_EXTRUDER_GRAB_DISTANCE 1 // mm to move beyond the parking point to grab the extruder + #define PARKING_EXTRUDER_SECURITY_RAISE 5 // Z-raise before parking + #define HOTEND_OFFSET_Z { 0.0, 1.3 } // Z-offsets of the two hotends. The first must be 0. +#endif + /** * "Mixing Extruder" * - Adds a new code, M165, to set the current mix factors. diff --git a/Marlin/example_configurations/SCARA/Configuration.h b/Marlin/example_configurations/SCARA/Configuration.h index 238fedcd1..413da1cdb 100644 --- a/Marlin/example_configurations/SCARA/Configuration.h +++ b/Marlin/example_configurations/SCARA/Configuration.h @@ -205,6 +205,21 @@ //#define HOTEND_OFFSET_Z { 0.0, 0.0 } #endif +/** + * Two separate X-carriages with extruders that connect to a moving part + * via a magnetic docking mechanism. Requires SOL1_PIN and SOL2_PIN. + */ +//#define PARKING_EXTRUDER +#if ENABLED(PARKING_EXTRUDER) + #define PARKING_EXTRUDER_SOLENOIDS_INVERT // If enabled, the solenoid is NOT magnetized with applied voltage + #define PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE LOW // LOW or HIGH pin signal energizes the coil + #define PARKING_EXTRUDER_SOLENOIDS_DELAY 250 // Delay (ms) for magnetic field. No delay if 0 or not defined. + #define PARKING_EXTRUDER_PARKING_X { -78, 184 } // X positions for parking the extruders + #define PARKING_EXTRUDER_GRAB_DISTANCE 1 // mm to move beyond the parking point to grab the extruder + #define PARKING_EXTRUDER_SECURITY_RAISE 5 // Z-raise before parking + #define HOTEND_OFFSET_Z { 0.0, 1.3 } // Z-offsets of the two hotends. The first must be 0. +#endif + /** * "Mixing Extruder" * - Adds a new code, M165, to set the current mix factors. diff --git a/Marlin/example_configurations/TinyBoy2/Configuration.h b/Marlin/example_configurations/TinyBoy2/Configuration.h index 1097b4889..99078d086 100644 --- a/Marlin/example_configurations/TinyBoy2/Configuration.h +++ b/Marlin/example_configurations/TinyBoy2/Configuration.h @@ -197,6 +197,21 @@ //#define HOTEND_OFFSET_Z { 0.0, 0.0 } #endif +/** + * Two separate X-carriages with extruders that connect to a moving part + * via a magnetic docking mechanism. Requires SOL1_PIN and SOL2_PIN. + */ +//#define PARKING_EXTRUDER +#if ENABLED(PARKING_EXTRUDER) + #define PARKING_EXTRUDER_SOLENOIDS_INVERT // If enabled, the solenoid is NOT magnetized with applied voltage + #define PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE LOW // LOW or HIGH pin signal energizes the coil + #define PARKING_EXTRUDER_SOLENOIDS_DELAY 250 // Delay (ms) for magnetic field. No delay if 0 or not defined. + #define PARKING_EXTRUDER_PARKING_X { -78, 184 } // X positions for parking the extruders + #define PARKING_EXTRUDER_GRAB_DISTANCE 1 // mm to move beyond the parking point to grab the extruder + #define PARKING_EXTRUDER_SECURITY_RAISE 5 // Z-raise before parking + #define HOTEND_OFFSET_Z { 0.0, 1.3 } // Z-offsets of the two hotends. The first must be 0. +#endif + /** * "Mixing Extruder" * - Adds a new code, M165, to set the current mix factors. diff --git a/Marlin/example_configurations/Velleman/K8200/Configuration.h b/Marlin/example_configurations/Velleman/K8200/Configuration.h index 598773266..a40eeca4c 100644 --- a/Marlin/example_configurations/Velleman/K8200/Configuration.h +++ b/Marlin/example_configurations/Velleman/K8200/Configuration.h @@ -195,6 +195,21 @@ //#define HOTEND_OFFSET_Z { 0.0, 0.0 } #endif +/** + * Two separate X-carriages with extruders that connect to a moving part + * via a magnetic docking mechanism. Requires SOL1_PIN and SOL2_PIN. + */ +//#define PARKING_EXTRUDER +#if ENABLED(PARKING_EXTRUDER) + #define PARKING_EXTRUDER_SOLENOIDS_INVERT // If enabled, the solenoid is NOT magnetized with applied voltage + #define PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE LOW // LOW or HIGH pin signal energizes the coil + #define PARKING_EXTRUDER_SOLENOIDS_DELAY 250 // Delay (ms) for magnetic field. No delay if 0 or not defined. + #define PARKING_EXTRUDER_PARKING_X { -78, 184 } // X positions for parking the extruders + #define PARKING_EXTRUDER_GRAB_DISTANCE 1 // mm to move beyond the parking point to grab the extruder + #define PARKING_EXTRUDER_SECURITY_RAISE 5 // Z-raise before parking + #define HOTEND_OFFSET_Z { 0.0, 1.3 } // Z-offsets of the two hotends. The first must be 0. +#endif + /** * "Mixing Extruder" * - Adds a new code, M165, to set the current mix factors. diff --git a/Marlin/example_configurations/Velleman/K8400/Configuration.h b/Marlin/example_configurations/Velleman/K8400/Configuration.h index 4cabd6915..50d9681b0 100644 --- a/Marlin/example_configurations/Velleman/K8400/Configuration.h +++ b/Marlin/example_configurations/Velleman/K8400/Configuration.h @@ -175,6 +175,21 @@ //#define HOTEND_OFFSET_Z { 0.0, 0.0 } #endif +/** + * Two separate X-carriages with extruders that connect to a moving part + * via a magnetic docking mechanism. Requires SOL1_PIN and SOL2_PIN. + */ +//#define PARKING_EXTRUDER +#if ENABLED(PARKING_EXTRUDER) + #define PARKING_EXTRUDER_SOLENOIDS_INVERT // If enabled, the solenoid is NOT magnetized with applied voltage + #define PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE LOW // LOW or HIGH pin signal energizes the coil + #define PARKING_EXTRUDER_SOLENOIDS_DELAY 250 // Delay (ms) for magnetic field. No delay if 0 or not defined. + #define PARKING_EXTRUDER_PARKING_X { -78, 184 } // X positions for parking the extruders + #define PARKING_EXTRUDER_GRAB_DISTANCE 1 // mm to move beyond the parking point to grab the extruder + #define PARKING_EXTRUDER_SECURITY_RAISE 5 // Z-raise before parking + #define HOTEND_OFFSET_Z { 0.0, 1.3 } // Z-offsets of the two hotends. The first must be 0. +#endif + /** * "Mixing Extruder" * - Adds a new code, M165, to set the current mix factors. diff --git a/Marlin/example_configurations/Velleman/K8400/Dual-head/Configuration.h b/Marlin/example_configurations/Velleman/K8400/Dual-head/Configuration.h index 95520e57f..309a47c57 100644 --- a/Marlin/example_configurations/Velleman/K8400/Dual-head/Configuration.h +++ b/Marlin/example_configurations/Velleman/K8400/Dual-head/Configuration.h @@ -175,6 +175,21 @@ //#define HOTEND_OFFSET_Z { 0.0, 0.0 } #endif +/** + * Two separate X-carriages with extruders that connect to a moving part + * via a magnetic docking mechanism. Requires SOL1_PIN and SOL2_PIN. + */ +//#define PARKING_EXTRUDER +#if ENABLED(PARKING_EXTRUDER) + #define PARKING_EXTRUDER_SOLENOIDS_INVERT // If enabled, the solenoid is NOT magnetized with applied voltage + #define PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE LOW // LOW or HIGH pin signal energizes the coil + #define PARKING_EXTRUDER_SOLENOIDS_DELAY 250 // Delay (ms) for magnetic field. No delay if 0 or not defined. + #define PARKING_EXTRUDER_PARKING_X { -78, 184 } // X positions for parking the extruders + #define PARKING_EXTRUDER_GRAB_DISTANCE 1 // mm to move beyond the parking point to grab the extruder + #define PARKING_EXTRUDER_SECURITY_RAISE 5 // Z-raise before parking + #define HOTEND_OFFSET_Z { 0.0, 1.3 } // Z-offsets of the two hotends. The first must be 0. +#endif + /** * "Mixing Extruder" * - Adds a new code, M165, to set the current mix factors. diff --git a/Marlin/example_configurations/adafruit/ST7565/Configuration.h b/Marlin/example_configurations/adafruit/ST7565/Configuration.h index b3761dc88..84a4cda1a 100644 --- a/Marlin/example_configurations/adafruit/ST7565/Configuration.h +++ b/Marlin/example_configurations/adafruit/ST7565/Configuration.h @@ -175,6 +175,21 @@ //#define HOTEND_OFFSET_Z { 0.0, 0.0 } #endif +/** + * Two separate X-carriages with extruders that connect to a moving part + * via a magnetic docking mechanism. Requires SOL1_PIN and SOL2_PIN. + */ +//#define PARKING_EXTRUDER +#if ENABLED(PARKING_EXTRUDER) + #define PARKING_EXTRUDER_SOLENOIDS_INVERT // If enabled, the solenoid is NOT magnetized with applied voltage + #define PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE LOW // LOW or HIGH pin signal energizes the coil + #define PARKING_EXTRUDER_SOLENOIDS_DELAY 250 // Delay (ms) for magnetic field. No delay if 0 or not defined. + #define PARKING_EXTRUDER_PARKING_X { -78, 184 } // X positions for parking the extruders + #define PARKING_EXTRUDER_GRAB_DISTANCE 1 // mm to move beyond the parking point to grab the extruder + #define PARKING_EXTRUDER_SECURITY_RAISE 5 // Z-raise before parking + #define HOTEND_OFFSET_Z { 0.0, 1.3 } // Z-offsets of the two hotends. The first must be 0. +#endif + /** * "Mixing Extruder" * - Adds a new code, M165, to set the current mix factors. diff --git a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h index 9dac8434a..f10cb75f6 100644 --- a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h +++ b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h @@ -175,6 +175,21 @@ //#define HOTEND_OFFSET_Z { 0.0, 0.0 } #endif +/** + * Two separate X-carriages with extruders that connect to a moving part + * via a magnetic docking mechanism. Requires SOL1_PIN and SOL2_PIN. + */ +//#define PARKING_EXTRUDER +#if ENABLED(PARKING_EXTRUDER) + #define PARKING_EXTRUDER_SOLENOIDS_INVERT // If enabled, the solenoid is NOT magnetized with applied voltage + #define PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE LOW // LOW or HIGH pin signal energizes the coil + #define PARKING_EXTRUDER_SOLENOIDS_DELAY 250 // Delay (ms) for magnetic field. No delay if 0 or not defined. + #define PARKING_EXTRUDER_PARKING_X { -78, 184 } // X positions for parking the extruders + #define PARKING_EXTRUDER_GRAB_DISTANCE 1 // mm to move beyond the parking point to grab the extruder + #define PARKING_EXTRUDER_SECURITY_RAISE 5 // Z-raise before parking + #define HOTEND_OFFSET_Z { 0.0, 1.3 } // Z-offsets of the two hotends. The first must be 0. +#endif + /** * "Mixing Extruder" * - Adds a new code, M165, to set the current mix factors. diff --git a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h index 631672cc8..70ddf89ff 100644 --- a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h +++ b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h @@ -175,6 +175,21 @@ //#define HOTEND_OFFSET_Z { 0.0, 0.0 } #endif +/** + * Two separate X-carriages with extruders that connect to a moving part + * via a magnetic docking mechanism. Requires SOL1_PIN and SOL2_PIN. + */ +//#define PARKING_EXTRUDER +#if ENABLED(PARKING_EXTRUDER) + #define PARKING_EXTRUDER_SOLENOIDS_INVERT // If enabled, the solenoid is NOT magnetized with applied voltage + #define PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE LOW // LOW or HIGH pin signal energizes the coil + #define PARKING_EXTRUDER_SOLENOIDS_DELAY 250 // Delay (ms) for magnetic field. No delay if 0 or not defined. + #define PARKING_EXTRUDER_PARKING_X { -78, 184 } // X positions for parking the extruders + #define PARKING_EXTRUDER_GRAB_DISTANCE 1 // mm to move beyond the parking point to grab the extruder + #define PARKING_EXTRUDER_SECURITY_RAISE 5 // Z-raise before parking + #define HOTEND_OFFSET_Z { 0.0, 1.3 } // Z-offsets of the two hotends. The first must be 0. +#endif + /** * "Mixing Extruder" * - Adds a new code, M165, to set the current mix factors. diff --git a/Marlin/example_configurations/delta/generic/Configuration.h b/Marlin/example_configurations/delta/generic/Configuration.h index 9259ece12..3fd105f08 100644 --- a/Marlin/example_configurations/delta/generic/Configuration.h +++ b/Marlin/example_configurations/delta/generic/Configuration.h @@ -175,6 +175,21 @@ //#define HOTEND_OFFSET_Z { 0.0, 0.0 } #endif +/** + * Two separate X-carriages with extruders that connect to a moving part + * via a magnetic docking mechanism. Requires SOL1_PIN and SOL2_PIN. + */ +//#define PARKING_EXTRUDER +#if ENABLED(PARKING_EXTRUDER) + #define PARKING_EXTRUDER_SOLENOIDS_INVERT // If enabled, the solenoid is NOT magnetized with applied voltage + #define PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE LOW // LOW or HIGH pin signal energizes the coil + #define PARKING_EXTRUDER_SOLENOIDS_DELAY 250 // Delay (ms) for magnetic field. No delay if 0 or not defined. + #define PARKING_EXTRUDER_PARKING_X { -78, 184 } // X positions for parking the extruders + #define PARKING_EXTRUDER_GRAB_DISTANCE 1 // mm to move beyond the parking point to grab the extruder + #define PARKING_EXTRUDER_SECURITY_RAISE 5 // Z-raise before parking + #define HOTEND_OFFSET_Z { 0.0, 1.3 } // Z-offsets of the two hotends. The first must be 0. +#endif + /** * "Mixing Extruder" * - Adds a new code, M165, to set the current mix factors. diff --git a/Marlin/example_configurations/delta/kossel_mini/Configuration.h b/Marlin/example_configurations/delta/kossel_mini/Configuration.h index 3c0da4ecd..1197ca2e1 100644 --- a/Marlin/example_configurations/delta/kossel_mini/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_mini/Configuration.h @@ -175,6 +175,21 @@ //#define HOTEND_OFFSET_Z { 0.0, 0.0 } #endif +/** + * Two separate X-carriages with extruders that connect to a moving part + * via a magnetic docking mechanism. Requires SOL1_PIN and SOL2_PIN. + */ +//#define PARKING_EXTRUDER +#if ENABLED(PARKING_EXTRUDER) + #define PARKING_EXTRUDER_SOLENOIDS_INVERT // If enabled, the solenoid is NOT magnetized with applied voltage + #define PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE LOW // LOW or HIGH pin signal energizes the coil + #define PARKING_EXTRUDER_SOLENOIDS_DELAY 250 // Delay (ms) for magnetic field. No delay if 0 or not defined. + #define PARKING_EXTRUDER_PARKING_X { -78, 184 } // X positions for parking the extruders + #define PARKING_EXTRUDER_GRAB_DISTANCE 1 // mm to move beyond the parking point to grab the extruder + #define PARKING_EXTRUDER_SECURITY_RAISE 5 // Z-raise before parking + #define HOTEND_OFFSET_Z { 0.0, 1.3 } // Z-offsets of the two hotends. The first must be 0. +#endif + /** * "Mixing Extruder" * - Adds a new code, M165, to set the current mix factors. diff --git a/Marlin/example_configurations/delta/kossel_pro/Configuration.h b/Marlin/example_configurations/delta/kossel_pro/Configuration.h index 5292042d5..2391046a4 100644 --- a/Marlin/example_configurations/delta/kossel_pro/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_pro/Configuration.h @@ -179,6 +179,21 @@ //#define HOTEND_OFFSET_Z { 0.0, 0.0 } #endif +/** + * Two separate X-carriages with extruders that connect to a moving part + * via a magnetic docking mechanism. Requires SOL1_PIN and SOL2_PIN. + */ +//#define PARKING_EXTRUDER +#if ENABLED(PARKING_EXTRUDER) + #define PARKING_EXTRUDER_SOLENOIDS_INVERT // If enabled, the solenoid is NOT magnetized with applied voltage + #define PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE LOW // LOW or HIGH pin signal energizes the coil + #define PARKING_EXTRUDER_SOLENOIDS_DELAY 250 // Delay (ms) for magnetic field. No delay if 0 or not defined. + #define PARKING_EXTRUDER_PARKING_X { -78, 184 } // X positions for parking the extruders + #define PARKING_EXTRUDER_GRAB_DISTANCE 1 // mm to move beyond the parking point to grab the extruder + #define PARKING_EXTRUDER_SECURITY_RAISE 5 // Z-raise before parking + #define HOTEND_OFFSET_Z { 0.0, 1.3 } // Z-offsets of the two hotends. The first must be 0. +#endif + /** * "Mixing Extruder" * - Adds a new code, M165, to set the current mix factors. diff --git a/Marlin/example_configurations/delta/kossel_xl/Configuration.h b/Marlin/example_configurations/delta/kossel_xl/Configuration.h index 721369da5..ad004dd29 100644 --- a/Marlin/example_configurations/delta/kossel_xl/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_xl/Configuration.h @@ -175,6 +175,21 @@ //#define HOTEND_OFFSET_Z { 0.0, 0.0 } #endif +/** + * Two separate X-carriages with extruders that connect to a moving part + * via a magnetic docking mechanism. Requires SOL1_PIN and SOL2_PIN. + */ +//#define PARKING_EXTRUDER +#if ENABLED(PARKING_EXTRUDER) + #define PARKING_EXTRUDER_SOLENOIDS_INVERT // If enabled, the solenoid is NOT magnetized with applied voltage + #define PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE LOW // LOW or HIGH pin signal energizes the coil + #define PARKING_EXTRUDER_SOLENOIDS_DELAY 250 // Delay (ms) for magnetic field. No delay if 0 or not defined. + #define PARKING_EXTRUDER_PARKING_X { -78, 184 } // X positions for parking the extruders + #define PARKING_EXTRUDER_GRAB_DISTANCE 1 // mm to move beyond the parking point to grab the extruder + #define PARKING_EXTRUDER_SECURITY_RAISE 5 // Z-raise before parking + #define HOTEND_OFFSET_Z { 0.0, 1.3 } // Z-offsets of the two hotends. The first must be 0. +#endif + /** * "Mixing Extruder" * - Adds a new code, M165, to set the current mix factors. diff --git a/Marlin/example_configurations/gCreate/gMax1.5+/Configuration.h b/Marlin/example_configurations/gCreate/gMax1.5+/Configuration.h index bf6104c71..51968f707 100644 --- a/Marlin/example_configurations/gCreate/gMax1.5+/Configuration.h +++ b/Marlin/example_configurations/gCreate/gMax1.5+/Configuration.h @@ -180,6 +180,21 @@ //#define HOTEND_OFFSET_Z { 0.0, 0.0 } #endif +/** + * Two separate X-carriages with extruders that connect to a moving part + * via a magnetic docking mechanism. Requires SOL1_PIN and SOL2_PIN. + */ +//#define PARKING_EXTRUDER +#if ENABLED(PARKING_EXTRUDER) + #define PARKING_EXTRUDER_SOLENOIDS_INVERT // If enabled, the solenoid is NOT magnetized with applied voltage + #define PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE LOW // LOW or HIGH pin signal energizes the coil + #define PARKING_EXTRUDER_SOLENOIDS_DELAY 250 // Delay (ms) for magnetic field. No delay if 0 or not defined. + #define PARKING_EXTRUDER_PARKING_X { -78, 184 } // X positions for parking the extruders + #define PARKING_EXTRUDER_GRAB_DISTANCE 1 // mm to move beyond the parking point to grab the extruder + #define PARKING_EXTRUDER_SECURITY_RAISE 5 // Z-raise before parking + #define HOTEND_OFFSET_Z { 0.0, 1.3 } // Z-offsets of the two hotends. The first must be 0. +#endif + /** * "Mixing Extruder" * - Adds a new code, M165, to set the current mix factors. diff --git a/Marlin/example_configurations/makibox/Configuration.h b/Marlin/example_configurations/makibox/Configuration.h index 3687e17b7..ac060155d 100644 --- a/Marlin/example_configurations/makibox/Configuration.h +++ b/Marlin/example_configurations/makibox/Configuration.h @@ -175,6 +175,21 @@ //#define HOTEND_OFFSET_Z { 0.0, 0.0 } #endif +/** + * Two separate X-carriages with extruders that connect to a moving part + * via a magnetic docking mechanism. Requires SOL1_PIN and SOL2_PIN. + */ +//#define PARKING_EXTRUDER +#if ENABLED(PARKING_EXTRUDER) + #define PARKING_EXTRUDER_SOLENOIDS_INVERT // If enabled, the solenoid is NOT magnetized with applied voltage + #define PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE LOW // LOW or HIGH pin signal energizes the coil + #define PARKING_EXTRUDER_SOLENOIDS_DELAY 250 // Delay (ms) for magnetic field. No delay if 0 or not defined. + #define PARKING_EXTRUDER_PARKING_X { -78, 184 } // X positions for parking the extruders + #define PARKING_EXTRUDER_GRAB_DISTANCE 1 // mm to move beyond the parking point to grab the extruder + #define PARKING_EXTRUDER_SECURITY_RAISE 5 // Z-raise before parking + #define HOTEND_OFFSET_Z { 0.0, 1.3 } // Z-offsets of the two hotends. The first must be 0. +#endif + /** * "Mixing Extruder" * - Adds a new code, M165, to set the current mix factors. diff --git a/Marlin/example_configurations/tvrrug/Round2/Configuration.h b/Marlin/example_configurations/tvrrug/Round2/Configuration.h index 0d9a1532a..3c7c10413 100644 --- a/Marlin/example_configurations/tvrrug/Round2/Configuration.h +++ b/Marlin/example_configurations/tvrrug/Round2/Configuration.h @@ -175,6 +175,21 @@ //#define HOTEND_OFFSET_Z { 0.0, 0.0 } #endif +/** + * Two separate X-carriages with extruders that connect to a moving part + * via a magnetic docking mechanism. Requires SOL1_PIN and SOL2_PIN. + */ +//#define PARKING_EXTRUDER +#if ENABLED(PARKING_EXTRUDER) + #define PARKING_EXTRUDER_SOLENOIDS_INVERT // If enabled, the solenoid is NOT magnetized with applied voltage + #define PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE LOW // LOW or HIGH pin signal energizes the coil + #define PARKING_EXTRUDER_SOLENOIDS_DELAY 250 // Delay (ms) for magnetic field. No delay if 0 or not defined. + #define PARKING_EXTRUDER_PARKING_X { -78, 184 } // X positions for parking the extruders + #define PARKING_EXTRUDER_GRAB_DISTANCE 1 // mm to move beyond the parking point to grab the extruder + #define PARKING_EXTRUDER_SECURITY_RAISE 5 // Z-raise before parking + #define HOTEND_OFFSET_Z { 0.0, 1.3 } // Z-offsets of the two hotends. The first must be 0. +#endif + /** * "Mixing Extruder" * - Adds a new code, M165, to set the current mix factors. diff --git a/Marlin/example_configurations/wt150/Configuration.h b/Marlin/example_configurations/wt150/Configuration.h index 4be73cce1..4db146fe4 100644 --- a/Marlin/example_configurations/wt150/Configuration.h +++ b/Marlin/example_configurations/wt150/Configuration.h @@ -175,6 +175,21 @@ //#define HOTEND_OFFSET_Z { 0.0, 0.0 } #endif +/** + * Two separate X-carriages with extruders that connect to a moving part + * via a magnetic docking mechanism. Requires SOL1_PIN and SOL2_PIN. + */ +//#define PARKING_EXTRUDER +#if ENABLED(PARKING_EXTRUDER) + #define PARKING_EXTRUDER_SOLENOIDS_INVERT // If enabled, the solenoid is NOT magnetized with applied voltage + #define PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE LOW // LOW or HIGH pin signal energizes the coil + #define PARKING_EXTRUDER_SOLENOIDS_DELAY 250 // Delay (ms) for magnetic field. No delay if 0 or not defined. + #define PARKING_EXTRUDER_PARKING_X { -78, 184 } // X positions for parking the extruders + #define PARKING_EXTRUDER_GRAB_DISTANCE 1 // mm to move beyond the parking point to grab the extruder + #define PARKING_EXTRUDER_SECURITY_RAISE 5 // Z-raise before parking + #define HOTEND_OFFSET_Z { 0.0, 1.3 } // Z-offsets of the two hotends. The first must be 0. +#endif + /** * "Mixing Extruder" * - Adds a new code, M165, to set the current mix factors. From 869d7f370324b5d2439ec6ebb92d391127cc02f9 Mon Sep 17 00:00:00 2001 From: GMagician Date: Thu, 17 Aug 2017 21:43:47 +0200 Subject: [PATCH 096/112] #7504 missing part #7504 integration has missed this part. When more than 1 servo is used with bltouch it's impossible to predefine default servo delay for it. In my original fix I completely removed this part but maybe this is a better compromise --- Marlin/Conditionals_LCD.h | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/Marlin/Conditionals_LCD.h b/Marlin/Conditionals_LCD.h index d36931662..69526dec7 100644 --- a/Marlin/Conditionals_LCD.h +++ b/Marlin/Conditionals_LCD.h @@ -376,8 +376,10 @@ #define NUM_SERVOS (Z_ENDSTOP_SERVO_NR + 1) #endif #undef DEACTIVATE_SERVOS_AFTER_MOVE - #undef SERVO_DELAY - #define SERVO_DELAY { 50 } + #if NUM_SERVOS = 1 + #undef SERVO_DELAY + #define SERVO_DELAY { 50 } + #endif #ifndef BLTOUCH_DELAY #define BLTOUCH_DELAY 375 #endif From 405a2132f3ba3fd6dbbd2193434daecef95e664f Mon Sep 17 00:00:00 2001 From: GMagician Date: Thu, 17 Aug 2017 22:04:28 +0200 Subject: [PATCH 097/112] #7529 compile fix I made an error in previous fix --- Marlin/Conditionals_LCD.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/Conditionals_LCD.h b/Marlin/Conditionals_LCD.h index 69526dec7..796caed56 100644 --- a/Marlin/Conditionals_LCD.h +++ b/Marlin/Conditionals_LCD.h @@ -376,7 +376,7 @@ #define NUM_SERVOS (Z_ENDSTOP_SERVO_NR + 1) #endif #undef DEACTIVATE_SERVOS_AFTER_MOVE - #if NUM_SERVOS = 1 + #if NUM_SERVOS == 1 #undef SERVO_DELAY #define SERVO_DELAY { 50 } #endif From b94a1c6b9f05b743bb99344c9934d3c4bf88e31d Mon Sep 17 00:00:00 2001 From: GMagician Date: Fri, 18 Aug 2017 11:11:00 +0200 Subject: [PATCH 098/112] Code reduction this some configurations When switching noozle and extruder but these operations are done by the same servo in 'setup' function there is a unnecessary call --- Marlin/Marlin_main.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index b25cf0097..93a539369 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -13484,7 +13484,7 @@ void setup() { setup_endstop_interrupts(); #endif - #if ENABLED(SWITCHING_EXTRUDER) + #if ENABLED(SWITCHING_EXTRUDER) && !DONT_SWITCH move_extruder_servo(0); // Initialize extruder servo #endif From 6127154af3e76b0b4dc527c5eab075a90f6f48c8 Mon Sep 17 00:00:00 2001 From: GMagician Date: Fri, 18 Aug 2017 11:34:55 +0200 Subject: [PATCH 099/112] Fix identation by tab There was a tab instead of spaces --- Marlin/Conditionals_LCD.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/Conditionals_LCD.h b/Marlin/Conditionals_LCD.h index 796caed56..171ca09ce 100644 --- a/Marlin/Conditionals_LCD.h +++ b/Marlin/Conditionals_LCD.h @@ -379,7 +379,7 @@ #if NUM_SERVOS == 1 #undef SERVO_DELAY #define SERVO_DELAY { 50 } - #endif + #endif #ifndef BLTOUCH_DELAY #define BLTOUCH_DELAY 375 #endif From c0409b85e737e0461dc238705d6e3f31d9261f2b Mon Sep 17 00:00:00 2001 From: Vben Date: Tue, 15 Aug 2017 14:48:10 +0200 Subject: [PATCH 100/112] New feature: Part-Cooling Fan Multiplexer --- .travis.yml | 1 + Marlin/Conditionals_post.h | 5 +++ Marlin/Configuration_adv.h | 11 +++++ Marlin/Marlin_main.cpp | 42 +++++++++++++++++-- Marlin/SanityCheck.h | 10 +++++ .../AlephObjects/TAZ4/Configuration_adv.h | 11 +++++ .../Anet/A6/Configuration_adv.h | 11 +++++ .../Anet/A8/Configuration_adv.h | 11 +++++ .../BQ/Hephestos/Configuration_adv.h | 11 +++++ .../BQ/Hephestos_2/Configuration_adv.h | 11 +++++ .../BQ/WITBOX/Configuration_adv.h | 11 +++++ .../Cartesio/Configuration_adv.h | 11 +++++ .../Felix/Configuration_adv.h | 11 +++++ .../Folger Tech/i3-2020/Configuration_adv.h | 11 +++++ .../Infitary/i3-M508/Configuration_adv.h | 11 +++++ .../Malyan/M150/Configuration_adv.h | 11 +++++ .../RigidBot/Configuration_adv.h | 11 +++++ .../SCARA/Configuration_adv.h | 11 +++++ .../TinyBoy2/Configuration_adv.h | 11 +++++ .../Velleman/K8200/Configuration_adv.h | 11 +++++ .../Velleman/K8400/Configuration_adv.h | 11 +++++ .../FLSUN/auto_calibrate/Configuration_adv.h | 11 +++++ .../FLSUN/kossel_mini/Configuration_adv.h | 11 +++++ .../delta/generic/Configuration_adv.h | 11 +++++ .../delta/kossel_mini/Configuration_adv.h | 11 +++++ .../delta/kossel_pro/Configuration_adv.h | 11 +++++ .../delta/kossel_xl/Configuration_adv.h | 11 +++++ .../gCreate/gMax1.5+/Configuration_adv.h | 11 +++++ .../makibox/Configuration_adv.h | 11 +++++ .../tvrrug/Round2/Configuration_adv.h | 11 +++++ .../wt150/Configuration_adv.h | 11 +++++ Marlin/pins.h | 10 +++++ 32 files changed, 361 insertions(+), 4 deletions(-) diff --git a/.travis.yml b/.travis.yml index b3461a932..bc22a9cb2 100644 --- a/.travis.yml +++ b/.travis.yml @@ -93,6 +93,7 @@ script: - opt_enable_adv FWRETRACT - opt_set ABL_GRID_POINTS_X 16 - opt_set ABL_GRID_POINTS_Y 16 + - opt_set_adv FANMUX0_PIN 53 - build_marlin # # Test a simple build of AUTO_BED_LEVELING_UBL diff --git a/Marlin/Conditionals_post.h b/Marlin/Conditionals_post.h index a98985373..773434962 100644 --- a/Marlin/Conditionals_post.h +++ b/Marlin/Conditionals_post.h @@ -688,6 +688,11 @@ #endif #define WRITE_FAN_N(n, v) WRITE_FAN##n(v) + /** + * Part Cooling fan multipliexer + */ + #define HAS_FANMUX PIN_EXISTS(FANMUX0) + /** * Servos and probes */ diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index fc7865401..beb77165c 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -220,6 +220,17 @@ #define EXTRUDER_AUTO_FAN_TEMPERATURE 50 #define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed +/** + * Part-Cooling Fan Multiplexer + * + * This feature allows you to digitally multiplex the fan output. + * The multiplexer is automatically switched at tool-change. + * Set FANMUX[012]_PINs below for up to 2, 4, or 8 multiplexed fans. + */ +#define FANMUX0_PIN -1 +#define FANMUX1_PIN -1 +#define FANMUX2_PIN -1 + /** * M355 Case Light on-off / brightness */ diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 93a539369..b48d7d27d 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -10271,6 +10271,31 @@ inline void invalid_extruder_error(const uint8_t e) { #endif // PARKING_EXTRUDER +#if HAS_FANMUX + + void fanmux_switch(const uint8_t e) { + WRITE(FANMUX0_PIN, TEST(e, 0) ? HIGH : LOW); + #if PIN_EXISTS(FANMUX1) + WRITE(FANMUX1_PIN, TEST(e, 1) ? HIGH : LOW); + #if PIN_EXISTS(FANMUX2) + WRITE(FANMUX2, TEST(e, 2) ? HIGH : LOW); + #endif + #endif + } + + FORCE_INLINE void fanmux_init(void){ + SET_OUTPUT(FANMUX0_PIN); + #if PIN_EXISTS(FANMUX1) + SET_OUTPUT(FANMUX1_PIN); + #if PIN_EXISTS(FANMUX2) + SET_OUTPUT(FANMUX2_PIN); + #endif + #endif + fanmux_switch(0); + } + +#endif // HAS_FANMUX + /** * Perform a tool-change, which may result in moving the * previous tool out of the way and the new tool into place. @@ -10353,7 +10378,7 @@ void tool_change(const uint8_t tmp_extruder, const float fr_mm_s/*=0.0*/, bool n 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 + // Activate the new extruder ahead of calling set_axis_is_at_home! active_extruder = tmp_extruder; // This function resets the max/min values - the current position may be overwritten below. @@ -10687,14 +10712,19 @@ void tool_change(const uint8_t tmp_extruder, const float fr_mm_s/*=0.0*/, bool n select_multiplexed_stepper(tmp_extruder); #endif + // Set the new active extruder + active_extruder = tmp_extruder; + #endif // HOTENDS <= 1 #if ENABLED(SWITCHING_EXTRUDER) && !DONT_SWITCH stepper.synchronize(); - move_extruder_servo(tmp_extruder); + move_extruder_servo(active_extruder); #endif - active_extruder = tmp_extruder; + #if HAS_FANMUX + fanmux_switch(active_extruder); + #endif SERIAL_ECHO_START(); SERIAL_ECHOLNPAIR(MSG_ACTIVE_EXTRUDER, (int)active_extruder); @@ -13433,7 +13463,11 @@ void setup() { SET_OUTPUT(E_MUX1_PIN); SET_OUTPUT(E_MUX2_PIN); #endif - + + #if HAS_FANMUX + fanmux_init(); + #endif + lcd_init(); #ifndef CUSTOM_BOOTSCREEN_TIMEOUT diff --git a/Marlin/SanityCheck.h b/Marlin/SanityCheck.h index 57128d3f1..79ced8bf8 100644 --- a/Marlin/SanityCheck.h +++ b/Marlin/SanityCheck.h @@ -443,6 +443,16 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE && Y_MAX_LENGTH >= Y_BED_SIZE, #endif #endif +/** + * Part-Cooling Fan Multiplexer requirements + */ +#if PIN_EXISTS(FANMUX1) + #if !HAS_FANMUX + #error "FANMUX0_PIN must be set before FANMUX1_PIN can be set." + #endif +#elif PIN_EXISTS(FANMUX2) + #error "FANMUX0_PIN and FANMUX1_PIN must be set before FANMUX2_PIN can be set." +#endif /** * Limited number of servos diff --git a/Marlin/example_configurations/AlephObjects/TAZ4/Configuration_adv.h b/Marlin/example_configurations/AlephObjects/TAZ4/Configuration_adv.h index 723d3d12e..8c52ba38a 100644 --- a/Marlin/example_configurations/AlephObjects/TAZ4/Configuration_adv.h +++ b/Marlin/example_configurations/AlephObjects/TAZ4/Configuration_adv.h @@ -220,6 +220,17 @@ #define EXTRUDER_AUTO_FAN_TEMPERATURE 50 #define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed +/** + * Part-Cooling Fan Multiplexer + * + * This feature allows you to digitally multiplex the fan output. + * The multiplexer is automatically switched at tool-change. + * Set FANMUX[012]_PINs below for up to 2, 4, or 8 multiplexed fans. + */ +#define FANMUX0_PIN -1 +#define FANMUX1_PIN -1 +#define FANMUX2_PIN -1 + /** * M355 Case Light on-off / brightness */ diff --git a/Marlin/example_configurations/Anet/A6/Configuration_adv.h b/Marlin/example_configurations/Anet/A6/Configuration_adv.h index 24ee3e25c..fbb7573a3 100644 --- a/Marlin/example_configurations/Anet/A6/Configuration_adv.h +++ b/Marlin/example_configurations/Anet/A6/Configuration_adv.h @@ -220,6 +220,17 @@ #define EXTRUDER_AUTO_FAN_TEMPERATURE 50 #define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed +/** + * Part-Cooling Fan Multiplexer + * + * This feature allows you to digitally multiplex the fan output. + * The multiplexer is automatically switched at tool-change. + * Set FANMUX[012]_PINs below for up to 2, 4, or 8 multiplexed fans. + */ +#define FANMUX0_PIN -1 +#define FANMUX1_PIN -1 +#define FANMUX2_PIN -1 + /** * M355 Case Light on-off / brightness */ diff --git a/Marlin/example_configurations/Anet/A8/Configuration_adv.h b/Marlin/example_configurations/Anet/A8/Configuration_adv.h index 0ff1fb0d1..4812733d5 100644 --- a/Marlin/example_configurations/Anet/A8/Configuration_adv.h +++ b/Marlin/example_configurations/Anet/A8/Configuration_adv.h @@ -220,6 +220,17 @@ #define EXTRUDER_AUTO_FAN_TEMPERATURE 50 #define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed +/** + * Part-Cooling Fan Multiplexer + * + * This feature allows you to digitally multiplex the fan output. + * The multiplexer is automatically switched at tool-change. + * Set FANMUX[012]_PINs below for up to 2, 4, or 8 multiplexed fans. + */ +#define FANMUX0_PIN -1 +#define FANMUX1_PIN -1 +#define FANMUX2_PIN -1 + /** * M355 Case Light on-off / brightness */ diff --git a/Marlin/example_configurations/BQ/Hephestos/Configuration_adv.h b/Marlin/example_configurations/BQ/Hephestos/Configuration_adv.h index e2a20f6da..aed6aad19 100644 --- a/Marlin/example_configurations/BQ/Hephestos/Configuration_adv.h +++ b/Marlin/example_configurations/BQ/Hephestos/Configuration_adv.h @@ -220,6 +220,17 @@ #define EXTRUDER_AUTO_FAN_TEMPERATURE 50 #define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed +/** + * Part-Cooling Fan Multiplexer + * + * This feature allows you to digitally multiplex the fan output. + * The multiplexer is automatically switched at tool-change. + * Set FANMUX[012]_PINs below for up to 2, 4, or 8 multiplexed fans. + */ +#define FANMUX0_PIN -1 +#define FANMUX1_PIN -1 +#define FANMUX2_PIN -1 + /** * M355 Case Light on-off / brightness */ diff --git a/Marlin/example_configurations/BQ/Hephestos_2/Configuration_adv.h b/Marlin/example_configurations/BQ/Hephestos_2/Configuration_adv.h index 2e4365a97..b0dbdadba 100644 --- a/Marlin/example_configurations/BQ/Hephestos_2/Configuration_adv.h +++ b/Marlin/example_configurations/BQ/Hephestos_2/Configuration_adv.h @@ -220,6 +220,17 @@ #define EXTRUDER_AUTO_FAN_TEMPERATURE 50 #define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed +/** + * Part-Cooling Fan Multiplexer + * + * This feature allows you to digitally multiplex the fan output. + * The multiplexer is automatically switched at tool-change. + * Set FANMUX[012]_PINs below for up to 2, 4, or 8 multiplexed fans. + */ +#define FANMUX0_PIN -1 +#define FANMUX1_PIN -1 +#define FANMUX2_PIN -1 + /** * M355 Case Light on-off / brightness */ diff --git a/Marlin/example_configurations/BQ/WITBOX/Configuration_adv.h b/Marlin/example_configurations/BQ/WITBOX/Configuration_adv.h index e2a20f6da..aed6aad19 100644 --- a/Marlin/example_configurations/BQ/WITBOX/Configuration_adv.h +++ b/Marlin/example_configurations/BQ/WITBOX/Configuration_adv.h @@ -220,6 +220,17 @@ #define EXTRUDER_AUTO_FAN_TEMPERATURE 50 #define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed +/** + * Part-Cooling Fan Multiplexer + * + * This feature allows you to digitally multiplex the fan output. + * The multiplexer is automatically switched at tool-change. + * Set FANMUX[012]_PINs below for up to 2, 4, or 8 multiplexed fans. + */ +#define FANMUX0_PIN -1 +#define FANMUX1_PIN -1 +#define FANMUX2_PIN -1 + /** * M355 Case Light on-off / brightness */ diff --git a/Marlin/example_configurations/Cartesio/Configuration_adv.h b/Marlin/example_configurations/Cartesio/Configuration_adv.h index b30fdf2ec..6782e070f 100644 --- a/Marlin/example_configurations/Cartesio/Configuration_adv.h +++ b/Marlin/example_configurations/Cartesio/Configuration_adv.h @@ -220,6 +220,17 @@ #define EXTRUDER_AUTO_FAN_TEMPERATURE 35 #define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed +/** + * Part-Cooling Fan Multiplexer + * + * This feature allows you to digitally multiplex the fan output. + * The multiplexer is automatically switched at tool-change. + * Set FANMUX[012]_PINs below for up to 2, 4, or 8 multiplexed fans. + */ +#define FANMUX0_PIN -1 +#define FANMUX1_PIN -1 +#define FANMUX2_PIN -1 + /** * M355 Case Light on-off / brightness */ diff --git a/Marlin/example_configurations/Felix/Configuration_adv.h b/Marlin/example_configurations/Felix/Configuration_adv.h index 706bf132e..638915b91 100644 --- a/Marlin/example_configurations/Felix/Configuration_adv.h +++ b/Marlin/example_configurations/Felix/Configuration_adv.h @@ -220,6 +220,17 @@ #define EXTRUDER_AUTO_FAN_TEMPERATURE 50 #define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed +/** + * Part-Cooling Fan Multiplexer + * + * This feature allows you to digitally multiplex the fan output. + * The multiplexer is automatically switched at tool-change. + * Set FANMUX[012]_PINs below for up to 2, 4, or 8 multiplexed fans. + */ +#define FANMUX0_PIN -1 +#define FANMUX1_PIN -1 +#define FANMUX2_PIN -1 + /** * M355 Case Light on-off / brightness */ diff --git a/Marlin/example_configurations/Folger Tech/i3-2020/Configuration_adv.h b/Marlin/example_configurations/Folger Tech/i3-2020/Configuration_adv.h index c8ee383db..960b1b5f8 100644 --- a/Marlin/example_configurations/Folger Tech/i3-2020/Configuration_adv.h +++ b/Marlin/example_configurations/Folger Tech/i3-2020/Configuration_adv.h @@ -220,6 +220,17 @@ #define EXTRUDER_AUTO_FAN_TEMPERATURE 50 #define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed +/** + * Part-Cooling Fan Multiplexer + * + * This feature allows you to digitally multiplex the fan output. + * The multiplexer is automatically switched at tool-change. + * Set FANMUX[012]_PINs below for up to 2, 4, or 8 multiplexed fans. + */ +#define FANMUX0_PIN -1 +#define FANMUX1_PIN -1 +#define FANMUX2_PIN -1 + /** * M355 Case Light on-off / brightness */ diff --git a/Marlin/example_configurations/Infitary/i3-M508/Configuration_adv.h b/Marlin/example_configurations/Infitary/i3-M508/Configuration_adv.h index 598f44138..751759c30 100644 --- a/Marlin/example_configurations/Infitary/i3-M508/Configuration_adv.h +++ b/Marlin/example_configurations/Infitary/i3-M508/Configuration_adv.h @@ -220,6 +220,17 @@ #define EXTRUDER_AUTO_FAN_TEMPERATURE 50 #define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed +/** + * Part-Cooling Fan Multiplexer + * + * This feature allows you to digitally multiplex the fan output. + * The multiplexer is automatically switched at tool-change. + * Set FANMUX[012]_PINs below for up to 2, 4, or 8 multiplexed fans. + */ +#define FANMUX0_PIN -1 +#define FANMUX1_PIN -1 +#define FANMUX2_PIN -1 + /** * M355 Case Light on-off / brightness */ diff --git a/Marlin/example_configurations/Malyan/M150/Configuration_adv.h b/Marlin/example_configurations/Malyan/M150/Configuration_adv.h index 4cd6f6766..4a7930605 100644 --- a/Marlin/example_configurations/Malyan/M150/Configuration_adv.h +++ b/Marlin/example_configurations/Malyan/M150/Configuration_adv.h @@ -220,6 +220,17 @@ #define EXTRUDER_AUTO_FAN_TEMPERATURE 50 #define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed +/** + * Part-Cooling Fan Multiplexer + * + * This feature allows you to digitally multiplex the fan output. + * The multiplexer is automatically switched at tool-change. + * Set FANMUX[012]_PINs below for up to 2, 4, or 8 multiplexed fans. + */ +#define FANMUX0_PIN -1 +#define FANMUX1_PIN -1 +#define FANMUX2_PIN -1 + /** * M355 Case Light on-off / brightness */ diff --git a/Marlin/example_configurations/RigidBot/Configuration_adv.h b/Marlin/example_configurations/RigidBot/Configuration_adv.h index 1bf040696..8fbd278c7 100644 --- a/Marlin/example_configurations/RigidBot/Configuration_adv.h +++ b/Marlin/example_configurations/RigidBot/Configuration_adv.h @@ -220,6 +220,17 @@ #define EXTRUDER_AUTO_FAN_TEMPERATURE 50 #define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed +/** + * Part-Cooling Fan Multiplexer + * + * This feature allows you to digitally multiplex the fan output. + * The multiplexer is automatically switched at tool-change. + * Set FANMUX[012]_PINs below for up to 2, 4, or 8 multiplexed fans. + */ +#define FANMUX0_PIN -1 +#define FANMUX1_PIN -1 +#define FANMUX2_PIN -1 + /** * M355 Case Light on-off / brightness */ diff --git a/Marlin/example_configurations/SCARA/Configuration_adv.h b/Marlin/example_configurations/SCARA/Configuration_adv.h index 0c7b8b4e3..cab69c2b1 100644 --- a/Marlin/example_configurations/SCARA/Configuration_adv.h +++ b/Marlin/example_configurations/SCARA/Configuration_adv.h @@ -220,6 +220,17 @@ #define EXTRUDER_AUTO_FAN_TEMPERATURE 50 #define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed +/** + * Part-Cooling Fan Multiplexer + * + * This feature allows you to digitally multiplex the fan output. + * The multiplexer is automatically switched at tool-change. + * Set FANMUX[012]_PINs below for up to 2, 4, or 8 multiplexed fans. + */ +#define FANMUX0_PIN -1 +#define FANMUX1_PIN -1 +#define FANMUX2_PIN -1 + /** * M355 Case Light on-off / brightness */ diff --git a/Marlin/example_configurations/TinyBoy2/Configuration_adv.h b/Marlin/example_configurations/TinyBoy2/Configuration_adv.h index 543dcd876..95630746d 100644 --- a/Marlin/example_configurations/TinyBoy2/Configuration_adv.h +++ b/Marlin/example_configurations/TinyBoy2/Configuration_adv.h @@ -220,6 +220,17 @@ #define EXTRUDER_AUTO_FAN_TEMPERATURE 50 #define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed +/** + * Part-Cooling Fan Multiplexer + * + * This feature allows you to digitally multiplex the fan output. + * The multiplexer is automatically switched at tool-change. + * Set FANMUX[012]_PINs below for up to 2, 4, or 8 multiplexed fans. + */ +#define FANMUX0_PIN -1 +#define FANMUX1_PIN -1 +#define FANMUX2_PIN -1 + /** * M355 Case Light on-off / brightness */ diff --git a/Marlin/example_configurations/Velleman/K8200/Configuration_adv.h b/Marlin/example_configurations/Velleman/K8200/Configuration_adv.h index 0960203a6..1a31f5eda 100644 --- a/Marlin/example_configurations/Velleman/K8200/Configuration_adv.h +++ b/Marlin/example_configurations/Velleman/K8200/Configuration_adv.h @@ -233,6 +233,17 @@ #define EXTRUDER_AUTO_FAN_TEMPERATURE 50 #define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed +/** + * Part-Cooling Fan Multiplexer + * + * This feature allows you to digitally multiplex the fan output. + * The multiplexer is automatically switched at tool-change. + * Set FANMUX[012]_PINs below for up to 2, 4, or 8 multiplexed fans. + */ +#define FANMUX0_PIN -1 +#define FANMUX1_PIN -1 +#define FANMUX2_PIN -1 + /** * M355 Case Light on-off / brightness */ diff --git a/Marlin/example_configurations/Velleman/K8400/Configuration_adv.h b/Marlin/example_configurations/Velleman/K8400/Configuration_adv.h index 7a28615d6..998b25bac 100644 --- a/Marlin/example_configurations/Velleman/K8400/Configuration_adv.h +++ b/Marlin/example_configurations/Velleman/K8400/Configuration_adv.h @@ -220,6 +220,17 @@ #define EXTRUDER_AUTO_FAN_TEMPERATURE 50 #define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed +/** + * Part-Cooling Fan Multiplexer + * + * This feature allows you to digitally multiplex the fan output. + * The multiplexer is automatically switched at tool-change. + * Set FANMUX[012]_PINs below for up to 2, 4, or 8 multiplexed fans. + */ +#define FANMUX0_PIN -1 +#define FANMUX1_PIN -1 +#define FANMUX2_PIN -1 + /** * M355 Case Light on-off / brightness */ diff --git a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h index 7b47e138b..3715a421a 100644 --- a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h +++ b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h @@ -220,6 +220,17 @@ #define EXTRUDER_AUTO_FAN_TEMPERATURE 50 #define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed +/** + * Part-Cooling Fan Multiplexer + * + * This feature allows you to digitally multiplex the fan output. + * The multiplexer is automatically switched at tool-change. + * Set FANMUX[012]_PINs below for up to 2, 4, or 8 multiplexed fans. + */ +#define FANMUX0_PIN -1 +#define FANMUX1_PIN -1 +#define FANMUX2_PIN -1 + /** * M355 Case Light on-off / brightness */ diff --git a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h index b48a6f8e6..e4eaec7c4 100644 --- a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h +++ b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h @@ -220,6 +220,17 @@ #define EXTRUDER_AUTO_FAN_TEMPERATURE 50 #define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed +/** + * Part-Cooling Fan Multiplexer + * + * This feature allows you to digitally multiplex the fan output. + * The multiplexer is automatically switched at tool-change. + * Set FANMUX[012]_PINs below for up to 2, 4, or 8 multiplexed fans. + */ +#define FANMUX0_PIN -1 +#define FANMUX1_PIN -1 +#define FANMUX2_PIN -1 + /** * M355 Case Light on-off / brightness */ diff --git a/Marlin/example_configurations/delta/generic/Configuration_adv.h b/Marlin/example_configurations/delta/generic/Configuration_adv.h index b48a6f8e6..e4eaec7c4 100644 --- a/Marlin/example_configurations/delta/generic/Configuration_adv.h +++ b/Marlin/example_configurations/delta/generic/Configuration_adv.h @@ -220,6 +220,17 @@ #define EXTRUDER_AUTO_FAN_TEMPERATURE 50 #define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed +/** + * Part-Cooling Fan Multiplexer + * + * This feature allows you to digitally multiplex the fan output. + * The multiplexer is automatically switched at tool-change. + * Set FANMUX[012]_PINs below for up to 2, 4, or 8 multiplexed fans. + */ +#define FANMUX0_PIN -1 +#define FANMUX1_PIN -1 +#define FANMUX2_PIN -1 + /** * M355 Case Light on-off / brightness */ diff --git a/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h index b48a6f8e6..e4eaec7c4 100644 --- a/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h @@ -220,6 +220,17 @@ #define EXTRUDER_AUTO_FAN_TEMPERATURE 50 #define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed +/** + * Part-Cooling Fan Multiplexer + * + * This feature allows you to digitally multiplex the fan output. + * The multiplexer is automatically switched at tool-change. + * Set FANMUX[012]_PINs below for up to 2, 4, or 8 multiplexed fans. + */ +#define FANMUX0_PIN -1 +#define FANMUX1_PIN -1 +#define FANMUX2_PIN -1 + /** * M355 Case Light on-off / brightness */ diff --git a/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h index 5cdd4aae7..ffabd4eed 100644 --- a/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h @@ -225,6 +225,17 @@ #define EXTRUDER_AUTO_FAN_TEMPERATURE 50 #define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed +/** + * Part-Cooling Fan Multiplexer + * + * This feature allows you to digitally multiplex the fan output. + * The multiplexer is automatically switched at tool-change. + * Set FANMUX[012]_PINs below for up to 2, 4, or 8 multiplexed fans. + */ +#define FANMUX0_PIN -1 +#define FANMUX1_PIN -1 +#define FANMUX2_PIN -1 + /** * M355 Case Light on-off / brightness */ diff --git a/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h index 4816afd25..57dc10197 100644 --- a/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h @@ -220,6 +220,17 @@ #define EXTRUDER_AUTO_FAN_TEMPERATURE 50 #define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed +/** + * Part-Cooling Fan Multiplexer + * + * This feature allows you to digitally multiplex the fan output. + * The multiplexer is automatically switched at tool-change. + * Set FANMUX[012]_PINs below for up to 2, 4, or 8 multiplexed fans. + */ +#define FANMUX0_PIN -1 +#define FANMUX1_PIN -1 +#define FANMUX2_PIN -1 + /** * M355 Case Light on-off / brightness */ diff --git a/Marlin/example_configurations/gCreate/gMax1.5+/Configuration_adv.h b/Marlin/example_configurations/gCreate/gMax1.5+/Configuration_adv.h index 54b75428a..b6df0fe5e 100644 --- a/Marlin/example_configurations/gCreate/gMax1.5+/Configuration_adv.h +++ b/Marlin/example_configurations/gCreate/gMax1.5+/Configuration_adv.h @@ -220,6 +220,17 @@ #define EXTRUDER_AUTO_FAN_TEMPERATURE 50 #define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed +/** + * Part-Cooling Fan Multiplexer + * + * This feature allows you to digitally multiplex the fan output. + * The multiplexer is automatically switched at tool-change. + * Set FANMUX[012]_PINs below for up to 2, 4, or 8 multiplexed fans. + */ +#define FANMUX0_PIN -1 +#define FANMUX1_PIN -1 +#define FANMUX2_PIN -1 + /** * M355 Case Light on-off / brightness */ diff --git a/Marlin/example_configurations/makibox/Configuration_adv.h b/Marlin/example_configurations/makibox/Configuration_adv.h index 82fe99679..2e755a1ec 100644 --- a/Marlin/example_configurations/makibox/Configuration_adv.h +++ b/Marlin/example_configurations/makibox/Configuration_adv.h @@ -220,6 +220,17 @@ #define EXTRUDER_AUTO_FAN_TEMPERATURE 50 #define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed +/** + * Part-Cooling Fan Multiplexer + * + * This feature allows you to digitally multiplex the fan output. + * The multiplexer is automatically switched at tool-change. + * Set FANMUX[012]_PINs below for up to 2, 4, or 8 multiplexed fans. + */ +#define FANMUX0_PIN -1 +#define FANMUX1_PIN -1 +#define FANMUX2_PIN -1 + /** * M355 Case Light on-off / brightness */ diff --git a/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h b/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h index 7a61aff1f..fc07c0456 100644 --- a/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h +++ b/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h @@ -220,6 +220,17 @@ #define EXTRUDER_AUTO_FAN_TEMPERATURE 50 #define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed +/** + * Part-Cooling Fan Multiplexer + * + * This feature allows you to digitally multiplex the fan output. + * The multiplexer is automatically switched at tool-change. + * Set FANMUX[012]_PINs below for up to 2, 4, or 8 multiplexed fans. + */ +#define FANMUX0_PIN -1 +#define FANMUX1_PIN -1 +#define FANMUX2_PIN -1 + /** * M355 Case Light on-off / brightness */ diff --git a/Marlin/example_configurations/wt150/Configuration_adv.h b/Marlin/example_configurations/wt150/Configuration_adv.h index bed6afd6b..d8f6c3a3b 100644 --- a/Marlin/example_configurations/wt150/Configuration_adv.h +++ b/Marlin/example_configurations/wt150/Configuration_adv.h @@ -220,6 +220,17 @@ #define EXTRUDER_AUTO_FAN_TEMPERATURE 50 #define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed +/** + * Part-Cooling Fan Multiplexer + * + * This feature allows you to digitally multiplex the fan output. + * The multiplexer is automatically switched at tool-change. + * Set FANMUX[012]_PINs below for up to 2, 4, or 8 multiplexed fans. + */ +#define FANMUX0_PIN -1 +#define FANMUX1_PIN -1 +#define FANMUX2_PIN -1 + /** * M355 Case Light on-off / brightness */ diff --git a/Marlin/pins.h b/Marlin/pins.h index 867b5ac25..c3fcf6c7c 100644 --- a/Marlin/pins.h +++ b/Marlin/pins.h @@ -245,6 +245,16 @@ #define CONTROLLER_FAN_PIN -1 #endif +#ifndef FANMUX0_PIN + #define FANMUX0_PIN -1 +#endif +#ifndef FANMUX1_PIN + #define FANMUX1_PIN -1 +#endif +#ifndef FANMUX2_PIN + #define FANMUX2_PIN -1 +#endif + #ifndef HEATER_0_PIN #define HEATER_0_PIN -1 #endif From e337df2e985c11734ec4d98b3b5858e6dc9b6a2a Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 21 Aug 2017 16:30:08 -0500 Subject: [PATCH 101/112] Miscellaneous tweaks to serial outputs, code cleanups --- Marlin/Marlin_main.cpp | 5 +++-- Marlin/configuration_store.cpp | 4 ++-- Marlin/pinsDebug.h | 5 ++++- Marlin/temperature.cpp | 2 +- 4 files changed, 10 insertions(+), 6 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 93a539369..8b38ecdf1 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -13324,6 +13324,7 @@ void setup() { SERIAL_ECHOPGM(MSG_CONFIGURATION_VER); SERIAL_ECHOPGM(STRING_DISTRIBUTION_DATE); SERIAL_ECHOLNPGM(MSG_AUTHOR STRING_CONFIG_H_AUTHOR); + SERIAL_ECHO_START(); SERIAL_ECHOLNPGM("Compiled: " __DATE__); #endif @@ -13491,12 +13492,12 @@ void setup() { #if ENABLED(SWITCHING_NOZZLE) move_nozzle_servo(0); // Initialize nozzle servo #endif - + #if ENABLED(PARKING_EXTRUDER) #if ENABLED(PARKING_EXTRUDER_SOLENOIDS_INVERT) pe_activate_magnet(0); pe_activate_magnet(1); - #else + #else pe_deactivate_magnet(0); pe_deactivate_magnet(1); #endif diff --git a/Marlin/configuration_store.cpp b/Marlin/configuration_store.cpp index 06e6bfea6..5ebbe85fb 100644 --- a/Marlin/configuration_store.cpp +++ b/Marlin/configuration_store.cpp @@ -659,7 +659,7 @@ void MarlinSettings::postprocess() { #if ENABLED(EEPROM_CHITCHAT) SERIAL_ECHO_START(); SERIAL_ECHOPAIR("Settings Stored (", eeprom_size - (EEPROM_OFFSET)); - SERIAL_ECHOPAIR(" bytes; crc ", final_crc); + SERIAL_ECHOPAIR(" bytes; crc ", (uint32_t)final_crc); SERIAL_ECHOLNPGM(")"); #endif } @@ -1010,7 +1010,7 @@ void MarlinSettings::postprocess() { SERIAL_ECHO_START(); SERIAL_ECHO(version); SERIAL_ECHOPAIR(" stored settings retrieved (", eeprom_index - (EEPROM_OFFSET)); - SERIAL_ECHOPAIR(" bytes; crc ", working_crc); + SERIAL_ECHOPAIR(" bytes; crc ", (uint32_t)working_crc); SERIAL_ECHOLNPGM(")"); #endif } diff --git a/Marlin/pinsDebug.h b/Marlin/pinsDebug.h index d1390e740..56f0916d2 100644 --- a/Marlin/pinsDebug.h +++ b/Marlin/pinsDebug.h @@ -272,7 +272,10 @@ const volatile uint8_t* const PWM_OCR[][3] PROGMEM = { static void err_is_counter() { SERIAL_PROTOCOLPGM(" non-standard PWM mode"); } static void err_is_interrupt() { SERIAL_PROTOCOLPGM(" compare interrupt enabled"); } static void err_prob_interrupt() { SERIAL_PROTOCOLPGM(" overflow interrupt enabled"); } -static void print_is_also_tied() { SERIAL_PROTOCOLPGM(" is also tied to this pin"); SERIAL_PROTOCOL_SP(14); } + +#if AVR_ATmega2560_FAMILY || AVR_AT90USB1286_FAMILY + static void print_is_also_tied() { SERIAL_PROTOCOLPGM(" is also tied to this pin"); SERIAL_PROTOCOL_SP(14); } +#endif void com_print(uint8_t N, uint8_t Z) { const uint8_t *TCCRA = (uint8_t*)TCCR_A(N); diff --git a/Marlin/temperature.cpp b/Marlin/temperature.cpp index bf757cef6..261e12cff 100644 --- a/Marlin/temperature.cpp +++ b/Marlin/temperature.cpp @@ -1559,7 +1559,7 @@ void Temperature::set_current_temp_raw() { if (endstop_change) { #if HAS_X_MIN - if (TEST(endstop_change, X_MIN)) SERIAL_PROTOCOLPAIR("X_MIN:", !!TEST(current_endstop_bits_local, 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)); From d29bf49b667b2209b0e526a867badc5fb572b0e6 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 19 Aug 2017 20:04:41 -0500 Subject: [PATCH 102/112] Add Sanguino 644p to ENV for PlatformIO --- platformio.ini | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/platformio.ini b/platformio.ini index 3b05bc566..3d7cff483 100644 --- a/platformio.ini +++ b/platformio.ini @@ -74,3 +74,9 @@ framework = arduino board = sanguino_atmega1284p upload_speed = 57600 lib_deps = ${common.lib_deps} + +[env:sanguino_atmega644p] +platform = atmelavr +framework = arduino +board = sanguino_atmega644p +lib_deps = ${common.lib_deps} From 11a724d8fc3eb51c271b540be4bf90a289eae2ae Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 23 Aug 2017 17:46:33 -0500 Subject: [PATCH 103/112] Sanguinololu example configuration --- .../Sanguinololu/Configuration.h | 1688 +++++++++++++++++ .../Sanguinololu/Configuration_adv.h | 1374 ++++++++++++++ 2 files changed, 3062 insertions(+) create mode 100644 Marlin/example_configurations/Sanguinololu/Configuration.h create mode 100644 Marlin/example_configurations/Sanguinololu/Configuration_adv.h diff --git a/Marlin/example_configurations/Sanguinololu/Configuration.h b/Marlin/example_configurations/Sanguinololu/Configuration.h new file mode 100644 index 000000000..44077d74a --- /dev/null +++ b/Marlin/example_configurations/Sanguinololu/Configuration.h @@ -0,0 +1,1688 @@ +/** + * 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 . + * + */ + +/** + * Configuration.h + * + * Basic settings such as: + * + * - Type of electronics + * - Type of temperature sensor + * - Printer geometry + * - Endstop configuration + * - LCD controller + * - Extra features + * + * Advanced settings can be found in Configuration_adv.h + * + */ +#ifndef CONFIGURATION_H +#define CONFIGURATION_H +#define CONFIGURATION_H_VERSION 010100 + +//=========================================================================== +//============================= Getting Started ============================= +//=========================================================================== + +/** + * Here are some standard links for getting your machine calibrated: + * + * http://reprap.org/wiki/Calibration + * http://youtu.be/wAL9d7FgInk + * http://calculator.josefprusa.cz + * http://reprap.org/wiki/Triffid_Hunter%27s_Calibration_Guide + * http://www.thingiverse.com/thing:5573 + * https://sites.google.com/site/repraplogphase/calibration-of-your-reprap + * http://www.thingiverse.com/thing:298812 + */ + +//=========================================================================== +//============================= DELTA Printer =============================== +//=========================================================================== +// For a Delta printer start with one of the configuration files in the +// example_configurations/delta directory and customize for your machine. +// + +//=========================================================================== +//============================= SCARA Printer =============================== +//=========================================================================== +// For a SCARA printer start with the configuration files in +// example_configurations/SCARA and customize for your machine. +// + +// @section info + +// User-specified version info of this build to display in [Pronterface, etc] terminal window during +// startup. Implementation of an idea by Prof Braino to inform user that any changes made to this +// build by the user have been successfully uploaded into firmware. +#define STRING_CONFIG_H_AUTHOR "(thinkyhead, Sanguinololu)" // Who made the changes. +#define SHOW_BOOTSCREEN +#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 ***************************************************** +// +// Marlin now allow you to have a vendor boot image to be displayed on machine +// start. When SHOW_CUSTOM_BOOTSCREEN is defined Marlin will first show your +// custom boot image and then the default Marlin boot image is shown. +// +// We suggest for you to take advantage of this new feature and keep the Marlin +// boot image unmodified. For an example have a look at the bq Hephestos 2 +// example configuration folder. +// +//#define SHOW_CUSTOM_BOOTSCREEN +// @section machine + +/** + * 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 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 +//#define BLUETOOTH + +// The following define selects which electronics board you have. +// Please choose the name from boards.h that matches your setup +#ifndef MOTHERBOARD + #define MOTHERBOARD BOARD_SANGUINOLOLU_12 +#endif + +// Optional custom name for your RepStrap or other custom machine +// Displayed in the LCD "Ready" message +#define CUSTOM_MACHINE_NAME "Sanguinololu" + +// 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 "00000000-0000-0000-0000-000000000000" + +// @section extruder + +// This defines the number of extruders +// :[1, 2, 3, 4, 5] +#define EXTRUDERS 1 + +// For Cyclops or any "multi-extruder" that shares a single nozzle. +//#define SINGLENOZZLE + +/** + * Průša MK2 Single Nozzle Multi-Material Multiplexer, and variants. + * + * This device allows one stepper driver on a control board to drive + * two to eight stepper motors, one at a time, in a manner suitable + * for extruders. + * + * This option only allows the multiplexer to switch on tool-change. + * Additional options to configure custom E moves are pending. + */ +//#define MK2_MULTIPLEXER +#if ENABLED(MK2_MULTIPLEXER) + // Override the default DIO selector pins here, if needed. + // Some pins files may provide defaults for these pins. + //#define E_MUX0_PIN 40 // Always Required + //#define E_MUX1_PIN 42 // Needed for 3 to 8 steppers + //#define E_MUX2_PIN 44 // Needed for 5 to 8 steppers +#endif + +// A dual extruder that uses a single stepper motor +//#define SWITCHING_EXTRUDER +#if ENABLED(SWITCHING_EXTRUDER) + #define SWITCHING_EXTRUDER_SERVO_NR 0 + #define SWITCHING_EXTRUDER_SERVO_ANGLES { 0, 90 } // Angles for E0, E1[, E2, E3] + #if EXTRUDERS > 3 + #define SWITCHING_EXTRUDER_E23_SERVO_NR 1 + #endif +#endif + +// A dual-nozzle that uses a servomotor to raise/lower one of the nozzles +//#define SWITCHING_NOZZLE +#if ENABLED(SWITCHING_NOZZLE) + #define SWITCHING_NOZZLE_SERVO_NR 0 + #define SWITCHING_NOZZLE_SERVO_ANGLES { 0, 90 } // Angles for E0, E1 + //#define HOTEND_OFFSET_Z { 0.0, 0.0 } +#endif + +/** + * Two separate X-carriages with extruders that connect to a moving part + * via a magnetic docking mechanism. Requires SOL1_PIN and SOL2_PIN. + */ +//#define PARKING_EXTRUDER +#if ENABLED(PARKING_EXTRUDER) + #define PARKING_EXTRUDER_SOLENOIDS_INVERT // If enabled, the solenoid not magnetized with applied voltage + #define PARKING_EXTRUDER_SOLENOIDS_PINS_ACTIVE LOW // LOW or HIGH pin signal energizes the coil + #define PARKING_EXTRUDER_SOLENOIDS_DELAY 250 // Delay (ms) for magnetic field. No delay if 0 or not defined. + #define PARKING_EXTRUDER_PARKING_X { -78, 184 } // X positions for parking the extruders + #define PARKING_EXTRUDER_GRAB_DISTANCE 1 // mm to move beyond the parking point to grab the extruder + #define PARKING_EXTRUDER_SECURITY_RAISE 5 // Z-raise before parking + #define HOTEND_OFFSET_Z { 0.0, 1.3 } // Z-offsets of the two hotends. The first must be 0. +#endif + +/** + * "Mixing Extruder" + * - Adds a new code, M165, to set the current mix factors. + * - Extends the stepping routines to move multiple steppers in proportion to the mix. + * - Optional support for Repetier Firmware M163, M164, and virtual extruder. + * - This implementation supports only a single extruder. + * - Enable DIRECT_MIXING_IN_G1 for Pia Taubert's reference implementation + */ +//#define MIXING_EXTRUDER +#if ENABLED(MIXING_EXTRUDER) + #define MIXING_STEPPERS 2 // Number of steppers in your mixing extruder + #define MIXING_VIRTUAL_TOOLS 16 // Use the Virtual Tool method with M163 and M164 + //#define DIRECT_MIXING_IN_G1 // Allow ABCDHI mix factors in G1 movement commands +#endif + +// Offset of the extruders (uncomment if using more than one and relying on firmware to position when changing). +// The offset has to be X=0, Y=0 for the extruder 0 hotend (default extruder). +// For the other hotends it is their distance from the extruder 0 hotend. +//#define 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 + +// @section machine + +/** + * 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 + +#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 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 + * 75 : 100k Generic Silicon Heat Pad with NTC 100K MGB18-104F39050L32 thermistor + * + * 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_4 0 +#define TEMP_SENSOR_BED 1 + +// 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 + +// Extruder temperature must be close to target for this long before M109 returns success +#define TEMP_RESIDENCY_TIME 10 // (seconds) +#define TEMP_HYSTERESIS 3 // (degC) range of +/- temperatures considered "close" to the target one +#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 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. + +// The minimal temperature defines the temperature below which the heater will not be enabled It is used +// to check that the wiring to the thermistor is not broken. +// Otherwise this would lead to the heater being powered on all the time. +#define HEATER_0_MINTEMP 5 +#define HEATER_1_MINTEMP 5 +#define HEATER_2_MINTEMP 5 +#define HEATER_3_MINTEMP 5 +#define HEATER_4_MINTEMP 5 +#define BED_MINTEMP 5 + +// When temperature exceeds max temp, your heater will be switched off. +// This feature exists to protect your hotend from overheating accidentally, but *NOT* from thermistor short/failure! +// You should use MINTEMP for thermistor short/failure protection. +#define HEATER_0_MAXTEMP 275 +#define HEATER_1_MAXTEMP 275 +#define HEATER_2_MAXTEMP 275 +#define HEATER_3_MAXTEMP 275 +#define HEATER_4_MAXTEMP 275 +#define BED_MAXTEMP 150 + +//=========================================================================== +//============================= PID Settings ================================ +//=========================================================================== +// PID Tuning Guide here: http://reprap.org/wiki/PID_Tuning + +// Comment the following line to disable PID and enable bang-bang. +#define PIDTEMP +#define BANG_MAX 255 // limits current to nozzle while in bang-bang mode; 255=full current +#define PID_MAX BANG_MAX // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 255=full current +#if ENABLED(PIDTEMP) + //#define PID_AUTOTUNE_MENU // Add PID Autotune to the LCD "Temperature" menu to run M303 and apply the result. + //#define PID_DEBUG // Sends debug data to the serial port. + //#define PID_OPENLOOP 1 // Puts PID in open loop. M104/M140 sets the output power from 0 to PID_MAX + //#define SLOW_PWM_HEATERS // PWM with very low frequency (roughly 0.125Hz=8s) and minimum state time of approximately 1s useful for heaters driven by a relay + //#define PID_PARAMS_PER_HOTEND // Uses separate PID parameters for each extruder (useful for mismatched extruders) + // 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 K1 0.95 //smoothing factor within the PID + + // If you are using a pre-configured hotend then you can use one of the value sets by uncommenting it + + // Ultimaker + #define DEFAULT_Kp 22.2 + #define DEFAULT_Ki 1.08 + #define DEFAULT_Kd 114 + + // MakerGear + //#define DEFAULT_Kp 7.0 + //#define DEFAULT_Ki 0.1 + //#define DEFAULT_Kd 12 + + // Mendel Parts V9 on 12V + //#define DEFAULT_Kp 63.0 + //#define DEFAULT_Ki 2.25 + //#define DEFAULT_Kd 440 + +#endif // PIDTEMP + +//=========================================================================== +//============================= PID > Bed Temperature Control =============== +//=========================================================================== +// Select PID or bang-bang with PIDTEMPBED. If bang-bang, BED_LIMIT_SWITCHING will enable hysteresis +// +// Uncomment this to enable PID on the bed. It uses the same frequency PWM as the extruder. +// If your PID_dT is the default, and correct for your hardware/configuration, that means 7.689Hz, +// which is fine for driving a square wave into a resistive load and does not significantly impact you FET heating. +// This also works fine on a Fotek SSR-10DA Solid State Relay into a 250W heater. +// If your configuration is significantly different than this and you don't understand the issues involved, you probably +// shouldn't use bed PID until someone else verifies your hardware works. +// If this is enabled, find your own PID constants below. +//#define PIDTEMPBED + +//#define BED_LIMIT_SWITCHING + +// This sets the max power delivered to the bed, and replaces the HEATER_BED_DUTY_CYCLE_DIVIDER option. +// all forms of bed control obey this (PID, bang-bang, bang-bang with hysteresis) +// setting this to anything other than 255 enables a form of PWM to the bed just like HEATER_BED_DUTY_CYCLE_DIVIDER did, +// so you shouldn't use it unless you are OK with PWM on your bed. (see the comment on enabling PIDTEMPBED) +#define MAX_BED_POWER 255 // limits duty cycle to bed; 255=full current + +#if ENABLED(PIDTEMPBED) + + //#define PID_BED_DEBUG // Sends debug data to the serial port. + + //120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+) + //from FOPDT model - kp=.39 Tp=405 Tdead=66, Tc set to 79.2, aggressive factor of .15 (vs .1, 1, 10) + #define DEFAULT_bedKp 10.00 + #define DEFAULT_bedKi .023 + #define DEFAULT_bedKd 305.4 + + //120V 250W silicone heater into 4mm borosilicate (MendelMax 1.5+) + //from pidautotune + //#define DEFAULT_bedKp 97.1 + //#define DEFAULT_bedKi 1.41 + //#define DEFAULT_bedKd 1675.16 + + // FIND YOUR OWN: "M303 E-1 C8 S90" to run autotune on the bed at 90 degreesC for 8 cycles. +#endif // PIDTEMPBED + +// @section extruder + +// 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 + +// 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 ======================= +//=========================================================================== + +/** + * Thermal Protection protects your printer from damage and fire if a + * thermistor falls out or temperature sensors fail in any way. + * + * The issue: If a thermistor falls out or a temperature sensor fails, + * Marlin can no longer sense the actual temperature. Since a disconnected + * thermistor reads as a low temperature, the firmware will keep the heater on. + * + * If you get "Thermal Runaway" or "Heating failed" errors the + * details can be tuned in Configuration_adv.h + */ + +#define THERMAL_PROTECTION_HOTENDS // Enable thermal protection for all extruders +#define THERMAL_PROTECTION_BED // Enable thermal protection for the heated bed + +//=========================================================================== +//============================= Mechanical Settings ========================= +//=========================================================================== + +// @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 + +//=========================================================================== +//============================== Endstop Settings =========================== +//=========================================================================== + +// @section homing + +// Specify here all the endstop connectors that are connected to any endstop or probe. +// Almost all printers will be using one per axis. Probes will use one or more of the +// extra connectors. Leave undefined any used for non-endstop and non-probe purposes. +#define USE_XMIN_PLUG +#define USE_YMIN_PLUG +#define USE_ZMIN_PLUG +//#define USE_XMAX_PLUG +//#define USE_YMAX_PLUG +//#define USE_ZMAX_PLUG + +// coarse Endstop Settings +#define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors + +#if DISABLED(ENDSTOPPULLUPS) + // fine endstop settings: Individual pullups. will be ignored if ENDSTOPPULLUPS is defined + //#define ENDSTOPPULLUP_XMAX + //#define ENDSTOPPULLUP_YMAX + //#define ENDSTOPPULLUP_ZMAX + //#define ENDSTOPPULLUP_XMIN + //#define ENDSTOPPULLUP_YMIN + //#define ENDSTOPPULLUP_ZMIN + //#define ENDSTOPPULLUP_ZMIN_PROBE +#endif + +// Mechanical endstop with COM to ground and NC to Signal uses "false" here (most common setup). +#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 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 probe. + +// 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 + * + * Note that if EEPROM is enabled, saved values will override these. + */ + +// +// Standard NEMA 17 with T2 belt and 20 tooth pulley +// +#define NEMA17_FULL_STEPS 200.0 +#define XY_MICROSTEPS 16.0 +#define E_MICROSTEPS 16.0 +#define Z_MICROSTEPS 16.0 + +#define XY_PULLEY_PITCH 2.0 +#define XY_PULLEY_TEETH 20.0 + +// +// Standard NEMA 17 with fancy 2mm lead screws +// +#define Z_RODS_PITCH 0.5 + +#define XY_MOTOR_STEPS (NEMA17_FULL_STEPS * XY_MICROSTEPS) +#define Z_MOTOR_STEPS (NEMA17_FULL_STEPS * Z_MICROSTEPS) +#define E_MOTOR_STEPS (NEMA17_FULL_STEPS * E_MICROSTEPS) + +// +// MK7 Direct Drive +// +#define MK7_GEAR_DIAM 10.56 +#define MK7_GEAR_CIRC (M_PI * MK7_GEAR_DIAM) +#define E_STEPS (E_MOTOR_STEPS / MK7_GEAR_CIRC) + +// Get steps/mm from selected results above +#define XY_STEPS (XY_MOTOR_STEPS / (XY_PULLEY_PITCH * XY_PULLEY_TEETH)) +#define Z_STEPS (Z_MOTOR_STEPS / Z_RODS_PITCH) + +/** + * With this option each E stepper can have its own factors for the + * following movement settings. If fewer factors are given than the + * total number of extruders, the last value applies to the rest. + */ +//#define DISTINCT_E_FACTORS + +/** + * Default Axis Steps Per Unit (steps/mm) + * Override with M92 + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] + */ +#define DEFAULT_AXIS_STEPS_PER_UNIT { XY_STEPS, XY_STEPS, Z_STEPS, E_STEPS } + +/** + * Default Max Feed Rate (mm/s) + * Override with M203 + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] + */ +#define DEFAULT_MAX_FEEDRATE { 500, 500, 8, 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[, E4]]]] + */ +#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) + * Override with M205 X Y Z E + * + * "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 + +// +// See http://marlinfw.org/configuration/probes.html +// + +/** + * Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN + * + * Enable this option for a probe connected to the Z Min endstop pin. + */ +#define Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN + +/** + * Z_MIN_PROBE_ENDSTOP + * + * Enable this option for a probe connected to any pin except Z-Min. + * (By default Marlin assumes the Z-Max endstop pin.) + * To use a custom Z Probe pin, set Z_MIN_PROBE_PIN below. + * + * - The simplest option is to use a free endstop connector. + * - Use 5V for powered (usually inductive) sensors. + * + * - RAMPS 1.3/1.4 boards may use the 5V, GND, and Aux4->D32 pin: + * - For simple switches connect... + * - normally-closed switches to GND and D32. + * - normally-open switches to 5V and D32. + * + * WARNING: Setting the wrong pin may have unexpected and potentially + * disastrous consequences. Use with caution and do your homework. + * + */ +//#define Z_MIN_PROBE_ENDSTOP + +/** + * Probe Type + * + * Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, etc. + * Activate one of these to use Auto Bed Leveling below. + */ + +/** + * The "Manual Probe" provides a means to do "Auto" Bed Leveling without a probe. + * Use G29 repeatedly, adjusting the Z height at each point with movement commands + * or (with LCD_BED_LEVELING) the LCD controller. + */ +//#define PROBE_MANUALLY + +/** + * A Fix-Mounted Probe either doesn't deploy or needs manual deployment. + * (e.g., an inductive probe or a nozzle-based probe-switch.) + */ +//#define FIX_MOUNTED_PROBE + +/** + * Z Servo Probe, such as an endstop switch on a rotating arm. + */ +//#define Z_ENDSTOP_SERVO_NR 0 // Defaults to SERVO 0 connector. +//#define Z_SERVO_ANGLES {70,0} // Z Servo Deploy and Stow angles + +/** + * The BLTouch probe uses a Hall effect sensor and emulates a servo. + */ +//#define BLTOUCH +#if ENABLED(BLTOUCH) + //#define BLTOUCH_DELAY 375 // (ms) Enable and increase if needed +#endif + +/** + * Enable one or more of the following if probing seems unreliable. + * Heaters and/or fans can be disabled during probing to minimize electrical + * noise. A delay can also be added to allow noise and vibration to settle. + * These options are most useful for the BLTouch probe, but may also improve + * readings with inductive probes and piezo sensors. + */ +//#define PROBING_HEATERS_OFF // Turn heaters off when probing +//#define PROBING_FANS_OFF // Turn fans off when probing +//#define DELAY_BEFORE_PROBING 200 // (ms) To prevent vibrations from triggering piezo sensors + +// A probe that is deployed and stowed with a solenoid pin (SOL1_PIN) +//#define SOLENOID_PROBE + +// A sled-mounted probe like those designed by Charles Bell. +//#define Z_PROBE_SLED +//#define SLED_DOCKING_OFFSET 5 // The extra distance the X axis must travel to pickup the sled. 0 should be fine but you can push it further if you'd like. + +// +// For Z_PROBE_ALLEN_KEY see the Delta example configurations. +// + +/** + * Z Probe to nozzle (X,Y) offset, relative to (0, 0). + * X and Y offsets must be integers. + * + * In the following example the X and Y offsets are both positive: + * #define X_PROBE_OFFSET_FROM_EXTRUDER 10 + * #define Y_PROBE_OFFSET_FROM_EXTRUDER 10 + * + * +-- BACK ---+ + * | | + * L | (+) P | R <-- probe (20,20) + * E | | I + * F | (-) N (+) | G <-- nozzle (10,10) + * T | | H + * | (-) | T + * | | + * O-- FRONT --+ + * (0,0) + */ +#define X_PROBE_OFFSET_FROM_EXTRUDER 10 // X offset: -left +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 + +// Speed for the first approach when double-probing (with PROBE_DOUBLE_TOUCH) +#define Z_PROBE_SPEED_FAST HOMING_FEEDRATE_Z + +// Speed for the "accurate" probe of each point +#define Z_PROBE_SPEED_SLOW (Z_PROBE_SPEED_FAST / 2) + +// Use double touch for probing +//#define PROBE_DOUBLE_TOUCH + +/** + * 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 +#define Z_PROBE_OFFSET_RANGE_MIN -20 +#define Z_PROBE_OFFSET_RANGE_MAX 20 + +// Enable the M48 repeatability test to test probe accuracy +//#define Z_MIN_PROBE_REPEATABILITY_TEST + +// For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1 +// :{ 0:'Low', 1:'High' } +#define X_ENABLE_ON 0 +#define Y_ENABLE_ON 0 +#define Z_ENABLE_ON 0 +#define E_ENABLE_ON 0 // For all extruders + +// Disables axis stepper immediately when it's not being used. +// 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 +// Warn on display about possibly reduced accuracy +//#define DISABLE_REDUCED_ACCURACY_WARNING + +// @section extruder + +#define DISABLE_E false // For all extruders +#define DISABLE_INACTIVE_EXTRUDER true // Keep only the active extruder enabled. + +// @section machine + +// 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 +#define INVERT_Z_DIR false + +// Enable this option for Toshiba stepper drivers +//#define CONFIG_STEPPERS_TOSHIBA + +// @section extruder + +// For direct drive extruder v9 set to true, for geared extruder set to false. +#define INVERT_E0_DIR false +#define INVERT_E1_DIR false +#define INVERT_E2_DIR false +#define INVERT_E3_DIR false +#define INVERT_E4_DIR false + +// @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. + +// Direction of endstops when homing; 1=MAX, -1=MIN +// :[-1,1] +#define X_HOME_DIR -1 +#define Y_HOME_DIR -1 +#define Z_HOME_DIR -1 + +// @section machine + +// The size of the print bed +#define X_BED_SIZE 200 +#define Y_BED_SIZE 200 + +// Travel limits (mm) after homing, corresponding to endstop positions. +#define X_MIN_POS 0 +#define Y_MIN_POS 0 +#define Z_MIN_POS 0 +#define X_MAX_POS X_BED_SIZE +#define Y_MAX_POS Y_BED_SIZE +#define Z_MAX_POS 170 + +// If enabled, axes won't move below MIN_POS in response to movement commands. +#define MIN_SOFTWARE_ENDSTOPS +// If enabled, axes won't move above MAX_POS in response to movement commands. +#define MAX_SOFTWARE_ENDSTOPS + +/** + * Filament Runout Sensor + * A mechanical or opto endstop is used to check for the presence of filament. + * + * RAMPS-based boards use SERVO3_PIN. + * For other boards you may need to define FIL_RUNOUT_PIN. + * By default the firmware assumes HIGH = has filament, LOW = ran out + */ +//#define FILAMENT_RUNOUT_SENSOR +#if ENABLED(FILAMENT_RUNOUT_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 + +//=========================================================================== +//=============================== Bed Leveling ============================== +//=========================================================================== +// @section bedlevel + +/** + * Choose one of the options below to enable G29 Bed Leveling. The parameters + * and behavior of G29 will change depending on your selection. + * + * If using a Probe for Z Homing, enable Z_SAFE_HOMING also! + * + * - AUTO_BED_LEVELING_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. + * + * - AUTO_BED_LEVELING_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. + * + * - AUTO_BED_LEVELING_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. + * + * - AUTO_BED_LEVELING_UBL (Unified Bed Leveling) + * A comprehensive bed leveling system combining the features and benefits + * of other systems. UBL also includes integrated Mesh Generation, Mesh + * Validation and Mesh Editing systems. Currently, UBL is only checked out + * for Cartesian Printers. That said, it was primarily designed to correct + * poor quality Delta Printers. If you feel adventurous and have a Delta, + * please post an issue if something doesn't work correctly. Initially, + * you will need to set a reduced bed size so you have a rectangular area + * to test on. + * + * - MESH_BED_LEVELING + * Probe a grid manually + * The result is a mesh, suitable for large or uneven beds. (See BILINEAR.) + * For machines without a probe, Mesh Bed Leveling provides a method to perform + * leveling in steps so you can manually adjust the Z height at each grid-point. + * With an LCD controller the process is guided step-by-step. + */ +//#define AUTO_BED_LEVELING_3POINT +//#define AUTO_BED_LEVELING_LINEAR +//#define AUTO_BED_LEVELING_BILINEAR +//#define AUTO_BED_LEVELING_UBL +//#define MESH_BED_LEVELING + +/** + * 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(MESH_BED_LEVELING) || ENABLED(AUTO_BED_LEVELING_BILINEAR) || ENABLED(AUTO_BED_LEVELING_UBL) + // 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 + +#if ENABLED(AUTO_BED_LEVELING_LINEAR) || ENABLED(AUTO_BED_LEVELING_BILINEAR) + + // Set the number of grid points per dimension. + #define GRID_MAX_POINTS_X 3 + #define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X + + // 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 + + // The Z probe minimum outer margin (to validate G29 parameters). + #define MIN_PROBE_EDGE 10 + + // Probe along the Y axis, advancing X after each column + //#define PROBE_Y_FIRST + + #if ENABLED(AUTO_BED_LEVELING_BILINEAR) + + // Beyond the probed grid, continue the implied tilt? + // Default is to maintain the height of the nearest edge. + //#define EXTRAPOLATE_BEYOND_GRID + + // + // Experimental Subdivision of the grid by Catmull-Rom method. + // Synthesizes intermediate points to produce a more detailed mesh. + // + //#define ABL_BILINEAR_SUBDIVISION + #if ENABLED(ABL_BILINEAR_SUBDIVISION) + // Number of subdivisions between probe points + #define BILINEAR_SUBDIVISIONS 3 + #endif + + #endif + +#elif ENABLED(AUTO_BED_LEVELING_3POINT) + + // 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 + +#elif ENABLED(AUTO_BED_LEVELING_UBL) + + //=========================================================================== + //========================= Unified Bed Leveling ============================ + //=========================================================================== + + #define UBL_MESH_INSET 1 // Mesh inset margin on print area + #define GRID_MAX_POINTS_X 10 // Don't use more than 15 points per axis, implementation limited. + #define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X + + #define UBL_PROBE_PT_1_X 39 // Probing points for 3-Point leveling of the mesh + #define UBL_PROBE_PT_1_Y 180 + #define UBL_PROBE_PT_2_X 39 + #define UBL_PROBE_PT_2_Y 20 + #define UBL_PROBE_PT_3_X 180 + #define UBL_PROBE_PT_3_Y 20 + + //#define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation + #define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle + +#elif ENABLED(MESH_BED_LEVELING) + + //=========================================================================== + //=================================== Mesh ================================== + //=========================================================================== + + #define MESH_INSET 10 // Mesh inset margin on print area + #define GRID_MAX_POINTS_X 3 // Don't use more than 7 points per axis, implementation limited. + #define GRID_MAX_POINTS_Y GRID_MAX_POINTS_X + + //#define MESH_G28_REST_ORIGIN // After homing all axes ('G28' or 'G28 XYZ') rest Z at Z_MIN_POS + +#endif // BED_LEVELING + +/** + * Use the LCD controller for bed leveling + * Requires MESH_BED_LEVELING or PROBE_MANUALLY + */ +//#define LCD_BED_LEVELING + +#if ENABLED(LCD_BED_LEVELING) + #define MBL_Z_STEP 0.025 // Step size while manually probing Z axis. + #define LCD_PROBE_Z_RANGE 4 // Z Range centered on Z_MIN_POS for LCD Z adjustment + #define LEVEL_BED_CORNERS // Add an option to move between corners +#endif + +/** + * 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 + +// The center of the bed is at (X=0, Y=0) +//#define BED_CENTER_AT_0_0 + +// Manually set the home position. Leave these undefined for automatic settings. +// For DELTA this is the top-center of the Cartesian print volume. +//#define MANUAL_X_HOME_POS 0 +//#define MANUAL_Y_HOME_POS 0 +//#define MANUAL_Z_HOME_POS 0 + +// Use "Z Safe Homing" to avoid homing with a Z probe outside the bed area. +// +// With this feature enabled: +// +// - Allow Z homing only after X and Y homing AND stepper drivers still enabled. +// - If stepper drivers time out, it will need X and Y homing again before Z homing. +// - Move the Z probe (or nozzle) to a defined XY point before Z Homing when homing all axes (G28). +// - Prevent Z homing when the Z probe is outside bed area. +// +//#define Z_SAFE_HOMING + +#if ENABLED(Z_SAFE_HOMING) + #define Z_SAFE_HOMING_X_POINT ((X_BED_SIZE) / 2) // X point for Z homing when homing all axis (G28). + #define Z_SAFE_HOMING_Y_POINT ((Y_BED_SIZE) / 2) // Y point for Z homing when homing all axis (G28). +#endif + +// Homing speeds (mm/m) +#define HOMING_FEEDRATE_XY (50*60) +#define HOMING_FEEDRATE_Z (6*60) + +//============================================================================= +//============================= Additional Features =========================== +//============================================================================= + +// @section extras + +// +// EEPROM +// +// The microcontroller can store settings in the EEPROM, e.g. max velocity... +// M500 - stores parameters in EEPROM +// 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 EEPROM_SETTINGS // Enable for M500 and M501 commands +//#define DISABLE_M503 // Saves ~2700 bytes of PROGMEM. Disable for release! +#define EEPROM_CHITCHAT // Give feedback on EEPROM commands. Disable to save PROGMEM. + +// +// Host Keepalive +// +// 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 BUSY_WHILE_HEATING // Some hosts require "busy" messages even during heating + +// +// M100 Free Memory Watcher +// +//#define M100_FREE_MEMORY_WATCHER // uncomment to add the M100 Free Memory Watcher for debug purpose + +// +// G20/G21 Inch mode support +// +//#define INCH_MODE_SUPPORT + +// +// M149 Set temperature units support +// +//#define TEMPERATURE_UNITS_SUPPORT + +// @section temperature + +// Preheat Constants +#define PREHEAT_1_TEMP_HOTEND 180 +#define PREHEAT_1_TEMP_BED 70 +#define PREHEAT_1_FAN_SPEED 0 // Value from 0 to 255 + +#define PREHEAT_2_TEMP_HOTEND 240 +#define PREHEAT_2_TEMP_BED 110 +#define PREHEAT_2_FAN_SPEED 0 // Value from 0 to 255 + +/** + * Nozzle Park -- EXPERIMENTAL + * + * Park the nozzle at the given XYZ position on idle or G27. + * + * The "P" parameter controls the action applied to the Z axis: + * + * P0 (Default) If Z is below park Z raise the nozzle. + * P1 Raise the nozzle always to Z-park height. + * P2 Raise the nozzle by Z-park amount, limited to Z_MAX_POS. + */ +//#define NOZZLE_PARK_FEATURE + +#if ENABLED(NOZZLE_PARK_FEATURE) + // Specify a park position as { X, Y, Z } + #define NOZZLE_PARK_POINT { (X_MIN_POS + 10), (Y_MAX_POS - 10), 20 } +#endif + +/** + * Clean Nozzle Feature -- EXPERIMENTAL + * + * Adds the G12 command to perform a nozzle cleaning process. + * + * Parameters: + * P Pattern + * S Strokes / Repetitions + * T Triangles (P1 only) + * + * Patterns: + * P0 Straight line (default). This process requires a sponge type material + * at a fixed bed location. "S" specifies strokes (i.e. back-forth motions) + * between the start / end points. + * + * P1 Zig-zag pattern between (X0, Y0) and (X1, Y1), "T" specifies the + * number of zig-zag triangles to do. "S" defines the number of strokes. + * Zig-zags are done in whichever is the narrower dimension. + * For example, "G12 P1 S1 T3" will execute: + * + * -- + * | (X0, Y1) | /\ /\ /\ | (X1, Y1) + * | | / \ / \ / \ | + * A | | / \ / \ / \ | + * | | / \ / \ / \ | + * | (X0, Y0) | / \/ \/ \ | (X1, Y0) + * -- +--------------------------------+ + * |________|_________|_________| + * T1 T2 T3 + * + * P2 Circular pattern with middle at NOZZLE_CLEAN_CIRCLE_MIDDLE. + * "R" specifies the radius. "S" specifies the stroke count. + * Before starting, the nozzle moves to NOZZLE_CLEAN_START_POINT. + * + * Caveats: The ending Z should be the same as starting Z. + * Attention: EXPERIMENTAL. G-code arguments may change. + * + */ +//#define NOZZLE_CLEAN_FEATURE + +#if ENABLED(NOZZLE_CLEAN_FEATURE) + // Default number of pattern repetitions + #define NOZZLE_CLEAN_STROKES 12 + + // Default number of triangles + #define NOZZLE_CLEAN_TRIANGLES 3 + + // Specify positions as { X, Y, Z } + #define NOZZLE_CLEAN_START_POINT { 30, 30, (Z_MIN_POS + 1)} + #define NOZZLE_CLEAN_END_POINT {100, 60, (Z_MIN_POS + 1)} + + // Circular pattern radius + #define NOZZLE_CLEAN_CIRCLE_RADIUS 6.5 + // Circular pattern circle fragments number + #define NOZZLE_CLEAN_CIRCLE_FN 10 + // Middle point of circle + #define NOZZLE_CLEAN_CIRCLE_MIDDLE NOZZLE_CLEAN_START_POINT + + // Moves the nozzle to the initial position + #define NOZZLE_CLEAN_GOBACK +#endif + +/** + * Print Job Timer + * + * Automatically start and stop the print job timer on M104/M109/M190. + * + * M104 (hotend, no wait) - high temp = none, low temp = stop timer + * M109 (hotend, wait) - high temp = start timer, low temp = stop timer + * M190 (bed, wait) - high temp = start timer, low temp = none + * + * The timer can also be controlled with the following commands: + * + * M75 - Start the print job timer + * M76 - Pause the print job timer + * M77 - Stop the print job timer + */ +#define PRINTJOB_TIMER_AUTOSTART + +/** + * Print Counter + * + * Track statistical data such as: + * + * - Total print jobs + * - Total successful print jobs + * - Total failed print jobs + * - Total time printing + * + * View the current statistics with M78. + */ +//#define PRINTCOUNTER + +//============================================================================= +//============================= LCD and SD support ============================ +//============================================================================= + +// @section lcd + +/** + * LCD LANGUAGE + * + * Select the language to display on the LCD. These languages are available: + * + * en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr, + * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, + * zh_CN, zh_TW, test + * + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } + */ +#define LCD_LANGUAGE en + +/** + * LCD Character Set + * + * Note: This option is NOT applicable to Graphical Displays. + * + * All character-based LCDs provide ASCII plus one of these + * language extensions: + * + * - JAPANESE ... the most common + * - WESTERN ... with more accented characters + * - CYRILLIC ... for the Russian language + * + * To determine the language extension installed on your controller: + * + * - Compile and upload with LCD_LANGUAGE set to 'test' + * - Click the controller to view the LCD menu + * - The LCD will display Japanese, Western, or Cyrillic text + * + * See https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language + * + * :['JAPANESE', 'WESTERN', 'CYRILLIC'] + */ +#define DISPLAY_CHARSET_HD44780 JAPANESE + +/** + * LCD TYPE + * + * Enable ULTRA_LCD for a 16x2, 16x4, 20x2, or 20x4 character-based LCD. + * Enable DOGLCD for a 128x64 (ST7565R) Full Graphical Display. + * (These options will be enabled automatically for most displays.) + * + * IMPORTANT: The U8glib library is required for Full Graphic Display! + * https://github.com/olikraus/U8glib_Arduino + */ +//#define ULTRA_LCD // Character based +//#define DOGLCD // Full graphics display + +/** + * SD CARD + * + * SD Card support is disabled by default. If your controller has an SD slot, + * you must uncomment the following option or it won't work. + * + */ +//#define SDSUPPORT + +/** + * SD CARD: SPI SPEED + * + * Enable one of the following items for a slower SPI transfer speed. + * This may be required to resolve "volume init" errors. + */ +//#define SPI_SPEED SPI_HALF_SPEED +//#define SPI_SPEED SPI_QUARTER_SPEED +//#define SPI_SPEED SPI_EIGHTH_SPEED + +/** + * SD CARD: ENABLE CRC + * + * Use CRC checks and retries on the SD communication. + */ +//#define SD_CHECK_AND_RETRY + +// +// ENCODER SETTINGS +// +// 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 + +// +// 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 + +/** + * Encoder Direction Options + * + * Test your encoder's behavior first with both options disabled. + * + * Reversed Value Edit and Menu Nav? Enable REVERSE_ENCODER_DIRECTION. + * Reversed Menu Navigation only? Enable REVERSE_MENU_DIRECTION. + * Reversed Value Editing only? Enable BOTH options. + */ + +// +// This option reverses the encoder direction everywhere. +// +// Set this option if CLOCKWISE causes values to DECREASE +// +//#define REVERSE_ENCODER_DIRECTION + +// +// This option reverses the encoder direction for navigating LCD menus. +// +// If CLOCKWISE normally moves DOWN this makes it go UP. +// If CLOCKWISE normally moves UP this makes it go DOWN. +// +//#define REVERSE_MENU_DIRECTION + +// +// Individual Axis Homing +// +// Add individual axis homing items (Home X, Home Y, and Home Z) to the LCD menu. +// +//#define INDIVIDUAL_AXIS_HOMING_MENU + +// +// SPEAKER/BUZZER +// +// If you have a speaker that can produce tones, enable it here. +// By default Marlin assumes you have a buzzer with a fixed frequency. +// +//#define SPEAKER + +// +// The duration and frequency for the UI feedback sound. +// Set these to 0 to disable audio feedback in the LCD menus. +// +// Note: Test audio output with the G-Code: +// M300 S P +// +//#define LCD_FEEDBACK_FREQUENCY_DURATION_MS 100 +//#define LCD_FEEDBACK_FREQUENCY_HZ 1000 + +// +// CONTROLLER TYPE: Standard +// +// Marlin supports a wide variety of controllers. +// Enable one of the following options to specify your controller. +// + +// +// ULTIMAKER Controller. +// +//#define ULTIMAKERCONTROLLER + +// +// ULTIPANEL as seen on Thingiverse. +// +//#define ULTIPANEL + +// +// PanelOne from T3P3 (via RAMPS 1.4 AUX2/AUX3) +// http://reprap.org/wiki/PanelOne +// +//#define PANEL_ONE + +// +// MaKr3d Makr-Panel with graphic controller and SD support. +// http://reprap.org/wiki/MaKr3d_MaKrPanel +// +//#define MAKRPANEL + +// +// ReprapWorld Graphical LCD +// https://reprapworld.com/?products_details&products_id/1218 +// +//#define REPRAPWORLD_GRAPHICAL_LCD + +// +// Activate one of these if you have a Panucatt Devices +// Viki 2.0 or mini Viki with Graphic LCD +// http://panucatt.com +// +//#define VIKI2 +//#define miniVIKI + +// +// Adafruit ST7565 Full Graphic Controller. +// https://github.com/eboston/Adafruit-ST7565-Full-Graphic-Controller/ +// +//#define ELB_FULL_GRAPHIC_CONTROLLER + +// +// RepRapDiscount Smart Controller. +// http://reprap.org/wiki/RepRapDiscount_Smart_Controller +// +// Note: Usually sold with a white PCB. +// +//#define REPRAP_DISCOUNT_SMART_CONTROLLER + +// +// GADGETS3D G3D LCD/SD Controller +// http://reprap.org/wiki/RAMPS_1.3/1.4_GADGETS3D_Shield_with_Panel +// +// Note: Usually sold with a blue PCB. +// +//#define G3D_PANEL + +// +// RepRapDiscount FULL GRAPHIC Smart Controller +// http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller +// +//#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER + +// +// MakerLab Mini Panel with graphic +// controller and SD support - http://reprap.org/wiki/Mini_panel +// +//#define MINIPANEL + +// +// RepRapWorld REPRAPWORLD_KEYPAD v1.1 +// http://reprapworld.com/?products_details&products_id=202&cPath=1591_1626 +// +// REPRAPWORLD_KEYPAD_MOVE_STEP sets how much should the robot move when a key +// is pressed, a value of 10.0 means 10mm per click. +// +//#define REPRAPWORLD_KEYPAD +//#define REPRAPWORLD_KEYPAD_MOVE_STEP 1.0 + +// +// RigidBot Panel V1.0 +// http://www.inventapart.com/ +// +//#define RIGIDBOT_PANEL + +// +// BQ LCD Smart Controller shipped by +// default with the BQ Hephestos 2 and Witbox 2. +// +//#define BQ_LCD_SMART_CONTROLLER + +// +// Cartesio UI +// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface +// +//#define CARTESIO_UI + +// +// ANET_10 Controller supported displays. +// +//#define ANET_KEYPAD_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin. + // This LCD is known to be susceptible to electrical interference + // which scrambles the display. Pressing any button clears it up. +//#define ANET_FULL_GRAPHICS_LCD // Anet 128x64 full graphics lcd with rotary encoder as used on Anet A6 + // A clone of the RepRapDiscount full graphics display but with + // different pins/wiring (see pins_ANET_10.h). + +// +// LCD for Melzi Card with Graphical LCD +// +//#define LCD_FOR_MELZI + +// +// CONTROLLER TYPE: I2C +// +// Note: These controllers require the installation of Arduino's LiquidCrystal_I2C +// library. For more info: https://github.com/kiyoshigawa/LiquidCrystal_I2C +// + +// +// Elefu RA Board Control Panel +// http://www.elefu.com/index.php?route=product/product&product_id=53 +// +//#define RA_CONTROL_PANEL + +// +// Sainsmart YW Robot (LCM1602) LCD Display +// +// Note: This controller requires F.Malpartida's LiquidCrystal_I2C library +// https://bitbucket.org/fmalpartida/new-liquidcrystal/wiki/Home +// +//#define LCD_I2C_SAINSMART_YWROBOT + +// +// Generic LCM1602 LCD adapter +// +//#define LCM1602 + +// +// PANELOLU2 LCD with status LEDs, +// separate encoder and click inputs. +// +// Note: This controller requires Arduino's LiquidTWI2 library v1.2.3 or later. +// For more info: https://github.com/lincomatic/LiquidTWI2 +// +// Note: The PANELOLU2 encoder click input can either be directly connected to +// a pin (if BTN_ENC defined to != -1) or read through I2C (when BTN_ENC == -1). +// +//#define LCD_I2C_PANELOLU2 + +// +// Panucatt VIKI LCD with status LEDs, +// integrated click & L/R/U/D buttons, separate encoder inputs. +// +//#define LCD_I2C_VIKI + +// +// SSD1306 OLED full graphics generic display +// +//#define U8GLIB_SSD1306 + +// +// SAV OLEd LCD module support using either SSD1306 or SH1106 based LCD modules +// +//#define SAV_3DGLCD +#if ENABLED(SAV_3DGLCD) + //#define U8GLIB_SSD1306 + #define U8GLIB_SH1106 +#endif + +// +// CONTROLLER TYPE: Shift register panels +// +// 2 wire Non-latching LCD SR from https://goo.gl/aJJ4sH +// LCD configuration: http://reprap.org/wiki/SAV_3D_LCD +// +//#define SAV_3DLCD + +// +// TinyBoy2 128x64 OLED / Encoder Panel +// +//#define OLED_PANEL_TINYBOY2 + +//============================================================================= +//=============================== Extra Features ============================== +//============================================================================= + +// @section extras + +// Increase the FAN PWM frequency. Removes the PWM noise but increases heating in the FET/Arduino +//#define FAST_PWM_FAN + +// Use software PWM to drive the fan, as for the heaters. This uses a very low frequency +// which is not as annoying as with the hardware PWM. On the other hand, if this frequency +// is too low, you should also increment SOFT_PWM_SCALE. +//#define FAN_SOFT_PWM + +// Incrementing this by 1 will double the software PWM frequency, +// affecting heaters, and the fan if FAN_SOFT_PWM is enabled. +// However, control resolution will be halved for each increment; +// at zero value, there are 128 effective control positions. +#define SOFT_PWM_SCALE 0 + +// If SOFT_PWM_SCALE is set to a value higher than 0, dithering can +// be used to mitigate the associated resolution loss. If enabled, +// some of the PWM cycles are stretched so on average the desired +// duty cycle is attained. +//#define SOFT_PWM_DITHER + +// Temperature status LEDs that display the hotend and bed temperature. +// If all hotends, bed temperature, and target temperature are under 54C +// then the BLUE led is on. Otherwise the RED led is on. (1C hysteresis) +//#define TEMP_STAT_LEDS + +// M240 Triggers a camera by emulating a Canon RC-1 Remote +// Data from: http://www.doc-diy.net/photo/rc-1_hacked/ +//#define PHOTOGRAPH_PIN 23 + +// SkeinForge sends the wrong arc g-codes when using Arc Point as fillet procedure +//#define SF_ARC_FIX + +// Support for the BariCUDA Paste Extruder +//#define BARICUDA + +// Support for BlinkM/CyzRgb +//#define BLINKM + +// Support for PCA9632 PWM LED driver +//#define PCA9632 + +/** + * RGB LED / LED Strip Control + * + * Enable support for an RGB LED connected to 5V digital pins, or + * an RGB Strip connected to MOSFETs controlled by digital pins. + * + * Adds the M150 command to set the LED (or LED strip) color. + * If pins are PWM capable (e.g., 4, 5, 6, 11) then a range of + * luminance values can be set from 0 to 255. + * + * *** CAUTION *** + * LED Strips require a MOFSET Chip between PWM lines and LEDs, + * as the Arduino cannot handle the current the LEDs will require. + * Failure to follow this precaution can destroy your Arduino! + * *** CAUTION *** + * + */ +#define RGB_LED +//#define RGBW_LED +#if ENABLED(RGB_LED) || ENABLED(RGBW_LED) + #define RGB_LED_R_PIN 11 + #define RGB_LED_G_PIN 10 + #define RGB_LED_B_PIN 17 + #define RGB_LED_W_PIN -1 +#endif + +// Support for Adafruit Neopixel LED driver +//#define NEOPIXEL_RGBW_LED +#if ENABLED(NEOPIXEL_RGBW_LED) + #define NEOPIXEL_PIN 4 // D4 (EXP2-5 on Printrboard) + #define NEOPIXEL_PIXELS 3 + //#define NEOPIXEL_STARTUP_TEST // Cycle through colors at startup +#endif + +/** + * Printer Event LEDs + * + * During printing, the LEDs will reflect the printer status: + * + * - Gradually change from blue to violet as the heated bed gets to target temp + * - Gradually change from violet to red as the hotend gets to temperature + * - Change to white to illuminate work surface + * - Change to green once print has finished + * - Turn off after the print has finished and the user has pushed a button + */ +#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_RGBW_LED) + #define PRINTER_EVENT_LEDS +#endif + +/*********************************************************************\ +* R/C SERVO support +* Sponsored by TrinityLabs, Reworked by codexmas +**********************************************************************/ + +// Number of servos +// +// If you select a configuration below, this will receive a default value and does not need to be set manually +// set it manually if you have more servos than extruders and wish to manually control some +// leaving it undefined or defining as 0 will disable the servo subsystem +// If unsure, leave commented / disabled +// +//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command + +// Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle. +// 300ms is a good value but you can try less delay. +// If the servo can't reach the requested position, increase it. +#define SERVO_DELAY { 300 } + +// Servo deactivation +// +// With this option servos are powered only during movement, then turned off to prevent jitter. +//#define DEACTIVATE_SERVOS_AFTER_MOVE + +/** + * Filament Width Sensor + * + * Measures the filament width in real-time and adjusts + * flow rate to compensate for any irregularities. + * + * Also allows the measured filament diameter to set the + * extrusion rate, so the slicer only has to specify the + * volume. + * + * Only a single extruder is supported at this time. + * + * 34 RAMPS_14 : Analog input 5 on the AUX2 connector + * 81 PRINTRBOARD : Analog input 2 on the Exp1 connector (version B,C,D,E) + * 301 RAMBO : Analog input 3 + * + * Note: May require analog pins to be defined for other boards. + */ +//#define FILAMENT_WIDTH_SENSOR + +#define DEFAULT_NOMINAL_FILAMENT_DIA 1.75 // (mm) Diameter of the filament generally used (3.0 or 1.75mm), also used in the slicer. Used to validate sensor reading. + +#if ENABLED(FILAMENT_WIDTH_SENSOR) + #define FILAMENT_SENSOR_EXTRUDER_NUM 0 // Index of the extruder that has the filament sensor (0,1,2,3) + #define MEASUREMENT_DELAY_CM 14 // (cm) The distance from the filament sensor to the melting chamber + + #define MEASURED_UPPER_LIMIT 3.30 // (mm) Upper limit used to validate sensor reading + #define MEASURED_LOWER_LIMIT 1.90 // (mm) Lower limit used to validate sensor reading + #define MAX_MEASUREMENT_DELAY 20 // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM. + + #define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially + + // Display filament width on the LCD status line. Status messages will expire after 5 seconds. + //#define FILAMENT_LCD_DISPLAY +#endif + +#endif // CONFIGURATION_H diff --git a/Marlin/example_configurations/Sanguinololu/Configuration_adv.h b/Marlin/example_configurations/Sanguinololu/Configuration_adv.h new file mode 100644 index 000000000..953894cba --- /dev/null +++ b/Marlin/example_configurations/Sanguinololu/Configuration_adv.h @@ -0,0 +1,1374 @@ +/** + * 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 . + * + */ + +/** + * Configuration_adv.h + * + * Advanced settings. + * Only change these if you know exactly what you're doing. + * Some of these settings can damage your printer if improperly set! + * + * Basic settings can be found in Configuration.h + * + */ +#ifndef CONFIGURATION_ADV_H +#define CONFIGURATION_ADV_H +#define CONFIGURATION_ADV_H_VERSION 010100 + +// @section temperature + +//=========================================================================== +//=============================Thermal Settings ============================ +//=========================================================================== + +#if DISABLED(PIDTEMPBED) + #define BED_CHECK_INTERVAL 5000 // ms between checks in bang-bang control + #if ENABLED(BED_LIMIT_SWITCHING) + #define BED_HYSTERESIS 2 // Only disable heating if T>target+BED_HYSTERESIS and enable heating if T>target-BED_HYSTERESIS + #endif +#endif + +/** + * Thermal Protection protects your printer from damage and fire if a + * thermistor falls out or temperature sensors fail in any way. + * + * The issue: If a thermistor falls out or a temperature sensor fails, + * Marlin can no longer sense the actual temperature. Since a disconnected + * thermistor reads as a low temperature, the firmware will keep the heater on. + * + * The solution: Once the temperature reaches the target, start observing. + * If the temperature stays too far below the target (hysteresis) for too long (period), + * the firmware will halt the machine as a safety precaution. + * + * If you get false positives for "Thermal Runaway" increase THERMAL_PROTECTION_HYSTERESIS and/or THERMAL_PROTECTION_PERIOD + */ +#if ENABLED(THERMAL_PROTECTION_HOTENDS) + #define THERMAL_PROTECTION_PERIOD 40 // Seconds + #define THERMAL_PROTECTION_HYSTERESIS 4 // Degrees Celsius + + /** + * Whenever an M104 or M109 increases the target temperature the firmware will wait for the + * WATCH_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_TEMP_INCREASE + * degrees, the machine is halted, requiring a hard reset. This test restarts with any M104/M109, + * but only if the current temperature is far enough below the target for a reliable test. + * + * If you get false positives for "Heating failed" increase WATCH_TEMP_PERIOD and/or decrease WATCH_TEMP_INCREASE + * WATCH_TEMP_INCREASE should not be below 2. + */ + #define WATCH_TEMP_PERIOD 20 // Seconds + #define WATCH_TEMP_INCREASE 2 // Degrees Celsius +#endif + +/** + * Thermal Protection parameters for the bed are 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 + + /** + * Whenever an M140 or M190 increases the target temperature the firmware will wait for the + * WATCH_BED_TEMP_PERIOD to expire, and if the temperature hasn't increased by WATCH_BED_TEMP_INCREASE + * degrees, the machine is halted, requiring a hard reset. This test restarts with any M140/M190, + * but only if the current temperature is far enough below the target for a reliable test. + * + * If you get too many "Heating failed" errors, increase WATCH_BED_TEMP_PERIOD and/or decrease + * WATCH_BED_TEMP_INCREASE. (WATCH_BED_TEMP_INCREASE should not be below 2.) + */ + #define WATCH_BED_TEMP_PERIOD 60 // Seconds + #define WATCH_BED_TEMP_INCREASE 2 // Degrees Celsius +#endif + +#if ENABLED(PIDTEMP) + // this adds an experimental additional term to the heating power, proportional to the extrusion speed. + // if Kc is chosen well, the additional required power due to increased melting should be compensated. + //#define PID_EXTRUSION_SCALING + #if ENABLED(PID_EXTRUSION_SCALING) + #define DEFAULT_Kc (100) //heating power=Kc*(e_speed) + #define LPQ_MAX_LEN 50 + #endif +#endif + +/** + * Automatic Temperature: + * The hotend target temperature is calculated by all the buffered lines of gcode. + * The maximum buffered steps/sec of the extruder motor is called "se". + * Start autotemp mode with M109 S B F + * The target temperature is set to mintemp+factor*se[steps/sec] and is limited by + * mintemp and maxtemp. Turn this off by executing M109 without F* + * Also, if the temperature is set to a value below mintemp, it will not be changed by autotemp. + * On an Ultimaker, some initial testing worked with M109 S215 B260 F1 in the start.gcode + */ +#define AUTOTEMP +#if ENABLED(AUTOTEMP) + #define AUTOTEMP_OLDWEIGHT 0.98 +#endif + +// Show Temperature ADC value +// Enable for M105 to include ADC values read from temperature sensors. +//#define SHOW_TEMP_ADC_VALUES + +/** + * High Temperature Thermistor Support + * + * Thermistors able to support high temperature tend to have a hard time getting + * good readings at room and lower temperatures. This means HEATER_X_RAW_LO_TEMP + * will probably be caught when the heating element first turns on during the + * preheating process, which will trigger a min_temp_error as a safety measure + * and force stop everything. + * To circumvent this limitation, we allow for a preheat time (during which, + * min_temp_error won't be triggered) and add a min_temp buffer to handle + * aberrant readings. + * + * If you want to enable this feature for your hotend thermistor(s) + * uncomment and set values > 0 in the constants below + */ + +// The number of consecutive low temperature errors that can occur +// before a min_temp_error is triggered. (Shouldn't be more than 10.) +//#define MAX_CONSECUTIVE_LOW_TEMPERATURE_ERROR_ALLOWED 0 + +// The number of milliseconds a hotend will preheat before starting to check +// the temperature. This value should NOT be set to the time it takes the +// hot end to reach the target temperature, but the time it takes to reach +// the minimum temperature your thermistor can read. The lower the better/safer. +// This shouldn't need to be more than 30 seconds (30000) +//#define MILLISECONDS_PREHEAT_TIME 0 + +// @section extruder + +// 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 +#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 + +//These defines help to calibrate the AD595 sensor in case you get wrong temperature measurements. +//The measured temperature is defined as "actualTemp = (measuredTemp * TEMP_SENSOR_AD595_GAIN) + TEMP_SENSOR_AD595_OFFSET" +#define TEMP_SENSOR_AD595_OFFSET 0.0 +#define TEMP_SENSOR_AD595_GAIN 1.0 + +/** + * Controller Fan + * To cool down the stepper drivers and MOSFETs. + * + * The fan will turn on automatically whenever any stepper is enabled + * and turn off after a set period after all steppers are turned off. + */ +//#define USE_CONTROLLER_FAN +#if ENABLED(USE_CONTROLLER_FAN) + //#define CONTROLLER_FAN_PIN FAN1_PIN // Set a custom pin for the controller fan + #define CONTROLLERFAN_SECS 60 // Duration in seconds for the fan to run after all motors are disabled + #define CONTROLLERFAN_SPEED 255 // 255 == full speed +#endif + +// When first starting the main fan, run it at full speed for the +// given number of milliseconds. This gets the fan spinning reliably +// before setting a PWM value. (Does not work with software PWM for fan on Sanguinololu) +//#define FAN_KICKSTART_TIME 100 + +// This defines the minimal speed for the main fan, run in PWM mode +// to enable uncomment and set minimal PWM speed for reliable running (1-255) +// if fan speed is [1 - (FAN_MIN_PWM-1)] it is set to FAN_MIN_PWM +//#define FAN_MIN_PWM 50 + +// @section extruder + +/** + * Extruder cooling fans + * + * 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 E4_AUTO_FAN_PIN -1 +#define EXTRUDER_AUTO_FAN_TEMPERATURE 50 +#define EXTRUDER_AUTO_FAN_SPEED 255 // == full speed + +/** + * M355 Case Light on-off / brightness + */ +//#define CASE_LIGHT_ENABLE +#if ENABLED(CASE_LIGHT_ENABLE) + //#define CASE_LIGHT_PIN 4 // Override the default pin if needed + #define INVERT_CASE_LIGHT false // Set true if Case Light is ON when pin is LOW + #define CASE_LIGHT_DEFAULT_ON true // Set default power-up state on + #define CASE_LIGHT_DEFAULT_BRIGHTNESS 105 // Set default power-up brightness (0-255, requires PWM pin) + //#define MENU_ITEM_CASE_LIGHT // Add a Case Light option to the LCD main menu +#endif + +//=========================================================================== +//============================ Mechanical Settings ========================== +//=========================================================================== + +// @section homing + +// If you want endstops to stay on (by default) even when not homing +// enable this option. Override at any time with M120, M121. +//#define ENDSTOPS_ALWAYS_ON_DEFAULT + +// @section extras + +//#define Z_LATE_ENABLE // Enable Z the last moment. Needed if your Z driver overheats. + +// Dual X Steppers +// Uncomment this option to drive two X axis motors. +// The next unused E driver will be assigned to the second X stepper. +//#define X_DUAL_STEPPER_DRIVERS +#if ENABLED(X_DUAL_STEPPER_DRIVERS) + // Set true if the two X motors need to rotate in opposite directions + #define INVERT_X2_VS_X_DIR true +#endif + +// Dual Y Steppers +// Uncomment this option to drive two Y axis motors. +// The next unused E driver will be assigned to the second Y stepper. +//#define Y_DUAL_STEPPER_DRIVERS +#if ENABLED(Y_DUAL_STEPPER_DRIVERS) + // Set true if the two Y motors need to rotate in opposite directions + #define INVERT_Y2_VS_Y_DIR true +#endif + +// A single Z stepper driver is usually used to drive 2 stepper motors. +// Uncomment this option to use a separate stepper driver for each Z axis motor. +// The next unused E driver will be assigned to the second Z stepper. +//#define Z_DUAL_STEPPER_DRIVERS + +#if ENABLED(Z_DUAL_STEPPER_DRIVERS) + + // Z_DUAL_ENDSTOPS is a feature to enable the use of 2 endstops for both Z steppers - Let's call them Z stepper and Z2 stepper. + // That way the machine is capable to align the bed during home, since both Z steppers are homed. + // There is also an implementation of M666 (software endstops adjustment) to this feature. + // After Z homing, this adjustment is applied to just one of the steppers in order to align the bed. + // One just need to home the Z axis and measure the distance difference between both Z axis and apply the math: Z adjust = Z - Z2. + // If the Z stepper axis is closer to the bed, the measure Z > Z2 (yes, it is.. think about it) and the Z adjust would be positive. + // Play a little bit with small adjustments (0.5mm) and check the behaviour. + // The M119 (endstops report) will start reporting the Z2 Endstop as well. + + //#define Z_DUAL_ENDSTOPS + + #if ENABLED(Z_DUAL_ENDSTOPS) + #define Z2_USE_ENDSTOP _XMAX_ + #define Z_DUAL_ENDSTOPS_ADJUSTMENT 0 // Use M666 to determine/test this value + #endif + +#endif // Z_DUAL_STEPPER_DRIVERS + +// Enable this for dual x-carriage printers. +// A dual x-carriage design has the advantage that the inactive extruder can be parked which +// prevents hot-end ooze contaminating the print. It also reduces the weight of each x-carriage +// allowing faster printing speeds. Connect your X2 stepper to the first unused E plug. +//#define DUAL_X_CARRIAGE +#if ENABLED(DUAL_X_CARRIAGE) + // Configuration for second X-carriage + // Note: the first x-carriage is defined as the x-carriage which homes to the minimum endstop; + // the second x-carriage always homes to the maximum endstop. + #define X2_MIN_POS 80 // set minimum to ensure second x-carriage doesn't hit the parked first X-carriage + #define X2_MAX_POS 353 // set maximum to the distance between toolheads when both heads are homed + #define X2_HOME_DIR 1 // the second X-carriage always homes to the maximum endstop position + #define X2_HOME_POS X2_MAX_POS // default home position is the maximum carriage position + // However: In this mode the HOTEND_OFFSET_X value for the second extruder provides a software + // override for X2_HOME_POS. This also allow recalibration of the distance between the two endstops + // without modifying the firmware (through the "M218 T1 X???" command). + // Remember: you should set the second extruder x-offset to 0 in your slicer. + + // There are a few selectable movement modes for dual x-carriages using M605 S + // Mode 0 (DXC_FULL_CONTROL_MODE): Full control. The slicer has full control over both x-carriages and can achieve optimal travel results + // as long as it supports dual x-carriages. (M605 S0) + // Mode 1 (DXC_AUTO_PARK_MODE) : Auto-park mode. The firmware will automatically park and unpark the x-carriages on tool changes so + // that additional slicer support is not required. (M605 S1) + // Mode 2 (DXC_DUPLICATION_MODE) : Duplication mode. The firmware will transparently make the second x-carriage and extruder copy all + // actions of the first x-carriage. This allows the printer to print 2 arbitrary items at + // once. (2nd extruder x offset and temp offset are set using: M605 S2 [Xnnn] [Rmmm]) + + // This is the default power-up mode which can be later using M605. + #define DEFAULT_DUAL_X_CARRIAGE_MODE 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 + #define TOOLCHANGE_UNPARK_ZLIFT 1 // the distance to raise Z axis when unparking an extruder + + // Default x offset in duplication mode (typically set to half print bed width) + #define DEFAULT_DUPLICATION_X_OFFSET 100 + +#endif // DUAL_X_CARRIAGE + +// Activate a solenoid on the active extruder with M380. Disable all with M381. +// Define SOL0_PIN, SOL1_PIN, etc., for each extruder that has a solenoid. +//#define EXT_SOLENOID + +// @section homing + +//homing hits the endstop, then retracts by this distance, before it tries to slowly bump again: +#define X_HOME_BUMP_MM 5 +#define Y_HOME_BUMP_MM 5 +#define Z_HOME_BUMP_MM 2 +#define HOMING_BUMP_DIVISOR {2, 2, 4} // Re-Bump Speed Divisor (Divides the Homing Feedrate) +#define QUICK_HOME //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially. + +// When G28 is called, this option will make Y home before X +//#define HOME_Y_BEFORE_X + +// @section machine + +#define AXIS_RELATIVE_MODES {false, false, false, false} + +// Allow duplication mode with a basic dual-nozzle extruder +//#define DUAL_NOZZLE_DUPLICATION_MODE + +// By default pololu step drivers require an active high signal. However, some high power drivers require an active low signal as step. +#define INVERT_X_STEP_PIN false +#define INVERT_Y_STEP_PIN false +#define INVERT_Z_STEP_PIN false +#define INVERT_E_STEP_PIN false + +// Default stepper release if idle. Set to 0 to deactivate. +// Steppers will shut down DEFAULT_STEPPER_DEACTIVE_TIME seconds after the last move when DISABLE_INACTIVE_? is true. +// Time can be set by M18 and M84. +#define DEFAULT_STEPPER_DEACTIVE_TIME 120 +#define DISABLE_INACTIVE_X true +#define DISABLE_INACTIVE_Y true +#define DISABLE_INACTIVE_Z true // set to false if the nozzle will fall down on your printed part when print has finished. +#define DISABLE_INACTIVE_E true + +#define DEFAULT_MINIMUMFEEDRATE 0.0 // minimum feedrate +#define DEFAULT_MINTRAVELFEEDRATE 0.0 + +//#define HOME_AFTER_DEACTIVATE // Require rehoming after steppers are deactivated + +// @section lcd + +#if ENABLED(ULTIPANEL) + #define MANUAL_FEEDRATE {50*60, 50*60, 4*60, 60} // Feedrates for manual moves along X, Y, Z, E from panel + #define ULTIPANEL_FEEDMULTIPLY // Comment to disable setting feedrate multiplier via encoder +#endif + +// @section extras + +// minimum time in microseconds that a movement needs to take if the buffer is emptied. +#define DEFAULT_MINSEGMENTTIME 20000 + +// If defined the movements slow down when the look ahead buffer is only half full +#define SLOWDOWN + +// Frequency limit +// See nophead's blog for more info +// Not working O +//#define XY_FREQUENCY_LIMIT 15 + +// Minimum planner junction speed. Sets the default minimum speed the planner plans for at the end +// of the buffer and all stops. This should not be much greater than zero and should only be changed +// if unwanted behavior is observed on a user's machine when running at very slow speeds. +#define MINIMUM_PLANNER_SPEED 0.05 // (mm/sec) + +// Microstep setting (Only functional when stepper driver microstep pins are connected to MCU. +#define MICROSTEP_MODES {16,16,16,16,16} // [1,2,4,8,16] + +/** + * @section stepper motor current + * + * Some boards have a means of setting the stepper motor current via firmware. + * + * The power on motor currents are set by: + * PWM_MOTOR_CURRENT - used by MINIRAMBO & ULTIMAIN_2 + * known compatible chips: A4982 + * DIGIPOT_MOTOR_CURRENT - used by BQ_ZUM_MEGA_3D, RAMBO & SCOOVO_X9H + * known compatible chips: AD5206 + * DAC_MOTOR_CURRENT_DEFAULT - used by PRINTRBOARD_REVF & RIGIDBOARD_V2 + * known compatible chips: MCP4728 + * DIGIPOT_I2C_MOTOR_CURRENTS - used by 5DPRINT, AZTEEG_X3_PRO, MIGHTYBOARD_REVE + * known compatible chips: MCP4451, MCP4018 + * + * Motor currents can also be set by M907 - M910 and by the LCD. + * M907 - applies to all. + * M908 - BQ_ZUM_MEGA_3D, RAMBO, PRINTRBOARD_REVF, RIGIDBOARD_V2 & SCOOVO_X9H + * M909, M910 & LCD - only PRINTRBOARD_REVF & RIGIDBOARD_V2 + */ +//#define PWM_MOTOR_CURRENT { 1300, 1300, 1250 } // Values in milliamps +//#define DIGIPOT_MOTOR_CURRENT { 135,135,135,135,135 } // Values 0-255 (RAMBO 135 = ~0.75A, 185 = ~1A) +//#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 } // Default drive percent - X, Y, Z, E axis + +// Uncomment to enable an I2C based DIGIPOT like on the Azteeg X3 Pro +//#define DIGIPOT_I2C +//#define DIGIPOT_MCP4018 // Requires library from https://github.com/stawel/SlowSoftI2CMaster +#define DIGIPOT_I2C_NUM_CHANNELS 8 // 5DPRINT: 4 AZTEEG_X3_PRO: 8 +// Actual motor currents in Amps, need as many here as DIGIPOT_I2C_NUM_CHANNELS +#define DIGIPOT_I2C_MOTOR_CURRENTS { 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0 } // AZTEEG_X3_PRO + +//=========================================================================== +//=============================Additional Features=========================== +//=========================================================================== + +#define ENCODER_RATE_MULTIPLIER // If defined, certain menu edit operations automatically multiply the steps when the encoder is moved quickly +#define ENCODER_10X_STEPS_PER_SEC 75 // If the encoder steps per sec exceeds this value, multiply steps moved x10 to quickly advance the value +#define ENCODER_100X_STEPS_PER_SEC 160 // If the encoder steps per sec exceeds this value, multiply steps moved x100 to really quickly advance the value + +//#define CHDK 4 //Pin for triggering CHDK to take a picture see how to use it here http://captain-slow.dk/2014/03/09/3d-printing-timelapses/ +#define CHDK_DELAY 50 //How long in ms the pin should stay HIGH before going LOW again + +// @section lcd + +// Include a page of printer information in the LCD Main Menu +//#define LCD_INFO_MENU + +// Scroll a longer status message into view +//#define STATUS_MESSAGE_SCROLLING + +// On the Info Screen, display XY with one decimal place when possible +//#define LCD_DECIMAL_SMALL_XY + +// The timeout (in ms) to return to the status screen from sub-menus +//#define LCD_TIMEOUT_TO_STATUS 15000 + +#if ENABLED(SDSUPPORT) + + // Some RAMPS and other boards don't detect when an SD card is inserted. You can work + // around this by connecting a push button or single throw switch to the pin defined + // as SD_DETECT_PIN in your board's pins definitions. + // This setting should be disabled unless you are using a push button, pulling the pin to ground. + // Note: This is always disabled for ULTIPANEL (except ELB_FULL_GRAPHIC_CONTROLLER). + #define SD_DETECT_INVERTED + + #define SD_FINISHED_STEPPERRELEASE true //if sd support and the file is finished: disable steppers? + #define SD_FINISHED_RELEASECOMMAND "M84 X Y Z E" // You might want to keep the z enabled so your bed stays in place. + + #define SDCARD_RATHERRECENTFIRST //reverse file order of sd card menu display. Its sorted practically after the file system block order. + // if a file is deleted, it frees a block. hence, the order is not purely chronological. To still have auto0.g accessible, there is again the option to do that. + // using: + //#define MENU_ADDAUTOSTART + + /** + * Sort SD file listings in alphabetical order. + * + * With this option enabled, items on SD cards will be sorted + * by name for easier navigation. + * + * By default... + * + * - Use the slowest -but safest- method for sorting. + * - Folders are sorted to the top. + * - The sort key is statically allocated. + * - No added G-code (M34) support. + * - 40 item sorting limit. (Items after the first 40 are unsorted.) + * + * SD sorting uses static allocation (as set by SDSORT_LIMIT), allowing the + * compiler to calculate the worst-case usage and throw an error if the SRAM + * limit is exceeded. + * + * - SDSORT_USES_RAM provides faster sorting via a static directory buffer. + * - SDSORT_USES_STACK does the same, but uses a local stack-based buffer. + * - SDSORT_CACHE_NAMES will retain the sorted file listing in RAM. (Expensive!) + * - SDSORT_DYNAMIC_RAM only uses RAM when the SD menu is visible. (Use with caution!) + */ + //#define SDCARD_SORT_ALPHA + + // SD Card Sorting options + #if ENABLED(SDCARD_SORT_ALPHA) + #define SDSORT_LIMIT 40 // Maximum number of sorted items (10-256). + #define FOLDER_SORTING -1 // -1=above 0=none 1=below + #define SDSORT_GCODE false // Allow turning sorting on/off with LCD and M34 g-code. + #define SDSORT_USES_RAM false // Pre-allocate a static array for faster pre-sorting. + #define SDSORT_USES_STACK false // Prefer the stack for pre-sorting to give back some SRAM. (Negated by next 2 options.) + #define SDSORT_CACHE_NAMES false // Keep sorted items in RAM longer for speedy performance. Most expensive option. + #define SDSORT_DYNAMIC_RAM false // Use dynamic allocation (within SD menus). Least expensive option. Set SDSORT_LIMIT before use! + #endif + + // Show a progress bar on HD44780 LCDs for SD printing + //#define LCD_PROGRESS_BAR + + #if ENABLED(LCD_PROGRESS_BAR) + // Amount of time (ms) to show the bar + #define PROGRESS_BAR_BAR_TIME 2000 + // Amount of time (ms) to show the status message + #define PROGRESS_BAR_MSG_TIME 3000 + // Amount of time (ms) to retain the status message (0=forever) + #define PROGRESS_MSG_EXPIRE 0 + // Enable this to show messages for MSG_TIME then hide them + //#define PROGRESS_MSG_ONCE + // Add a menu item to test the progress bar: + //#define LCD_PROGRESS_BAR_TEST + #endif + + // This allows hosts to request long names for files and folders with M33 + //#define LONG_FILENAME_HOST_SUPPORT + + // This option allows you to abort SD printing when any endstop is triggered. + // This feature must be enabled with "M540 S1" or from the LCD menu. + // To have any effect, endstops must be enabled during SD printing. + //#define ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED + +#endif // SDSUPPORT + +/** + * Additional options for Graphical Displays + * + * Use the optimizations here to improve printing performance, + * which can be adversely affected by graphical display drawing, + * especially when doing several short moves, and when printing + * on DELTA and SCARA machines. + * + * Some of these options may result in the display lagging behind + * controller events, as there is a trade-off between reliable + * printing performance versus fast display updates. + */ +#if ENABLED(DOGLCD) + // Enable to save many cycles by drawing a hollow frame on the Info Screen + #define XYZ_HOLLOW_FRAME + + // Enable to save many cycles by drawing a hollow frame on Menu Screens + #define MENU_HOLLOW_FRAME + + // 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 + + // 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 + +// The hardware watchdog should reset the microcontroller disabling all outputs, +// in case the firmware gets stuck and doesn't do temperature regulation. +#define USE_WATCHDOG + +#if ENABLED(USE_WATCHDOG) + // If you have a watchdog reboot in an ArduinoMega2560 then the device will hang forever, as a watchdog reset will leave the watchdog on. + // The "WATCHDOG_RESET_MANUAL" goes around this by not using the hardware reset. + // However, THIS FEATURE IS UNSAFE!, as it will only work if interrupts are disabled. And the code could hang in an interrupt routine with interrupts disabled. + //#define WATCHDOG_RESET_MANUAL +#endif + +// @section lcd + +/** + * Babystepping enables movement of the axes by tiny increments without changing + * the current position values. This feature is used primarily to adjust the Z + * axis in the first layer of a print in real-time. + * + * Warning: Does not respect endstops! + */ +//#define BABYSTEPPING +#if ENABLED(BABYSTEPPING) + #define BABYSTEP_XY // Also enable X/Y Babystepping. Not supported on DELTA! + #define BABYSTEP_INVERT_Z false // Change if Z babysteps should go the other way + #define BABYSTEP_MULTIPLICATOR 1 // Babysteps are very small. Increase for faster motion. + //#define BABYSTEP_ZPROBE_OFFSET // Enable to combine M851 and Babystepping + //#define DOUBLECLICK_FOR_Z_BABYSTEPPING // Double-click on the Status Screen for Z Babystepping. + #define DOUBLECLICK_MAX_INTERVAL 1250 // Maximum interval between clicks, in milliseconds. + // Note: Extra time may be added to mitigate controller latency. +#endif + +// @section extruder + +// extruder advance constant (s2/mm3) +// +// advance (steps) = STEPS_PER_CUBIC_MM_E * EXTRUDER_ADVANCE_K * cubic mm per second ^ 2 +// +// Hooke's law says: force = k * distance +// Bernoulli's principle says: v ^ 2 / 2 + g . h + pressure / density = constant +// so: v ^ 2 is proportional to number of steps we advance the extruder +//#define ADVANCE + +#if ENABLED(ADVANCE) + #define EXTRUDER_ADVANCE_K .0 + #define D_FILAMENT 2.85 +#endif + +/** + * Implementation of linear pressure control + * + * Assumption: advance = k * (delta velocity) + * K=0 means advance disabled. + * See Marlin documentation for calibration instructions. + */ +//#define LIN_ADVANCE + +#if ENABLED(LIN_ADVANCE) + #define LIN_ADVANCE_K 75 + + /** + * Some Slicers produce Gcode with randomly jumping extrusion widths occasionally. + * For example within a 0.4mm perimeter it may produce a single segment of 0.05mm width. + * While this is harmless for normal printing (the fluid nature of the filament will + * close this very, very tiny gap), it throws off the LIN_ADVANCE pressure adaption. + * + * For this case LIN_ADVANCE_E_D_RATIO can be used to set the extrusion:distance ratio + * to a fixed value. Note that using a fixed ratio will lead to wrong nozzle pressures + * if the slicer is using variable widths or layer heights within one print! + * + * This option sets the default E:D ratio at startup. Use `M900` to override this value. + * + * Example: `M900 W0.4 H0.2 D1.75`, where: + * - W is the extrusion width in mm + * - H is the layer height in mm + * - D is the filament diameter in mm + * + * Example: `M900 R0.0458` to set the ratio directly. + * + * Set to 0 to auto-detect the ratio based on given Gcode G1 print moves. + * + * Slic3r (including Průša Control) produces Gcode compatible with the automatic mode. + * Cura (as of this writing) may produce Gcode incompatible with the automatic mode. + */ + #define LIN_ADVANCE_E_D_RATIO 0 // The calculated ratio (or 0) according to the formula W * H / ((D / 2) ^ 2 * PI) + // Example: 0.4 * 0.2 / ((1.75 / 2) ^ 2 * PI) = 0.033260135 +#endif + +// @section leveling + +// Default mesh area is an area with an inset margin on the print area. +// Below are the macros that are used to define the borders for the mesh area, +// made available here for specialized needs, ie dual extruder setup. +#if ENABLED(MESH_BED_LEVELING) + #define MESH_MIN_X MESH_INSET + #define MESH_MAX_X (X_BED_SIZE - (MESH_INSET)) + #define MESH_MIN_Y MESH_INSET + #define MESH_MAX_Y (Y_BED_SIZE - (MESH_INSET)) +#elif ENABLED(AUTO_BED_LEVELING_UBL) + #define UBL_MESH_MIN_X UBL_MESH_INSET + #define UBL_MESH_MAX_X (X_BED_SIZE - (UBL_MESH_INSET)) + #define UBL_MESH_MIN_Y UBL_MESH_INSET + #define UBL_MESH_MAX_Y (Y_BED_SIZE - (UBL_MESH_INSET)) + + // If this is defined, the currently active mesh will be saved in the + // current slot on M500. + #define UBL_SAVE_ACTIVE_ON_M500 +#endif + +// @section extras + +// +// G2/G3 Arc Support +// +#define ARC_SUPPORT // Disable this feature to save ~3226 bytes +#if ENABLED(ARC_SUPPORT) + #define MM_PER_ARC_SEGMENT 1 // Length of each arc segment + #define N_ARC_CORRECTION 25 // Number of intertpolated segments between corrections + //#define ARC_P_CIRCLES // Enable the 'P' parameter to specify complete circles + //#define CNC_WORKSPACE_PLANES // Allow G2/G3 to operate in XY, ZX, or YZ planes +#endif + +// Support for G5 with XYZE destination and IJPQ offsets. Requires ~2666 bytes. +//#define BEZIER_CURVE_SUPPORT + +// G38.2 and G38.3 Probe Target +// Enable PROBE_DOUBLE_TOUCH if you want G38 to double touch +//#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 + +// Control heater 0 and heater 1 in parallel. +//#define HEATERS_PARALLEL + +//=========================================================================== +//================================= Buffers ================================= +//=========================================================================== + +// @section hidden + +// The number of linear motions that can be in the plan at any give time. +// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2, i.g. 8,16,32 because shifts and ors are used to do the ring-buffering. +#if ENABLED(SDSUPPORT) + #define BLOCK_BUFFER_SIZE 16 // SD,LCD,Buttons take more memory, block buffer needs to be smaller +#else + #define BLOCK_BUFFER_SIZE 16 // maximize block buffer +#endif + +// @section serial + +// The ASCII buffer for serial input +#define MAX_CMD_SIZE 96 +#define BUFSIZE 4 + +// Transfer Buffer Size +// To save 386 bytes of PROGMEM (and TX_BUFFER_SIZE+3 bytes of RAM) set to 0. +// To buffer a simple "ok" you need 4 bytes. +// 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 + +// Enable an emergency-command parser to intercept certain commands as they +// enter the serial receive buffer, so they cannot be blocked. +// Currently handles M108, M112, M410 +// Does not work on boards using AT90USB (USBCON) processors! +#define EMERGENCY_PARSER + +// Bad Serial-connections can miss a received command by sending an 'ok' +// Therefore some clients abort after 30 seconds in a timeout. +// Some other clients start sending commands while receiving a 'wait'. +// This "wait" is only sent when the buffer is empty. 1 second is a good value here. +//#define NO_TIMEOUTS 1000 // Milliseconds + +// Some clients will have this feature soon. This could make the NO_TIMEOUTS unnecessary. +//#define ADVANCED_OK + +// @section extras + +/** + * Firmware-based and LCD-controlled retract + * + * Add G10 / G11 commands for automatic firmware-based retract / recover. + * Use M207 and M208 to define parameters for retract / recover. + * + * Use M209 to enable or disable auto-retract. + * With auto-retract enabled, all G1 E moves within the set range + * will be converted to firmware-based retract/recover moves. + * + * Be sure to turn off auto-retract during filament change. + * + * Note that M207 / M208 / M209 settings are saved to EEPROM. + * + */ +//#define FWRETRACT // ONLY PARTIALLY TESTED +#if ENABLED(FWRETRACT) + #define MIN_AUTORETRACT 0.1 // When auto-retract is on, convert E moves of this length and over + #define MAX_AUTORETRACT 10.0 // Upper limit for auto-retract conversion + #define RETRACT_LENGTH 3 // Default retract length (positive mm) + #define RETRACT_LENGTH_SWAP 13 // Default swap retract length (positive mm), for extruder change + #define RETRACT_FEEDRATE 45 // Default feedrate for retracting (mm/s) + #define RETRACT_ZLIFT 0 // Default retract Z-lift + #define RETRACT_RECOVER_LENGTH 0 // Default additional recover length (mm, added to retract length when recovering) + #define RETRACT_RECOVER_LENGTH_SWAP 0 // Default additional swap recover length (mm, added to retract length when recovering from extruder change) + #define RETRACT_RECOVER_FEEDRATE 8 // Default feedrate for recovering from retraction (mm/s) + #define RETRACT_RECOVER_FEEDRATE_SWAP 8 // Default feedrate for recovering from swap retraction (mm/s) +#endif + +/** + * Advanced Pause + * Experimental feature for filament change support and for parking the nozzle when paused. + * Adds the GCode M600 for initiating filament change. + * If PARK_HEAD_ON_PAUSE enabled, adds the GCode M125 to pause printing and park the nozzle. + * + * Requires an LCD display. + * This feature is required for the default FILAMENT_RUNOUT_SCRIPT. + */ +//#define ADVANCED_PAUSE_FEATURE +#if ENABLED(ADVANCED_PAUSE_FEATURE) + #define PAUSE_PARK_X_POS 3 // X position of hotend + #define PAUSE_PARK_Y_POS 3 // Y position of hotend + #define PAUSE_PARK_Z_ADD 10 // Z addition of hotend (lift) + #define PAUSE_PARK_XY_FEEDRATE 100 // X and Y axes feedrate in mm/s (also used for delta printers Z axis) + #define PAUSE_PARK_Z_FEEDRATE 5 // Z axis feedrate in mm/s (not used for delta printers) + #define PAUSE_PARK_RETRACT_FEEDRATE 60 // Initial retract feedrate in mm/s + #define PAUSE_PARK_RETRACT_LENGTH 2 // Initial retract in mm + // It is a short retract used immediately after print interrupt before move to filament exchange position + #define FILAMENT_CHANGE_UNLOAD_FEEDRATE 10 // Unload filament feedrate in mm/s - filament unloading can be fast + #define FILAMENT_CHANGE_UNLOAD_LENGTH 100 // Unload filament length from hotend in mm + // Longer length for bowden printers to unload filament from whole bowden tube, + // shorter length for printers without bowden to unload filament from extruder only, + // 0 to disable unloading for manual unloading + #define FILAMENT_CHANGE_LOAD_FEEDRATE 6 // Load filament feedrate in mm/s - filament loading into the bowden tube can be fast + #define FILAMENT_CHANGE_LOAD_LENGTH 0 // Load filament length over hotend in mm + // Longer length for bowden printers to fast load filament into whole bowden tube over the hotend, + // Short or zero length for printers without bowden where loading is not used + #define ADVANCED_PAUSE_EXTRUDE_FEEDRATE 3 // Extrude filament feedrate in mm/s - must be slower than load feedrate + #define ADVANCED_PAUSE_EXTRUDE_LENGTH 50 // Extrude filament length in mm after filament is loaded over the hotend, + // 0 to disable for manual extrusion + // Filament can be extruded repeatedly from the filament exchange menu to fill the hotend, + // or until outcoming filament color is not clear for filament color change + #define PAUSE_PARK_NOZZLE_TIMEOUT 45 // Turn off nozzle if user doesn't change filament within this time limit in seconds + #define FILAMENT_CHANGE_NUMBER_OF_ALERT_BEEPS 5 // Number of alert beeps before printer goes quiet + #define PAUSE_PARK_NO_STEPPER_TIMEOUT // Enable to have stepper motors hold position during filament change + // even if it takes longer than DEFAULT_STEPPER_DEACTIVE_TIME. + //#define PARK_HEAD_ON_PAUSE // Go to filament change position on pause, return to print position on resume + //#define HOME_BEFORE_FILAMENT_CHANGE // Ensure homing has been completed prior to parking for filament change +#endif + +// @section tmc + +/** + * Enable this section if you have TMC26X motor drivers. + * You will need to import the TMC26XStepper library into the Arduino IDE for this + * (https://github.com/trinamic/TMC26XStepper.git) + */ +//#define HAVE_TMCDRIVER + +#if ENABLED(HAVE_TMCDRIVER) + + //#define X_IS_TMC + //#define X2_IS_TMC + //#define Y_IS_TMC + //#define Y2_IS_TMC + //#define Z_IS_TMC + //#define Z2_IS_TMC + //#define E0_IS_TMC + //#define E1_IS_TMC + //#define E2_IS_TMC + //#define E3_IS_TMC + //#define E4_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_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 + + #define E4_MAX_CURRENT 1000 + #define E4_SENSE_RESISTOR 91 + #define E4_MICROSTEPS 16 + +#endif + +// @section TMC2130 + +/** + * Enable this for SilentStepStick Trinamic TMC2130 SPI-configurable stepper drivers. + * + * You'll also need the TMC2130Stepper Arduino library + * (https://github.com/teemuatlut/TMC2130Stepper). + * + * 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_TMC2130 + +#if ENABLED(HAVE_TMC2130) + + // 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 + //#define E4_IS_TMC2130 + + /** + * Stepper driver settings + */ + + #define R_SENSE 0.11 // R_sense resistor for SilentStepStick2130 + #define HOLD_MULTIPLIER 0.5 // Scales down the holding current from run current + #define INTERPOLATE 1 // Interpolate X/Y/Z_MICROSTEPS to 256 + + #define X_CURRENT 1000 // rms current in mA. Multiply by 1.41 for peak current. + #define X_MICROSTEPS 16 // 0..256 + + #define Y_CURRENT 1000 + #define Y_MICROSTEPS 16 + + #define Z_CURRENT 1000 + #define Z_MICROSTEPS 16 + + //#define X2_CURRENT 1000 + //#define X2_MICROSTEPS 16 + + //#define Y2_CURRENT 1000 + //#define Y2_MICROSTEPS 16 + + //#define Z2_CURRENT 1000 + //#define Z2_MICROSTEPS 16 + + //#define E0_CURRENT 1000 + //#define E0_MICROSTEPS 16 + + //#define E1_CURRENT 1000 + //#define E1_MICROSTEPS 16 + + //#define E2_CURRENT 1000 + //#define E2_MICROSTEPS 16 + + //#define E3_CURRENT 1000 + //#define E3_MICROSTEPS 16 + + //#define E4_CURRENT 1000 + //#define E4_MICROSTEPS 16 + + /** + * Use Trinamic's ultra quiet stepping mode. + * When disabled, Marlin will use spreadCycle stepping mode. + */ + #define STEALTHCHOP + + /** + * Let Marlin automatically control stepper current. + * This is still an experimental feature. + * Increase current every 5s by CURRENT_STEP until stepper temperature prewarn gets triggered, + * then decrease current by CURRENT_STEP until temperature prewarn is cleared. + * Adjusting starts from X/Y/Z/E_CURRENT but will not increase over AUTO_ADJUST_MAX + * Relevant g-codes: + * M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given. + * M906 S1 - Start adjusting current + * M906 S0 - Stop adjusting current + * M911 - Report stepper driver overtemperature pre-warn condition. + * M912 - Clear stepper driver overtemperature pre-warn condition flag. + */ + //#define AUTOMATIC_CURRENT_CONTROL + + #if ENABLED(AUTOMATIC_CURRENT_CONTROL) + #define CURRENT_STEP 50 // [mA] + #define AUTO_ADJUST_MAX 1300 // [mA], 1300mA_rms = 1840mA_peak + #define REPORT_CURRENT_CHANGE + #endif + + /** + * The driver will switch to spreadCycle when stepper speed is over HYBRID_THRESHOLD. + * This mode allows for faster movements at the expense of higher noise levels. + * STEALTHCHOP needs to be enabled. + * M913 X/Y/Z/E to live tune the setting + */ + //#define HYBRID_THRESHOLD + + #define X_HYBRID_THRESHOLD 100 // [mm/s] + #define X2_HYBRID_THRESHOLD 100 + #define Y_HYBRID_THRESHOLD 100 + #define Y2_HYBRID_THRESHOLD 100 + #define Z_HYBRID_THRESHOLD 4 + #define Z2_HYBRID_THRESHOLD 4 + #define E0_HYBRID_THRESHOLD 30 + #define E1_HYBRID_THRESHOLD 30 + #define E2_HYBRID_THRESHOLD 30 + #define E3_HYBRID_THRESHOLD 30 + #define E4_HYBRID_THRESHOLD 30 + + /** + * Use stallGuard2 to sense an obstacle and trigger an endstop. + * You need to place a wire from the driver's DIAG1 pin to the X/Y endstop pin. + * If used along with STEALTHCHOP, the movement will be louder when homing. This is normal. + * + * X/Y_HOMING_SENSITIVITY is used for tuning the trigger sensitivity. + * Higher values make the system LESS sensitive. + * Lower value make the system MORE sensitive. + * Too low values can lead to false positives, while too high values will collide the axis without triggering. + * It is advised to set X/Y_HOME_BUMP_MM to 0. + * M914 X/Y to live tune the setting + */ + //#define SENSORLESS_HOMING + + #if ENABLED(SENSORLESS_HOMING) + #define X_HOMING_SENSITIVITY 19 + #define Y_HOMING_SENSITIVITY 19 + #endif + + /** + * You can set your own advanced settings by filling in predefined functions. + * A list of available functions can be found on the library github page + * https://github.com/teemuatlut/TMC2130Stepper + * + * Example: + * #define TMC2130_ADV() { \ + * stepperX.diag0_temp_prewarn(1); \ + * stepperX.interpolate(0); \ + * } + */ + #define TMC2130_ADV() { } + +#endif // HAVE_TMC2130 + +// @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 X2_IS_L6470 + //#define Y_IS_L6470 + //#define Y2_IS_L6470 + //#define Z_IS_L6470 + //#define Z2_IS_L6470 + //#define E0_IS_L6470 + //#define E1_IS_L6470 + //#define E2_IS_L6470 + //#define E3_IS_L6470 + //#define E4_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_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 + + #define E4_MICROSTEPS 16 + #define E4_K_VAL 50 + #define E4_OVERCURRENT 2000 + #define E4_STALLCURRENT 1500 + +#endif + +/** + * TWI/I2C BUS + * + * This feature is an EXPERIMENTAL feature so it shall not be used on production + * machines. Enabling this will allow you to send and receive I2C data from slave + * devices on the bus. + * + * ; Example #1 + * ; This macro send the string "Marlin" to the slave device with address 0x63 (99) + * ; 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) + * M261 A99 B5 + * + * ; Example #3 + * ; 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 + +// @section extras + +/** + * Spindle & Laser control + * + * Add the M3, M4, and M5 commands to turn the spindle/laser on and off, and + * to set spindle speed, spindle direction, and laser power. + * + * SuperPid is a router/spindle speed controller used in the CNC milling community. + * Marlin can be used to turn the spindle on and off. It can also be used to set + * the spindle speed from 5,000 to 30,000 RPM. + * + * You'll need to select a pin for the ON/OFF function and optionally choose a 0-5V + * hardware PWM pin for the speed control and a pin for the rotation direction. + * + * See http://marlinfw.org/docs/configuration/laser_spindle.html for more config details. + */ +//#define SPINDLE_LASER_ENABLE +#if ENABLED(SPINDLE_LASER_ENABLE) + + #define SPINDLE_LASER_ENABLE_INVERT false // set to "true" if the on/off function is reversed + #define SPINDLE_LASER_PWM true // set to true if your controller supports setting the speed/power + #define SPINDLE_LASER_PWM_INVERT true // set to "true" if the speed/power goes up when you want it to go slower + #define SPINDLE_LASER_POWERUP_DELAY 5000 // delay in milliseconds to allow the spindle/laser to come up to speed/power + #define SPINDLE_LASER_POWERDOWN_DELAY 5000 // delay in milliseconds to allow the spindle to stop + #define SPINDLE_DIR_CHANGE true // set to true if your spindle controller supports changing spindle direction + #define SPINDLE_INVERT_DIR false + #define SPINDLE_STOP_ON_DIR_CHANGE true // set to true if Marlin should stop the spindle before changing rotation direction + + /** + * The M3 & M4 commands use the following equation to convert PWM duty cycle to speed/power + * + * SPEED/POWER = PWM duty cycle * SPEED_POWER_SLOPE + SPEED_POWER_INTERCEPT + * where PWM duty cycle varies from 0 to 255 + * + * set the following for your controller (ALL MUST BE SET) + */ + + #define SPEED_POWER_SLOPE 118.4 + #define SPEED_POWER_INTERCEPT 0 + #define SPEED_POWER_MIN 5000 + #define SPEED_POWER_MAX 30000 // SuperPID router controller 0 - 30,000 RPM + + //#define SPEED_POWER_SLOPE 0.3922 + //#define SPEED_POWER_INTERCEPT 0 + //#define SPEED_POWER_MIN 10 + //#define SPEED_POWER_MAX 100 // 0-100% +#endif + +/** + * M43 - display pin status, watch pins for changes, watch endstops & toggle LED, Z servo probe test, toggle pins + */ +//#define PINS_DEBUGGING + +/** + * Auto-report temperatures with M155 S + */ +#define AUTO_REPORT_TEMPERATURES + +/** + * Include capabilities in M115 output + */ +#define EXTENDED_CAPABILITIES_REPORT + +/** + * Volumetric extrusion default state + * Activate to make volumetric extrusion the default method, + * with DEFAULT_NOMINAL_FILAMENT_DIA as the default diameter. + * + * M200 D0 to disable, M200 Dn to set a new diameter. + */ +//#define VOLUMETRIC_DEFAULT_ON + +/** + * Enable this option for a leaner build of Marlin that removes all + * workspace offsets, simplifying coordinate transformations, leveling, etc. + * + * - M206 and M428 are disabled. + * - G92 will revert to its behavior from Marlin 1.0. + */ +#define NO_WORKSPACE_OFFSETS + +/** + * Set the number of proportional font spaces required to fill up a typical character space. + * This can help to better align the output of commands like `G29 O` Mesh Output. + * + * For clients that use a fixed-width font (like OctoPrint), leave this set to 1.0. + * Otherwise, adjust according to your client and font. + */ +#define PROPORTIONAL_FONT_RATIO 1.0 + +/** + * Spend 28 bytes of SRAM to optimize the GCode parser + */ +#define FASTER_GCODE_PARSER + +/** + * User-defined menu items that execute custom GCode + */ +//#define CUSTOM_USER_MENUS +#if ENABLED(CUSTOM_USER_MENUS) + #define USER_SCRIPT_DONE "M117 User Script Done" + #define USER_SCRIPT_AUDIBLE_FEEDBACK + + #define USER_DESC_1 "Home & UBL Info" + #define USER_GCODE_1 "G28\nG29 W" + + #define USER_DESC_2 "Preheat for PLA" + #define USER_GCODE_2 "M140 S" STRINGIFY(PREHEAT_1_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_1_TEMP_HOTEND) + + #define USER_DESC_3 "Preheat for ABS" + #define USER_GCODE_3 "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_2_TEMP_HOTEND) + + #define USER_DESC_4 "Heat Bed/Home/Level" + #define USER_GCODE_4 "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nG28\nG29" + + #define USER_DESC_5 "Home & Info" + #define USER_GCODE_5 "G28\nM503" +#endif + +/** + * Specify an action command to send to the host when the printer is killed. + * Will be sent in the form '//action:ACTION_ON_KILL', e.g. '//action:poweroff'. + * The host must be configured to handle the action command. + */ +//#define ACTION_ON_KILL "poweroff" + +//=========================================================================== +//====================== I2C Position Encoder Settings ====================== +//=========================================================================== + +/** + * I2C position encoders for closed loop control. + * Developed by Chris Barr at Aus3D. + * + * Wiki: http://wiki.aus3d.com.au/Magnetic_Encoder + * Github: https://github.com/Aus3D/MagneticEncoder + * + * Supplier: http://aus3d.com.au/magnetic-encoder-module + * Alternative Supplier: http://reliabuild3d.com/ + * + * Reilabuild encoders have been modified to improve reliability. + */ + +//#define I2C_POSITION_ENCODERS +#if ENABLED(I2C_POSITION_ENCODERS) + + #define I2CPE_ENCODER_CNT 1 // The number of encoders installed; max of 5 + // encoders supported currently. + + #define I2CPE_ENC_1_ADDR I2CPE_PRESET_ADDR_X // I2C address of the encoder. 30-200. + #define I2CPE_ENC_1_AXIS X_AXIS // Axis the encoder module is installed on. _AXIS. + #define I2CPE_ENC_1_TYPE I2CPE_ENC_TYPE_LINEAR // Type of encoder: I2CPE_ENC_TYPE_LINEAR -or- + // I2CPE_ENC_TYPE_ROTARY. + #define I2CPE_ENC_1_TICKS_UNIT 2048 // 1024 for magnetic strips with 2mm poles; 2048 for + // 1mm poles. For linear encoders this is ticks / mm, + // for rotary encoders this is ticks / revolution. + //#define I2CPE_ENC_1_TICKS_REV (16 * 200) // Only needed for rotary encoders; number of stepper + // steps per full revolution (motor steps/rev * microstepping) + //#define I2CPE_ENC_1_INVERT // Invert the direction of axis travel. + #define I2CPE_ENC_1_EC_METHOD I2CPE_ECM_NONE // Type of error error correction. + #define I2CPE_ENC_1_EC_THRESH 0.10 // Threshold size for error (in mm) above which the + // printer will attempt to correct the error; errors + // smaller than this are ignored to minimize effects of + // measurement noise / latency (filter). + + #define I2CPE_ENC_2_ADDR I2CPE_PRESET_ADDR_Y // Same as above, but for encoder 2. + #define I2CPE_ENC_2_AXIS Y_AXIS + #define I2CPE_ENC_2_TYPE I2CPE_ENC_TYPE_LINEAR + #define I2CPE_ENC_2_TICKS_UNIT 2048 + //#define I2CPE_ENC_2_TICKS_REV (16 * 200) + //#define I2CPE_ENC_2_INVERT + #define I2CPE_ENC_2_EC_METHOD I2CPE_ECM_NONE + #define I2CPE_ENC_2_EC_THRESH 0.10 + + #define I2CPE_ENC_3_ADDR I2CPE_PRESET_ADDR_Z // Encoder 3. Add additional configuration options + #define I2CPE_ENC_3_AXIS Z_AXIS // as above, or use defaults below. + + #define I2CPE_ENC_4_ADDR I2CPE_PRESET_ADDR_E // Encoder 4. + #define I2CPE_ENC_4_AXIS E_AXIS + + #define I2CPE_ENC_5_ADDR 34 // Encoder 5. + #define I2CPE_ENC_5_AXIS E_AXIS + + // Default settings for encoders which are enabled, but without settings configured above. + #define I2CPE_DEF_TYPE I2CPE_ENC_TYPE_LINEAR + #define I2CPE_DEF_ENC_TICKS_UNIT 2048 + #define I2CPE_DEF_TICKS_REV (16 * 200) + #define I2CPE_DEF_EC_METHOD I2CPE_ECM_NONE + #define I2CPE_DEF_EC_THRESH 0.1 + + //#define I2CPE_ERR_THRESH_ABORT 100.0 // Threshold size for error (in mm) error on any given + // axis after which the printer will abort. Comment out to + // disable abort behaviour. + + #define I2CPE_TIME_TRUSTED 10000 // After an encoder fault, there must be no further fault + // for this amount of time (in ms) before the encoder + // is trusted again. + + /** + * Position is checked every time a new command is executed from the buffer but during long moves, + * this setting determines the minimum update time between checks. A value of 100 works well with + * error rolling average when attempting to correct only for skips and not for vibration. + */ + #define I2CPE_MIN_UPD_TIME_MS 100 // Minimum time in miliseconds between encoder checks. + + // Use a rolling average to identify persistant errors that indicate skips, as opposed to vibration and noise. + #define I2CPE_ERR_ROLLING_AVERAGE + +#endif // I2C_POSITION_ENCODERS + +#endif // CONFIGURATION_ADV_H From 356af7dcb0cc80a0573a61279c7680ec2b9e7352 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 23 Aug 2017 18:20:40 -0500 Subject: [PATCH 104/112] Tweak Sanguinololu-related pins files --- Marlin/pins_AZTEEG_X1.h | 3 +-- Marlin/pins_MELZI.h | 9 ++------- Marlin/pins_MELZI_CREALITY.h | 9 ++------- Marlin/pins_MELZI_MAKR3D.h | 9 ++------- Marlin/pins_SANGUINOLOLU_11.h | 29 ++++++++++++++++++++--------- Marlin/pins_SANGUINOLOLU_12.h | 7 +++---- Marlin/pins_STB_11.h | 8 +------- 7 files changed, 31 insertions(+), 43 deletions(-) diff --git a/Marlin/pins_AZTEEG_X1.h b/Marlin/pins_AZTEEG_X1.h index 8f87a7eaa..17290d110 100644 --- a/Marlin/pins_AZTEEG_X1.h +++ b/Marlin/pins_AZTEEG_X1.h @@ -26,5 +26,4 @@ #define BOARD_NAME "Azteeg X1" -#define SANGUINOLOLU_V_1_2 -#include "pins_SANGUINOLOLU_11.h" +#include "pins_SANGUINOLOLU_12.h" diff --git a/Marlin/pins_MELZI.h b/Marlin/pins_MELZI.h index 7c99373f3..4f6ccb5e0 100644 --- a/Marlin/pins_MELZI.h +++ b/Marlin/pins_MELZI.h @@ -25,10 +25,5 @@ */ #define BOARD_NAME "Melzi" - -#ifdef __AVR_ATmega1284P__ - #define LARGE_FLASH true -#endif - -#define SANGUINOLOLU_V_1_2 -#include "pins_SANGUINOLOLU_11.h" +#define IS_MELZI +#include "pins_SANGUINOLOLU_12.h" diff --git a/Marlin/pins_MELZI_CREALITY.h b/Marlin/pins_MELZI_CREALITY.h index d66f589fe..b2f0cf871 100644 --- a/Marlin/pins_MELZI_CREALITY.h +++ b/Marlin/pins_MELZI_CREALITY.h @@ -25,17 +25,12 @@ */ #define BOARD_NAME "Melzi (Creality)" - -#ifdef __AVR_ATmega1284P__ - #define LARGE_FLASH true -#endif +#define IS_MELZI +#include "pins_SANGUINOLOLU_12.h" // For the stock CR-10 use the REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER // option for the display in Configuration.h -#define SANGUINOLOLU_V_1_2 -#include "pins_SANGUINOLOLU_11.h" - #undef LCD_SDSS #undef LED_PIN diff --git a/Marlin/pins_MELZI_MAKR3D.h b/Marlin/pins_MELZI_MAKR3D.h index bd86f59c0..556f9ce87 100644 --- a/Marlin/pins_MELZI_MAKR3D.h +++ b/Marlin/pins_MELZI_MAKR3D.h @@ -25,10 +25,5 @@ */ #define BOARD_NAME "Melzi (ATmega1284)" - -#ifdef __AVR_ATmega1284P__ - #define LARGE_FLASH true -#endif - -#define SANGUINOLOLU_V_1_2 -#include "pins_SANGUINOLOLU_11.h" +#define IS_MELZI +#include "pins_SANGUINOLOLU_12.h" diff --git a/Marlin/pins_SANGUINOLOLU_11.h b/Marlin/pins_SANGUINOLOLU_11.h index 0691fb321..4ed004549 100644 --- a/Marlin/pins_SANGUINOLOLU_11.h +++ b/Marlin/pins_SANGUINOLOLU_11.h @@ -59,7 +59,9 @@ #define BOARD_NAME "Sanguinololu <1.2" #endif -#define IS_MELZI (MB(MELZI) || MB(MELZI_MAKR3D) || MB(MELZI_CREALITY)) +#ifdef __AVR_ATmega1284P__ + #define LARGE_FLASH true +#endif // // Limit Switches @@ -116,7 +118,7 @@ #endif -#if MB(AZTEEG_X1) || MB(STB_11) || IS_MELZI +#if MB(AZTEEG_X1) || MB(STB_11) || ENABLED(IS_MELZI) #define FAN_PIN 4 // Works for Panelolu2 too #endif @@ -133,16 +135,25 @@ //#define SDSS 24 #define SDSS 31 -#if IS_MELZI - #define LED_PIN 27 +#if ENABLED(IS_MELZI) + #define LED_PIN 27 #elif MB(STB_11) #define LCD_BACKLIGHT_PIN 17 // LCD backlight LED #endif #if DISABLED(SPINDLE_LASER_ENABLE) && ENABLED(SANGUINOLOLU_V_1_2) && !(ENABLED(ULTRA_LCD) && ENABLED(NEWPANEL)) // try to use IO Header - #define CASE_LIGHT_PIN 4 // MUST BE HARDWARE PWM - see if IO Header is available + #define CASE_LIGHT_PIN 4 // MUST BE HARDWARE PWM - see if IO Header is available #endif +/** + * Sanguinololu 1.4 AUX pins: + * + * PWM TX1 RX1 SDA SCL + * 12V 5V D12 D11 D10 D17 D16 + * GND GND D31 D30 D29 D28 D27 + * A4 A3 A2 A1 A0 + */ + // // LCD / Controller // @@ -152,7 +163,7 @@ #if ENABLED(U8GLIB_ST7920) // SPI GLCD 12864 ST7920 ( like [www.digole.com] ) For Melzi V2.0 - #if IS_MELZI // Melzi board + #if ENABLED(IS_MELZI) #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 @@ -160,7 +171,7 @@ // Marlin so this can be used for BEEPER_PIN. You can use this pin // with M42 instead of BEEPER_PIN. #define BEEPER_PIN 27 - #else // Sanguinololu 1.3 + #else // Sanguinololu >=1.3 #define LCD_PINS_RS 4 #define LCD_PINS_ENABLE 17 #define LCD_PINS_D4 30 @@ -210,7 +221,7 @@ #if ENABLED(LCD_I2C_PANELOLU2) - #if IS_MELZI + #if ENABLED(IS_MELZI) #define BTN_ENC 29 #define LCD_SDSS 30 // Panelolu2 SD card reader rather than the Melzi #else @@ -280,7 +291,7 @@ * MS3 O| |O 2A * /RESET O| |O 1A * /SLEEP O| |O 1B - * SPINDLE_LASER_PWM_PIN STEP O| |O VDD + * SPINDLE_LASER_PWM_PIN STEP O| |O VDD * SPINDLE_LASER_ENABLE_PIN DIR O| |O GND * ------- * diff --git a/Marlin/pins_SANGUINOLOLU_12.h b/Marlin/pins_SANGUINOLOLU_12.h index 19c9e4939..f648dce08 100644 --- a/Marlin/pins_SANGUINOLOLU_12.h +++ b/Marlin/pins_SANGUINOLOLU_12.h @@ -27,15 +27,14 @@ * * AZTEEG_X1 * MELZI + * MELZI_CREALITY * MELZI_MAKR3D * SANGUINOLOLU_12 * STB_11 */ -#define BOARD_NAME "Sanguinololu 1.2" - -#ifdef __AVR_ATmega1284P__ - #define LARGE_FLASH true +#ifndef BOARD_NAME + #define BOARD_NAME "Sanguinololu 1.2" #endif #define SANGUINOLOLU_V_1_2 diff --git a/Marlin/pins_STB_11.h b/Marlin/pins_STB_11.h index 05fc40481..de769fcb6 100644 --- a/Marlin/pins_STB_11.h +++ b/Marlin/pins_STB_11.h @@ -25,10 +25,4 @@ */ #define BOARD_NAME "STB V1.1" - -#ifdef __AVR_ATmega1284P__ - #define LARGE_FLASH true -#endif - -#define SANGUINOLOLU_V_1_2 -#include "pins_SANGUINOLOLU_11.h" +#include "pins_SANGUINOLOLU_12.h" From c7b07d20f2dabbd44a6ea50de1daba9fedf7ea26 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 23 Aug 2017 18:23:19 -0500 Subject: [PATCH 105/112] Minor patches to pins files --- Marlin/pins_GEN6.h | 6 ++---- Marlin/pins_GT2560_REV_A_PLUS.h | 1 + 2 files changed, 3 insertions(+), 4 deletions(-) diff --git a/Marlin/pins_GEN6.h b/Marlin/pins_GEN6.h index 5611e4d92..1c5e2069a 100644 --- a/Marlin/pins_GEN6.h +++ b/Marlin/pins_GEN6.h @@ -51,10 +51,8 @@ * */ -#ifndef __AVR_ATmega644P__ - #ifndef __AVR_ATmega1284P__ - #error "Oops! Make sure you have 'Sanguino' selected from the 'Tools -> Boards' menu." - #endif +#if !defined(__AVR_ATmega644P__) && !defined(__AVR_ATmega1284P__) + #error "Oops! Make sure you have 'Sanguino' selected from the 'Tools -> Boards' menu." #endif #ifndef BOARD_NAME diff --git a/Marlin/pins_GT2560_REV_A_PLUS.h b/Marlin/pins_GT2560_REV_A_PLUS.h index b722c04fd..7eed3b859 100644 --- a/Marlin/pins_GT2560_REV_A_PLUS.h +++ b/Marlin/pins_GT2560_REV_A_PLUS.h @@ -26,6 +26,7 @@ #include "pins_GT2560_REV_A.h" +#undef BOARD_NAME #define BOARD_NAME "GT2560 Rev.A+" #define SERVO0_PIN 11 From 86c024ce98f822420706af28c842a7dc10e11838 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 23 Aug 2017 18:24:02 -0500 Subject: [PATCH 106/112] Organize, document pins.h include lines --- Marlin/pins.h | 261 ++++++++++++++++++++++++++++---------------------- 1 file changed, 148 insertions(+), 113 deletions(-) diff --git a/Marlin/pins.h b/Marlin/pins.h index 867b5ac25..99cb18756 100644 --- a/Marlin/pins.h +++ b/Marlin/pins.h @@ -35,27 +35,11 @@ #ifndef __PINS_H__ #define __PINS_H__ -#if MB(GEN7_CUSTOM) - #include "pins_GEN7_CUSTOM.h" -#elif MB(GEN7_12) - #include "pins_GEN7_12.h" -#elif MB(GEN7_13) - #include "pins_GEN7_13.h" -#elif MB(GEN7_14) - #include "pins_GEN7_14.h" -#elif MB(CNCONTROLS_11) - #include "pins_CNCONTROLS_11.h" -#elif MB(CNCONTROLS_12) - #include "pins_CNCONTROLS_12.h" -#elif MB(CHEAPTRONIC) - #include "pins_CHEAPTRONIC.h" -#elif MB(CHEAPTRONIC_V2) - #include "pins_CHEAPTRONICv2.h" -#elif MB(SETHI) - #include "pins_SETHI.h" -#elif MB(MIGHTYBOARD_REVE) - #include "pins_MIGHTYBOARD_REVE.h" -#elif MB(RAMPS_OLD) +// +// RAMPS 1.3 / 1.4 - ATmega1280, ATmega2560 +// + +#if MB(RAMPS_OLD) #include "pins_RAMPS_OLD.h" #elif MB(RAMPS_13_EFB) #define IS_RAMPS_EFB @@ -87,115 +71,166 @@ #elif MB(RAMPS_14_SF) #define IS_RAMPS_SF #include "pins_RAMPS.h" -#elif MB(GEN6) - #include "pins_GEN6.h" -#elif MB(GEN6_DELUXE) - #include "pins_GEN6_DELUXE.h" -#elif MB(SANGUINOLOLU_11) - #include "pins_SANGUINOLOLU_11.h" -#elif MB(SANGUINOLOLU_12) - #include "pins_SANGUINOLOLU_12.h" -#elif MB(MELZI) - #include "pins_MELZI.h" -#elif MB(MELZI_MAKR3D) - #include "pins_MELZI_MAKR3D.h" -#elif MB(MELZI_CREALITY) - #include "pins_MELZI_CREALITY.h" -#elif MB(STB_11) - #include "pins_STB_11.h" -#elif MB(AZTEEG_X1) - #include "pins_AZTEEG_X1.h" -#elif MB(AZTEEG_X3) - #include "pins_AZTEEG_X3.h" -#elif MB(AZTEEG_X3_PRO) - #include "pins_AZTEEG_X3_PRO.h" -#elif MB(ANET_10) - #include "pins_ANET_10.h" -#elif MB(ULTIMAKER) - #include "pins_ULTIMAKER.h" -#elif MB(ULTIMAKER_OLD) - #include "pins_ULTIMAKER_OLD.h" -#elif MB(ULTIMAIN_2) - #include "pins_ULTIMAIN_2.h" + +// +// RAMPS Derivatives - ATmega1280, ATmega2560 +// + #elif MB(3DRAG) - #include "pins_3DRAG.h" + #include "pins_3DRAG.h" // ATmega1280, ATmega2560 #elif MB(K8200) - #include "pins_K8200.h" + #include "pins_K8200.h" // ATmega1280, ATmega2560 (3DRAG) #elif MB(K8400) - #include "pins_K8400.h" -#elif MB(TEENSYLU) - #include "pins_TEENSYLU.h" + #include "pins_K8400.h" // ATmega1280, ATmega2560 (3DRAG) +#elif MB(BAM_DICE) + #include "pins_RAMPS.h" // ATmega1280, ATmega2560 +#elif MB(BAM_DICE_DUE) + #include "pins_BAM_DICE_DUE.h" // ATmega1280, ATmega2560 +#elif MB(MKS_BASE) + #include "pins_MKS_BASE.h" // ATmega1280, ATmega2560 +#elif MB(MKS_13) + #include "pins_MKS_13.h" // ATmega1280, ATmega2560 +#elif MB(ZRIB_V20) + #include "pins_ZRIB_V20.h" // ATmega1280, ATmega2560 (MKS_13) +#elif MB(FELIX2) + #include "pins_FELIX2.h" // ATmega1280, ATmega2560 +#elif MB(RIGIDBOARD) + #include "pins_RIGIDBOARD.h" // ATmega1280, ATmega2560 +#elif MB(RIGIDBOARD_V2) + #include "pins_RIGIDBOARD_V2.h" // ATmega1280, ATmega2560 +#elif MB(SAINSMART_2IN1) + #include "pins_SAINSMART_2IN1.h" // ATmega1280, ATmega2560 +#elif MB(ULTIMAKER) + #include "pins_ULTIMAKER.h" // ATmega1280, ATmega2560 +#elif MB(ULTIMAKER_OLD) + #include "pins_ULTIMAKER_OLD.h" // ATmega1280, ATmega2560 +#elif MB(AZTEEG_X3) + #include "pins_AZTEEG_X3.h" // ATmega2560 +#elif MB(AZTEEG_X3_PRO) + #include "pins_AZTEEG_X3_PRO.h" // ATmega2560 +#elif MB(ULTIMAIN_2) + #include "pins_ULTIMAIN_2.h" // ATmega2560 #elif MB(RUMBA) - #include "pins_RUMBA.h" -#elif MB(PRINTRBOARD) - #include "pins_PRINTRBOARD.h" -#elif MB(PRINTRBOARD_REVF) - #include "pins_PRINTRBOARD_REVF.h" -#elif MB(BRAINWAVE) - #include "pins_BRAINWAVE.h" -#elif MB(BRAINWAVE_PRO) - #include "pins_BRAINWAVE_PRO.h" -#elif MB(SAV_MKI) - #include "pins_SAV_MKI.h" -#elif MB(TEENSY2) - #include "pins_TEENSY2.h" -#elif MB(GEN3_PLUS) - #include "pins_GEN3_PLUS.h" -#elif MB(GEN3_MONOLITHIC) - #include "pins_GEN3_MONOLITHIC.h" + #include "pins_RUMBA.h" // ATmega2560 +#elif MB(BQ_ZUM_MEGA_3D) + #include "pins_BQ_ZUM_MEGA_3D.h" // ATmega2560 + +// +// Other ATmega1280, ATmega2560 +// + +#elif MB(CNCONTROLS_11) + #include "pins_CNCONTROLS_11.h" // ATmega1280, ATmega2560 +#elif MB(CNCONTROLS_12) + #include "pins_CNCONTROLS_12.h" // ATmega1280, ATmega2560 +#elif MB(MIGHTYBOARD_REVE) + #include "pins_MIGHTYBOARD_REVE.h" // ATmega1280, ATmega2560 +#elif MB(CHEAPTRONIC) + #include "pins_CHEAPTRONIC.h" // ATmega2560 +#elif MB(CHEAPTRONIC_V2) + #include "pins_CHEAPTRONICv2.h" // ATmega2560 #elif MB(MEGATRONICS) - #include "pins_MEGATRONICS.h" -#elif MB(MINITRONICS) - #include "pins_MINITRONICS.h" + #include "pins_MEGATRONICS.h" // ATmega2560 #elif MB(MEGATRONICS_2) - #include "pins_MEGATRONICS_2.h" + #include "pins_MEGATRONICS_2.h" // ATmega2560 #elif MB(MEGATRONICS_3) - #include "pins_MEGATRONICS_3.h" + #include "pins_MEGATRONICS_3.h" // ATmega2560 #elif MB(MEGATRONICS_31) #define MEGATRONICS_31 - #include "pins_MEGATRONICS_3.h" -#elif MB(OMCA_A) - #include "pins_OMCA_A.h" -#elif MB(OMCA) - #include "pins_OMCA.h" + #include "pins_MEGATRONICS_3.h" // ATmega2560 #elif MB(RAMBO) - #include "pins_RAMBO.h" + #include "pins_RAMBO.h" // ATmega2560 #elif MB(MINIRAMBO) - #include "pins_MINIRAMBO.h" + #include "pins_MINIRAMBO.h" // ATmega2560 #elif MB(ELEFU_3) - #include "pins_ELEFU_3.h" -#elif MB(5DPRINT) - #include "pins_5DPRINT.h" + #include "pins_ELEFU_3.h" // ATmega2560 #elif MB(LEAPFROG) - #include "pins_LEAPFROG.h" -#elif MB(BAM_DICE) - #include "pins_RAMPS.h" -#elif MB(BAM_DICE_DUE) - #include "pins_BAM_DICE_DUE.h" -#elif MB(FELIX2) - #include "pins_FELIX2.h" -#elif MB(MKS_BASE) - #include "pins_MKS_BASE.h" -#elif MB(RIGIDBOARD) - #include "pins_RIGIDBOARD.h" -#elif MB(RIGIDBOARD_V2) - #include "pins_RIGIDBOARD_V2.h" + #include "pins_LEAPFROG.h" // ATmega1280, ATmega2560 #elif MB(MEGACONTROLLER) - #include "pins_MEGACONTROLLER.h" -#elif MB(BQ_ZUM_MEGA_3D) - #include "pins_BQ_ZUM_MEGA_3D.h" + #include "pins_MEGACONTROLLER.h" // ATmega2560 #elif MB(SCOOVO_X9H) - #include "pins_SCOOVO_X9H.h" -#elif MB(MKS_13) - #include "pins_MKS_13.h" -#elif MB(SAINSMART_2IN1) - #include "pins_SAINSMART_2IN1.h" -#elif MB(ZRIB_V20) - #include "pins_ZRIB_V20.h" + #include "pins_SCOOVO_X9H.h" // ATmega2560 #elif MB(GT2560_REV_A) - #include "pins_GT2560_REV_A.h" + #include "pins_GT2560_REV_A.h" // ATmega1280, ATmega2560 #elif MB(GT2560_REV_A_PLUS) - #include "pins_GT2560_REV_A_PLUS.h" + #include "pins_GT2560_REV_A_PLUS.h" // ATmega1280, ATmega2560 + +// +// ATmega1281, ATmega2561 +// + +#elif MB(MINITRONICS) + #include "pins_MINITRONICS.h" // ATmega1281 + +// +// Sanguinololu and Derivatives - ATmega644P, ATmega1284P +// + +#elif MB(SANGUINOLOLU_11) + #include "pins_SANGUINOLOLU_11.h" // ATmega644P, ATmega1284P +#elif MB(SANGUINOLOLU_12) + #include "pins_SANGUINOLOLU_12.h" // ATmega644P, ATmega1284P +#elif MB(MELZI) + #include "pins_MELZI.h" // ATmega644P, ATmega1284P +#elif MB(MELZI_MAKR3D) + #include "pins_MELZI_MAKR3D.h" // ATmega644P, ATmega1284P +#elif MB(MELZI_CREALITY) + #include "pins_MELZI_CREALITY.h" // ATmega644P, ATmega1284P +#elif MB(STB_11) + #include "pins_STB_11.h" // ATmega644P, ATmega1284P +#elif MB(AZTEEG_X1) + #include "pins_AZTEEG_X1.h" // ATmega644P, ATmega1284P + +// +// Other ATmega644P, ATmega644, ATmega1284P +// + +#elif MB(GEN3_MONOLITHIC) + #include "pins_GEN3_MONOLITHIC.h" // ATmega644P +#elif MB(GEN3_PLUS) + #include "pins_GEN3_PLUS.h" // ATmega644P, ATmega1284P +#elif MB(GEN6) + #include "pins_GEN6.h" // ATmega644P, ATmega1284P +#elif MB(GEN6_DELUXE) + #include "pins_GEN6_DELUXE.h" // ATmega644P, ATmega1284P +#elif MB(GEN7_CUSTOM) + #include "pins_GEN7_CUSTOM.h" // ATmega644P, ATmega644, ATmega1284P +#elif MB(GEN7_12) + #include "pins_GEN7_12.h" // ATmega644P, ATmega644, ATmega1284P +#elif MB(GEN7_13) + #include "pins_GEN7_13.h" // ATmega644P, ATmega644, ATmega1284P +#elif MB(GEN7_14) + #include "pins_GEN7_14.h" // ATmega644P, ATmega644, ATmega1284P +#elif MB(OMCA_A) + #include "pins_OMCA_A.h" // ATmega644 +#elif MB(OMCA) + #include "pins_OMCA.h" // ATmega644P, ATmega644 +#elif MB(ANET_10) + #include "pins_ANET_10.h" // ATmega1284P +#elif MB(SETHI) + #include "pins_SETHI.h" // ATmega644P, ATmega644, ATmega1284P + +// +// Teensyduino - AT90USB1286, AT90USB1286P +// + +#elif MB(TEENSYLU) + #include "pins_TEENSYLU.h" // AT90USB1286, AT90USB1286P +#elif MB(PRINTRBOARD) + #include "pins_PRINTRBOARD.h" // AT90USB1286 +#elif MB(PRINTRBOARD_REVF) + #include "pins_PRINTRBOARD_REVF.h" // AT90USB1286 +#elif MB(BRAINWAVE) + #include "pins_BRAINWAVE.h" // AT90USB646 +#elif MB(BRAINWAVE_PRO) + #include "pins_BRAINWAVE_PRO.h" // AT90USB1286 +#elif MB(SAV_MKI) + #include "pins_SAV_MKI.h" // AT90USB1286 +#elif MB(TEENSY2) + #include "pins_TEENSY2.h" // AT90USB1286 +#elif MB(5DPRINT) + #include "pins_5DPRINT.h" // AT90USB1286 + #else #error "Unknown MOTHERBOARD value set in Configuration.h" #endif From 54d48130f3632a90b4436588e47bca559b612d78 Mon Sep 17 00:00:00 2001 From: Michal Holes Date: Sun, 20 Aug 2017 10:34:02 +0200 Subject: [PATCH 107/112] Slovak UTF-8 translation Slovak UTF-8 translation --- Marlin/Configuration.h | 6 +- .../AlephObjects/TAZ4/Configuration.h | 6 +- .../AliExpress/CL-260/Configuration.h | 6 +- .../Anet/A6/Configuration.h | 6 +- .../Anet/A8/Configuration.h | 6 +- .../BQ/Hephestos/Configuration.h | 6 +- .../BQ/Hephestos_2/Configuration.h | 6 +- .../BQ/WITBOX/Configuration.h | 6 +- .../Cartesio/Configuration.h | 6 +- .../Creality/CR-10/Configuration.h | 6 +- .../Felix/Configuration.h | 6 +- .../Felix/DUAL/Configuration.h | 6 +- .../Folger Tech/i3-2020/Configuration.h | 6 +- .../Geeetech/GT2560/Configuration.h | 6 +- .../Geeetech/I3_Pro_X-GT2560/Configuration.h | 6 +- .../Infitary/i3-M508/Configuration.h | 6 +- .../Malyan/M150/Configuration.h | 6 +- .../RepRapWorld/Megatronics/Configuration.h | 6 +- .../RigidBot/Configuration.h | 6 +- .../SCARA/Configuration.h | 6 +- .../TinyBoy2/Configuration.h | 6 +- .../Velleman/K8200/Configuration.h | 6 +- .../Velleman/K8400/Configuration.h | 6 +- .../Velleman/K8400/Dual-head/Configuration.h | 6 +- .../adafruit/ST7565/Configuration.h | 6 +- .../FLSUN/auto_calibrate/Configuration.h | 6 +- .../delta/FLSUN/kossel_mini/Configuration.h | 6 +- .../delta/generic/Configuration.h | 6 +- .../delta/kossel_mini/Configuration.h | 6 +- .../delta/kossel_pro/Configuration.h | 6 +- .../delta/kossel_xl/Configuration.h | 6 +- .../gCreate/gMax1.5+/Configuration.h | 6 +- .../makibox/Configuration.h | 6 +- .../tvrrug/Round2/Configuration.h | 6 +- .../wt150/Configuration.h | 6 +- Marlin/language.h | 6 +- Marlin/language_pl.h | 2 +- Marlin/language_sk_utf8.h | 354 ++++++++++++++++++ Marlin/utf_mapper.h | 7 +- 39 files changed, 471 insertions(+), 108 deletions(-) create mode 100644 Marlin/language_sk_utf8.h diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 66085fbcc..36caf2ecb 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -1173,10 +1173,10 @@ * Select the language to display on the LCD. These languages are available: * * en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr, - * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, - * zh_CN, zh_TW, test + * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8, + * tr, uk, zh_CN, zh_TW, test * - * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } */ #define LCD_LANGUAGE en diff --git a/Marlin/example_configurations/AlephObjects/TAZ4/Configuration.h b/Marlin/example_configurations/AlephObjects/TAZ4/Configuration.h index b556c7d0f..e8e57f045 100644 --- a/Marlin/example_configurations/AlephObjects/TAZ4/Configuration.h +++ b/Marlin/example_configurations/AlephObjects/TAZ4/Configuration.h @@ -1193,10 +1193,10 @@ * Select the language to display on the LCD. These languages are available: * * en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr, - * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, - * zh_CN, zh_TW, test + * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8, + * tr, uk, zh_CN, zh_TW, test * - * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } */ #define LCD_LANGUAGE en diff --git a/Marlin/example_configurations/AliExpress/CL-260/Configuration.h b/Marlin/example_configurations/AliExpress/CL-260/Configuration.h index d38a1b531..3a8f59309 100644 --- a/Marlin/example_configurations/AliExpress/CL-260/Configuration.h +++ b/Marlin/example_configurations/AliExpress/CL-260/Configuration.h @@ -1173,10 +1173,10 @@ * Select the language to display on the LCD. These languages are available: * * en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr, - * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, - * zh_CN, zh_TW, test + * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8, + * tr, uk, zh_CN, zh_TW, test * - * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } */ #define LCD_LANGUAGE en diff --git a/Marlin/example_configurations/Anet/A6/Configuration.h b/Marlin/example_configurations/Anet/A6/Configuration.h index daf4829a8..5f5779900 100644 --- a/Marlin/example_configurations/Anet/A6/Configuration.h +++ b/Marlin/example_configurations/Anet/A6/Configuration.h @@ -1330,10 +1330,10 @@ * Select the language to display on the LCD. These languages are available: * * en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr, - * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, - * zh_CN, zh_TW, test + * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8, + * tr, uk, zh_CN, zh_TW, test * - * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } */ #define LCD_LANGUAGE en diff --git a/Marlin/example_configurations/Anet/A8/Configuration.h b/Marlin/example_configurations/Anet/A8/Configuration.h index f112b7413..52ba39a19 100644 --- a/Marlin/example_configurations/Anet/A8/Configuration.h +++ b/Marlin/example_configurations/Anet/A8/Configuration.h @@ -1179,10 +1179,10 @@ * Select the language to display on the LCD. These languages are available: * * en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr, - * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, - * zh_CN, zh_TW, test + * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8, + * tr, uk, zh_CN, zh_TW, test * - * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } */ #define LCD_LANGUAGE en diff --git a/Marlin/example_configurations/BQ/Hephestos/Configuration.h b/Marlin/example_configurations/BQ/Hephestos/Configuration.h index 0b6b5980d..3ef608475 100644 --- a/Marlin/example_configurations/BQ/Hephestos/Configuration.h +++ b/Marlin/example_configurations/BQ/Hephestos/Configuration.h @@ -1164,10 +1164,10 @@ * Select the language to display on the LCD. These languages are available: * * en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr, - * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, - * zh_CN, zh_TW, test + * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8, + * tr, uk, zh_CN, zh_TW, test * - * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } */ //#define LCD_LANGUAGE en diff --git a/Marlin/example_configurations/BQ/Hephestos_2/Configuration.h b/Marlin/example_configurations/BQ/Hephestos_2/Configuration.h index a7b4650f9..d5cdb474b 100644 --- a/Marlin/example_configurations/BQ/Hephestos_2/Configuration.h +++ b/Marlin/example_configurations/BQ/Hephestos_2/Configuration.h @@ -1174,10 +1174,10 @@ * Select the language to display on the LCD. These languages are available: * * en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr, - * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, - * zh_CN, zh_TW, test + * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8, + * tr, uk, zh_CN, zh_TW, test * - * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } */ #define LCD_LANGUAGE en diff --git a/Marlin/example_configurations/BQ/WITBOX/Configuration.h b/Marlin/example_configurations/BQ/WITBOX/Configuration.h index 3ada39ed1..43211e295 100644 --- a/Marlin/example_configurations/BQ/WITBOX/Configuration.h +++ b/Marlin/example_configurations/BQ/WITBOX/Configuration.h @@ -1164,10 +1164,10 @@ * Select the language to display on the LCD. These languages are available: * * en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr, - * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, - * zh_CN, zh_TW, test + * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8, + * tr, uk, zh_CN, zh_TW, test * - * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } */ //#define LCD_LANGUAGE en diff --git a/Marlin/example_configurations/Cartesio/Configuration.h b/Marlin/example_configurations/Cartesio/Configuration.h index 7024a8ae6..28f03e386 100644 --- a/Marlin/example_configurations/Cartesio/Configuration.h +++ b/Marlin/example_configurations/Cartesio/Configuration.h @@ -1172,10 +1172,10 @@ * Select the language to display on the LCD. These languages are available: * * en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr, - * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, - * zh_CN, zh_TW, test + * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8, + * tr, uk, zh_CN, zh_TW, test * - * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } */ #define LCD_LANGUAGE en diff --git a/Marlin/example_configurations/Creality/CR-10/Configuration.h b/Marlin/example_configurations/Creality/CR-10/Configuration.h index a19df6c91..101f0058f 100644 --- a/Marlin/example_configurations/Creality/CR-10/Configuration.h +++ b/Marlin/example_configurations/Creality/CR-10/Configuration.h @@ -1185,10 +1185,10 @@ * Select the language to display on the LCD. These languages are available: * * en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr, - * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, - * zh_CN, zh_TW, test + * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8, + * tr, uk, zh_CN, zh_TW, test * - * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } */ #define LCD_LANGUAGE en diff --git a/Marlin/example_configurations/Felix/Configuration.h b/Marlin/example_configurations/Felix/Configuration.h index ce6226258..12cb35a95 100644 --- a/Marlin/example_configurations/Felix/Configuration.h +++ b/Marlin/example_configurations/Felix/Configuration.h @@ -1155,10 +1155,10 @@ * Select the language to display on the LCD. These languages are available: * * en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr, - * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, - * zh_CN, zh_TW, test + * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8, + * tr, uk, zh_CN, zh_TW, test * - * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } */ //#define LCD_LANGUAGE en diff --git a/Marlin/example_configurations/Felix/DUAL/Configuration.h b/Marlin/example_configurations/Felix/DUAL/Configuration.h index 4df92ec4f..deb7f11c1 100644 --- a/Marlin/example_configurations/Felix/DUAL/Configuration.h +++ b/Marlin/example_configurations/Felix/DUAL/Configuration.h @@ -1155,10 +1155,10 @@ * Select the language to display on the LCD. These languages are available: * * en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr, - * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, - * zh_CN, zh_TW, test + * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8, + * tr, uk, zh_CN, zh_TW, test * - * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } */ //#define LCD_LANGUAGE en diff --git a/Marlin/example_configurations/Folger Tech/i3-2020/Configuration.h b/Marlin/example_configurations/Folger Tech/i3-2020/Configuration.h index 21d0b12fb..935fdc9a8 100644 --- a/Marlin/example_configurations/Folger Tech/i3-2020/Configuration.h +++ b/Marlin/example_configurations/Folger Tech/i3-2020/Configuration.h @@ -1178,10 +1178,10 @@ * Select the language to display on the LCD. These languages are available: * * en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr, - * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, - * zh_CN, zh_TW, test + * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8, + * tr, uk, zh_CN, zh_TW, test * - * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } */ #define LCD_LANGUAGE en diff --git a/Marlin/example_configurations/Geeetech/GT2560/Configuration.h b/Marlin/example_configurations/Geeetech/GT2560/Configuration.h index fa750794d..cb1db4610 100644 --- a/Marlin/example_configurations/Geeetech/GT2560/Configuration.h +++ b/Marlin/example_configurations/Geeetech/GT2560/Configuration.h @@ -1188,10 +1188,10 @@ * Select the language to display on the LCD. These languages are available: * * en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr, - * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, - * zh_CN, zh_TW, test + * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8, + * tr, uk, zh_CN, zh_TW, test * - * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } */ #define LCD_LANGUAGE en diff --git a/Marlin/example_configurations/Geeetech/I3_Pro_X-GT2560/Configuration.h b/Marlin/example_configurations/Geeetech/I3_Pro_X-GT2560/Configuration.h index 2f6983668..7a70c9f03 100644 --- a/Marlin/example_configurations/Geeetech/I3_Pro_X-GT2560/Configuration.h +++ b/Marlin/example_configurations/Geeetech/I3_Pro_X-GT2560/Configuration.h @@ -1173,10 +1173,10 @@ * Select the language to display on the LCD. These languages are available: * * en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr, - * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, - * zh_CN, zh_TW, test + * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8, + * tr, uk, zh_CN, zh_TW, test * - * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } */ #define LCD_LANGUAGE en diff --git a/Marlin/example_configurations/Infitary/i3-M508/Configuration.h b/Marlin/example_configurations/Infitary/i3-M508/Configuration.h index 875daa064..006c73f99 100644 --- a/Marlin/example_configurations/Infitary/i3-M508/Configuration.h +++ b/Marlin/example_configurations/Infitary/i3-M508/Configuration.h @@ -1177,10 +1177,10 @@ * Select the language to display on the LCD. These languages are available: * * en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr, - * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, - * zh_CN, zh_TW, test + * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8, + * tr, uk, zh_CN, zh_TW, test * - * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } */ #define LCD_LANGUAGE en diff --git a/Marlin/example_configurations/Malyan/M150/Configuration.h b/Marlin/example_configurations/Malyan/M150/Configuration.h index a51b477d1..82a3c5e34 100644 --- a/Marlin/example_configurations/Malyan/M150/Configuration.h +++ b/Marlin/example_configurations/Malyan/M150/Configuration.h @@ -1201,10 +1201,10 @@ * Select the language to display on the LCD. These languages are available: * * en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr, - * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, - * zh_CN, zh_TW, test + * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8, + * tr, uk, zh_CN, zh_TW, test * - * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } */ #define LCD_LANGUAGE en diff --git a/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h b/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h index 8a98c92f6..3de04088b 100644 --- a/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h +++ b/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h @@ -1173,10 +1173,10 @@ * Select the language to display on the LCD. These languages are available: * * en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr, - * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, - * zh_CN, zh_TW, test + * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8, + * tr, uk, zh_CN, zh_TW, test * - * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } */ #define LCD_LANGUAGE en diff --git a/Marlin/example_configurations/RigidBot/Configuration.h b/Marlin/example_configurations/RigidBot/Configuration.h index 74985a443..89fb1bd08 100644 --- a/Marlin/example_configurations/RigidBot/Configuration.h +++ b/Marlin/example_configurations/RigidBot/Configuration.h @@ -1171,10 +1171,10 @@ * Select the language to display on the LCD. These languages are available: * * en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr, - * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, - * zh_CN, zh_TW, test + * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8, + * tr, uk, zh_CN, zh_TW, test * - * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } */ #define LCD_LANGUAGE en diff --git a/Marlin/example_configurations/SCARA/Configuration.h b/Marlin/example_configurations/SCARA/Configuration.h index 413da1cdb..0f26a111e 100644 --- a/Marlin/example_configurations/SCARA/Configuration.h +++ b/Marlin/example_configurations/SCARA/Configuration.h @@ -1185,10 +1185,10 @@ * Select the language to display on the LCD. These languages are available: * * en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr, - * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, - * zh_CN, zh_TW, test + * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8, + * tr, uk, zh_CN, zh_TW, test * - * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } */ //#define LCD_LANGUAGE en diff --git a/Marlin/example_configurations/TinyBoy2/Configuration.h b/Marlin/example_configurations/TinyBoy2/Configuration.h index 99078d086..b854242c5 100644 --- a/Marlin/example_configurations/TinyBoy2/Configuration.h +++ b/Marlin/example_configurations/TinyBoy2/Configuration.h @@ -1229,10 +1229,10 @@ * Select the language to display on the LCD. These languages are available: * * en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr, - * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, - * zh_CN, zh_TW, test + * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8, + * tr, uk, zh_CN, zh_TW, test * - * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } */ #define LCD_LANGUAGE en diff --git a/Marlin/example_configurations/Velleman/K8200/Configuration.h b/Marlin/example_configurations/Velleman/K8200/Configuration.h index a40eeca4c..0289aaf27 100644 --- a/Marlin/example_configurations/Velleman/K8200/Configuration.h +++ b/Marlin/example_configurations/Velleman/K8200/Configuration.h @@ -1205,10 +1205,10 @@ * Select the language to display on the LCD. These languages are available: * * en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr, - * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, - * zh_CN, zh_TW, test + * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8, + * tr, uk, zh_CN, zh_TW, test * - * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } */ #define LCD_LANGUAGE en diff --git a/Marlin/example_configurations/Velleman/K8400/Configuration.h b/Marlin/example_configurations/Velleman/K8400/Configuration.h index 50d9681b0..68ac58e8f 100644 --- a/Marlin/example_configurations/Velleman/K8400/Configuration.h +++ b/Marlin/example_configurations/Velleman/K8400/Configuration.h @@ -1173,10 +1173,10 @@ * Select the language to display on the LCD. These languages are available: * * en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr, - * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, - * zh_CN, zh_TW, test + * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8, + * tr, uk, zh_CN, zh_TW, test * - * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } */ #define LCD_LANGUAGE en diff --git a/Marlin/example_configurations/Velleman/K8400/Dual-head/Configuration.h b/Marlin/example_configurations/Velleman/K8400/Dual-head/Configuration.h index 309a47c57..cb3fc4fe7 100644 --- a/Marlin/example_configurations/Velleman/K8400/Dual-head/Configuration.h +++ b/Marlin/example_configurations/Velleman/K8400/Dual-head/Configuration.h @@ -1173,10 +1173,10 @@ * Select the language to display on the LCD. These languages are available: * * en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr, - * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, - * zh_CN, zh_TW, test + * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8, + * tr, uk, zh_CN, zh_TW, test * - * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } */ #define LCD_LANGUAGE en diff --git a/Marlin/example_configurations/adafruit/ST7565/Configuration.h b/Marlin/example_configurations/adafruit/ST7565/Configuration.h index 84a4cda1a..0352d2460 100644 --- a/Marlin/example_configurations/adafruit/ST7565/Configuration.h +++ b/Marlin/example_configurations/adafruit/ST7565/Configuration.h @@ -1173,10 +1173,10 @@ * Select the language to display on the LCD. These languages are available: * * en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr, - * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, - * zh_CN, zh_TW, test + * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8, + * tr, uk, zh_CN, zh_TW, test * - * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } */ #define LCD_LANGUAGE en diff --git a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h index f10cb75f6..32d865f57 100644 --- a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h +++ b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h @@ -1300,10 +1300,10 @@ * Select the language to display on the LCD. These languages are available: * * en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr, - * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, - * zh_CN, zh_TW, test + * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8, + * tr, uk, zh_CN, zh_TW, test * - * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } */ #define LCD_LANGUAGE en diff --git a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h index 70ddf89ff..5953fb869 100644 --- a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h +++ b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h @@ -1294,10 +1294,10 @@ * Select the language to display on the LCD. These languages are available: * * en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr, - * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, - * zh_CN, zh_TW, test + * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8, + * tr, uk, zh_CN, zh_TW, test * - * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } */ #define LCD_LANGUAGE en diff --git a/Marlin/example_configurations/delta/generic/Configuration.h b/Marlin/example_configurations/delta/generic/Configuration.h index 3fd105f08..4c6d33099 100644 --- a/Marlin/example_configurations/delta/generic/Configuration.h +++ b/Marlin/example_configurations/delta/generic/Configuration.h @@ -1289,10 +1289,10 @@ * Select the language to display on the LCD. These languages are available: * * en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr, - * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, - * zh_CN, zh_TW, test + * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8, + * tr, uk, zh_CN, zh_TW, test * - * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } */ #define LCD_LANGUAGE en diff --git a/Marlin/example_configurations/delta/kossel_mini/Configuration.h b/Marlin/example_configurations/delta/kossel_mini/Configuration.h index 1197ca2e1..62d7f2f0d 100644 --- a/Marlin/example_configurations/delta/kossel_mini/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_mini/Configuration.h @@ -1292,10 +1292,10 @@ * Select the language to display on the LCD. These languages are available: * * en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr, - * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, - * zh_CN, zh_TW, test + * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8, + * tr, uk, zh_CN, zh_TW, test * - * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } */ #define LCD_LANGUAGE en diff --git a/Marlin/example_configurations/delta/kossel_pro/Configuration.h b/Marlin/example_configurations/delta/kossel_pro/Configuration.h index 2391046a4..8cd192b6f 100644 --- a/Marlin/example_configurations/delta/kossel_pro/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_pro/Configuration.h @@ -1292,10 +1292,10 @@ * Select the language to display on the LCD. These languages are available: * * en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr, - * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, - * zh_CN, zh_TW, test + * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8, + * tr, uk, zh_CN, zh_TW, test * - * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } */ #define LCD_LANGUAGE en diff --git a/Marlin/example_configurations/delta/kossel_xl/Configuration.h b/Marlin/example_configurations/delta/kossel_xl/Configuration.h index ad004dd29..d7531f779 100644 --- a/Marlin/example_configurations/delta/kossel_xl/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_xl/Configuration.h @@ -1301,10 +1301,10 @@ * Select the language to display on the LCD. These languages are available: * * en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr, - * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, - * zh_CN, zh_TW, test + * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8, + * tr, uk, zh_CN, zh_TW, test * - * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } */ #define LCD_LANGUAGE en diff --git a/Marlin/example_configurations/gCreate/gMax1.5+/Configuration.h b/Marlin/example_configurations/gCreate/gMax1.5+/Configuration.h index 51968f707..7d5d25e86 100644 --- a/Marlin/example_configurations/gCreate/gMax1.5+/Configuration.h +++ b/Marlin/example_configurations/gCreate/gMax1.5+/Configuration.h @@ -1187,10 +1187,10 @@ * Select the language to display on the LCD. These languages are available: * * en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr, - * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, - * zh_CN, zh_TW, test + * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8, + * tr, uk, zh_CN, zh_TW, test * - * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } */ #define LCD_LANGUAGE en diff --git a/Marlin/example_configurations/makibox/Configuration.h b/Marlin/example_configurations/makibox/Configuration.h index ac060155d..5648fe07c 100644 --- a/Marlin/example_configurations/makibox/Configuration.h +++ b/Marlin/example_configurations/makibox/Configuration.h @@ -1176,10 +1176,10 @@ * Select the language to display on the LCD. These languages are available: * * en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr, - * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, - * zh_CN, zh_TW, test + * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8, + * tr, uk, zh_CN, zh_TW, test * - * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } */ //#define LCD_LANGUAGE en diff --git a/Marlin/example_configurations/tvrrug/Round2/Configuration.h b/Marlin/example_configurations/tvrrug/Round2/Configuration.h index 3c7c10413..7a43a8e84 100644 --- a/Marlin/example_configurations/tvrrug/Round2/Configuration.h +++ b/Marlin/example_configurations/tvrrug/Round2/Configuration.h @@ -1168,10 +1168,10 @@ * Select the language to display on the LCD. These languages are available: * * en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr, - * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, - * zh_CN, zh_TW, test + * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8, + * tr, uk, zh_CN, zh_TW, test * - * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } */ //#define LCD_LANGUAGE en diff --git a/Marlin/example_configurations/wt150/Configuration.h b/Marlin/example_configurations/wt150/Configuration.h index 4db146fe4..82018feb3 100644 --- a/Marlin/example_configurations/wt150/Configuration.h +++ b/Marlin/example_configurations/wt150/Configuration.h @@ -1178,10 +1178,10 @@ * Select the language to display on the LCD. These languages are available: * * en, an, bg, ca, cn, cz, cz_utf8, de, el, el-gr, es, eu, fi, fr, gl, hr, - * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, tr, uk, - * zh_CN, zh_TW, test + * it, kana, kana_utf8, nl, pl, pt, pt_utf8, pt-br, pt-br_utf8, ru, sk_utf8, + * tr, uk, zh_CN, zh_TW, test * - * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } + * :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'cz_utf8':'Czech (UTF8)', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'sk_utf8':'Slovak (UTF8)', 'tr':'Turkish', 'uk':'Ukrainian', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Taiwan)', test':'TEST' } */ #define LCD_LANGUAGE en diff --git a/Marlin/language.h b/Marlin/language.h index e0cad44e2..5dfc176d9 100644 --- a/Marlin/language.h +++ b/Marlin/language.h @@ -73,8 +73,11 @@ // pt-br_utf8 Portuguese (Brazilian) (UTF8) // pt_utf8 Portuguese (UTF8) // ru Russian +// sk Slovak (UTF8) // tr Turkish // uk Ukrainian +// zh_CN Chinese (Simplified) +// zh_TW Chinese (Taiwan) #ifdef DEFAULT_SOURCE_CODE_URL #undef SOURCE_CODE_URL @@ -301,7 +304,8 @@ && DISABLED(DISPLAY_CHARSET_ISO10646_CN) \ && DISABLED(DISPLAY_CHARSET_ISO10646_TR) \ && DISABLED(DISPLAY_CHARSET_ISO10646_PL) \ - && DISABLED(DISPLAY_CHARSET_ISO10646_CZ) + && DISABLED(DISPLAY_CHARSET_ISO10646_CZ) \ + && DISABLED(DISPLAY_CHARSET_ISO10646_SK) #define DISPLAY_CHARSET_ISO10646_1 // use the better font on full graphic displays. #endif diff --git a/Marlin/language_pl.h b/Marlin/language_pl.h index f4d1fbe4b..f99802744 100644 --- a/Marlin/language_pl.h +++ b/Marlin/language_pl.h @@ -30,8 +30,8 @@ #ifndef LANGUAGE_PL_H #define LANGUAGE_PL_H -#define DISPLAY_CHARSET_ISO10646_PL #define MAPPER_C3C4C5_PL +#define DISPLAY_CHARSET_ISO10646_PL /** * One version with accented characters and one without diff --git a/Marlin/language_sk_utf8.h b/Marlin/language_sk_utf8.h new file mode 100644 index 000000000..8ee778694 --- /dev/null +++ b/Marlin/language_sk_utf8.h @@ -0,0 +1,354 @@ +/** + * 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 . + * + */ + +/** + * Slovak + * UTF-8 for Graphical Display + * + * LCD Menu Messages + * See also https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language + * + * Translated by Michal Holeš, Farma MaM + * http://www.facebook.com/farmamam + * + */ +#ifndef LANGUAGE_SK_UTF_H +#define LANGUAGE_SK_UTF_H + +#define MAPPER_NON +#define DISPLAY_CHARSET_ISO10646_1 + +// TBD +//#define MAPPER_C3C4C5_SK +//#define DISPLAY_CHARSET_ISO10646_SK + +#define WELCOME_MSG MACHINE_NAME _UxGT(" pripravená.") +#define MSG_BACK _UxGT("Naspať") +#define MSG_SD_INSERTED _UxGT("Karta vložená") +#define MSG_SD_REMOVED _UxGT("Karta vybratá") +#define MSG_LCD_ENDSTOPS _UxGT("Endstopy") // max 8 znakov +#define MSG_MAIN _UxGT("Hlavná ponuka") +#define MSG_AUTOSTART _UxGT("Autoštart") +#define MSG_DISABLE_STEPPERS _UxGT("Uvolniť motory") +#define MSG_DEBUG_MENU _UxGT("Ponuka ladenia") +#define MSG_PROGRESS_BAR_TEST _UxGT("Test uk. priebehu") +#define MSG_AUTO_HOME _UxGT("Domovská pozícia") +#define MSG_AUTO_HOME_X _UxGT("Domov os X") +#define MSG_AUTO_HOME_Y _UxGT("Domov os Y") +#define MSG_AUTO_HOME_Z _UxGT("Domov os Z") +#define MSG_LEVEL_BED_HOMING _UxGT("Meranie podložky") +#define MSG_LEVEL_BED_WAITING _UxGT("Kliknutím spusťte") +#define MSG_LEVEL_BED_NEXT_POINT _UxGT("Ďalší bod") +#define MSG_LEVEL_BED_DONE _UxGT("Meranie hotové!") +#define MSG_Z_FADE_HEIGHT _UxGT("Výška merania") +#define MSG_SET_HOME_OFFSETS _UxGT("Nastaviť offsety") +#define MSG_HOME_OFFSETS_APPLIED _UxGT("Offsety nastavené") +#define MSG_SET_ORIGIN _UxGT("Nastaviť začiatok") +#define MSG_PREHEAT_1 _UxGT("Zahriať PLA") +#define MSG_PREHEAT_1_N MSG_PREHEAT_1 _UxGT(" ") +#define MSG_PREHEAT_1_ALL MSG_PREHEAT_1 _UxGT(" všetko") +#define MSG_PREHEAT_1_END MSG_PREHEAT_1 _UxGT(" hotend") +#define MSG_PREHEAT_1_BEDONLY MSG_PREHEAT_1 _UxGT(" podlož") +#define MSG_PREHEAT_1_SETTINGS MSG_PREHEAT_1 _UxGT(" nast") +#define MSG_PREHEAT_2 _UxGT("Zahriať ABS") +#define MSG_PREHEAT_2_N MSG_PREHEAT_2 _UxGT(" ") +#define MSG_PREHEAT_2_ALL MSG_PREHEAT_2 _UxGT(" všetko") +#define MSG_PREHEAT_2_END MSG_PREHEAT_2 _UxGT(" hotend") +#define MSG_PREHEAT_2_BEDONLY MSG_PREHEAT_2 _UxGT(" podlož") +#define MSG_PREHEAT_2_SETTINGS MSG_PREHEAT_2 _UxGT(" nast") +#define MSG_COOLDOWN _UxGT("Schladiť") +#define MSG_SWITCH_PS_ON _UxGT("Zapnúť napájanie") +#define MSG_SWITCH_PS_OFF _UxGT("Vypnúť napájanie") +#define MSG_EXTRUDE _UxGT("Vytlačiť (extr.)") +#define MSG_RETRACT _UxGT("Vytiahnuť (retr.)") +#define MSG_MOVE_AXIS _UxGT("Posunúť osy") +#define MSG_BED_LEVELING _UxGT("Vyrovnať podložku") +#define MSG_LEVEL_BED _UxGT("Vyrovnať podložku") +#define MSG_EDITING_STOPPED _UxGT("Koniec úprav siete") + +#define MSG_UBL_DOING_G29 _UxGT("Vykonávam G29") +#define MSG_UBL_UNHOMED _UxGT("Prejdite domov") +#define MSG_UBL_TOOLS _UxGT("UBL nástroje") +#define MSG_UBL_LEVEL_BED _UxGT("Unified Bed Leveling") +#define MSG_UBL_MANUAL_MESH _UxGT("Manuálna sieť bodov") +#define MSG_UBL_BC_INSERT _UxGT("Vložte kartu, zmerajte") +#define MSG_UBL_BC_INSERT2 _UxGT("Zmerajte") +#define MSG_UBL_BC_REMOVE _UxGT("Odstráňte a zmerajte") +#define MSG_UBL_MOVING_TO_NEXT _UxGT("Presun na ďalší") +#define MSG_UBL_ACTIVATE_MESH _UxGT("Aktivovať UBL") +#define MSG_UBL_DEACTIVATE_MESH _UxGT("Deaktivovať UBL") +#define MSG_UBL_SET_BED_TEMP _UxGT("Teplota podložky") +#define MSG_UBL_CUSTOM_BED_TEMP MSG_UBL_SET_BED_TEMP +#define MSG_UBL_SET_HOTEND_TEMP _UxGT("Teplota hotendu") +#define MSG_UBL_CUSTOM_HOTEND_TEMP MSG_UBL_SET_HOTEND_TEMP +#define MSG_UBL_EDIT_CUSTOM_MESH _UxGT("Upraviť vlastnú sieť") +#define MSG_UBL_FINE_TUNE_MESH _UxGT("Doladiť sieť bodov") +#define MSG_UBL_DONE_EDITING_MESH _UxGT("Koniec úprav siete") +#define MSG_UBL_BUILD_CUSTOM_MESH _UxGT("Vlastná sieť") +#define MSG_UBL_BUILD_MESH_MENU _UxGT("Vytvoriť sieť") +#define MSG_UBL_BUILD_PLA_MESH _UxGT("Sieť bodov PLA") +#define MSG_UBL_BUILD_ABS_MESH _UxGT("Sieť bodov ABS") +#define MSG_UBL_BUILD_COLD_MESH _UxGT("Studená sieť bodov") +#define MSG_UBL_MESH_HEIGHT_ADJUST _UxGT("Upraviť výšku siete") +#define MSG_UBL_MESH_HEIGHT_AMOUNT _UxGT("Výška") +#define MSG_UBL_VALIDATE_MESH_MENU _UxGT("Skontrolovať sieť") +#define MSG_UBL_VALIDATE_PLA_MESH _UxGT("Kontrola siete PLA") +#define MSG_UBL_VALIDATE_ABS_MESH _UxGT("Kontrola siete ABS") +#define MSG_UBL_VALIDATE_CUSTOM_MESH _UxGT("Kontrola vlast. siete") +#define MSG_UBL_CONTINUE_MESH _UxGT("Pokračovať v sieti") +#define MSG_UBL_MESH_LEVELING _UxGT("Sieťové rovnanie") +#define MSG_UBL_3POINT_MESH_LEVELING _UxGT("3-bodove rovnanie") +#define MSG_UBL_GRID_MESH_LEVELING _UxGT("Mriežkové rovnanie") +#define MSG_UBL_MESH_LEVEL _UxGT("Vyrovnať podložku") +#define MSG_UBL_SIDE_POINTS _UxGT("Postranné body") +#define MSG_UBL_MAP_TYPE _UxGT("Typ siete bodov") +#define MSG_UBL_OUTPUT_MAP _UxGT("Exportovať sieť") +#define MSG_UBL_OUTPUT_MAP_HOST _UxGT("Exportovať do PC") +#define MSG_UBL_OUTPUT_MAP_CSV _UxGT("Exportovať do CSV") +#define MSG_UBL_OUTPUT_MAP_BACKUP _UxGT("Záloha do PC") +#define MSG_UBL_INFO_UBL _UxGT("Info o UBL do PC") +#define MSG_UBL_EDIT_MESH_MENU _UxGT("Upraviť sieť bodov") +#define MSG_UBL_FILLIN_AMOUNT _UxGT("Hustota mriežky") +#define MSG_UBL_MANUAL_FILLIN _UxGT("Ručná hustota") +#define MSG_UBL_SMART_FILLIN _UxGT("Smart hustota") +#define MSG_UBL_FILLIN_MESH _UxGT("Zaplniť mriežku") +#define MSG_UBL_INVALIDATE_ALL _UxGT("Zrušiť všetko") +#define MSG_UBL_INVALIDATE_CLOSEST _UxGT("Zrušiť posledný") +#define MSG_UBL_FINE_TUNE_ALL _UxGT("Upraviť všetky") +#define MSG_UBL_FINE_TUNE_CLOSEST _UxGT("Upraviť posledný") +#define MSG_UBL_STORAGE_MESH_MENU _UxGT("Uložisko sietí") +#define MSG_UBL_STORAGE_SLOT _UxGT("Pamaťový slot") +#define MSG_UBL_LOAD_MESH _UxGT("Načítať sieť bodov") +#define MSG_UBL_SAVE_MESH _UxGT("Uložiť sieť bodov") +#define MSG_UBL_SAVE_ERROR _UxGT("Err: Uložiť UBL") +#define MSG_UBL_RESTORE_ERROR _UxGT("Err: Obnoviť UBL") +#define MSG_UBL_Z_OFFSET_STOPPED _UxGT("Koniec Z-Offsetu") +#define MSG_UBL_STEP_BY_STEP_MENU _UxGT("UBL Postupne") + +#define MSG_USER_MENU _UxGT("Vlastné príkazy") +#define MSG_MOVING _UxGT("Posun...") +#define MSG_FREE_XY _UxGT("Uvolniť XY") +#define MSG_MOVE_X _UxGT("Posunúť X") +#define MSG_MOVE_Y _UxGT("Posunúť Y") +#define MSG_MOVE_Z _UxGT("Posunúť Z") +#define MSG_MOVE_E _UxGT("Extrúder") +#define MSG_MOVE_01MM _UxGT("Posunúť o 0,1mm") +#define MSG_MOVE_1MM _UxGT("Posunúť o 1mm") +#define MSG_MOVE_10MM _UxGT("Posunúť o 10mm") +#define MSG_SPEED _UxGT("Rýchlosť") +#define MSG_BED_Z _UxGT("Výška podl.") +#define MSG_NOZZLE _UxGT("Tryska") +#define MSG_BED _UxGT("Podložka") +#define MSG_FAN_SPEED _UxGT("Rýchlosť vent.") +#define MSG_FLOW _UxGT("Prietok") +#define MSG_CONTROL _UxGT("Ovládanie") +#define MSG_MIN _UxGT(" ") LCD_STR_THERMOMETER _UxGT(" Min") +#define MSG_MAX _UxGT(" ") LCD_STR_THERMOMETER _UxGT(" Max") +#define MSG_FACTOR _UxGT(" ") LCD_STR_THERMOMETER _UxGT(" Fakt") +#define MSG_AUTOTEMP _UxGT("Autoteplota") +#define MSG_ON _UxGT("Zap") +#define MSG_OFF _UxGT("Vyp") +#define MSG_PID_P _UxGT("PID-P") +#define MSG_PID_I _UxGT("PID-I") +#define MSG_PID_D _UxGT("PID-D") +#define MSG_PID_C _UxGT("PID-C") +#define MSG_SELECT _UxGT("Vybrať") +#define MSG_ACC _UxGT("Zrýchl") +#define MSG_JERK _UxGT("Skok") +#define MSG_VX_JERK _UxGT("Vx-skok") +#define MSG_VY_JERK _UxGT("Vy-skok") +#define MSG_VZ_JERK _UxGT("Vz-skok") +#define MSG_VE_JERK _UxGT("Ve-skok") +#define MSG_VELOCITY _UxGT("Rýchlosť") +#define MSG_VMAX _UxGT("Vmax ") +#define MSG_VMIN _UxGT("Vmin") +#define MSG_VTRAV_MIN _UxGT("VTrav min") +#define MSG_ACCELERATION _UxGT("Akcelerácia") +#define MSG_AMAX _UxGT("Amax ") +#define MSG_A_RETRACT _UxGT("A-retrakt") +#define MSG_A_TRAVEL _UxGT("A-prejazd") +#define MSG_STEPS_PER_MM _UxGT("Krokov/mm") +#define MSG_XSTEPS _UxGT("Xkrokov/mm") +#define MSG_YSTEPS _UxGT("Ykrokov/mm") +#define MSG_ZSTEPS _UxGT("Zkrokov/mm") +#define MSG_ESTEPS _UxGT("Ekrokov/mm") +#define MSG_E1STEPS _UxGT("E1krokov/mm") +#define MSG_E2STEPS _UxGT("E2krokov/mm") +#define MSG_E3STEPS _UxGT("E3krokov/mm") +#define MSG_E4STEPS _UxGT("E4krokov/mm") +#define MSG_E5STEPS _UxGT("E5kroků/mm") +#define MSG_TEMPERATURE _UxGT("Teplota") +#define MSG_MOTION _UxGT("Pohyb") +#define MSG_FILAMENT _UxGT("Filament") +#define MSG_VOLUMETRIC_ENABLED _UxGT("E na mm3") +#define MSG_FILAMENT_DIAM _UxGT("Fil. Priem.") +#define MSG_ADVANCE_K _UxGT("K pro posun") +#define MSG_CONTRAST _UxGT("Kontrast LCD") +#define MSG_STORE_EEPROM _UxGT("Uložiť nastavenie") +#define MSG_LOAD_EEPROM _UxGT("Načítať nastaveníe") +#define MSG_RESTORE_FAILSAFE _UxGT("Obnoviť nastavenie") +#define MSG_INIT_EEPROM _UxGT("Inic. EEPROM") +#define MSG_REFRESH _UxGT("Obnoviť") +#define MSG_WATCH _UxGT("Info obrazovka") +#define MSG_PREPARE _UxGT("Príprava tlače") +#define MSG_TUNE _UxGT("Doladenie tlače") +#define MSG_PAUSE_PRINT _UxGT("Pozastaviť tlač") +#define MSG_RESUME_PRINT _UxGT("Obnoviť tlač") +#define MSG_STOP_PRINT _UxGT("Zastaviť tlač") +#define MSG_CARD_MENU _UxGT("Tlačiť z SD") +#define MSG_NO_CARD _UxGT("Žiadna SD karta") +#define MSG_DWELL _UxGT("Spím...") +#define MSG_USERWAIT _UxGT("Čakám...") +#define MSG_PRINT_PAUSED _UxGT("Tlač pozastavená") +#define MSG_RESUMING _UxGT("Obnovovanie tlače") +#define MSG_PRINT_ABORTED _UxGT("Tlač zrušená") +#define MSG_NO_MOVE _UxGT("Žiadny pohyb.") +#define MSG_KILLED _UxGT("PRERUŠENÉ. ") +#define MSG_STOPPED _UxGT("ZASTAVENÉ. ") +#define MSG_CONTROL_RETRACT _UxGT("Retrakt mm") +#define MSG_CONTROL_RETRACT_SWAP _UxGT("Výmena Re.mm") +#define MSG_CONTROL_RETRACTF _UxGT("Retraktovať V") +#define MSG_CONTROL_RETRACT_ZLIFT _UxGT("Zdvih Z mm") +#define MSG_CONTROL_RETRACT_RECOVER _UxGT("UnRet mm") +#define MSG_CONTROL_RETRACT_RECOVER_SWAP _UxGT("S UnRet mm") +#define MSG_CONTROL_RETRACT_RECOVERF _UxGT("UnRet V") +#define MSG_AUTORETRACT _UxGT("AutoRetr.") +#define MSG_FILAMENTCHANGE _UxGT("Vymeniť filament") +#define MSG_INIT_SDCARD _UxGT("Načítať SD kartu") +#define MSG_CNG_SDCARD _UxGT("Vymeniť SD kartu") +#define MSG_ZPROBE_OUT _UxGT("Sonda Z mimo podl") +#define MSG_BLTOUCH _UxGT("BLTouch") +#define MSG_BLTOUCH_SELFTEST _UxGT("BLTouch Self-Test") +#define MSG_BLTOUCH_RESET _UxGT("BLTouch Reset") +#define MSG_BLTOUCH_DEPLOY _UxGT("BLTouch Vysunúť") +#define MSG_BLTOUCH_STOW _UxGT("BLTouch Zasunúť") +#define MSG_HOME _UxGT("Najprv") // Used as MSG_HOME " " MSG_X MSG_Y MSG_Z " " MSG_FIRST +#define MSG_FIRST _UxGT("domov") +#define MSG_ZPROBE_ZOFFSET _UxGT("Z offset") +#define MSG_BABYSTEP_X _UxGT("Babystep X") +#define MSG_BABYSTEP_Y _UxGT("Babystep Y") +#define MSG_BABYSTEP_Z _UxGT("Babystep Z") +#define MSG_ENDSTOP_ABORT _UxGT("Endstop zastavil") +#define MSG_HEATING_FAILED_LCD _UxGT("Chyba ohrevu") +#define MSG_ERR_REDUNDANT_TEMP _UxGT("REDUND. TEPLOTA") +#define MSG_THERMAL_RUNAWAY _UxGT("TEPLOTNÝ SKOK") +#define MSG_ERR_MAXTEMP _UxGT("VYSOKÁ TEPLOTA") +#define MSG_ERR_MINTEMP _UxGT("NÍZKA TEPLOTA") +#define MSG_ERR_MAXTEMP_BED _UxGT("VYS. TEPL. PODL.") +#define MSG_ERR_MINTEMP_BED _UxGT("NÍZ. TEPL. PODL.") +#define MSG_ERR_Z_HOMING _UxGT("G28 Z ZAKÁZANÉ") +#define MSG_HALTED _UxGT("TLAČ. ZASTAVENÁ") +#define MSG_PLEASE_RESET _UxGT("Spravte reset") +#define MSG_SHORT_DAY _UxGT("d") +#define MSG_SHORT_HOUR _UxGT("h") +#define MSG_SHORT_MINUTE _UxGT("m") +#define MSG_HEATING _UxGT("Ohrev...") +#define MSG_HEATING_COMPLETE _UxGT("Ohrev prebehol.") +#define MSG_BED_HEATING _UxGT("Ohrev podl.") +#define MSG_BED_DONE _UxGT("Podložka hotová.") +#define MSG_DELTA_CALIBRATE _UxGT("Delta Kalibrácia") +#define MSG_DELTA_CALIBRATE_X _UxGT("Kalibrovať X") +#define MSG_DELTA_CALIBRATE_Y _UxGT("Kalibrovať Y") +#define MSG_DELTA_CALIBRATE_Z _UxGT("Kalibrovať Z") +#define MSG_DELTA_CALIBRATE_CENTER _UxGT("Kalibrovať Stred") +#define MSG_DELTA_AUTO_CALIBRATE _UxGT("Autokalibrácia") +#define MSG_DELTA_HEIGHT_CALIBRATE _UxGT("Nast.výšku delty") +#define MSG_INFO_MENU _UxGT("O tlačiarni") +#define MSG_INFO_PRINTER_MENU _UxGT("Info o tlačiarni") +#define MSG_3POINT_LEVELING _UxGT("3-bodové rovnanie") +#define MSG_LINEAR_LEVELING _UxGT("Lineárne rovnanie") +#define MSG_BILINEAR_LEVELING _UxGT("Bilineárne rovnanie") +#define MSG_UBL_LEVELING _UxGT("Unified Bed Leveling") +#define MSG_MESH_LEVELING _UxGT("Mriežkové rovnanie") +#define MSG_INFO_STATS_MENU _UxGT("Štatistika") +#define MSG_INFO_BOARD_MENU _UxGT("Info o doske") +#define MSG_INFO_THERMISTOR_MENU _UxGT("Termistory") +#define MSG_INFO_EXTRUDERS _UxGT("Extrudéry") +#define MSG_INFO_BAUDRATE _UxGT("Rýchlosť") +#define MSG_INFO_PROTOCOL _UxGT("Protokol") +#define MSG_CASE_LIGHT _UxGT("Osvetlenie") +#define MSG_CASE_LIGHT_BRIGHTNESS _UxGT("Jas svetla") + +#if LCD_WIDTH >= 20 + #define MSG_INFO_PRINT_COUNT _UxGT("Počet tlačí") + #define MSG_INFO_COMPLETED_PRINTS _UxGT("Dokončené") + #define MSG_INFO_PRINT_TIME _UxGT("Celkový čas") + #define MSG_INFO_PRINT_LONGEST _UxGT("Najdlhšia tlač") + #define MSG_INFO_PRINT_FILAMENT _UxGT("Celkom vytlačené") +#else + #define MSG_INFO_PRINT_COUNT _UxGT("Tlače") + #define MSG_INFO_COMPLETED_PRINTS _UxGT("Hotovo") + #define MSG_INFO_PRINT_TIME _UxGT("Čas") + #define MSG_INFO_PRINT_LONGEST _UxGT("Najdlhšia") + #define MSG_INFO_PRINT_FILAMENT _UxGT("Vytlačené") +#endif + +#define MSG_INFO_MIN_TEMP _UxGT("Teplota min") +#define MSG_INFO_MAX_TEMP _UxGT("Teplota max") +#define MSG_INFO_PSU _UxGT("Nap. zdroj") +#define MSG_DRIVE_STRENGTH _UxGT("Budenie motorov") +#define MSG_DAC_PERCENT _UxGT("Motor %") +#define MSG_DAC_EEPROM_WRITE _UxGT("Uložiť do EEPROM") + +#define MSG_FILAMENT_CHANGE_HEADER _UxGT("PAUZA TLAČE") +#define MSG_FILAMENT_CHANGE_OPTION_HEADER _UxGT("MOŽN. POKRAČ.:") +#define MSG_FILAMENT_CHANGE_OPTION_EXTRUDE _UxGT("Ešte vytlačiť") +#define MSG_FILAMENT_CHANGE_OPTION_RESUME _UxGT("Obnoviť tlač") +#define MSG_FILAMENT_CHANGE_MINTEMP _UxGT("Min. teplota je ") +#define MSG_FILAMENT_CHANGE_NOZZLE _UxGT(" Tryska: ") + +#if LCD_HEIGHT >= 4 + // Up to 3 lines allowed + #define MSG_FILAMENT_CHANGE_INIT_1 _UxGT("Čakajte prosím") + #define MSG_FILAMENT_CHANGE_INIT_2 _UxGT("na spustenie") + #define MSG_FILAMENT_CHANGE_INIT_3 _UxGT("výmeny filamentu") + #define MSG_FILAMENT_CHANGE_UNLOAD_1 _UxGT("Čakejte prosím") + #define MSG_FILAMENT_CHANGE_UNLOAD_2 _UxGT("na vysunutie") + #define MSG_FILAMENT_CHANGE_UNLOAD_3 _UxGT("filamentu") + #define MSG_FILAMENT_CHANGE_INSERT_1 _UxGT("Vložte filament") + #define MSG_FILAMENT_CHANGE_INSERT_2 _UxGT("a stlačte") + #define MSG_FILAMENT_CHANGE_INSERT_3 _UxGT("tlačidlo...") + #define MSG_FILAMENT_CHANGE_HEAT_1 _UxGT("Kliknite pre") + #define MSG_FILAMENT_CHANGE_HEAT_2 _UxGT("ohrev trysky") + #define MSG_FILAMENT_CHANGE_HEATING_1 _UxGT("Čakajte prosím") + #define MSG_FILAMENT_CHANGE_HEATING_2 _UxGT("na teplotu tr.") + #define MSG_FILAMENT_CHANGE_LOAD_1 _UxGT("Čakajte prosím") + #define MSG_FILAMENT_CHANGE_LOAD_2 _UxGT("na zavedenie") + #define MSG_FILAMENT_CHANGE_LOAD_3 _UxGT("filamentu") + #define MSG_FILAMENT_CHANGE_EXTRUDE_1 _UxGT("Čakajte prosím") + #define MSG_FILAMENT_CHANGE_EXTRUDE_2 _UxGT("na vytlačenie") + #define MSG_FILAMENT_CHANGE_EXTRUDE_3 _UxGT("filamentu") + #define MSG_FILAMENT_CHANGE_RESUME_1 _UxGT("Čakajte prosím") + #define MSG_FILAMENT_CHANGE_RESUME_2 _UxGT("na pokračovanie") + #define MSG_FILAMENT_CHANGE_RESUME_3 _UxGT("tlače") +#else // LCD_HEIGHT < 4 + // Up to 2 lines allowed + #define MSG_FILAMENT_CHANGE_INIT_1 _UxGT("Čakajte...") + #define MSG_FILAMENT_CHANGE_UNLOAD_1 _UxGT("Vysúvanie...") + #define MSG_FILAMENT_CHANGE_INSERT_1 _UxGT("Vložte, kliknite") + #define MSG_FILAMENT_CHANGE_HEATING_1 _UxGT("Ohrev...") + #define MSG_FILAMENT_CHANGE_LOAD_1 _UxGT("Zavádzanie...") + #define MSG_FILAMENT_CHANGE_EXTRUDE_1 _UxGT("Vytlačovanie...") + #define MSG_FILAMENT_CHANGE_RESUME_1 _UxGT("Pokračovanie...") +#endif // LCD_HEIGHT < 4 + +#endif // LANGUAGE_SK_UTF_H diff --git a/Marlin/utf_mapper.h b/Marlin/utf_mapper.h index 35dac27a1..13fb0187e 100644 --- a/Marlin/utf_mapper.h +++ b/Marlin/utf_mapper.h @@ -449,7 +449,7 @@ HARDWARE_CHAR_OUT((char)d) ; } else if (seen_c3) { - switch(d) { + switch(d) { case 0x93u: d = 0x8Au; break; //Ó case 0xB3u: d = 0x8Bu; break; //ó d = '?'; @@ -556,6 +556,11 @@ return 1; } +#elif ENABLED(MAPPER_C3C4C5_SK) + + // TBD + #error "No mapping for Slovak at this time. Use MAPPER_NON." + #else #define MAPPER_NON From 0067bb2840619acde1d32d487b7799a0ae0a1a2f Mon Sep 17 00:00:00 2001 From: GMagician Date: Thu, 24 Aug 2017 22:04:49 +0200 Subject: [PATCH 108/112] Addressing #7552 When M405 is used it changes 'volumetric_multiplier[FILAMENT_SENSOR_EXTRUDER_NUM]' value. When M406 disables M405 it leaves the value unchanged. This PR applies 'calculate_volumetric_multipliers' in M406 instead of resetting it to 1.0 because M200 may not be compatible with M405 hence I'm sure to restore anyway with correct value. --- Marlin/Marlin_main.cpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index f6b7fd755..5196bca81 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -9241,7 +9241,10 @@ inline void gcode_M400() { stepper.synchronize(); } /** * M406: Turn off filament sensor for control */ - inline void gcode_M406() { filament_sensor = false; } + inline void gcode_M406() { + filament_sensor = false; + calculate_volumetric_multipliers(); // Restore correct 'volumetric_multiplier' value + } /** * M407: Get measured filament diameter on serial output From 3f0b38ed5df318cfd28ac7433c21f2c4ceab5ddc Mon Sep 17 00:00:00 2001 From: Roxy-3D Date: Fri, 25 Aug 2017 17:03:07 -0500 Subject: [PATCH 109/112] Add Max7219 LED Matrix Debug Support (#7563) * Add Max7219 LED Matrix Debug Support The Max7219 8x8 LED Matrix's are very helpful for debugging new code. And for that matter, just trying to maximize printer settings without causing stuttering. The displays are very inexpensive (under $2.00 with shipping) and provide a lot of help when trying to debug complicated code. * Try to keep Makefile up to date. --- Marlin/Makefile | 2 +- Marlin/Marlin_main.cpp | 18 +- Marlin/Max7219_Debug_LEDs.cpp | 286 ++++++++++++++++++ Marlin/Max7219_Debug_LEDs.h | 85 ++++++ .../AlephObjects/TAZ4/Configuration_adv.h | 26 ++ .../Anet/A6/Configuration_adv.h | 26 ++ .../Anet/A8/Configuration_adv.h | 26 ++ .../BQ/Hephestos/Configuration_adv.h | 26 ++ .../BQ/Hephestos_2/Configuration_adv.h | 26 ++ .../BQ/WITBOX/Configuration_adv.h | 26 ++ .../Cartesio/Configuration_adv.h | 26 ++ .../Felix/Configuration_adv.h | 26 ++ .../Folger Tech/i3-2020/Configuration_adv.h | 26 ++ .../Infitary/i3-M508/Configuration_adv.h | 26 ++ .../Malyan/M150/Configuration_adv.h | 26 ++ .../RigidBot/Configuration_adv.h | 26 ++ .../SCARA/Configuration_adv.h | 26 ++ .../Sanguinololu/Configuration_adv.h | 26 ++ .../TinyBoy2/Configuration_adv.h | 26 ++ .../Velleman/K8200/Configuration_adv.h | 26 ++ .../Velleman/K8400/Configuration_adv.h | 26 ++ .../FLSUN/auto_calibrate/Configuration_adv.h | 26 ++ .../FLSUN/kossel_mini/Configuration_adv.h | 26 ++ .../delta/generic/Configuration_adv.h | 26 ++ .../delta/kossel_mini/Configuration_adv.h | 26 ++ .../delta/kossel_pro/Configuration_adv.h | 26 ++ .../delta/kossel_xl/Configuration_adv.h | 26 ++ .../gCreate/gMax1.5+/Configuration.h | 2 +- .../gCreate/gMax1.5+/Configuration_adv.h | 26 ++ .../makibox/Configuration_adv.h | 26 ++ .../tvrrug/Round2/Configuration_adv.h | 26 ++ .../wt150/Configuration_adv.h | 26 ++ 32 files changed, 1090 insertions(+), 5 deletions(-) create mode 100644 Marlin/Max7219_Debug_LEDs.cpp create mode 100644 Marlin/Max7219_Debug_LEDs.h diff --git a/Marlin/Makefile b/Marlin/Makefile index 98d035d95..150f07439 100644 --- a/Marlin/Makefile +++ b/Marlin/Makefile @@ -310,7 +310,7 @@ CXXSRC = WMath.cpp WString.cpp Print.cpp Marlin_main.cpp \ temperature.cpp cardreader.cpp configuration_store.cpp \ watchdog.cpp SPI.cpp servo.cpp Tone.cpp ultralcd.cpp digipot_mcp4451.cpp \ dac_mcp4728.cpp vector_3.cpp least_squares_fit.cpp endstops.cpp stopwatch.cpp utility.cpp \ - printcounter.cpp nozzle.cpp serial.cpp gcode.cpp + printcounter.cpp nozzle.cpp serial.cpp gcode.cpp Max7219_Debug_LEDs.cpp ifeq ($(NEOPIXEL), 1) CXXSRC += Adafruit_NeoPixel.cpp endif diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 5196bca81..113432403 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -279,6 +279,10 @@ #include "watchdog.h" #endif +#if ENABLED(MAX7219_DEBUG) + #include "Max7219_Debug_LEDs.h" +#endif + #if ENABLED(NEOPIXEL_RGBW_LED) #include #endif @@ -10292,7 +10296,7 @@ inline void invalid_extruder_error(const uint8_t e) { SET_OUTPUT(FANMUX1_PIN); #if PIN_EXISTS(FANMUX2) SET_OUTPUT(FANMUX2_PIN); - #endif + #endif #endif fanmux_switch(0); } @@ -13201,6 +13205,10 @@ void idle( bool no_stepper_sleep/*=false*/ #endif ) { + #if ENABLED(MAX7219_DEBUG) + Max7219_idle_tasks(); + #endif // MAX7219_DEBUG + lcd_update(); host_keepalive(); @@ -13316,6 +13324,10 @@ void stop() { */ void setup() { + #if ENABLED(MAX7219_DEBUG) + Max7219_init(); + #endif + #ifdef DISABLE_JTAG // Disable JTAG on AT90USB chips to free up pins for IO MCUCR = 0x80; @@ -13467,11 +13479,11 @@ void setup() { SET_OUTPUT(E_MUX1_PIN); SET_OUTPUT(E_MUX2_PIN); #endif - + #if HAS_FANMUX fanmux_init(); #endif - + lcd_init(); #ifndef CUSTOM_BOOTSCREEN_TIMEOUT diff --git a/Marlin/Max7219_Debug_LEDs.cpp b/Marlin/Max7219_Debug_LEDs.cpp new file mode 100644 index 000000000..a5aa3e50d --- /dev/null +++ b/Marlin/Max7219_Debug_LEDs.cpp @@ -0,0 +1,286 @@ +/** + * 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 . + * + */ + +/** + * This module is normally not enabled. It can be enabled to facilitate + * the display of extra debug information during code development. + * It assumes the existance of a Max7219 LED Matrix. A suitable + * device can be obtained on eBay similar to this: http://www.ebay.com/itm/191781645249 + * for under $2.00 including shipping. + * + * Just connect up +5v and Gnd to give it power. And then 3 wires declared in the + * #define's below. Actual pin assignments can be changed in MAX7219_DEBUG section + * of configuration_adv.h + * + * #define Max7219_clock 77 + * #define Max7219_data_in 78 + * #define Max7219_load 79 + * + * First call Max7219_init() and then there are a number of support functions available + * to control the LED's in the 8x8 grid. + * + * void Max7219_init(); + * void Max7219_PutByte(uint8_t data); + * void Max7219(uint8_t reg, uint8_t data); + * void Max7219_LED_On( int8_t row, int8_t col); + * void Max7219_LED_Off( int8_t row, int8_t col); + * void Max7219_LED_Toggle( int8_t row, int8_t col); + * void Max7219_Clear_Row( int8_t row); + * void Max7219_Clear_Column( int8_t col); + */ + + +#include "Marlin.h" + +#if ENABLED(MAX7219_DEBUG) + #include "planner.h" + #include "stepper.h" + #include "Max7219_Debug_LEDs.h" + + static uint8_t LEDs[8] = {0}; + + void Max7219_PutByte(uint8_t data) { + uint8_t i = 8; + while(i > 0) { + digitalWrite( Max7219_clock, LOW); // tick + if (data & 0x80) // check bit + digitalWrite(Max7219_data_in,HIGH); // send 1 + else + digitalWrite(Max7219_data_in,LOW); // send 0 + digitalWrite(Max7219_clock, HIGH); // tock + data = data << 0x01; + --i; // move to lesser bit + } + } + + void Max7219( uint8_t reg, uint8_t data) { + digitalWrite(Max7219_load, LOW); // begin + Max7219_PutByte(reg); // specify register + Max7219_PutByte(data); // put data + digitalWrite(Max7219_load, LOW); // and tell the chip to load the data + digitalWrite(Max7219_load,HIGH); + } + + void Max7219_LED_On( int8_t row, int8_t col) { + int x_index; + if ( row>=8 || row<0 || col>=8 || col<0) + return; + if ( LEDs[row] & (0x01<=8 || row<0 || col>=8 || col<0) + return; + if ( !(LEDs[row] & (0x01<=8 || row<0 || col>=8 || col<0) + return; + if ( (LEDs[row] & (0x01<=8 || col<0 ) + return; + LEDs[col] = 0; + x_index = 7-col; + Max7219( x_index+1, LEDs[col] ); + } + + void Max7219_Clear_Row( int8_t row) { + int c; + if ( row>=8 || row<0 ) + return; + + for(c=0; c<8; c++) + Max7219_LED_Off( c, row); + } + + void Max7219_Set_Row( int8_t row, uint8_t val) { + int b; + + if ( row<0 || row>7 ) + return; + + if ( val<0 || val>255 ) + return; + + for(b=0; b<8; b++) + if ( val & (0x01 << b) ) + Max7219_LED_On( 7-b, row); + else + Max7219_LED_Off( 7-b, row); + } + + void Max7219_Set_Column( int8_t col, uint8_t val) { + int x_index; + + if ( col>=8 || col<0 ) + return; + + if ( val<0 || val>255 ) + return; + + LEDs[col] = val; + x_index = 7-col; + Max7219( x_index+1, LEDs[col] ); + } + + + void Max7219_init() { + int i, x, y; + + pinMode(Max7219_data_in, OUTPUT); + pinMode(Max7219_clock, OUTPUT); + pinMode(Max7219_load, OUTPUT); + + digitalWrite(Max7219_load, HIGH); + + //initiation of the max 7219 + Max7219(max7219_reg_scanLimit, 0x07); + Max7219(max7219_reg_decodeMode, 0x00); // using an led matrix (not digits) + Max7219(max7219_reg_shutdown, 0x01); // not in shutdown mode + Max7219(max7219_reg_displayTest, 0x00); // no display test + Max7219(max7219_reg_intensity, 0x01 & 0x0f); // the first 0x0f is the value you can set + // range: 0x00 to 0x0f + for (i=0; i<8; i++) { // empty registers, turn all LEDs off + LEDs[i] = 0x00; + Max7219(i+1,0); + } + + for(x=0; x<8; x++) { // Do an austetically pleasing pattern to fully test + for(y=0; y<8; y++) { // the Max7219 module and LED's. First, turn them + Max7219_LED_On( x, y); // all on. + delay(3); + } + } + for(x=0; x<8; x++) { // Now, turn them all off. + for(y=0; y<8; y++) { + Max7219_LED_Off( x, y); + delay(3); // delay() is OK here. Max7219_init() is only called from + } // setup() and nothing is running yet. + } + + delay(150); + + for(x=7; x>=0; x--) { // Now, do the same thing from the opposite direction + for(y=0; y<8; y++) { + Max7219_LED_On( x, y); + delay(2); + } + } + + for(x=7; x>=0; x--) { + for(y=0; y<8; y++) { + Max7219_LED_Off( x, y); + delay(2); + } + } + } + +/* + * These are sample debug features to demonstrate the usage of the 8x8 LED Matrix for debug purposes. + * There is very little CPU burden added to the system by displaying information within the idle() + * task. + * + * But with that said, if your debugging can be facilitated by making calls into the library from + * other places in the code, feel free to do it. The CPU burden for a few calls to toggle an LED + * or clear a row is not very significant. + */ + void Max7219_idle_tasks() { + #ifdef MAX7219_DEBUG_PRINTER_ALIVE + static int debug_cnt=0; + if (debug_cnt++ > 100) { + Max7219_LED_Toggle(7,7); + debug_cnt = 0; + } + #endif + + #ifdef MAX7219_DEBUG_STEPPER_HEAD + Max7219_Clear_Row(MAX7219_DEBUG_STEPPER_HEAD); + Max7219_Clear_Row(MAX7219_DEBUG_STEPPER_HEAD+1); + if ( planner.block_buffer_head < 8) + Max7219_LED_On( planner.block_buffer_head, MAX7219_DEBUG_STEPPER_HEAD); + else + Max7219_LED_On( planner.block_buffer_head-8, MAX7219_DEBUG_STEPPER_HEAD+1); + #endif + + #ifdef MAX7219_DEBUG_STEPPER_TAIL + Max7219_Clear_Row(MAX7219_DEBUG_STEPPER_TAIL); + Max7219_Clear_Row(MAX7219_DEBUG_STEPPER_TAIL+1); + if ( planner.block_buffer_tail < 8) + Max7219_LED_On( planner.block_buffer_tail, MAX7219_DEBUG_STEPPER_TAIL ); + else + Max7219_LED_On( planner.block_buffer_tail-8, MAX7219_DEBUG_STEPPER_TAIL+1 ); + #endif + + #ifdef MAX7219_DEBUG_STEPPER_QUEUE + static int16_t last_depth=0, current_depth; + uint8_t i; + current_depth = planner.block_buffer_head - planner.block_buffer_tail; + if (current_depth != last_depth) { // usually, no update will be needed. + + if ( current_depth < 0 ) + current_depth += BLOCK_BUFFER_SIZE; + + if ( current_depth >= BLOCK_BUFFER_SIZE ) + current_depth = BLOCK_BUFFER_SIZE; + + if ( current_depth > 16 ) // if the BLOCK_BUFFER_SIZE is greater than 16 two lines + current_depth = 16; // of LED's is enough to see if the buffer is draining + + if ( current_depth < last_depth ) + for(i=current_depth; i<=last_depth; i++) { // clear the highest order LED's + if ( i & 1) + Max7219_LED_Off(i>>1, MAX7219_DEBUG_STEPPER_QUEUE+1); + else + Max7219_LED_Off(i>>1, MAX7219_DEBUG_STEPPER_QUEUE+0); + } + else + for(i=last_depth; i<=current_depth; i++) { // light up the highest order LED's + if ( i & 1) + Max7219_LED_On(i>>1, MAX7219_DEBUG_STEPPER_QUEUE+1); + else + Max7219_LED_On(i>>1, MAX7219_DEBUG_STEPPER_QUEUE+0); + } + last_depth = current_depth; + } + #endif + } +#endif //MAX7219_DEBUG + diff --git a/Marlin/Max7219_Debug_LEDs.h b/Marlin/Max7219_Debug_LEDs.h new file mode 100644 index 000000000..d2a502953 --- /dev/null +++ b/Marlin/Max7219_Debug_LEDs.h @@ -0,0 +1,85 @@ +/** + * 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 . + * + */ + +/** + * This module is normally not enabled and does not generate any code. But it + * can be enabled to facilitate the display of extra debug information during + * code development. It assumes the existance of a Max7219 LED Matrix. You + * can get one on eBay similar to this: http://www.ebay.com/itm/191781645249 + * for under $2.00 including shipping. + * + * Just connect up +5v and Gnd to give it power. And then 3 wires declared in the + * #define's below. Actual pin assignments can be changed in MAX7219_DEBUG section + * of configuration_adv.h + * + * You first call Max7219_init() and then you have 3 support functions available + * to control the LED's in the 8x8 grid. + * + * void Max7219_init(); + * void Max7219_PutByte(uint8_t data); + * void Max7219(uint8_t reg, uint8_t data); + * void Max7219_LED_On( int8_t row, int8_t col); + * void Max7219_LED_Off( int8_t row, int8_t col); + * void Max7219_LED_Toggle( int8_t row, int8_t col); + * void Max7219_Clear_Row( int8_t row); + * void Max7219_Clear_Column( int8_t col); + * void Max7219_Set_Row( int8_t row, int8_t val); + * void Max7219_Set_Column( int8_t column, int8_t val); + * void Max7219_idle_tasks(); + */ + + +#if ENABLED(MAX7219_DEBUG) + // + // define max7219 registers + // + #define max7219_reg_noop 0x00 + #define max7219_reg_digit0 0x01 + #define max7219_reg_digit1 0x02 + #define max7219_reg_digit2 0x03 + #define max7219_reg_digit3 0x04 + #define max7219_reg_digit4 0x05 + #define max7219_reg_digit5 0x06 + #define max7219_reg_digit6 0x07 + #define max7219_reg_digit7 0x08 + + #define max7219_reg_intensity 0x0a + #define max7219_reg_displayTest 0x0f + #define max7219_reg_decodeMode 0x09 + #define max7219_reg_scanLimit 0x0b + #define max7219_reg_shutdown 0x0c + + + void Max7219_init(); + void Max7219_PutByte(uint8_t data); + void Max7219(uint8_t reg, uint8_t data); + void Max7219_LED_On( int8_t row, int8_t col); + void Max7219_LED_Off( int8_t row, int8_t col); + void Max7219_LED_Toggle( int8_t row, int8_t col); + void Max7219_Clear_Row( int8_t row); + void Max7219_Clear_Column( int8_t col); + void Max7219_Set_Row( int8_t row, uint8_t val); + void Max7219_Set_Column( int8_t col, uint8_t val); + void Max7219_idle_tasks(); +#endif + + diff --git a/Marlin/example_configurations/AlephObjects/TAZ4/Configuration_adv.h b/Marlin/example_configurations/AlephObjects/TAZ4/Configuration_adv.h index 8c52ba38a..71bfc4a69 100644 --- a/Marlin/example_configurations/AlephObjects/TAZ4/Configuration_adv.h +++ b/Marlin/example_configurations/AlephObjects/TAZ4/Configuration_adv.h @@ -1382,4 +1382,30 @@ #endif // I2C_POSITION_ENCODERS +/** + * Debug LED's using an 8x8 LED Matrix driven by a Max7219 chip. Fully assembled versions are available on + * eBay for under $2.00 (including shipping) and only require 3 signal wires. + * + * Check out auctions similar to this: https://www.ebay.com/sch/i.html?_from=R40&_trksid=m570.l1313&_nkw=332349290049&_sacat=0 + */ + +//#define MAX7219_DEBUG +#if ENABLED(MAX7219_DEBUG) + #define Max7219_clock 64 // 77 on Re-ARM // Configuration of the 3 pins to control the display + #define Max7219_data_in 57 // 78 on Re-ARM + #define Max7219_load 44 // 79 on Re-ARM + + /* + * These are sample debug features that can be turned on and configured for your use. + * The developer will need to manage the use of the various LED's in the 8x8 matrix to avoid conflicts. + */ + #define MAX7219_DEBUG_PRINTER_ALIVE // Blink corner LED of 8x8 matrix from idle() routine if firmware is functioning + #define MAX7219_DEBUG_STEPPER_HEAD 3 // Display row position of stepper queue head on this line and the next line of LED matrix + #define MAX7219_DEBUG_STEPPER_TAIL 5 // Display row position of stepper queue tail on this line and the next line of LED matrix + + #define MAX7219_DEBUG_STEPPER_QUEUE 0 // Display row position of stepper queue depth on this line and the next line of LED matrix + // If you have stuttering on your Delta printer, this option may help you understand how + // various tweaks you make to your configuration are affecting the printer. +#endif + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/Anet/A6/Configuration_adv.h b/Marlin/example_configurations/Anet/A6/Configuration_adv.h index fbb7573a3..e12347eb9 100644 --- a/Marlin/example_configurations/Anet/A6/Configuration_adv.h +++ b/Marlin/example_configurations/Anet/A6/Configuration_adv.h @@ -1382,4 +1382,30 @@ #endif // I2C_POSITION_ENCODERS +/** + * Debug LED's using an 8x8 LED Matrix driven by a Max7219 chip. Fully assembled versions are available on + * eBay for under $2.00 (including shipping) and only require 3 signal wires. + * + * Check out auctions similar to this: https://www.ebay.com/sch/i.html?_from=R40&_trksid=m570.l1313&_nkw=332349290049&_sacat=0 + */ + +//#define MAX7219_DEBUG +#if ENABLED(MAX7219_DEBUG) + #define Max7219_clock 64 // 77 on Re-ARM // Configuration of the 3 pins to control the display + #define Max7219_data_in 57 // 78 on Re-ARM + #define Max7219_load 44 // 79 on Re-ARM + + /* + * These are sample debug features that can be turned on and configured for your use. + * The developer will need to manage the use of the various LED's in the 8x8 matrix to avoid conflicts. + */ + #define MAX7219_DEBUG_PRINTER_ALIVE // Blink corner LED of 8x8 matrix from idle() routine if firmware is functioning + #define MAX7219_DEBUG_STEPPER_HEAD 3 // Display row position of stepper queue head on this line and the next line of LED matrix + #define MAX7219_DEBUG_STEPPER_TAIL 5 // Display row position of stepper queue tail on this line and the next line of LED matrix + + #define MAX7219_DEBUG_STEPPER_QUEUE 0 // Display row position of stepper queue depth on this line and the next line of LED matrix + // If you have stuttering on your Delta printer, this option may help you understand how + // various tweaks you make to your configuration are affecting the printer. +#endif + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/Anet/A8/Configuration_adv.h b/Marlin/example_configurations/Anet/A8/Configuration_adv.h index 4812733d5..73dcf7595 100644 --- a/Marlin/example_configurations/Anet/A8/Configuration_adv.h +++ b/Marlin/example_configurations/Anet/A8/Configuration_adv.h @@ -1382,4 +1382,30 @@ #endif // I2C_POSITION_ENCODERS +/** + * Debug LED's using an 8x8 LED Matrix driven by a Max7219 chip. Fully assembled versions are available on + * eBay for under $2.00 (including shipping) and only require 3 signal wires. + * + * Check out auctions similar to this: https://www.ebay.com/sch/i.html?_from=R40&_trksid=m570.l1313&_nkw=332349290049&_sacat=0 + */ + +//#define MAX7219_DEBUG +#if ENABLED(MAX7219_DEBUG) + #define Max7219_clock 64 // 77 on Re-ARM // Configuration of the 3 pins to control the display + #define Max7219_data_in 57 // 78 on Re-ARM + #define Max7219_load 44 // 79 on Re-ARM + + /* + * These are sample debug features that can be turned on and configured for your use. + * The developer will need to manage the use of the various LED's in the 8x8 matrix to avoid conflicts. + */ + #define MAX7219_DEBUG_PRINTER_ALIVE // Blink corner LED of 8x8 matrix from idle() routine if firmware is functioning + #define MAX7219_DEBUG_STEPPER_HEAD 3 // Display row position of stepper queue head on this line and the next line of LED matrix + #define MAX7219_DEBUG_STEPPER_TAIL 5 // Display row position of stepper queue tail on this line and the next line of LED matrix + + #define MAX7219_DEBUG_STEPPER_QUEUE 0 // Display row position of stepper queue depth on this line and the next line of LED matrix + // If you have stuttering on your Delta printer, this option may help you understand how + // various tweaks you make to your configuration are affecting the printer. +#endif + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/BQ/Hephestos/Configuration_adv.h b/Marlin/example_configurations/BQ/Hephestos/Configuration_adv.h index aed6aad19..1157da121 100644 --- a/Marlin/example_configurations/BQ/Hephestos/Configuration_adv.h +++ b/Marlin/example_configurations/BQ/Hephestos/Configuration_adv.h @@ -1382,4 +1382,30 @@ #endif // I2C_POSITION_ENCODERS +/** + * Debug LED's using an 8x8 LED Matrix driven by a Max7219 chip. Fully assembled versions are available on + * eBay for under $2.00 (including shipping) and only require 3 signal wires. + * + * Check out auctions similar to this: https://www.ebay.com/sch/i.html?_from=R40&_trksid=m570.l1313&_nkw=332349290049&_sacat=0 + */ + +//#define MAX7219_DEBUG +#if ENABLED(MAX7219_DEBUG) + #define Max7219_clock 64 // 77 on Re-ARM // Configuration of the 3 pins to control the display + #define Max7219_data_in 57 // 78 on Re-ARM + #define Max7219_load 44 // 79 on Re-ARM + + /* + * These are sample debug features that can be turned on and configured for your use. + * The developer will need to manage the use of the various LED's in the 8x8 matrix to avoid conflicts. + */ + #define MAX7219_DEBUG_PRINTER_ALIVE // Blink corner LED of 8x8 matrix from idle() routine if firmware is functioning + #define MAX7219_DEBUG_STEPPER_HEAD 3 // Display row position of stepper queue head on this line and the next line of LED matrix + #define MAX7219_DEBUG_STEPPER_TAIL 5 // Display row position of stepper queue tail on this line and the next line of LED matrix + + #define MAX7219_DEBUG_STEPPER_QUEUE 0 // Display row position of stepper queue depth on this line and the next line of LED matrix + // If you have stuttering on your Delta printer, this option may help you understand how + // various tweaks you make to your configuration are affecting the printer. +#endif + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/BQ/Hephestos_2/Configuration_adv.h b/Marlin/example_configurations/BQ/Hephestos_2/Configuration_adv.h index b0dbdadba..b22e092d1 100644 --- a/Marlin/example_configurations/BQ/Hephestos_2/Configuration_adv.h +++ b/Marlin/example_configurations/BQ/Hephestos_2/Configuration_adv.h @@ -1382,4 +1382,30 @@ #endif // I2C_POSITION_ENCODERS +/** + * Debug LED's using an 8x8 LED Matrix driven by a Max7219 chip. Fully assembled versions are available on + * eBay for under $2.00 (including shipping) and only require 3 signal wires. + * + * Check out auctions similar to this: https://www.ebay.com/sch/i.html?_from=R40&_trksid=m570.l1313&_nkw=332349290049&_sacat=0 + */ + +//#define MAX7219_DEBUG +#if ENABLED(MAX7219_DEBUG) + #define Max7219_clock 64 // 77 on Re-ARM // Configuration of the 3 pins to control the display + #define Max7219_data_in 57 // 78 on Re-ARM + #define Max7219_load 44 // 79 on Re-ARM + + /* + * These are sample debug features that can be turned on and configured for your use. + * The developer will need to manage the use of the various LED's in the 8x8 matrix to avoid conflicts. + */ + #define MAX7219_DEBUG_PRINTER_ALIVE // Blink corner LED of 8x8 matrix from idle() routine if firmware is functioning + #define MAX7219_DEBUG_STEPPER_HEAD 3 // Display row position of stepper queue head on this line and the next line of LED matrix + #define MAX7219_DEBUG_STEPPER_TAIL 5 // Display row position of stepper queue tail on this line and the next line of LED matrix + + #define MAX7219_DEBUG_STEPPER_QUEUE 0 // Display row position of stepper queue depth on this line and the next line of LED matrix + // If you have stuttering on your Delta printer, this option may help you understand how + // various tweaks you make to your configuration are affecting the printer. +#endif + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/BQ/WITBOX/Configuration_adv.h b/Marlin/example_configurations/BQ/WITBOX/Configuration_adv.h index aed6aad19..1157da121 100644 --- a/Marlin/example_configurations/BQ/WITBOX/Configuration_adv.h +++ b/Marlin/example_configurations/BQ/WITBOX/Configuration_adv.h @@ -1382,4 +1382,30 @@ #endif // I2C_POSITION_ENCODERS +/** + * Debug LED's using an 8x8 LED Matrix driven by a Max7219 chip. Fully assembled versions are available on + * eBay for under $2.00 (including shipping) and only require 3 signal wires. + * + * Check out auctions similar to this: https://www.ebay.com/sch/i.html?_from=R40&_trksid=m570.l1313&_nkw=332349290049&_sacat=0 + */ + +//#define MAX7219_DEBUG +#if ENABLED(MAX7219_DEBUG) + #define Max7219_clock 64 // 77 on Re-ARM // Configuration of the 3 pins to control the display + #define Max7219_data_in 57 // 78 on Re-ARM + #define Max7219_load 44 // 79 on Re-ARM + + /* + * These are sample debug features that can be turned on and configured for your use. + * The developer will need to manage the use of the various LED's in the 8x8 matrix to avoid conflicts. + */ + #define MAX7219_DEBUG_PRINTER_ALIVE // Blink corner LED of 8x8 matrix from idle() routine if firmware is functioning + #define MAX7219_DEBUG_STEPPER_HEAD 3 // Display row position of stepper queue head on this line and the next line of LED matrix + #define MAX7219_DEBUG_STEPPER_TAIL 5 // Display row position of stepper queue tail on this line and the next line of LED matrix + + #define MAX7219_DEBUG_STEPPER_QUEUE 0 // Display row position of stepper queue depth on this line and the next line of LED matrix + // If you have stuttering on your Delta printer, this option may help you understand how + // various tweaks you make to your configuration are affecting the printer. +#endif + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/Cartesio/Configuration_adv.h b/Marlin/example_configurations/Cartesio/Configuration_adv.h index 6782e070f..928e98935 100644 --- a/Marlin/example_configurations/Cartesio/Configuration_adv.h +++ b/Marlin/example_configurations/Cartesio/Configuration_adv.h @@ -1382,4 +1382,30 @@ #endif // I2C_POSITION_ENCODERS +/** + * Debug LED's using an 8x8 LED Matrix driven by a Max7219 chip. Fully assembled versions are available on + * eBay for under $2.00 (including shipping) and only require 3 signal wires. + * + * Check out auctions similar to this: https://www.ebay.com/sch/i.html?_from=R40&_trksid=m570.l1313&_nkw=332349290049&_sacat=0 + */ + +//#define MAX7219_DEBUG +#if ENABLED(MAX7219_DEBUG) + #define Max7219_clock 64 // 77 on Re-ARM // Configuration of the 3 pins to control the display + #define Max7219_data_in 57 // 78 on Re-ARM + #define Max7219_load 44 // 79 on Re-ARM + + /* + * These are sample debug features that can be turned on and configured for your use. + * The developer will need to manage the use of the various LED's in the 8x8 matrix to avoid conflicts. + */ + #define MAX7219_DEBUG_PRINTER_ALIVE // Blink corner LED of 8x8 matrix from idle() routine if firmware is functioning + #define MAX7219_DEBUG_STEPPER_HEAD 3 // Display row position of stepper queue head on this line and the next line of LED matrix + #define MAX7219_DEBUG_STEPPER_TAIL 5 // Display row position of stepper queue tail on this line and the next line of LED matrix + + #define MAX7219_DEBUG_STEPPER_QUEUE 0 // Display row position of stepper queue depth on this line and the next line of LED matrix + // If you have stuttering on your Delta printer, this option may help you understand how + // various tweaks you make to your configuration are affecting the printer. +#endif + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/Felix/Configuration_adv.h b/Marlin/example_configurations/Felix/Configuration_adv.h index 638915b91..a16fbf766 100644 --- a/Marlin/example_configurations/Felix/Configuration_adv.h +++ b/Marlin/example_configurations/Felix/Configuration_adv.h @@ -1382,4 +1382,30 @@ #endif // I2C_POSITION_ENCODERS +/** + * Debug LED's using an 8x8 LED Matrix driven by a Max7219 chip. Fully assembled versions are available on + * eBay for under $2.00 (including shipping) and only require 3 signal wires. + * + * Check out auctions similar to this: https://www.ebay.com/sch/i.html?_from=R40&_trksid=m570.l1313&_nkw=332349290049&_sacat=0 + */ + +//#define MAX7219_DEBUG +#if ENABLED(MAX7219_DEBUG) + #define Max7219_clock 64 // 77 on Re-ARM // Configuration of the 3 pins to control the display + #define Max7219_data_in 57 // 78 on Re-ARM + #define Max7219_load 44 // 79 on Re-ARM + + /* + * These are sample debug features that can be turned on and configured for your use. + * The developer will need to manage the use of the various LED's in the 8x8 matrix to avoid conflicts. + */ + #define MAX7219_DEBUG_PRINTER_ALIVE // Blink corner LED of 8x8 matrix from idle() routine if firmware is functioning + #define MAX7219_DEBUG_STEPPER_HEAD 3 // Display row position of stepper queue head on this line and the next line of LED matrix + #define MAX7219_DEBUG_STEPPER_TAIL 5 // Display row position of stepper queue tail on this line and the next line of LED matrix + + #define MAX7219_DEBUG_STEPPER_QUEUE 0 // Display row position of stepper queue depth on this line and the next line of LED matrix + // If you have stuttering on your Delta printer, this option may help you understand how + // various tweaks you make to your configuration are affecting the printer. +#endif + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/Folger Tech/i3-2020/Configuration_adv.h b/Marlin/example_configurations/Folger Tech/i3-2020/Configuration_adv.h index 960b1b5f8..e3ce65ad9 100644 --- a/Marlin/example_configurations/Folger Tech/i3-2020/Configuration_adv.h +++ b/Marlin/example_configurations/Folger Tech/i3-2020/Configuration_adv.h @@ -1382,4 +1382,30 @@ #endif // I2C_POSITION_ENCODERS +/** + * Debug LED's using an 8x8 LED Matrix driven by a Max7219 chip. Fully assembled versions are available on + * eBay for under $2.00 (including shipping) and only require 3 signal wires. + * + * Check out auctions similar to this: https://www.ebay.com/sch/i.html?_from=R40&_trksid=m570.l1313&_nkw=332349290049&_sacat=0 + */ + +//#define MAX7219_DEBUG +#if ENABLED(MAX7219_DEBUG) + #define Max7219_clock 64 // 77 on Re-ARM // Configuration of the 3 pins to control the display + #define Max7219_data_in 57 // 78 on Re-ARM + #define Max7219_load 44 // 79 on Re-ARM + + /* + * These are sample debug features that can be turned on and configured for your use. + * The developer will need to manage the use of the various LED's in the 8x8 matrix to avoid conflicts. + */ + #define MAX7219_DEBUG_PRINTER_ALIVE // Blink corner LED of 8x8 matrix from idle() routine if firmware is functioning + #define MAX7219_DEBUG_STEPPER_HEAD 3 // Display row position of stepper queue head on this line and the next line of LED matrix + #define MAX7219_DEBUG_STEPPER_TAIL 5 // Display row position of stepper queue tail on this line and the next line of LED matrix + + #define MAX7219_DEBUG_STEPPER_QUEUE 0 // Display row position of stepper queue depth on this line and the next line of LED matrix + // If you have stuttering on your Delta printer, this option may help you understand how + // various tweaks you make to your configuration are affecting the printer. +#endif + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/Infitary/i3-M508/Configuration_adv.h b/Marlin/example_configurations/Infitary/i3-M508/Configuration_adv.h index 751759c30..e86f802ae 100644 --- a/Marlin/example_configurations/Infitary/i3-M508/Configuration_adv.h +++ b/Marlin/example_configurations/Infitary/i3-M508/Configuration_adv.h @@ -1382,4 +1382,30 @@ #endif // I2C_POSITION_ENCODERS +/** + * Debug LED's using an 8x8 LED Matrix driven by a Max7219 chip. Fully assembled versions are available on + * eBay for under $2.00 (including shipping) and only require 3 signal wires. + * + * Check out auctions similar to this: https://www.ebay.com/sch/i.html?_from=R40&_trksid=m570.l1313&_nkw=332349290049&_sacat=0 + */ + +//#define MAX7219_DEBUG +#if ENABLED(MAX7219_DEBUG) + #define Max7219_clock 64 // 77 on Re-ARM // Configuration of the 3 pins to control the display + #define Max7219_data_in 57 // 78 on Re-ARM + #define Max7219_load 44 // 79 on Re-ARM + + /* + * These are sample debug features that can be turned on and configured for your use. + * The developer will need to manage the use of the various LED's in the 8x8 matrix to avoid conflicts. + */ + #define MAX7219_DEBUG_PRINTER_ALIVE // Blink corner LED of 8x8 matrix from idle() routine if firmware is functioning + #define MAX7219_DEBUG_STEPPER_HEAD 3 // Display row position of stepper queue head on this line and the next line of LED matrix + #define MAX7219_DEBUG_STEPPER_TAIL 5 // Display row position of stepper queue tail on this line and the next line of LED matrix + + #define MAX7219_DEBUG_STEPPER_QUEUE 0 // Display row position of stepper queue depth on this line and the next line of LED matrix + // If you have stuttering on your Delta printer, this option may help you understand how + // various tweaks you make to your configuration are affecting the printer. +#endif + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/Malyan/M150/Configuration_adv.h b/Marlin/example_configurations/Malyan/M150/Configuration_adv.h index 4a7930605..f29f66217 100644 --- a/Marlin/example_configurations/Malyan/M150/Configuration_adv.h +++ b/Marlin/example_configurations/Malyan/M150/Configuration_adv.h @@ -1382,4 +1382,30 @@ #endif // I2C_POSITION_ENCODERS +/** + * Debug LED's using an 8x8 LED Matrix driven by a Max7219 chip. Fully assembled versions are available on + * eBay for under $2.00 (including shipping) and only require 3 signal wires. + * + * Check out auctions similar to this: https://www.ebay.com/sch/i.html?_from=R40&_trksid=m570.l1313&_nkw=332349290049&_sacat=0 + */ + +//#define MAX7219_DEBUG +#if ENABLED(MAX7219_DEBUG) + #define Max7219_clock 64 // 77 on Re-ARM // Configuration of the 3 pins to control the display + #define Max7219_data_in 57 // 78 on Re-ARM + #define Max7219_load 44 // 79 on Re-ARM + + /* + * These are sample debug features that can be turned on and configured for your use. + * The developer will need to manage the use of the various LED's in the 8x8 matrix to avoid conflicts. + */ + #define MAX7219_DEBUG_PRINTER_ALIVE // Blink corner LED of 8x8 matrix from idle() routine if firmware is functioning + #define MAX7219_DEBUG_STEPPER_HEAD 3 // Display row position of stepper queue head on this line and the next line of LED matrix + #define MAX7219_DEBUG_STEPPER_TAIL 5 // Display row position of stepper queue tail on this line and the next line of LED matrix + + #define MAX7219_DEBUG_STEPPER_QUEUE 0 // Display row position of stepper queue depth on this line and the next line of LED matrix + // If you have stuttering on your Delta printer, this option may help you understand how + // various tweaks you make to your configuration are affecting the printer. +#endif + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/RigidBot/Configuration_adv.h b/Marlin/example_configurations/RigidBot/Configuration_adv.h index 8fbd278c7..b57af74b3 100644 --- a/Marlin/example_configurations/RigidBot/Configuration_adv.h +++ b/Marlin/example_configurations/RigidBot/Configuration_adv.h @@ -1382,4 +1382,30 @@ #endif // I2C_POSITION_ENCODERS +/** + * Debug LED's using an 8x8 LED Matrix driven by a Max7219 chip. Fully assembled versions are available on + * eBay for under $2.00 (including shipping) and only require 3 signal wires. + * + * Check out auctions similar to this: https://www.ebay.com/sch/i.html?_from=R40&_trksid=m570.l1313&_nkw=332349290049&_sacat=0 + */ + +//#define MAX7219_DEBUG +#if ENABLED(MAX7219_DEBUG) + #define Max7219_clock 64 // 77 on Re-ARM // Configuration of the 3 pins to control the display + #define Max7219_data_in 57 // 78 on Re-ARM + #define Max7219_load 44 // 79 on Re-ARM + + /* + * These are sample debug features that can be turned on and configured for your use. + * The developer will need to manage the use of the various LED's in the 8x8 matrix to avoid conflicts. + */ + #define MAX7219_DEBUG_PRINTER_ALIVE // Blink corner LED of 8x8 matrix from idle() routine if firmware is functioning + #define MAX7219_DEBUG_STEPPER_HEAD 3 // Display row position of stepper queue head on this line and the next line of LED matrix + #define MAX7219_DEBUG_STEPPER_TAIL 5 // Display row position of stepper queue tail on this line and the next line of LED matrix + + #define MAX7219_DEBUG_STEPPER_QUEUE 0 // Display row position of stepper queue depth on this line and the next line of LED matrix + // If you have stuttering on your Delta printer, this option may help you understand how + // various tweaks you make to your configuration are affecting the printer. +#endif + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/SCARA/Configuration_adv.h b/Marlin/example_configurations/SCARA/Configuration_adv.h index cab69c2b1..da8e0ae0e 100644 --- a/Marlin/example_configurations/SCARA/Configuration_adv.h +++ b/Marlin/example_configurations/SCARA/Configuration_adv.h @@ -1382,4 +1382,30 @@ #endif // I2C_POSITION_ENCODERS +/** + * Debug LED's using an 8x8 LED Matrix driven by a Max7219 chip. Fully assembled versions are available on + * eBay for under $2.00 (including shipping) and only require 3 signal wires. + * + * Check out auctions similar to this: https://www.ebay.com/sch/i.html?_from=R40&_trksid=m570.l1313&_nkw=332349290049&_sacat=0 + */ + +//#define MAX7219_DEBUG +#if ENABLED(MAX7219_DEBUG) + #define Max7219_clock 64 // 77 on Re-ARM // Configuration of the 3 pins to control the display + #define Max7219_data_in 57 // 78 on Re-ARM + #define Max7219_load 44 // 79 on Re-ARM + + /* + * These are sample debug features that can be turned on and configured for your use. + * The developer will need to manage the use of the various LED's in the 8x8 matrix to avoid conflicts. + */ + #define MAX7219_DEBUG_PRINTER_ALIVE // Blink corner LED of 8x8 matrix from idle() routine if firmware is functioning + #define MAX7219_DEBUG_STEPPER_HEAD 3 // Display row position of stepper queue head on this line and the next line of LED matrix + #define MAX7219_DEBUG_STEPPER_TAIL 5 // Display row position of stepper queue tail on this line and the next line of LED matrix + + #define MAX7219_DEBUG_STEPPER_QUEUE 0 // Display row position of stepper queue depth on this line and the next line of LED matrix + // If you have stuttering on your Delta printer, this option may help you understand how + // various tweaks you make to your configuration are affecting the printer. +#endif + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/Sanguinololu/Configuration_adv.h b/Marlin/example_configurations/Sanguinololu/Configuration_adv.h index 953894cba..46384be46 100644 --- a/Marlin/example_configurations/Sanguinololu/Configuration_adv.h +++ b/Marlin/example_configurations/Sanguinololu/Configuration_adv.h @@ -1371,4 +1371,30 @@ #endif // I2C_POSITION_ENCODERS +/** + * Debug LED's using an 8x8 LED Matrix driven by a Max7219 chip. Fully assembled versions are available on + * eBay for under $2.00 (including shipping) and only require 3 signal wires. + * + * Check out auctions similar to this: https://www.ebay.com/sch/i.html?_from=R40&_trksid=m570.l1313&_nkw=332349290049&_sacat=0 + */ + +//#define MAX7219_DEBUG +#if ENABLED(MAX7219_DEBUG) + #define Max7219_clock 64 // 77 on Re-ARM // Configuration of the 3 pins to control the display + #define Max7219_data_in 57 // 78 on Re-ARM + #define Max7219_load 44 // 79 on Re-ARM + + /* + * These are sample debug features that can be turned on and configured for your use. + * The developer will need to manage the use of the various LED's in the 8x8 matrix to avoid conflicts. + */ + #define MAX7219_DEBUG_PRINTER_ALIVE // Blink corner LED of 8x8 matrix from idle() routine if firmware is functioning + #define MAX7219_DEBUG_STEPPER_HEAD 3 // Display row position of stepper queue head on this line and the next line of LED matrix + #define MAX7219_DEBUG_STEPPER_TAIL 5 // Display row position of stepper queue tail on this line and the next line of LED matrix + + #define MAX7219_DEBUG_STEPPER_QUEUE 0 // Display row position of stepper queue depth on this line and the next line of LED matrix + // If you have stuttering on your Delta printer, this option may help you understand how + // various tweaks you make to your configuration are affecting the printer. +#endif + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/TinyBoy2/Configuration_adv.h b/Marlin/example_configurations/TinyBoy2/Configuration_adv.h index 95630746d..610c084ce 100644 --- a/Marlin/example_configurations/TinyBoy2/Configuration_adv.h +++ b/Marlin/example_configurations/TinyBoy2/Configuration_adv.h @@ -1382,4 +1382,30 @@ #endif // I2C_POSITION_ENCODERS +/** + * Debug LED's using an 8x8 LED Matrix driven by a Max7219 chip. Fully assembled versions are available on + * eBay for under $2.00 (including shipping) and only require 3 signal wires. + * + * Check out auctions similar to this: https://www.ebay.com/sch/i.html?_from=R40&_trksid=m570.l1313&_nkw=332349290049&_sacat=0 + */ + +//#define MAX7219_DEBUG +#if ENABLED(MAX7219_DEBUG) + #define Max7219_clock 64 // 77 on Re-ARM // Configuration of the 3 pins to control the display + #define Max7219_data_in 57 // 78 on Re-ARM + #define Max7219_load 44 // 79 on Re-ARM + + /* + * These are sample debug features that can be turned on and configured for your use. + * The developer will need to manage the use of the various LED's in the 8x8 matrix to avoid conflicts. + */ + #define MAX7219_DEBUG_PRINTER_ALIVE // Blink corner LED of 8x8 matrix from idle() routine if firmware is functioning + #define MAX7219_DEBUG_STEPPER_HEAD 3 // Display row position of stepper queue head on this line and the next line of LED matrix + #define MAX7219_DEBUG_STEPPER_TAIL 5 // Display row position of stepper queue tail on this line and the next line of LED matrix + + #define MAX7219_DEBUG_STEPPER_QUEUE 0 // Display row position of stepper queue depth on this line and the next line of LED matrix + // If you have stuttering on your Delta printer, this option may help you understand how + // various tweaks you make to your configuration are affecting the printer. +#endif + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/Velleman/K8200/Configuration_adv.h b/Marlin/example_configurations/Velleman/K8200/Configuration_adv.h index 1a31f5eda..6265725f1 100644 --- a/Marlin/example_configurations/Velleman/K8200/Configuration_adv.h +++ b/Marlin/example_configurations/Velleman/K8200/Configuration_adv.h @@ -1395,4 +1395,30 @@ #endif // I2C_POSITION_ENCODERS +/** + * Debug LED's using an 8x8 LED Matrix driven by a Max7219 chip. Fully assembled versions are available on + * eBay for under $2.00 (including shipping) and only require 3 signal wires. + * + * Check out auctions similar to this: https://www.ebay.com/sch/i.html?_from=R40&_trksid=m570.l1313&_nkw=332349290049&_sacat=0 + */ + +//#define MAX7219_DEBUG +#if ENABLED(MAX7219_DEBUG) + #define Max7219_clock 64 // 77 on Re-ARM // Configuration of the 3 pins to control the display + #define Max7219_data_in 57 // 78 on Re-ARM + #define Max7219_load 44 // 79 on Re-ARM + + /* + * These are sample debug features that can be turned on and configured for your use. + * The developer will need to manage the use of the various LED's in the 8x8 matrix to avoid conflicts. + */ + #define MAX7219_DEBUG_PRINTER_ALIVE // Blink corner LED of 8x8 matrix from idle() routine if firmware is functioning + #define MAX7219_DEBUG_STEPPER_HEAD 3 // Display row position of stepper queue head on this line and the next line of LED matrix + #define MAX7219_DEBUG_STEPPER_TAIL 5 // Display row position of stepper queue tail on this line and the next line of LED matrix + + #define MAX7219_DEBUG_STEPPER_QUEUE 0 // Display row position of stepper queue depth on this line and the next line of LED matrix + // If you have stuttering on your Delta printer, this option may help you understand how + // various tweaks you make to your configuration are affecting the printer. +#endif + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/Velleman/K8400/Configuration_adv.h b/Marlin/example_configurations/Velleman/K8400/Configuration_adv.h index 998b25bac..703300a67 100644 --- a/Marlin/example_configurations/Velleman/K8400/Configuration_adv.h +++ b/Marlin/example_configurations/Velleman/K8400/Configuration_adv.h @@ -1382,4 +1382,30 @@ #endif // I2C_POSITION_ENCODERS +/** + * Debug LED's using an 8x8 LED Matrix driven by a Max7219 chip. Fully assembled versions are available on + * eBay for under $2.00 (including shipping) and only require 3 signal wires. + * + * Check out auctions similar to this: https://www.ebay.com/sch/i.html?_from=R40&_trksid=m570.l1313&_nkw=332349290049&_sacat=0 + */ + +//#define MAX7219_DEBUG +#if ENABLED(MAX7219_DEBUG) + #define Max7219_clock 64 // 77 on Re-ARM // Configuration of the 3 pins to control the display + #define Max7219_data_in 57 // 78 on Re-ARM + #define Max7219_load 44 // 79 on Re-ARM + + /* + * These are sample debug features that can be turned on and configured for your use. + * The developer will need to manage the use of the various LED's in the 8x8 matrix to avoid conflicts. + */ + #define MAX7219_DEBUG_PRINTER_ALIVE // Blink corner LED of 8x8 matrix from idle() routine if firmware is functioning + #define MAX7219_DEBUG_STEPPER_HEAD 3 // Display row position of stepper queue head on this line and the next line of LED matrix + #define MAX7219_DEBUG_STEPPER_TAIL 5 // Display row position of stepper queue tail on this line and the next line of LED matrix + + #define MAX7219_DEBUG_STEPPER_QUEUE 0 // Display row position of stepper queue depth on this line and the next line of LED matrix + // If you have stuttering on your Delta printer, this option may help you understand how + // various tweaks you make to your configuration are affecting the printer. +#endif + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h index 3715a421a..1f21b2f21 100644 --- a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h +++ b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h @@ -1384,4 +1384,30 @@ #endif // I2C_POSITION_ENCODERS +/** + * Debug LED's using an 8x8 LED Matrix driven by a Max7219 chip. Fully assembled versions are available on + * eBay for under $2.00 (including shipping) and only require 3 signal wires. + * + * Check out auctions similar to this: https://www.ebay.com/sch/i.html?_from=R40&_trksid=m570.l1313&_nkw=332349290049&_sacat=0 + */ + +//#define MAX7219_DEBUG +#if ENABLED(MAX7219_DEBUG) + #define Max7219_clock 64 // 77 on Re-ARM // Configuration of the 3 pins to control the display + #define Max7219_data_in 57 // 78 on Re-ARM + #define Max7219_load 44 // 79 on Re-ARM + + /* + * These are sample debug features that can be turned on and configured for your use. + * The developer will need to manage the use of the various LED's in the 8x8 matrix to avoid conflicts. + */ + #define MAX7219_DEBUG_PRINTER_ALIVE // Blink corner LED of 8x8 matrix from idle() routine if firmware is functioning + #define MAX7219_DEBUG_STEPPER_HEAD 3 // Display row position of stepper queue head on this line and the next line of LED matrix + #define MAX7219_DEBUG_STEPPER_TAIL 5 // Display row position of stepper queue tail on this line and the next line of LED matrix + + #define MAX7219_DEBUG_STEPPER_QUEUE 0 // Display row position of stepper queue depth on this line and the next line of LED matrix + // If you have stuttering on your Delta printer, this option may help you understand how + // various tweaks you make to your configuration are affecting the printer. +#endif + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h index e4eaec7c4..4d41b9280 100644 --- a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h +++ b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h @@ -1384,4 +1384,30 @@ #endif // I2C_POSITION_ENCODERS +/** + * Debug LED's using an 8x8 LED Matrix driven by a Max7219 chip. Fully assembled versions are available on + * eBay for under $2.00 (including shipping) and only require 3 signal wires. + * + * Check out auctions similar to this: https://www.ebay.com/sch/i.html?_from=R40&_trksid=m570.l1313&_nkw=332349290049&_sacat=0 + */ + +//#define MAX7219_DEBUG +#if ENABLED(MAX7219_DEBUG) + #define Max7219_clock 64 // 77 on Re-ARM // Configuration of the 3 pins to control the display + #define Max7219_data_in 57 // 78 on Re-ARM + #define Max7219_load 44 // 79 on Re-ARM + + /* + * These are sample debug features that can be turned on and configured for your use. + * The developer will need to manage the use of the various LED's in the 8x8 matrix to avoid conflicts. + */ + #define MAX7219_DEBUG_PRINTER_ALIVE // Blink corner LED of 8x8 matrix from idle() routine if firmware is functioning + #define MAX7219_DEBUG_STEPPER_HEAD 3 // Display row position of stepper queue head on this line and the next line of LED matrix + #define MAX7219_DEBUG_STEPPER_TAIL 5 // Display row position of stepper queue tail on this line and the next line of LED matrix + + #define MAX7219_DEBUG_STEPPER_QUEUE 0 // Display row position of stepper queue depth on this line and the next line of LED matrix + // If you have stuttering on your Delta printer, this option may help you understand how + // various tweaks you make to your configuration are affecting the printer. +#endif + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/delta/generic/Configuration_adv.h b/Marlin/example_configurations/delta/generic/Configuration_adv.h index e4eaec7c4..4d41b9280 100644 --- a/Marlin/example_configurations/delta/generic/Configuration_adv.h +++ b/Marlin/example_configurations/delta/generic/Configuration_adv.h @@ -1384,4 +1384,30 @@ #endif // I2C_POSITION_ENCODERS +/** + * Debug LED's using an 8x8 LED Matrix driven by a Max7219 chip. Fully assembled versions are available on + * eBay for under $2.00 (including shipping) and only require 3 signal wires. + * + * Check out auctions similar to this: https://www.ebay.com/sch/i.html?_from=R40&_trksid=m570.l1313&_nkw=332349290049&_sacat=0 + */ + +//#define MAX7219_DEBUG +#if ENABLED(MAX7219_DEBUG) + #define Max7219_clock 64 // 77 on Re-ARM // Configuration of the 3 pins to control the display + #define Max7219_data_in 57 // 78 on Re-ARM + #define Max7219_load 44 // 79 on Re-ARM + + /* + * These are sample debug features that can be turned on and configured for your use. + * The developer will need to manage the use of the various LED's in the 8x8 matrix to avoid conflicts. + */ + #define MAX7219_DEBUG_PRINTER_ALIVE // Blink corner LED of 8x8 matrix from idle() routine if firmware is functioning + #define MAX7219_DEBUG_STEPPER_HEAD 3 // Display row position of stepper queue head on this line and the next line of LED matrix + #define MAX7219_DEBUG_STEPPER_TAIL 5 // Display row position of stepper queue tail on this line and the next line of LED matrix + + #define MAX7219_DEBUG_STEPPER_QUEUE 0 // Display row position of stepper queue depth on this line and the next line of LED matrix + // If you have stuttering on your Delta printer, this option may help you understand how + // various tweaks you make to your configuration are affecting the printer. +#endif + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h index e4eaec7c4..4d41b9280 100644 --- a/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h @@ -1384,4 +1384,30 @@ #endif // I2C_POSITION_ENCODERS +/** + * Debug LED's using an 8x8 LED Matrix driven by a Max7219 chip. Fully assembled versions are available on + * eBay for under $2.00 (including shipping) and only require 3 signal wires. + * + * Check out auctions similar to this: https://www.ebay.com/sch/i.html?_from=R40&_trksid=m570.l1313&_nkw=332349290049&_sacat=0 + */ + +//#define MAX7219_DEBUG +#if ENABLED(MAX7219_DEBUG) + #define Max7219_clock 64 // 77 on Re-ARM // Configuration of the 3 pins to control the display + #define Max7219_data_in 57 // 78 on Re-ARM + #define Max7219_load 44 // 79 on Re-ARM + + /* + * These are sample debug features that can be turned on and configured for your use. + * The developer will need to manage the use of the various LED's in the 8x8 matrix to avoid conflicts. + */ + #define MAX7219_DEBUG_PRINTER_ALIVE // Blink corner LED of 8x8 matrix from idle() routine if firmware is functioning + #define MAX7219_DEBUG_STEPPER_HEAD 3 // Display row position of stepper queue head on this line and the next line of LED matrix + #define MAX7219_DEBUG_STEPPER_TAIL 5 // Display row position of stepper queue tail on this line and the next line of LED matrix + + #define MAX7219_DEBUG_STEPPER_QUEUE 0 // Display row position of stepper queue depth on this line and the next line of LED matrix + // If you have stuttering on your Delta printer, this option may help you understand how + // various tweaks you make to your configuration are affecting the printer. +#endif + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h index ffabd4eed..35836cefa 100644 --- a/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h @@ -1389,4 +1389,30 @@ #endif // I2C_POSITION_ENCODERS +/** + * Debug LED's using an 8x8 LED Matrix driven by a Max7219 chip. Fully assembled versions are available on + * eBay for under $2.00 (including shipping) and only require 3 signal wires. + * + * Check out auctions similar to this: https://www.ebay.com/sch/i.html?_from=R40&_trksid=m570.l1313&_nkw=332349290049&_sacat=0 + */ + +//#define MAX7219_DEBUG +#if ENABLED(MAX7219_DEBUG) + #define Max7219_clock 64 // 77 on Re-ARM // Configuration of the 3 pins to control the display + #define Max7219_data_in 57 // 78 on Re-ARM + #define Max7219_load 44 // 79 on Re-ARM + + /* + * These are sample debug features that can be turned on and configured for your use. + * The developer will need to manage the use of the various LED's in the 8x8 matrix to avoid conflicts. + */ + #define MAX7219_DEBUG_PRINTER_ALIVE // Blink corner LED of 8x8 matrix from idle() routine if firmware is functioning + #define MAX7219_DEBUG_STEPPER_HEAD 3 // Display row position of stepper queue head on this line and the next line of LED matrix + #define MAX7219_DEBUG_STEPPER_TAIL 5 // Display row position of stepper queue tail on this line and the next line of LED matrix + + #define MAX7219_DEBUG_STEPPER_QUEUE 0 // Display row position of stepper queue depth on this line and the next line of LED matrix + // If you have stuttering on your Delta printer, this option may help you understand how + // various tweaks you make to your configuration are affecting the printer. +#endif + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h index 57dc10197..a7cd5c764 100644 --- a/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h @@ -1384,4 +1384,30 @@ #endif // I2C_POSITION_ENCODERS +/** + * Debug LED's using an 8x8 LED Matrix driven by a Max7219 chip. Fully assembled versions are available on + * eBay for under $2.00 (including shipping) and only require 3 signal wires. + * + * Check out auctions similar to this: https://www.ebay.com/sch/i.html?_from=R40&_trksid=m570.l1313&_nkw=332349290049&_sacat=0 + */ + +//#define MAX7219_DEBUG +#if ENABLED(MAX7219_DEBUG) + #define Max7219_clock 64 // 77 on Re-ARM // Configuration of the 3 pins to control the display + #define Max7219_data_in 57 // 78 on Re-ARM + #define Max7219_load 44 // 79 on Re-ARM + + /* + * These are sample debug features that can be turned on and configured for your use. + * The developer will need to manage the use of the various LED's in the 8x8 matrix to avoid conflicts. + */ + #define MAX7219_DEBUG_PRINTER_ALIVE // Blink corner LED of 8x8 matrix from idle() routine if firmware is functioning + #define MAX7219_DEBUG_STEPPER_HEAD 3 // Display row position of stepper queue head on this line and the next line of LED matrix + #define MAX7219_DEBUG_STEPPER_TAIL 5 // Display row position of stepper queue tail on this line and the next line of LED matrix + + #define MAX7219_DEBUG_STEPPER_QUEUE 0 // Display row position of stepper queue depth on this line and the next line of LED matrix + // If you have stuttering on your Delta printer, this option may help you understand how + // various tweaks you make to your configuration are affecting the printer. +#endif + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/gCreate/gMax1.5+/Configuration.h b/Marlin/example_configurations/gCreate/gMax1.5+/Configuration.h index 51968f707..df49c31a0 100644 --- a/Marlin/example_configurations/gCreate/gMax1.5+/Configuration.h +++ b/Marlin/example_configurations/gCreate/gMax1.5+/Configuration.h @@ -1625,7 +1625,7 @@ // Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle. // 300ms is a good value but you can try less delay. // If the servo can't reach the requested position, increase it. -#define SERVO_DELAY { 300 } +#define SERVO_DELAY { 300, 300 } // Servo deactivation // diff --git a/Marlin/example_configurations/gCreate/gMax1.5+/Configuration_adv.h b/Marlin/example_configurations/gCreate/gMax1.5+/Configuration_adv.h index b6df0fe5e..1848bcf50 100644 --- a/Marlin/example_configurations/gCreate/gMax1.5+/Configuration_adv.h +++ b/Marlin/example_configurations/gCreate/gMax1.5+/Configuration_adv.h @@ -1382,4 +1382,30 @@ #endif // I2C_POSITION_ENCODERS +/** + * Debug LED's using an 8x8 LED Matrix driven by a Max7219 chip. Fully assembled versions are available on + * eBay for under $2.00 (including shipping) and only require 3 signal wires. + * + * Check out auctions similar to this: https://www.ebay.com/sch/i.html?_from=R40&_trksid=m570.l1313&_nkw=332349290049&_sacat=0 + */ + +#define MAX7219_DEBUG +#if ENABLED(MAX7219_DEBUG) + #define Max7219_clock 64 // 77 on Re-ARM // Configuration of the 3 pins to control the display + #define Max7219_data_in 57 // 78 on Re-ARM + #define Max7219_load 44 // 79 on Re-ARM + + /* + * These are sample debug features that can be turned on and configured for your use. + * The developer will need to manage the use of the various LED's in the 8x8 matrix to avoid conflicts. + */ + #define MAX7219_DEBUG_PRINTER_ALIVE // Blink corner LED of 8x8 matrix from idle() routine if firmware is functioning + #define MAX7219_DEBUG_STEPPER_HEAD 3 // Display row position of stepper queue head on this line and the next line of LED matrix + #define MAX7219_DEBUG_STEPPER_TAIL 5 // Display row position of stepper queue tail on this line and the next line of LED matrix + + #define MAX7219_DEBUG_STEPPER_QUEUE 0 // Display row position of stepper queue depth on this line and the next line of LED matrix + // If you have stuttering on your Delta printer, this option may help you understand how + // various tweaks you make to your configuration are affecting the printer. +#endif + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/makibox/Configuration_adv.h b/Marlin/example_configurations/makibox/Configuration_adv.h index 2e755a1ec..2ea7f33e8 100644 --- a/Marlin/example_configurations/makibox/Configuration_adv.h +++ b/Marlin/example_configurations/makibox/Configuration_adv.h @@ -1382,4 +1382,30 @@ #endif // I2C_POSITION_ENCODERS +/** + * Debug LED's using an 8x8 LED Matrix driven by a Max7219 chip. Fully assembled versions are available on + * eBay for under $2.00 (including shipping) and only require 3 signal wires. + * + * Check out auctions similar to this: https://www.ebay.com/sch/i.html?_from=R40&_trksid=m570.l1313&_nkw=332349290049&_sacat=0 + */ + +//#define MAX7219_DEBUG +#if ENABLED(MAX7219_DEBUG) + #define Max7219_clock 64 // 77 on Re-ARM // Configuration of the 3 pins to control the display + #define Max7219_data_in 57 // 78 on Re-ARM + #define Max7219_load 44 // 79 on Re-ARM + + /* + * These are sample debug features that can be turned on and configured for your use. + * The developer will need to manage the use of the various LED's in the 8x8 matrix to avoid conflicts. + */ + #define MAX7219_DEBUG_PRINTER_ALIVE // Blink corner LED of 8x8 matrix from idle() routine if firmware is functioning + #define MAX7219_DEBUG_STEPPER_HEAD 3 // Display row position of stepper queue head on this line and the next line of LED matrix + #define MAX7219_DEBUG_STEPPER_TAIL 5 // Display row position of stepper queue tail on this line and the next line of LED matrix + + #define MAX7219_DEBUG_STEPPER_QUEUE 0 // Display row position of stepper queue depth on this line and the next line of LED matrix + // If you have stuttering on your Delta printer, this option may help you understand how + // various tweaks you make to your configuration are affecting the printer. +#endif + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h b/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h index fc07c0456..c878d4951 100644 --- a/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h +++ b/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h @@ -1382,4 +1382,30 @@ #endif // I2C_POSITION_ENCODERS +/** + * Debug LED's using an 8x8 LED Matrix driven by a Max7219 chip. Fully assembled versions are available on + * eBay for under $2.00 (including shipping) and only require 3 signal wires. + * + * Check out auctions similar to this: https://www.ebay.com/sch/i.html?_from=R40&_trksid=m570.l1313&_nkw=332349290049&_sacat=0 + */ + +//#define MAX7219_DEBUG +#if ENABLED(MAX7219_DEBUG) + #define Max7219_clock 64 // 77 on Re-ARM // Configuration of the 3 pins to control the display + #define Max7219_data_in 57 // 78 on Re-ARM + #define Max7219_load 44 // 79 on Re-ARM + + /* + * These are sample debug features that can be turned on and configured for your use. + * The developer will need to manage the use of the various LED's in the 8x8 matrix to avoid conflicts. + */ + #define MAX7219_DEBUG_PRINTER_ALIVE // Blink corner LED of 8x8 matrix from idle() routine if firmware is functioning + #define MAX7219_DEBUG_STEPPER_HEAD 3 // Display row position of stepper queue head on this line and the next line of LED matrix + #define MAX7219_DEBUG_STEPPER_TAIL 5 // Display row position of stepper queue tail on this line and the next line of LED matrix + + #define MAX7219_DEBUG_STEPPER_QUEUE 0 // Display row position of stepper queue depth on this line and the next line of LED matrix + // If you have stuttering on your Delta printer, this option may help you understand how + // various tweaks you make to your configuration are affecting the printer. +#endif + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/wt150/Configuration_adv.h b/Marlin/example_configurations/wt150/Configuration_adv.h index d8f6c3a3b..0aa8b7ef0 100644 --- a/Marlin/example_configurations/wt150/Configuration_adv.h +++ b/Marlin/example_configurations/wt150/Configuration_adv.h @@ -1382,4 +1382,30 @@ #endif // I2C_POSITION_ENCODERS +/** + * Debug LED's using an 8x8 LED Matrix driven by a Max7219 chip. Fully assembled versions are available on + * eBay for under $2.00 (including shipping) and only require 3 signal wires. + * + * Check out auctions similar to this: https://www.ebay.com/sch/i.html?_from=R40&_trksid=m570.l1313&_nkw=332349290049&_sacat=0 + */ + +//#define MAX7219_DEBUG +#if ENABLED(MAX7219_DEBUG) + #define Max7219_clock 64 // 77 on Re-ARM // Configuration of the 3 pins to control the display + #define Max7219_data_in 57 // 78 on Re-ARM + #define Max7219_load 44 // 79 on Re-ARM + + /* + * These are sample debug features that can be turned on and configured for your use. + * The developer will need to manage the use of the various LED's in the 8x8 matrix to avoid conflicts. + */ + #define MAX7219_DEBUG_PRINTER_ALIVE // Blink corner LED of 8x8 matrix from idle() routine if firmware is functioning + #define MAX7219_DEBUG_STEPPER_HEAD 3 // Display row position of stepper queue head on this line and the next line of LED matrix + #define MAX7219_DEBUG_STEPPER_TAIL 5 // Display row position of stepper queue tail on this line and the next line of LED matrix + + #define MAX7219_DEBUG_STEPPER_QUEUE 0 // Display row position of stepper queue depth on this line and the next line of LED matrix + // If you have stuttering on your Delta printer, this option may help you understand how + // various tweaks you make to your configuration are affecting the printer. +#endif + #endif // CONFIGURATION_ADV_H From 36771e949252244652dffa1c32502b4fdf49a2d0 Mon Sep 17 00:00:00 2001 From: jneilliii Date: Sat, 26 Aug 2017 03:11:47 -0400 Subject: [PATCH 110/112] Fixes required for Creality CR-10 --- Marlin/pins_MELZI_CREALITY.h | 25 ++++++++++++++++++++----- 1 file changed, 20 insertions(+), 5 deletions(-) diff --git a/Marlin/pins_MELZI_CREALITY.h b/Marlin/pins_MELZI_CREALITY.h index b2f0cf871..e9199ed36 100644 --- a/Marlin/pins_MELZI_CREALITY.h +++ b/Marlin/pins_MELZI_CREALITY.h @@ -22,10 +22,17 @@ /** * Melzi (Creality) pin assignments + * + * The Creality board needs a bootloader installed before Marlin can be uploaded. + * If you don't have a chip programmer you can use a spare Arduino plus a few + * electronic components to write the bootloader. + * + * See http://www.instructables.com/id/Burn-Arduino-Bootloader-with-Arduino-MEGA/ */ #define BOARD_NAME "Melzi (Creality)" #define IS_MELZI + #include "pins_SANGUINOLOLU_12.h" // For the stock CR-10 use the REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER @@ -33,19 +40,27 @@ #undef LCD_SDSS #undef LED_PIN - #undef LCD_PINS_RS #undef LCD_PINS_ENABLE - -#define LCD_PINS_RS 28 // st9720 CS -#define LCD_PINS_ENABLE 17 // st9720 DAT - #undef LCD_PINS_D4 #undef LCD_PINS_D5 #undef LCD_PINS_D6 #undef LCD_PINS_D7 +#undef FIL_RUNOUT_PIN +#define LCD_SDSS 31 // Smart Controller SD card reader (rather than the Melzi) +#define LCD_PINS_RS 28 // st9720 CS +#define LCD_PINS_ENABLE 17 // st9720 DAT #define LCD_PINS_D4 30 // st9720 CLK +#define LCD_PINS_D5 -1 +#define LCD_PINS_D6 -1 +#define LCD_PINS_D7 -1 +#define FIL_RUNOUT_PIN -1 // Uses Beeper/LED Pin Pulled to GND + +// Alter timing for graphical display +#define ST7920_DELAY_1 DELAY_2_NOP +#define ST7920_DELAY_2 DELAY_2_NOP +#define ST7920_DELAY_3 DELAY_2_NOP /** PIN: 0 Port: B0 E0_DIR_PIN protected From 321f98f867552b23faf9f9a2ac07cdfa87010a18 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 27 Aug 2017 20:53:27 -0500 Subject: [PATCH 111/112] Fix servo delay in Folgertech config --- .../example_configurations/Folger Tech/i3-2020/Configuration.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/example_configurations/Folger Tech/i3-2020/Configuration.h b/Marlin/example_configurations/Folger Tech/i3-2020/Configuration.h index 21d0b12fb..28fe69fec 100644 --- a/Marlin/example_configurations/Folger Tech/i3-2020/Configuration.h +++ b/Marlin/example_configurations/Folger Tech/i3-2020/Configuration.h @@ -1616,7 +1616,7 @@ // Delay (in milliseconds) before the next move will start, to give the servo time to reach its target angle. // 300ms is a good value but you can try less delay. // If the servo can't reach the requested position, increase it. -#define SERVO_DELAY 500 +#define SERVO_DELAY { 500, 500 } // Servo deactivation // From 9c00cff89836706776f6353635368a47cc5bf881 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 28 Aug 2017 18:46:39 -0500 Subject: [PATCH 112/112] Version 1.1.5 --- Marlin/Version.h | 4 ++-- README.md | 2 +- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index a14d8202c..bba230100 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -35,7 +35,7 @@ /** * Marlin release version identifier */ - #define SHORT_BUILD_VERSION "1.1.4" + #define SHORT_BUILD_VERSION "1.1.5" /** * Verbose version identifier which should contain a reference to the location @@ -48,7 +48,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ - #define STRING_DISTRIBUTION_DATE "2017-07-04 12:00" + #define STRING_DISTRIBUTION_DATE "2017-08-28 12:00" /** * Required minimum Configuration.h and Configuration_adv.h file versions. diff --git a/README.md b/README.md index c353194fe..274dddd95 100644 --- a/README.md +++ b/README.md @@ -9,7 +9,7 @@ For complete Marlin documentation click over to the [Marlin Homepage