From 61db0fd1025a45d532441b882d23768f98cd296b Mon Sep 17 00:00:00 2001 From: Christopher Pepper Date: Thu, 1 Jun 2017 20:33:39 +0100 Subject: [PATCH 001/180] Add issue template for github --- .github/issue_template.md | 7 +++++++ 1 file changed, 7 insertions(+) create mode 100644 .github/issue_template.md diff --git a/.github/issue_template.md b/.github/issue_template.md new file mode 100644 index 0000000000..8be2b3e995 --- /dev/null +++ b/.github/issue_template.md @@ -0,0 +1,7 @@ +### Expected behaviour + +### Actual behaviour + +### Steps to reproduce the behaviour + +#### please add your Configuration.h and Configuration_adv.h to a zip file and attach it to this issue From bfe7fbe5c0aa02047aac6a573c331cdb886b5d40 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 4 Jun 2017 17:00:11 -0500 Subject: [PATCH 002/180] Maintain message scroll rate --- Marlin/ultralcd_impl_DOGM.h | 13 +++++++++---- Marlin/ultralcd_impl_HD44780.h | 12 ++++++++---- 2 files changed, 17 insertions(+), 8 deletions(-) diff --git a/Marlin/ultralcd_impl_DOGM.h b/Marlin/ultralcd_impl_DOGM.h index 80f2c4a473..89fbdf3d98 100644 --- a/Marlin/ultralcd_impl_DOGM.h +++ b/Marlin/ultralcd_impl_DOGM.h @@ -406,12 +406,17 @@ FORCE_INLINE void _draw_axis_label(const AxisEnum axis, const char* const pstr, inline void lcd_implementation_status_message() { #if ENABLED(STATUS_MESSAGE_SCROLLING) + static bool last_blink = false; lcd_print_utf(lcd_status_message + status_scroll_pos); const uint8_t slen = lcd_strlen(lcd_status_message); if (slen > LCD_WIDTH) { - // Skip any non-printing bytes - while (!PRINTABLE(lcd_status_message[status_scroll_pos++])) { /* nada */ } - if (status_scroll_pos > slen - LCD_WIDTH) status_scroll_pos = 0; + const bool new_blink = lcd_blink(); + if (last_blink != new_blink) { + last_blink = new_blink; + // Skip any non-printing bytes + while (!PRINTABLE(lcd_status_message[status_scroll_pos])) status_scroll_pos++; + if (++status_scroll_pos > slen - LCD_WIDTH) status_scroll_pos = 0; + } } #else lcd_print_utf(lcd_status_message); @@ -422,7 +427,7 @@ inline void lcd_implementation_status_message() { static void lcd_implementation_status_screen() { - bool blink = lcd_blink(); + const bool blink = lcd_blink(); // Status Menu Font lcd_setFont(FONT_STATUSMENU); diff --git a/Marlin/ultralcd_impl_HD44780.h b/Marlin/ultralcd_impl_HD44780.h index 9192912a8a..866bfd62b7 100644 --- a/Marlin/ultralcd_impl_HD44780.h +++ b/Marlin/ultralcd_impl_HD44780.h @@ -655,7 +655,7 @@ Possible status screens: |01234567890123456789| */ static void lcd_implementation_status_screen() { - bool blink = lcd_blink(); + const bool blink = lcd_blink(); // // Line 1 @@ -825,12 +825,16 @@ static void lcd_implementation_status_screen() { #endif // FILAMENT_LCD_DISPLAY && SDSUPPORT #if ENABLED(STATUS_MESSAGE_SCROLLING) + static bool last_blink = false; lcd_print_utf(lcd_status_message + status_scroll_pos); const uint8_t slen = lcd_strlen(lcd_status_message); if (slen > LCD_WIDTH) { - // Skip any non-printing bytes - while (!PRINTABLE(lcd_status_message[status_scroll_pos++])) { /* nada */ } - if (status_scroll_pos > slen - LCD_WIDTH) status_scroll_pos = 0; + if (last_blink != blink) { + last_blink = blink; + // Skip any non-printing bytes + while (!PRINTABLE(lcd_status_message[status_scroll_pos])) status_scroll_pos++; + if (++status_scroll_pos > slen - LCD_WIDTH) status_scroll_pos = 0; + } } #else lcd_print_utf(lcd_status_message); From eb8af486d2e153b57a8e6d508333feb7e12d751c Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 4 Jun 2017 17:03:22 -0500 Subject: [PATCH 003/180] Ensure safe temperature for M600 --- Marlin/Marlin_main.cpp | 24 ++++++++++++++++++++++-- Marlin/ultralcd.cpp | 4 +++- 2 files changed, 25 insertions(+), 3 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index c3635ca8d1..d88286c4df 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -5921,6 +5921,25 @@ inline void gcode_M17() { return true; } + static void ensure_safe_temperature() { + bool did_show = false; + wait_for_heatup = true; + while (wait_for_heatup) { + idle(); + wait_for_heatup = false; + HOTEND_LOOP() { + if (thermalManager.degTargetHotend(e) && abs(thermalManager.degHotend(e) - thermalManager.degTargetHotend(e)) > 3) { + wait_for_heatup = true; + if (!did_show) { // Show "wait for heating" + lcd_advanced_pause_show_message(ADVANCED_PAUSE_MESSAGE_WAIT_FOR_NOZZLES_TO_HEAT); + did_show = true; + } + break; + } + } + } + } + static void wait_for_filament_reload(int8_t max_beep_count = 0) { bool nozzle_timed_out = false; @@ -5937,8 +5956,7 @@ inline void gcode_M17() { nozzle_timed_out |= thermalManager.is_heater_idle(e); #if ENABLED(ULTIPANEL) - if (nozzle_timed_out) - lcd_advanced_pause_show_message(ADVANCED_PAUSE_MESSAGE_CLICK_TO_HEAT_NOZZLE); + if (nozzle_timed_out) ensure_safe_temperature(); #endif idle(true); @@ -9204,6 +9222,8 @@ inline void gcode_M503() { */ inline void gcode_M600() { + ensure_safe_temperature(); + // 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 diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index 0508bca6ce..cb6eabfc3a 100755 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -1094,6 +1094,7 @@ void kill_screen(const char* lcd_msg) { #endif #if ENABLED(ADVANCED_PAUSE_FEATURE) + void lcd_enqueue_filament_change() { if (!DEBUGGING(DRYRUN) && thermalManager.tooColdToExtrude(active_extruder)) { lcd_save_previous_screen(); @@ -1103,7 +1104,8 @@ void kill_screen(const char* lcd_msg) { lcd_advanced_pause_show_message(ADVANCED_PAUSE_MESSAGE_INIT); enqueue_and_echo_commands_P(PSTR("M600 B0")); } - #endif + + #endif // ADVANCED_PAUSE_FEATURE /** * From 04b07a6ecc65133d0e32bcd75f2825390a5a50c5 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 4 Jun 2017 17:24:34 -0500 Subject: [PATCH 004/180] Unused var in Stepper --- Marlin/stepper.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/Marlin/stepper.cpp b/Marlin/stepper.cpp index 4c35113e90..d2d4d09d0d 100644 --- a/Marlin/stepper.cpp +++ b/Marlin/stepper.cpp @@ -1353,7 +1353,6 @@ void Stepper::report_positions() { // No other ISR should ever interrupt this! void Stepper::babystep(const AxisEnum axis, const bool direction) { cli(); - uint8_t old_dir; switch (axis) { From ba0bd33c38d9e0a19d76f75ac0566aeea2e8103e Mon Sep 17 00:00:00 2001 From: Bob-the-Kuhn Date: Sun, 4 Jun 2017 22:16:27 -0500 Subject: [PATCH 005/180] Removed check for 2560 family --- Marlin/Sd2Card.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/Sd2Card.h b/Marlin/Sd2Card.h index b1f442c4e2..f91958ac03 100644 --- a/Marlin/Sd2Card.h +++ b/Marlin/Sd2Card.h @@ -125,7 +125,7 @@ uint8_t const SD_CARD_TYPE_SDHC = 3; * define SOFTWARE_SPI to use bit-bang SPI */ //------------------------------------------------------------------------------ -#if MEGA_SOFT_SPI && (defined(__AVR_ATmega1280__)||defined(__AVR_ATmega2560__)) +#if MEGA_SOFT_SPI #define SOFTWARE_SPI #elif USE_SOFTWARE_SPI #define SOFTWARE_SPI From 0dd0033b3360a94bb3f4e484d6cb06353f8c500e Mon Sep 17 00:00:00 2001 From: Roxy-3D Date: Mon, 5 Jun 2017 17:02:00 -0500 Subject: [PATCH 006/180] Save up to 94 bytes of RAM on 20x4 LCD Display machines (#6964) * Save up to 94 bytes of RAM on 20x4 LCD Display machines Moved the custom screen characters out of RAM into Program Memory. With SD-Card support and the Progress Bar enabled, this saves 94 bytes of RAM memory. This was tested using the example_configurations/FolgerTech-i3-2020 files. So a couple small changes to those files snuck into this Pull Request. Probably... We can find similar savings in the Graphics LCD code it we comb through it. And if so... That is the place we really need to save RAM memory! * Tidy up white space and indentation --- Marlin/Conditionals_LCD.h | 14 +-- .../FolgerTech-i3-2020/Configuration.h | 2 +- .../FolgerTech-i3-2020/Configuration_adv.h | 4 +- Marlin/ultralcd_impl_HD44780.h | 111 +++++++++++------- 4 files changed, 77 insertions(+), 54 deletions(-) diff --git a/Marlin/Conditionals_LCD.h b/Marlin/Conditionals_LCD.h index 2ec73eb7c4..3c39512a93 100644 --- a/Marlin/Conditionals_LCD.h +++ b/Marlin/Conditionals_LCD.h @@ -241,14 +241,14 @@ #define LCD_STR_FILAM_MUL "\xa4" #else /* Custom characters defined in the first 8 characters of the LCD */ - #define LCD_STR_BEDTEMP "\x00" // Print only as a char. This will have 'unexpected' results when used in a string! - #define LCD_STR_DEGREE "\x01" - #define LCD_STR_THERMOMETER "\x02" - #define LCD_STR_UPLEVEL "\x03" - #define LCD_STR_REFRESH "\x04" + #define LCD_BEDTEMP_CHAR 0x00 // Print only as a char. This will have 'unexpected' results when used in a string! + #define LCD_DEGREE_CHAR 0x01 + #define LCD_STR_THERMOMETER "\x02" // Too many places use preprocessor string concatination to change this to a char right now. + #define LCD_UPLEVEL_CHAR 0x03 + #define LCD_REFRESH_CHAR 0x04 #define LCD_STR_FOLDER "\x05" - #define LCD_STR_FEEDRATE "\x06" - #define LCD_STR_CLOCK "\x07" + #define LCD_FEEDRATE_CHAR 0x06 + #define LCD_CLOCK_CHAR 0x07 #define LCD_STR_ARROW_RIGHT ">" /* from the default character set */ #endif diff --git a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h index 46c7660013..ee45fa7bd5 100644 --- a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h +++ b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h @@ -649,7 +649,7 @@ */ #define X_PROBE_OFFSET_FROM_EXTRUDER 38 // X offset: -left +right [of the nozzle] #define Y_PROBE_OFFSET_FROM_EXTRUDER -7 // Y offset: -front +behind [the nozzle] -#define Z_PROBE_OFFSET_FROM_EXTRUDER -10.1 // Z offset: -below +above [the nozzle] +#define Z_PROBE_OFFSET_FROM_EXTRUDER -10.4 // Z offset: -below +above [the nozzle] // X and Y axis travel speed (mm/m) between probes #define XY_PROBE_SPEED 7500 diff --git a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h index 803fd44bae..e1579fcb5e 100644 --- a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h +++ b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h @@ -509,7 +509,7 @@ #endif // Show a progress bar on HD44780 LCDs for SD printing - //#define LCD_PROGRESS_BAR + #define LCD_PROGRESS_BAR #if ENABLED(LCD_PROGRESS_BAR) // Amount of time (ms) to show the bar @@ -1228,7 +1228,7 @@ * - M206 and M428 are disabled. * - G92 will revert to its behavior from Marlin 1.0. */ -//#define NO_WORKSPACE_OFFSETS +#define NO_WORKSPACE_OFFSETS /** * Set the number of proportional font spaces required to fill up a typical character space. diff --git a/Marlin/ultralcd_impl_HD44780.h b/Marlin/ultralcd_impl_HD44780.h index 866bfd62b7..d1ddd3ba1b 100644 --- a/Marlin/ultralcd_impl_HD44780.h +++ b/Marlin/ultralcd_impl_HD44780.h @@ -193,12 +193,18 @@ extern volatile uint8_t buttons; //an extended version of the last checked butt static void lcd_implementation_update_indicators(); #endif -static void lcd_set_custom_characters( - #if ENABLED(LCD_PROGRESS_BAR) - const bool info_screen_charset = true - #endif -) { - static byte bedTemp[8] = { + +static void createChar_P(char c, PROGMEM byte *ptr) { + byte temp[8]; + int8_t i; + + for(i=0; i<8; i++) { + temp[i] = pgm_read_byte(&ptr[i]); + } + lcd.createChar(c, temp); +} + +const static PROGMEM byte bedTemp[8] = { B00000, B11111, B10101, @@ -207,8 +213,9 @@ static void lcd_set_custom_characters( B11111, B00000, B00000 - }; //thanks Sonny Mounicou - static byte degree[8] = { +}; + +const static PROGMEM byte degree[8] = { B01100, B10010, B10010, @@ -218,7 +225,8 @@ static void lcd_set_custom_characters( B00000, B00000 }; - static byte thermometer[8] = { + +const static PROGMEM byte thermometer[8] = { B00100, B01010, B01010, @@ -228,7 +236,8 @@ static void lcd_set_custom_characters( B10001, B01110 }; - static byte uplevel[8] = { + +const static PROGMEM byte uplevel[8] = { B00100, B01110, B11111, @@ -237,8 +246,9 @@ static void lcd_set_custom_characters( B00000, B00000, B00000 - }; //thanks joris - static byte feedrate[8] = { +}; + +const static PROGMEM byte feedrate[8] = { B11100, B10000, B11000, @@ -247,8 +257,9 @@ static void lcd_set_custom_characters( B00110, B00101, B00000 - }; //thanks Sonny Mounicou - static byte clock[8] = { +}; + +const static PROGMEM byte clock[8] = { B00000, B01110, B10011, @@ -257,16 +268,10 @@ static void lcd_set_custom_characters( B01110, B00000, B00000 - }; //thanks Sonny Mounicou +}; - lcd.createChar(LCD_STR_BEDTEMP[0], bedTemp); - lcd.createChar(LCD_STR_DEGREE[0], degree); - lcd.createChar(LCD_STR_THERMOMETER[0], thermometer); - lcd.createChar(LCD_STR_FEEDRATE[0], feedrate); - lcd.createChar(LCD_STR_CLOCK[0], clock); - - #if ENABLED(SDSUPPORT) - static byte refresh[8] = { +#if ENABLED(SDSUPPORT) + const static PROGMEM byte refresh[8] = { B00000, B00110, B11001, @@ -275,8 +280,8 @@ static void lcd_set_custom_characters( B10011, B01100, B00000, - }; //thanks joris - static byte folder[8] = { + }; + const static PROGMEM byte folder[8] = { B00000, B11100, B11111, @@ -285,10 +290,10 @@ static void lcd_set_custom_characters( B11111, B00000, B00000 - }; //thanks joris + }; - #if ENABLED(LCD_PROGRESS_BAR) - static byte progress[3][8] = { { + #if ENABLED(LCD_PROGRESS_BAR) + const static PROGMEM byte progress[3][8] = { { B00000, B10000, B10000, @@ -316,26 +321,43 @@ static void lcd_set_custom_characters( B10101, B00000 } }; + #endif +#endif + +static void lcd_set_custom_characters( + #if ENABLED(LCD_PROGRESS_BAR) + const bool info_screen_charset = true + #endif +) { + + createChar_P(LCD_BEDTEMP_CHAR, bedTemp); + createChar_P(LCD_DEGREE_CHAR, degree); + createChar_P(LCD_STR_THERMOMETER[0], thermometer); + createChar_P(LCD_FEEDRATE_CHAR, feedrate); + createChar_P(LCD_CLOCK_CHAR, clock); + + #if ENABLED(SDSUPPORT) + #if ENABLED(LCD_PROGRESS_BAR) static bool char_mode = false; if (info_screen_charset != char_mode) { char_mode = info_screen_charset; if (info_screen_charset) { // Progress bar characters for info screen - for (int i = 3; i--;) lcd.createChar(LCD_STR_PROGRESS[i], progress[i]); + for (int i = 3; i--;) createChar_P(LCD_STR_PROGRESS[i], progress[i]); } else { // Custom characters for submenus - lcd.createChar(LCD_STR_UPLEVEL[0], uplevel); - lcd.createChar(LCD_STR_REFRESH[0], refresh); - lcd.createChar(LCD_STR_FOLDER[0], folder); + createChar_P(LCD_UPLEVEL_CHAR, uplevel); + createChar_P(LCD_REFRESH_CHAR, refresh); + createChar_P(LCD_STR_FOLDER[0], folder); } } #else - lcd.createChar(LCD_STR_UPLEVEL[0], uplevel); - lcd.createChar(LCD_STR_REFRESH[0], refresh); - lcd.createChar(LCD_STR_FOLDER[0], folder); + createChar_P(LCD_UPLEVEL_CHAR, uplevel); + createChar_P(LCD_REFRESH_CHAR, refresh); + createChar_P(LCD_STR_FOLDER[0], folder); #endif #else - lcd.createChar(LCD_STR_UPLEVEL[0], uplevel); + createChar_P(LCD_UPLEVEL_CHAR, uplevel); #endif } @@ -607,7 +629,8 @@ FORCE_INLINE void _draw_heater_status(const int8_t heater, const char prefix, co lcd.print(itostr3left(t2 + 0.5)); if (prefix >= 0) { - lcd_printPGM(PSTR(LCD_STR_DEGREE " ")); + lcd.print((char)LCD_DEGREE_CHAR); + lcd.print(' '); if (t2 < 10) lcd.print(' '); } } @@ -677,10 +700,10 @@ static void lcd_implementation_status_screen() { lcd.setCursor(8, 0); #if HOTENDS > 1 - lcd.print(LCD_STR_THERMOMETER[0]); + lcd.print((CHAR)LCD_STR_THERMOMETER[0]); _draw_heater_status(1, -1, blink); #else - lcd.print(LCD_STR_BEDTEMP[0]); + lcd.print((CHAR)LCD_BEDTEMP_CHAR); _draw_heater_status(-1, -1, blink); #endif @@ -701,7 +724,7 @@ static void lcd_implementation_status_screen() { #if HOTENDS > 1 _draw_heater_status(1, LCD_STR_THERMOMETER[0], blink); #else - _draw_heater_status(-1, LCD_STR_BEDTEMP[0], blink); + _draw_heater_status(-1, LCD_BEDTEMP_CHAR, blink); #endif #endif // HOTENDS > 1 || TEMP_SENSOR_BED != 0 @@ -735,7 +758,7 @@ static void lcd_implementation_status_screen() { // If we both have a 2nd extruder and a heated bed, // show the heated bed temp on the left, // since the first line is filled with extruder temps - _draw_heater_status(-1, LCD_STR_BEDTEMP[0], blink); + _draw_heater_status(-1, LCD_BEDTEMP_CHAR, blink); #else // Before homing the axis letters are blinking 'X' <-> '?'. @@ -767,7 +790,7 @@ static void lcd_implementation_status_screen() { #if LCD_HEIGHT > 3 lcd.setCursor(0, 2); - lcd.print(LCD_STR_FEEDRATE[0]); + lcd.print((char)LCD_FEEDRATE_CHAR); lcd.print(itostr3(feedrate_percentage)); lcd.print('%'); @@ -788,7 +811,7 @@ static void lcd_implementation_status_screen() { uint8_t len = elapsed.toDigital(buffer); lcd.setCursor(LCD_WIDTH - len - 1, 2); - lcd.print(LCD_STR_CLOCK[0]); + lcd.print((char)LCD_CLOCK_CHAR); lcd_print(buffer); #endif // LCD_HEIGHT > 3 @@ -980,7 +1003,7 @@ static void lcd_implementation_status_screen() { #endif // SDSUPPORT - #define lcd_implementation_drawmenu_back(sel, row, pstr, dummy) lcd_implementation_drawmenu_generic(sel, row, pstr, LCD_STR_UPLEVEL[0], LCD_STR_UPLEVEL[0]) + #define lcd_implementation_drawmenu_back(sel, row, pstr, dummy) lcd_implementation_drawmenu_generic(sel, row, pstr, LCD_UPLEVEL_CHAR,LCD_UPLEVEL_CHAR) #define lcd_implementation_drawmenu_submenu(sel, row, pstr, data) lcd_implementation_drawmenu_generic(sel, row, pstr, '>', LCD_STR_ARROW_RIGHT[0]) #define lcd_implementation_drawmenu_gcode(sel, row, pstr, gcode) lcd_implementation_drawmenu_generic(sel, row, pstr, '>', ' ') #define lcd_implementation_drawmenu_function(sel, row, pstr, data) lcd_implementation_drawmenu_generic(sel, row, pstr, '>', ' ') From 2c2b991b598e0cedb7c67f72dca0e22bcc9705ee Mon Sep 17 00:00:00 2001 From: Tannoo Date: Tue, 6 Jun 2017 21:14:18 -0600 Subject: [PATCH 007/180] UBL Manual Build Menu Option (#6972) One click option to manually build UBL mesh. --- Marlin/language_en.h | 3 +++ Marlin/ultralcd.cpp | 2 ++ 2 files changed, 5 insertions(+) diff --git a/Marlin/language_en.h b/Marlin/language_en.h index 4e7256535b..6f79272d7d 100644 --- a/Marlin/language_en.h +++ b/Marlin/language_en.h @@ -170,6 +170,9 @@ #ifndef MSG_UBL_LEVEL_BED #define MSG_UBL_LEVEL_BED _UxGT("Unified Bed Leveling") #endif + #ifndef MSG_UBL_MANUAL_MESH + #define MSG_UBL_MANUAL_MESH _UxGT("Manually Build Mesh") + #endif #ifndef MSG_UBL_ACTIVATE_MESH #define MSG_UBL_ACTIVATE_MESH _UxGT("Activate UBL") #endif diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index cb6eabfc3a..5b519493de 100755 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -2080,6 +2080,7 @@ void kill_screen(const char* lcd_msg) { * * Prepare * - Unified Bed Leveling + * - Manually Build Mesh * - Activate UBL * - Deactivate UBL * - Mesh Storage @@ -2134,6 +2135,7 @@ 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_STORAGE_MESH_MENU, _lcd_ubl_storage_mesh); From 82e662fc698694fc53b7e7d7e332f636761aa6d8 Mon Sep 17 00:00:00 2001 From: bgort Date: Wed, 7 Jun 2017 02:24:36 -0400 Subject: [PATCH 008/180] Remove requirement for LCD when UBL is used. (#6971) * Remove requirement for LCD when UBL is used. * fix previous oversights * further refinement - error messages for P2 & P4 * require R on G26 when not using LCD; default to all points --- Marlin/G26_Mesh_Validation_Tool.cpp | 182 +++++--- Marlin/SanityCheck.h | 2 - Marlin/ubl_G29.cpp | 641 +++++++++++++++------------- 3 files changed, 452 insertions(+), 373 deletions(-) diff --git a/Marlin/G26_Mesh_Validation_Tool.cpp b/Marlin/G26_Mesh_Validation_Tool.cpp index 7cdfab55d9..5c8802ef41 100644 --- a/Marlin/G26_Mesh_Validation_Tool.cpp +++ b/Marlin/G26_Mesh_Validation_Tool.cpp @@ -99,7 +99,8 @@ * 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. + * 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 * un-retraction is at 1.2mm These numbers will be scaled by the specified amount @@ -108,6 +109,11 @@ * 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 + * 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 + * parameter, every point will be printed. + * * 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 @@ -131,9 +137,11 @@ void set_destination_to_current(); void set_current_to_destination(); void prepare_move_to_destination(); - void lcd_setstatusPGM(const char* const message, const int8_t level); void sync_plan_position_e(); - void chirp_at_user(); + #if ENABLED(NEWPANEL) + void lcd_setstatusPGM(const char* const message, const int8_t level); + void chirp_at_user(); + #endif // Private functions @@ -173,28 +181,30 @@ feedrate_mm_s = save_feedrate; // restore global feed rate } - /** - * Detect ubl_lcd_clicked, debounce it, and return true for cancel - */ - bool user_canceled() { - if (!ubl_lcd_clicked()) return false; - safe_delay(10); // Wait for click to settle + #if ENABLED(NEWPANEL) + /** + * Detect ubl_lcd_clicked, debounce it, and return true for cancel + */ + bool user_canceled() { + if (!ubl_lcd_clicked()) return false; + safe_delay(10); // Wait for click to settle - #if ENABLED(ULTRA_LCD) - lcd_setstatusPGM(PSTR("Mesh Validation Stopped."), 99); - lcd_quick_feedback(); - #endif + #if ENABLED(ULTRA_LCD) + lcd_setstatusPGM(PSTR("Mesh Validation Stopped."), 99); + lcd_quick_feedback(); + #endif - while (!ubl_lcd_clicked()) idle(); // Wait for button release + while (!ubl_lcd_clicked()) idle(); // Wait for button release - // If the button is suddenly pressed again, - // ask the user to resolve the issue - lcd_setstatusPGM(PSTR("Release button"), 99); // will never appear... - while (ubl_lcd_clicked()) idle(); // unless this loop happens - lcd_reset_status(); + // If the button is suddenly pressed again, + // ask the user to resolve the issue + lcd_setstatusPGM(PSTR("Release button"), 99); // will never appear... + while (ubl_lcd_clicked()) idle(); // unless this loop happens + lcd_reset_status(); - return true; - } + return true; + } + #endif /** * G26: Mesh Validation Pattern generation. @@ -310,7 +320,9 @@ for (tmp = start_angle; tmp < end_angle - 0.1; tmp += 30.0) { - if (user_canceled()) goto LEAVE; // Check if the user wants to stop the Mesh Validation + #if ENABLED(NEWPANEL) + if (user_canceled()) goto LEAVE; // Check if the user wants to stop the Mesh Validation + #endif int tmp_div_30 = tmp / 30.0; if (tmp_div_30 < 0) tmp_div_30 += 360 / 30; @@ -426,7 +438,9 @@ for (uint8_t i = 0; i < GRID_MAX_POINTS_X; i++) { for (uint8_t j = 0; j < GRID_MAX_POINTS_Y; j++) { - if (user_canceled()) return true; // Check if the user wants to stop the Mesh Validation + #if ENABLED(NEWPANEL) + if (user_canceled()) return true; // Check if the user wants to stop the Mesh Validation + #endif if (i < GRID_MAX_POINTS_X) { // We can't connect to anything to the right than GRID_MAX_POINTS_X. // This is already a half circle because we are at the edge of the bed. @@ -663,9 +677,14 @@ } if (parser.seen('P')) { - if (!parser.has_value()) - g26_prime_flag = -1; - else { + if (!parser.has_value()) { + #if ENABLED(NEWPANEL) + g26_prime_flag = -1; + #else + SERIAL_PROTOCOLLNPGM("?Prime length must be specified when not using an LCD."); + return UBL_ERR; + #endif + } else { g26_prime_flag++; g26_prime_length = parser.value_linear_units(); if (!WITHIN(g26_prime_length, 0.0, 25.0)) { @@ -682,7 +701,7 @@ return UBL_ERR; } } - g26_extrusion_multiplier *= sq(1.75) / sq(g26_filament_diameter); // If we aren't using 1.75mm filament, we need to + g26_extrusion_multiplier *= sq(1.75) / sq(g26_filament_diameter); // If we aren't using 1.75mm filament, we need to // scale up or down the length needed to get the // same volume of filament @@ -702,7 +721,14 @@ random_deviation = parser.has_value() ? parser.value_float() : 50.0; } - g26_repeats = parser.seen('R') ? (parser.has_value() ? parser.value_int() : GRID_MAX_POINTS + 1) : GRID_MAX_POINTS + 1; + #if ENABLED(NEWPANEL) + g26_repeats = parser.seen('R') && parser.has_value() ? parser.value_int() : GRID_MAX_POINTS + 1; + #else + if (!parser.seen('R')) { + SERIAL_PROTOCOLLNPGM("?(R)epeat must be specified when not using an LCD."); + return UBL_ERR; + } else g26_repeats = parser.has_value() ? parser.value_int() : GRID_MAX_POINTS + 1; + #endif if (g26_repeats < 1) { SERIAL_PROTOCOLLNPGM("?(R)epeat value not plausible; must be at least 1."); return UBL_ERR; @@ -723,11 +749,13 @@ return UBL_OK; } - bool unified_bed_leveling::exit_from_g26() { - lcd_setstatusPGM(PSTR("Leaving G26"), -1); - while (ubl_lcd_clicked()) idle(); - return UBL_ERR; - } + #if ENABLED(NEWPANEL) + bool unified_bed_leveling::exit_from_g26() { + lcd_setstatusPGM(PSTR("Leaving G26"), -1); + while (ubl_lcd_clicked()) idle(); + return UBL_ERR; + } + #endif /** * Turn on the bed and nozzle heat and @@ -744,7 +772,11 @@ has_control_of_lcd_panel = true; thermalManager.setTargetBed(g26_bed_temp); while (abs(thermalManager.degBed() - g26_bed_temp) > 3) { - if (ubl_lcd_clicked()) return exit_from_g26(); + + #if ENABLED(NEWPANEL) + if (ubl_lcd_clicked()) return exit_from_g26(); + #endif + if (PENDING(millis(), next)) { next = millis() + 5000UL; print_heaterstates(); @@ -761,7 +793,11 @@ // Start heating the nozzle and wait for it to reach temperature. thermalManager.setTargetHotend(g26_hotend_temp, 0); while (abs(thermalManager.degHotend(0) - g26_hotend_temp) > 3) { - if (ubl_lcd_clicked()) return exit_from_g26(); + + #if ENABLED(NEWPANEL) + if (ubl_lcd_clicked()) return exit_from_g26(); + #endif + if (PENDING(millis(), next)) { next = millis() + 5000UL; print_heaterstates(); @@ -781,49 +817,53 @@ * Prime the nozzle if needed. Return true on error. */ bool unified_bed_leveling::prime_nozzle() { - float Total_Prime = 0.0; - if (g26_prime_flag == -1) { // The user wants to control how much filament gets purged + #if ENABLED(NEWPANEL) + float Total_Prime = 0.0; - has_control_of_lcd_panel = true; + if (g26_prime_flag == -1) { // The user wants to control how much filament gets purged - lcd_setstatusPGM(PSTR("User-Controlled Prime"), 99); - chirp_at_user(); - - set_destination_to_current(); - - recover_filament(destination); // Make sure G26 doesn't think the filament is retracted(). - - while (!ubl_lcd_clicked()) { + has_control_of_lcd_panel = true; + lcd_setstatusPGM(PSTR("User-Controlled Prime"), 99); chirp_at_user(); - destination[E_AXIS] += 0.25; - #ifdef PREVENT_LENGTHY_EXTRUDE - Total_Prime += 0.25; - if (Total_Prime >= EXTRUDE_MAXLENGTH) return UBL_ERR; - #endif - G26_line_to_destination(planner.max_feedrate_mm_s[E_AXIS] / 15.0); - 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 - // action to give the user a more responsive 'Stop'. set_destination_to_current(); - idle(); + + recover_filament(destination); // Make sure G26 doesn't think the filament is retracted(). + + while (!ubl_lcd_clicked()) { + chirp_at_user(); + destination[E_AXIS] += 0.25; + #ifdef PREVENT_LENGTHY_EXTRUDE + Total_Prime += 0.25; + if (Total_Prime >= EXTRUDE_MAXLENGTH) return UBL_ERR; + #endif + G26_line_to_destination(planner.max_feedrate_mm_s[E_AXIS] / 15.0); + + 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 + // action to give the user a more responsive 'Stop'. + set_destination_to_current(); + idle(); + } + + while (ubl_lcd_clicked()) idle(); // Debounce Encoder Wheel + + #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. + lcd_setstatusPGM(PSTR("Done Priming"), 99); + lcd_quick_feedback(); + #endif + + has_control_of_lcd_panel = false; + } - - while (ubl_lcd_clicked()) idle(); // Debounce Encoder Wheel - - #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. - lcd_setstatusPGM(PSTR("Done Priming"), 99); - lcd_quick_feedback(); - #endif - - has_control_of_lcd_panel = false; - - } - else { + else { + #else + { + #endif #if ENABLED(ULTRA_LCD) lcd_setstatusPGM(PSTR("Fixed Length Prime."), 99); lcd_quick_feedback(); diff --git a/Marlin/SanityCheck.h b/Marlin/SanityCheck.h index db36517bbb..83dabc975e 100644 --- a/Marlin/SanityCheck.h +++ b/Marlin/SanityCheck.h @@ -468,8 +468,6 @@ static_assert(1 >= 0 #if ENABLED(AUTO_BED_LEVELING_UBL) #if IS_SCARA #error "AUTO_BED_LEVELING_UBL does not yet support SCARA printers." - #elif DISABLED(NEWPANEL) - #error "AUTO_BED_LEVELING_UBL requires an LCD controller." #endif #endif diff --git a/Marlin/ubl_G29.cpp b/Marlin/ubl_G29.cpp index 9201fe9101..28a1cb3bd1 100644 --- a/Marlin/ubl_G29.cpp +++ b/Marlin/ubl_G29.cpp @@ -40,11 +40,14 @@ extern float destination[XYZE], current_position[XYZE]; - void lcd_return_to_status(); - void lcd_mesh_edit_setup(float initial); - float lcd_mesh_edit(); - void lcd_z_offset_edit_setup(float); - float lcd_z_offset_edit(); + #if ENABLED(NEWPANEL) + void lcd_return_to_status(); + void lcd_mesh_edit_setup(float initial); + float lcd_mesh_edit(); + void lcd_z_offset_edit_setup(float); + float lcd_z_offset_edit(); + #endif + extern float meshedit_done; extern long babysteps_done; extern float probe_pt(const float &x, const float &y, bool, int); @@ -149,9 +152,10 @@ * parameter can be given to prioritize where the command should be trying to measure points. * If the X and Y parameters are not specified the current probe position is used. * P1 accepts a 'T' (Topology) parameter so you can observe mesh generation. - * P1 also watches for the LCD Panel Encoder Switch to be held down, and will suspend - * generation of the Mesh in that case. (Note: This check is only done between probe points, - * so you must press and hold the switch until the Phase 1 command detects it.) + * P1 also watches for the LCD Panel Encoder Switch to be held down (assuming you have one), + * and will suspend generation of the Mesh in that case. (Note: This check is only done + * between probe points, so you must press and hold the switch until the Phase 1 command + * detects it.) * * P2 Phase 2 Probe areas of the Mesh that can't be automatically handled. Phase 2 respects an H * parameter to control the height between Mesh points. The default height for movement @@ -187,6 +191,8 @@ * Phase 2 allows the T (Map) parameter to be specified. This helps the user see the progression * of the Mesh being built. * + * NOTE: P2 is not available unless you have LCD support enabled! + * * P3 Phase 3 Fill the unpopulated regions of the Mesh with a fixed value. There are two different paths the * user can go down. If the user specifies the value using the C parameter, the closest invalid * mesh points to the nozzle will be filled. The user can specify a repeat count using the R @@ -204,8 +210,9 @@ * numbers. You should use some scrutiny and caution. * * P4 Phase 4 Fine tune the Mesh. The Delta Mesh Compensation System assume the existence of - * an LCD Panel. It is possible to fine tune the mesh without the use of an LCD Panel. - * (More work and details on doing this later!) + * an LCD Panel. It is possible to fine tune the mesh without the use of an LCD Panel using + * G42 and M421; see the UBL documentation for further details. + * * The System will search for the closest Mesh Point to the nozzle. It will move the * nozzle to this location. The user can use the LCD Panel to carefully adjust the nozzle * so it is just barely touching the bed. When the user clicks the control, the System @@ -228,6 +235,7 @@ * LOWER the Mesh Point at the location. If you did not get good adheasion, you want to * RAISE the Mesh Point at that location. * + * NOTE: P4 is not available unless you have LCD support enabled! * * P5 Phase 5 Find Mean Mesh Height and Standard Deviation. Typically, it is easier to use and * work with the Mesh if it is Mean Adjusted. You can specify a C parameter to @@ -452,52 +460,57 @@ break; case 2: { - // - // Manually Probe Mesh in areas that can't be reached by the probe - // - SERIAL_PROTOCOLLNPGM("Manually probing unreachable mesh locations."); - do_blocking_move_to_z(Z_CLEARANCE_BETWEEN_PROBES); - if (!g29_x_flag && !g29_y_flag) { - /** - * Use a good default location for the path. - * The flipped > and < operators in these comparisons is intentional. - * It should cause the probed points to follow a nice path on Cartesian printers. - * It may make sense to have Delta printers default to the center of the bed. - * Until that is decided, this can be forced with the X and Y parameters. - */ - #if IS_KINEMATIC - 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; - #endif - } + #if ENABLED(NEWPANEL) + // + // Manually Probe Mesh in areas that can't be reached by the probe + // + SERIAL_PROTOCOLLNPGM("Manually probing unreachable mesh locations."); + do_blocking_move_to_z(Z_CLEARANCE_BETWEEN_PROBES); + if (!g29_x_flag && !g29_y_flag) { + /** + * Use a good default location for the path. + * The flipped > and < operators in these comparisons is intentional. + * It should cause the probed points to follow a nice path on Cartesian printers. + * It may make sense to have Delta printers default to the center of the bed. + * Until that is decided, this can be forced with the X and Y parameters. + */ + #if IS_KINEMATIC + 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; + #endif + } - if (parser.seen('C')) { - g29_x_pos = current_position[X_AXIS]; - g29_y_pos = current_position[Y_AXIS]; - } + if (parser.seen('C')) { + g29_x_pos = current_position[X_AXIS]; + g29_y_pos = current_position[Y_AXIS]; + } - float height = Z_CLEARANCE_BETWEEN_PROBES; + float height = Z_CLEARANCE_BETWEEN_PROBES; - if (parser.seen('B')) { - g29_card_thickness = parser.has_value() ? parser.value_float() : measure_business_card_thickness(height); - if (fabs(g29_card_thickness) > 1.5) { - SERIAL_PROTOCOLLNPGM("?Error in Business Card measurement."); + if (parser.seen('B')) { + g29_card_thickness = parser.has_value() ? parser.value_float() : measure_business_card_thickness(height); + if (fabs(g29_card_thickness) > 1.5) { + SERIAL_PROTOCOLLNPGM("?Error in Business Card measurement."); + return; + } + } + + if (parser.seen('H') && parser.has_value()) height = parser.value_float(); + + if (!position_is_reachable_xy(g29_x_pos, g29_y_pos)) { + SERIAL_PROTOCOLLNPGM("XY outside printable radius."); return; } - } - if (parser.seen('H') && parser.has_value()) height = parser.value_float(); - - if (!position_is_reachable_xy(g29_x_pos, g29_y_pos)) { - SERIAL_PROTOCOLLNPGM("XY outside printable radius."); + manually_probe_remaining_mesh(g29_x_pos, g29_y_pos, height, g29_card_thickness, parser.seen('T')); + SERIAL_PROTOCOLLNPGM("G29 P2 finished."); + #else + SERIAL_PROTOCOLLNPGM("?P2 is only available when an LCD is present."); return; - } - - manually_probe_remaining_mesh(g29_x_pos, g29_y_pos, height, g29_card_thickness, parser.seen('T')); - SERIAL_PROTOCOLLNPGM("G29 P2 finished."); + #endif } break; case 3: { @@ -557,11 +570,13 @@ break; } - case 4: - // - // Fine Tune (i.e., Edit) the Mesh - // - fine_tune_mesh(g29_x_pos, g29_y_pos, parser.seen('T')); + case 4: // Fine Tune (i.e., Edit) the Mesh + #if ENABLED(NEWPANEL) + fine_tune_mesh(g29_x_pos, g29_y_pos, parser.seen('T')); + #else + SERIAL_PROTOCOLLNPGM("?P4 is only available when an LCD is present."); + return; + #endif break; case 5: find_mean_mesh_height(); break; @@ -716,11 +731,15 @@ LEAVE: - lcd_reset_alert_level(); - LCD_MESSAGEPGM(""); - lcd_quick_feedback(); + #if ENABLED(NEWPANEL) + lcd_reset_alert_level(); + LCD_MESSAGEPGM(""); + lcd_quick_feedback(); - has_control_of_lcd_panel = false; + has_control_of_lcd_panel = false; + #endif + + return; } void unified_bed_leveling::find_mean_mesh_height() { @@ -782,16 +801,18 @@ uint16_t max_iterations = GRID_MAX_POINTS; do { - if (ubl_lcd_clicked()) { - SERIAL_PROTOCOLLNPGM("\nMesh only partially populated.\n"); - lcd_quick_feedback(); - STOW_PROBE(); - while (ubl_lcd_clicked()) idle(); - has_control_of_lcd_panel = false; - restore_ubl_active_state_and_leave(); - safe_delay(50); // Debounce the Encoder wheel - return; - } + #if ENABLED(NEWPANEL) + if (ubl_lcd_clicked()) { + SERIAL_PROTOCOLLNPGM("\nMesh only partially populated.\n"); + lcd_quick_feedback(); + STOW_PROBE(); + while (ubl_lcd_clicked()) idle(); + has_control_of_lcd_panel = false; + restore_ubl_active_state_and_leave(); + safe_delay(50); // Debounce the Encoder wheel + return; + } + #endif location = find_closest_mesh_point_of_type(INVALID, lx, ly, USE_PROBE_AS_REFERENCE, NULL, close_or_far); @@ -920,155 +941,165 @@ } } - float unified_bed_leveling::measure_point_with_encoder() { + #if ENABLED(NEWPANEL) + float unified_bed_leveling::measure_point_with_encoder() { - while (ubl_lcd_clicked()) delay(50); // wait for user to release encoder wheel - delay(50); // debounce - - KEEPALIVE_STATE(PAUSED_FOR_USER); - while (!ubl_lcd_clicked()) { // we need the loop to move the nozzle based on the encoder wheel here! - idle(); - if (encoder_diff) { - do_blocking_move_to_z(current_position[Z_AXIS] + 0.01 * float(encoder_diff)); - encoder_diff = 0; - } - } - KEEPALIVE_STATE(IN_HANDLER); - return current_position[Z_AXIS]; - } - - static void echo_and_take_a_measurement() { SERIAL_PROTOCOLLNPGM(" and take a measurement."); } - - float unified_bed_leveling::measure_business_card_thickness(float &in_height) { - has_control_of_lcd_panel = true; - save_ubl_active_state_and_disable(); // Disable bed level correction for probing - - do_blocking_move_to_z(in_height); - do_blocking_move_to_xy(0.5 * (UBL_MESH_MAX_X - (UBL_MESH_MIN_X)), 0.5 * (UBL_MESH_MAX_Y - (UBL_MESH_MIN_Y))); - //, min(planner.max_feedrate_mm_s[X_AXIS], planner.max_feedrate_mm_s[Y_AXIS]) / 2.0); - stepper.synchronize(); - - SERIAL_PROTOCOLPGM("Place shim under nozzle"); - LCD_MESSAGEPGM("Place shim & measure"); // TODO: Make translatable string - lcd_return_to_status(); - echo_and_take_a_measurement(); - - const float z1 = measure_point_with_encoder(); - do_blocking_move_to_z(current_position[Z_AXIS] + SIZE_OF_LITTLE_RAISE); - stepper.synchronize(); - - SERIAL_PROTOCOLPGM("Remove shim"); - LCD_MESSAGEPGM("Remove & measure bed"); // TODO: Make translatable string - echo_and_take_a_measurement(); - - const float z2 = measure_point_with_encoder(); - - do_blocking_move_to_z(current_position[Z_AXIS] + Z_CLEARANCE_BETWEEN_PROBES); - - const float thickness = abs(z1 - z2); - - if (g29_verbose_level > 1) { - SERIAL_PROTOCOLPGM("Business Card is "); - SERIAL_PROTOCOL_F(thickness, 4); - SERIAL_PROTOCOLLNPGM("mm thick."); - } - - in_height = current_position[Z_AXIS]; // do manual probing at lower height - - has_control_of_lcd_panel = false; - - restore_ubl_active_state_and_leave(); - - return thickness; - } - - void unified_bed_leveling::manually_probe_remaining_mesh(const float &lx, const float &ly, const float &z_clearance, const float &thick, const bool do_ubl_mesh_map) { - - has_control_of_lcd_panel = true; - save_ubl_active_state_and_disable(); // we don't do bed level correction because we want the raw data when we probe - do_blocking_move_to_z(Z_CLEARANCE_BETWEEN_PROBES); - do_blocking_move_to_xy(lx, ly); - - lcd_return_to_status(); - mesh_index_pair location; - do { - location = find_closest_mesh_point_of_type(INVALID, lx, ly, USE_NOZZLE_AS_REFERENCE, NULL, false); - // It doesn't matter if the probe can't reach the NAN location. This is a manual probe. - if (location.x_index < 0 && location.y_index < 0) continue; - - const float rawx = mesh_index_to_xpos(location.x_index), - rawy = mesh_index_to_ypos(location.y_index), - xProbe = LOGICAL_X_POSITION(rawx), - yProbe = LOGICAL_Y_POSITION(rawy); - - if (!position_is_reachable_raw_xy(rawx, rawy)) break; // SHOULD NOT OCCUR (find_closest_mesh_point only returns reachable points) - - do_blocking_move_to_z(Z_CLEARANCE_BETWEEN_PROBES); - - LCD_MESSAGEPGM("Moving to next"); // TODO: Make translatable string - - do_blocking_move_to_xy(xProbe, yProbe); - do_blocking_move_to_z(z_clearance); + while (ubl_lcd_clicked()) delay(50); // wait for user to release encoder wheel + delay(50); // debounce KEEPALIVE_STATE(PAUSED_FOR_USER); - has_control_of_lcd_panel = true; - - if (do_ubl_mesh_map) display_map(g29_map_type); // show user where we're probing - - serialprintPGM(parser.seen('B') ? PSTR("Place shim & measure") : PSTR("Measure")); // TODO: Make translatable strings - - const float z_step = 0.01; // existing behavior: 0.01mm per click, occasionally step - //const float z_step = 1.0 / planner.axis_steps_per_mm[Z_AXIS]; // approx one step each click - - while (ubl_lcd_clicked()) delay(50); // wait for user to release encoder wheel - delay(50); // debounce - while (!ubl_lcd_clicked()) { // we need the loop to move the nozzle based on the encoder wheel here! + while (!ubl_lcd_clicked()) { // we need the loop to move the nozzle based on the encoder wheel here! idle(); if (encoder_diff) { - do_blocking_move_to_z(current_position[Z_AXIS] + float(encoder_diff) * z_step); + do_blocking_move_to_z(current_position[Z_AXIS] + 0.01 * float(encoder_diff)); encoder_diff = 0; } } + KEEPALIVE_STATE(IN_HANDLER); + return current_position[Z_AXIS]; + } - // this sequence to detect an ubl_lcd_clicked() debounce it and leave if it is - // a Press and Hold is repeated in a lot of places (including G26_Mesh_Validation.cpp). This - // should be redone and compressed. - const millis_t nxt = millis() + 1500L; - while (ubl_lcd_clicked()) { // debounce and watch for abort - idle(); - if (ELAPSED(millis(), nxt)) { - SERIAL_PROTOCOLLNPGM("\nMesh only partially populated."); - do_blocking_move_to_z(Z_CLEARANCE_DEPLOY_PROBE); - lcd_quick_feedback(); - while (ubl_lcd_clicked()) idle(); - has_control_of_lcd_panel = false; - KEEPALIVE_STATE(IN_HANDLER); - restore_ubl_active_state_and_leave(); - return; + static void echo_and_take_a_measurement() { SERIAL_PROTOCOLLNPGM(" and take a measurement."); } + + float unified_bed_leveling::measure_business_card_thickness(float &in_height) { + has_control_of_lcd_panel = true; + save_ubl_active_state_and_disable(); // Disable bed level correction for probing + + do_blocking_move_to_z(in_height); + do_blocking_move_to_xy(0.5 * (UBL_MESH_MAX_X - (UBL_MESH_MIN_X)), 0.5 * (UBL_MESH_MAX_Y - (UBL_MESH_MIN_Y))); + //, min(planner.max_feedrate_mm_s[X_AXIS], planner.max_feedrate_mm_s[Y_AXIS]) / 2.0); + stepper.synchronize(); + + SERIAL_PROTOCOLPGM("Place shim under nozzle"); + LCD_MESSAGEPGM("Place shim & measure"); // TODO: Make translatable string + lcd_return_to_status(); + echo_and_take_a_measurement(); + + const float z1 = measure_point_with_encoder(); + do_blocking_move_to_z(current_position[Z_AXIS] + SIZE_OF_LITTLE_RAISE); + stepper.synchronize(); + + SERIAL_PROTOCOLPGM("Remove shim"); + LCD_MESSAGEPGM("Remove & measure bed"); // TODO: Make translatable string + echo_and_take_a_measurement(); + + const float z2 = measure_point_with_encoder(); + + do_blocking_move_to_z(current_position[Z_AXIS] + Z_CLEARANCE_BETWEEN_PROBES); + + const float thickness = abs(z1 - z2); + + if (g29_verbose_level > 1) { + SERIAL_PROTOCOLPGM("Business Card is "); + SERIAL_PROTOCOL_F(thickness, 4); + SERIAL_PROTOCOLLNPGM("mm thick."); + } + + in_height = current_position[Z_AXIS]; // do manual probing at lower height + + has_control_of_lcd_panel = false; + + restore_ubl_active_state_and_leave(); + + return thickness; + } + + void unified_bed_leveling::manually_probe_remaining_mesh(const float &lx, const float &ly, const float &z_clearance, const float &thick, const bool do_ubl_mesh_map) { + + has_control_of_lcd_panel = true; + + save_ubl_active_state_and_disable(); // we don't do bed level correction because we want the raw data when we probe + do_blocking_move_to_z(Z_CLEARANCE_BETWEEN_PROBES); + do_blocking_move_to_xy(lx, ly); + + lcd_return_to_status(); + + mesh_index_pair location; + do { + location = find_closest_mesh_point_of_type(INVALID, lx, ly, USE_NOZZLE_AS_REFERENCE, NULL, false); + // It doesn't matter if the probe can't reach the NAN location. This is a manual probe. + if (location.x_index < 0 && location.y_index < 0) continue; + + const float rawx = mesh_index_to_xpos(location.x_index), + rawy = mesh_index_to_ypos(location.y_index), + xProbe = LOGICAL_X_POSITION(rawx), + yProbe = LOGICAL_Y_POSITION(rawy); + + if (!position_is_reachable_raw_xy(rawx, rawy)) break; // SHOULD NOT OCCUR (find_closest_mesh_point only returns reachable points) + + do_blocking_move_to_z(Z_CLEARANCE_BETWEEN_PROBES); + + LCD_MESSAGEPGM("Moving to next"); // TODO: Make translatable string + + do_blocking_move_to_xy(xProbe, yProbe); + do_blocking_move_to_z(z_clearance); + + KEEPALIVE_STATE(PAUSED_FOR_USER); + has_control_of_lcd_panel = true; + + if (do_ubl_mesh_map) display_map(g29_map_type); // show user where we're probing + + serialprintPGM(parser.seen('B') ? PSTR("Place shim & measure") : PSTR("Measure")); // TODO: Make translatable strings + + const float z_step = 0.01; // existing behavior: 0.01mm per click, occasionally step + //const float z_step = 1.0 / planner.axis_steps_per_mm[Z_AXIS]; // approx one step each click + + while (ubl_lcd_clicked()) delay(50); // wait for user to release encoder wheel + delay(50); // debounce + while (!ubl_lcd_clicked()) { // we need the loop to move the nozzle based on the encoder wheel here! + idle(); + if (encoder_diff) { + do_blocking_move_to_z(current_position[Z_AXIS] + float(encoder_diff) * z_step); + encoder_diff = 0; + } } - } - z_values[location.x_index][location.y_index] = current_position[Z_AXIS] - thick; - if (g29_verbose_level > 2) { - SERIAL_PROTOCOLPGM("Mesh Point Measured at: "); - SERIAL_PROTOCOL_F(z_values[location.x_index][location.y_index], 6); - SERIAL_EOL; - } - } while (location.x_index >= 0 && location.y_index >= 0); + // this sequence to detect an ubl_lcd_clicked() debounce it and leave if it is + // a Press and Hold is repeated in a lot of places (including G26_Mesh_Validation.cpp). This + // should be redone and compressed. + const millis_t nxt = millis() + 1500L; + while (ubl_lcd_clicked()) { // debounce and watch for abort + idle(); + if (ELAPSED(millis(), nxt)) { + SERIAL_PROTOCOLLNPGM("\nMesh only partially populated."); + do_blocking_move_to_z(Z_CLEARANCE_DEPLOY_PROBE); - if (do_ubl_mesh_map) display_map(g29_map_type); + #if ENABLED(NEWPANEL) + lcd_quick_feedback(); + while (ubl_lcd_clicked()) idle(); + has_control_of_lcd_panel = false; + #endif - restore_ubl_active_state_and_leave(); - KEEPALIVE_STATE(IN_HANDLER); - do_blocking_move_to_z(Z_CLEARANCE_DEPLOY_PROBE); - do_blocking_move_to_xy(lx, ly); - } + KEEPALIVE_STATE(IN_HANDLER); + restore_ubl_active_state_and_leave(); + return; + } + } + + z_values[location.x_index][location.y_index] = current_position[Z_AXIS] - thick; + if (g29_verbose_level > 2) { + SERIAL_PROTOCOLPGM("Mesh Point Measured at: "); + SERIAL_PROTOCOL_F(z_values[location.x_index][location.y_index], 6); + SERIAL_EOL; + } + } while (location.x_index >= 0 && location.y_index >= 0); + + if (do_ubl_mesh_map) display_map(g29_map_type); + + restore_ubl_active_state_and_leave(); + KEEPALIVE_STATE(IN_HANDLER); + do_blocking_move_to_z(Z_CLEARANCE_DEPLOY_PROBE); + do_blocking_move_to_xy(lx, ly); + } + #endif bool unified_bed_leveling::g29_parameter_parsing() { bool err_flag = false; - LCD_MESSAGEPGM("Doing G29 UBL!"); // TODO: Make translatable string - lcd_quick_feedback(); + #if ENABLED(NEWPANEL) + LCD_MESSAGEPGM("Doing G29 UBL!"); // TODO: Make translatable string + lcd_quick_feedback(); + #endif g29_constant = 0.0; g29_repetition_cnt = 0; @@ -1174,8 +1205,12 @@ ubl_state_recursion_chk++; if (ubl_state_recursion_chk != 1) { SERIAL_ECHOLNPGM("save_ubl_active_state_and_disabled() called multiple times in a row."); - LCD_MESSAGEPGM("save_UBL_active() error"); // TODO: Make translatable string - lcd_quick_feedback(); + + #if ENABLED(NEWPANEL) + LCD_MESSAGEPGM("save_UBL_active() error"); // TODO: Make translatable string + lcd_quick_feedback(); + #endif + return; } ubl_state_at_invocation = state.active; @@ -1185,8 +1220,12 @@ void unified_bed_leveling::restore_ubl_active_state_and_leave() { if (--ubl_state_recursion_chk) { SERIAL_ECHOLNPGM("restore_ubl_active_state_and_leave() called too many times."); - LCD_MESSAGEPGM("restore_UBL_active() error"); // TODO: Make translatable string - lcd_quick_feedback(); + + #if ENABLED(NEWPANEL) + LCD_MESSAGEPGM("restore_UBL_active() error"); // TODO: Make translatable string + lcd_quick_feedback(); + #endif + return; } set_bed_leveling_enabled(ubl_state_at_invocation); @@ -1420,114 +1459,116 @@ return out_mesh; } - void unified_bed_leveling::fine_tune_mesh(const float &lx, const float &ly, const bool do_ubl_mesh_map) { - if (!parser.seen('R')) // fine_tune_mesh() is special. If no repetition count flag is specified - g29_repetition_cnt = 1; // do exactly one mesh location. Otherwise use what the parser decided. + #if ENABLED(NEWPANEL) + void unified_bed_leveling::fine_tune_mesh(const float &lx, const float &ly, const bool do_ubl_mesh_map) { + if (!parser.seen('R')) // fine_tune_mesh() is special. If no repetition count flag is specified + g29_repetition_cnt = 1; // do exactly one mesh location. Otherwise use what the parser decided. - mesh_index_pair location; - uint16_t not_done[16]; + mesh_index_pair location; + uint16_t not_done[16]; - if (!position_is_reachable_xy(lx, ly)) { - SERIAL_PROTOCOLLNPGM("(X,Y) outside printable radius."); - return; - } - - save_ubl_active_state_and_disable(); - - memset(not_done, 0xFF, sizeof(not_done)); - - LCD_MESSAGEPGM("Fine Tuning Mesh"); // TODO: Make translatable string - - do_blocking_move_to_z(Z_CLEARANCE_BETWEEN_PROBES); - do_blocking_move_to_xy(lx, ly); - do { - location = find_closest_mesh_point_of_type(SET_IN_BITMAP, lx, ly, USE_NOZZLE_AS_REFERENCE, not_done, false); - - if (location.x_index < 0) break; // stop when we can't find any more reachable points. - - bit_clear(not_done, location.x_index, location.y_index); // Mark this location as 'adjusted' so we will find a - // different location the next time through the loop - - const float rawx = mesh_index_to_xpos(location.x_index), - rawy = mesh_index_to_ypos(location.y_index); - - if (!position_is_reachable_raw_xy(rawx, rawy)) // SHOULD NOT OCCUR because find_closest_mesh_point_of_type will only return reachable - break; - - float new_z = z_values[location.x_index][location.y_index]; - - if (isnan(new_z)) // if the mesh point is invalid, set it to 0.0 so it can be edited - new_z = 0.0; - - do_blocking_move_to_z(Z_CLEARANCE_BETWEEN_PROBES); // Move the nozzle to where we are going to edit - do_blocking_move_to_xy(LOGICAL_X_POSITION(rawx), LOGICAL_Y_POSITION(rawy)); - - new_z = floor(new_z * 1000.0) * 0.001; // Chop off digits after the 1000ths place - - KEEPALIVE_STATE(PAUSED_FOR_USER); - has_control_of_lcd_panel = true; - - if (do_ubl_mesh_map) display_map(g29_map_type); // show the user which point is being adjusted - - lcd_refresh(); - - lcd_mesh_edit_setup(new_z); - - do { - new_z = lcd_mesh_edit(); - #ifdef UBL_MESH_EDIT_MOVES_Z - do_blocking_move_to_z(Z_CLEARANCE_BETWEEN_PROBES + new_z); // Move the nozzle as the point is edited - #endif - idle(); - } while (!ubl_lcd_clicked()); - - lcd_return_to_status(); - - // The technique used here generates a race condition for the encoder click. - // It could get detected in lcd_mesh_edit (actually _lcd_mesh_fine_tune) or here. - // Let's work on specifying a proper API for the LCD ASAP, OK? - has_control_of_lcd_panel = true; - - // this sequence to detect an ubl_lcd_clicked() debounce it and leave if it is - // a Press and Hold is repeated in a lot of places (including G26_Mesh_Validation.cpp). This - // should be redone and compressed. - const millis_t nxt = millis() + 1500UL; - while (ubl_lcd_clicked()) { // debounce and watch for abort - idle(); - if (ELAPSED(millis(), nxt)) { - lcd_return_to_status(); - //SERIAL_PROTOCOLLNPGM("\nFine Tuning of Mesh Stopped."); - do_blocking_move_to_z(Z_CLEARANCE_BETWEEN_PROBES); - LCD_MESSAGEPGM("Mesh Editing Stopped"); // TODO: Make translatable string - - while (ubl_lcd_clicked()) idle(); - - goto FINE_TUNE_EXIT; - } + if (!position_is_reachable_xy(lx, ly)) { + SERIAL_PROTOCOLLNPGM("(X,Y) outside printable radius."); + return; } - safe_delay(20); // We don't want any switch noise. + save_ubl_active_state_and_disable(); - z_values[location.x_index][location.y_index] = new_z; + memset(not_done, 0xFF, sizeof(not_done)); - lcd_refresh(); + LCD_MESSAGEPGM("Fine Tuning Mesh"); // TODO: Make translatable string - } while (location.x_index >= 0 && --g29_repetition_cnt > 0); + do_blocking_move_to_z(Z_CLEARANCE_BETWEEN_PROBES); + do_blocking_move_to_xy(lx, ly); + do { + location = find_closest_mesh_point_of_type(SET_IN_BITMAP, lx, ly, USE_NOZZLE_AS_REFERENCE, not_done, false); - FINE_TUNE_EXIT: + if (location.x_index < 0) break; // stop when we can't find any more reachable points. - has_control_of_lcd_panel = false; - KEEPALIVE_STATE(IN_HANDLER); + bit_clear(not_done, location.x_index, location.y_index); // Mark this location as 'adjusted' so we will find a + // different location the next time through the loop - if (do_ubl_mesh_map) display_map(g29_map_type); - restore_ubl_active_state_and_leave(); - do_blocking_move_to_z(Z_CLEARANCE_BETWEEN_PROBES); + const float rawx = mesh_index_to_xpos(location.x_index), + rawy = mesh_index_to_ypos(location.y_index); - do_blocking_move_to_xy(lx, ly); + if (!position_is_reachable_raw_xy(rawx, rawy)) // SHOULD NOT OCCUR because find_closest_mesh_point_of_type will only return reachable + break; - LCD_MESSAGEPGM("Done Editing Mesh"); // TODO: Make translatable string - SERIAL_ECHOLNPGM("Done Editing Mesh"); - } + float new_z = z_values[location.x_index][location.y_index]; + + if (isnan(new_z)) // if the mesh point is invalid, set it to 0.0 so it can be edited + new_z = 0.0; + + do_blocking_move_to_z(Z_CLEARANCE_BETWEEN_PROBES); // Move the nozzle to where we are going to edit + do_blocking_move_to_xy(LOGICAL_X_POSITION(rawx), LOGICAL_Y_POSITION(rawy)); + + new_z = floor(new_z * 1000.0) * 0.001; // Chop off digits after the 1000ths place + + KEEPALIVE_STATE(PAUSED_FOR_USER); + has_control_of_lcd_panel = true; + + if (do_ubl_mesh_map) display_map(g29_map_type); // show the user which point is being adjusted + + lcd_refresh(); + + lcd_mesh_edit_setup(new_z); + + do { + new_z = lcd_mesh_edit(); + #ifdef UBL_MESH_EDIT_MOVES_Z + do_blocking_move_to_z(Z_CLEARANCE_BETWEEN_PROBES + new_z); // Move the nozzle as the point is edited + #endif + idle(); + } while (!ubl_lcd_clicked()); + + lcd_return_to_status(); + + // The technique used here generates a race condition for the encoder click. + // It could get detected in lcd_mesh_edit (actually _lcd_mesh_fine_tune) or here. + // Let's work on specifying a proper API for the LCD ASAP, OK? + has_control_of_lcd_panel = true; + + // this sequence to detect an ubl_lcd_clicked() debounce it and leave if it is + // a Press and Hold is repeated in a lot of places (including G26_Mesh_Validation.cpp). This + // should be redone and compressed. + const millis_t nxt = millis() + 1500UL; + while (ubl_lcd_clicked()) { // debounce and watch for abort + idle(); + if (ELAPSED(millis(), nxt)) { + lcd_return_to_status(); + //SERIAL_PROTOCOLLNPGM("\nFine Tuning of Mesh Stopped."); + do_blocking_move_to_z(Z_CLEARANCE_BETWEEN_PROBES); + LCD_MESSAGEPGM("Mesh Editing Stopped"); // TODO: Make translatable string + + while (ubl_lcd_clicked()) idle(); + + goto FINE_TUNE_EXIT; + } + } + + safe_delay(20); // We don't want any switch noise. + + z_values[location.x_index][location.y_index] = new_z; + + lcd_refresh(); + + } while (location.x_index >= 0 && --g29_repetition_cnt > 0); + + FINE_TUNE_EXIT: + + has_control_of_lcd_panel = false; + KEEPALIVE_STATE(IN_HANDLER); + + if (do_ubl_mesh_map) display_map(g29_map_type); + restore_ubl_active_state_and_leave(); + do_blocking_move_to_z(Z_CLEARANCE_BETWEEN_PROBES); + + do_blocking_move_to_xy(lx, ly); + + LCD_MESSAGEPGM("Done Editing Mesh"); // TODO: Make translatable string + SERIAL_ECHOLNPGM("Done Editing Mesh"); + } + #endif /** * 'Smart Fill': Scan from the outward edges of the mesh towards the center. From 8db1197c9b04df54b877883c661b3b19b136bb1b Mon Sep 17 00:00:00 2001 From: bgort Date: Wed, 7 Jun 2017 02:36:34 -0400 Subject: [PATCH 009/180] Enable extended capabilities report by default (#6969) Ref #5139 --- Marlin/Configuration_adv.h | 2 +- Marlin/example_configurations/Cartesio/Configuration_adv.h | 2 +- Marlin/example_configurations/Felix/Configuration_adv.h | 2 +- .../FolgerTech-i3-2020/Configuration_adv.h | 2 +- Marlin/example_configurations/Hephestos/Configuration_adv.h | 2 +- Marlin/example_configurations/Hephestos_2/Configuration_adv.h | 2 +- Marlin/example_configurations/K8200/Configuration_adv.h | 2 +- Marlin/example_configurations/K8400/Configuration_adv.h | 2 +- Marlin/example_configurations/M150/Configuration_adv.h | 2 +- Marlin/example_configurations/RigidBot/Configuration_adv.h | 2 +- Marlin/example_configurations/SCARA/Configuration_adv.h | 2 +- Marlin/example_configurations/TAZ4/Configuration_adv.h | 2 +- Marlin/example_configurations/WITBOX/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 +- 23 files changed, 23 insertions(+), 23 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 16865c4878..2665bddb6f 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1206,7 +1206,7 @@ /** * Include capabilities in M115 output */ -//#define EXTENDED_CAPABILITIES_REPORT +#define EXTENDED_CAPABILITIES_REPORT /** * Volumetric extrusion default state diff --git a/Marlin/example_configurations/Cartesio/Configuration_adv.h b/Marlin/example_configurations/Cartesio/Configuration_adv.h index 36d2a43667..42183ac74d 100644 --- a/Marlin/example_configurations/Cartesio/Configuration_adv.h +++ b/Marlin/example_configurations/Cartesio/Configuration_adv.h @@ -1197,7 +1197,7 @@ /** * Include capabilities in M115 output */ -//#define EXTENDED_CAPABILITIES_REPORT +#define EXTENDED_CAPABILITIES_REPORT /** * Volumetric extrusion default state diff --git a/Marlin/example_configurations/Felix/Configuration_adv.h b/Marlin/example_configurations/Felix/Configuration_adv.h index 8a09f18c05..28368b4280 100644 --- a/Marlin/example_configurations/Felix/Configuration_adv.h +++ b/Marlin/example_configurations/Felix/Configuration_adv.h @@ -1197,7 +1197,7 @@ /** * Include capabilities in M115 output */ -//#define EXTENDED_CAPABILITIES_REPORT +#define EXTENDED_CAPABILITIES_REPORT /** * Volumetric extrusion default state diff --git a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h index e1579fcb5e..5cee9c6a71 100644 --- a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h +++ b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h @@ -1210,7 +1210,7 @@ /** * Include capabilities in M115 output */ -//#define EXTENDED_CAPABILITIES_REPORT +#define EXTENDED_CAPABILITIES_REPORT /** * Volumetric extrusion default state diff --git a/Marlin/example_configurations/Hephestos/Configuration_adv.h b/Marlin/example_configurations/Hephestos/Configuration_adv.h index de751085a4..52da5bfb49 100644 --- a/Marlin/example_configurations/Hephestos/Configuration_adv.h +++ b/Marlin/example_configurations/Hephestos/Configuration_adv.h @@ -1197,7 +1197,7 @@ /** * Include capabilities in M115 output */ -//#define EXTENDED_CAPABILITIES_REPORT +#define EXTENDED_CAPABILITIES_REPORT /** * Volumetric extrusion default state diff --git a/Marlin/example_configurations/Hephestos_2/Configuration_adv.h b/Marlin/example_configurations/Hephestos_2/Configuration_adv.h index 09e91b5d8e..144f2e829f 100644 --- a/Marlin/example_configurations/Hephestos_2/Configuration_adv.h +++ b/Marlin/example_configurations/Hephestos_2/Configuration_adv.h @@ -1181,7 +1181,7 @@ /** * Include capabilities in M115 output */ -//#define EXTENDED_CAPABILITIES_REPORT +#define EXTENDED_CAPABILITIES_REPORT /** * Volumetric extrusion default state diff --git a/Marlin/example_configurations/K8200/Configuration_adv.h b/Marlin/example_configurations/K8200/Configuration_adv.h index ddb7404863..894cc2c0b4 100644 --- a/Marlin/example_configurations/K8200/Configuration_adv.h +++ b/Marlin/example_configurations/K8200/Configuration_adv.h @@ -1210,7 +1210,7 @@ /** * Include capabilities in M115 output */ -//#define EXTENDED_CAPABILITIES_REPORT +#define EXTENDED_CAPABILITIES_REPORT /** * Volumetric extrusion default state diff --git a/Marlin/example_configurations/K8400/Configuration_adv.h b/Marlin/example_configurations/K8400/Configuration_adv.h index a529888051..0a6208ab4c 100644 --- a/Marlin/example_configurations/K8400/Configuration_adv.h +++ b/Marlin/example_configurations/K8400/Configuration_adv.h @@ -1197,7 +1197,7 @@ /** * Include capabilities in M115 output */ -//#define EXTENDED_CAPABILITIES_REPORT +#define EXTENDED_CAPABILITIES_REPORT /** * Volumetric extrusion default state diff --git a/Marlin/example_configurations/M150/Configuration_adv.h b/Marlin/example_configurations/M150/Configuration_adv.h index 3962f2d40e..5c46854c28 100644 --- a/Marlin/example_configurations/M150/Configuration_adv.h +++ b/Marlin/example_configurations/M150/Configuration_adv.h @@ -1204,7 +1204,7 @@ /** * Include capabilities in M115 output */ -//#define EXTENDED_CAPABILITIES_REPORT +#define EXTENDED_CAPABILITIES_REPORT /** * Volumetric extrusion default state diff --git a/Marlin/example_configurations/RigidBot/Configuration_adv.h b/Marlin/example_configurations/RigidBot/Configuration_adv.h index f939c4d2c7..f973a648a7 100644 --- a/Marlin/example_configurations/RigidBot/Configuration_adv.h +++ b/Marlin/example_configurations/RigidBot/Configuration_adv.h @@ -1197,7 +1197,7 @@ /** * Include capabilities in M115 output */ -//#define EXTENDED_CAPABILITIES_REPORT +#define EXTENDED_CAPABILITIES_REPORT /** * Volumetric extrusion default state diff --git a/Marlin/example_configurations/SCARA/Configuration_adv.h b/Marlin/example_configurations/SCARA/Configuration_adv.h index 7fe55a0b78..d3fab11d2e 100644 --- a/Marlin/example_configurations/SCARA/Configuration_adv.h +++ b/Marlin/example_configurations/SCARA/Configuration_adv.h @@ -1197,7 +1197,7 @@ /** * Include capabilities in M115 output */ -//#define EXTENDED_CAPABILITIES_REPORT +#define EXTENDED_CAPABILITIES_REPORT /** * Volumetric extrusion default state diff --git a/Marlin/example_configurations/TAZ4/Configuration_adv.h b/Marlin/example_configurations/TAZ4/Configuration_adv.h index 5ee685360f..72a6b1d8bc 100644 --- a/Marlin/example_configurations/TAZ4/Configuration_adv.h +++ b/Marlin/example_configurations/TAZ4/Configuration_adv.h @@ -1197,7 +1197,7 @@ /** * Include capabilities in M115 output */ -//#define EXTENDED_CAPABILITIES_REPORT +#define EXTENDED_CAPABILITIES_REPORT /** * Volumetric extrusion default state diff --git a/Marlin/example_configurations/WITBOX/Configuration_adv.h b/Marlin/example_configurations/WITBOX/Configuration_adv.h index de751085a4..52da5bfb49 100644 --- a/Marlin/example_configurations/WITBOX/Configuration_adv.h +++ b/Marlin/example_configurations/WITBOX/Configuration_adv.h @@ -1197,7 +1197,7 @@ /** * Include capabilities in M115 output */ -//#define EXTENDED_CAPABILITIES_REPORT +#define EXTENDED_CAPABILITIES_REPORT /** * Volumetric extrusion default state 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 51f95e1f27..7782959a89 100644 --- a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h +++ b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h @@ -1202,7 +1202,7 @@ /** * Include capabilities in M115 output */ -//#define EXTENDED_CAPABILITIES_REPORT +#define EXTENDED_CAPABILITIES_REPORT /** * Volumetric extrusion default state 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 c9dc15e7a2..392cde7c6b 100644 --- a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h +++ b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h @@ -1201,7 +1201,7 @@ /** * Include capabilities in M115 output */ -//#define EXTENDED_CAPABILITIES_REPORT +#define EXTENDED_CAPABILITIES_REPORT /** * Volumetric extrusion default state diff --git a/Marlin/example_configurations/delta/generic/Configuration_adv.h b/Marlin/example_configurations/delta/generic/Configuration_adv.h index 334fba863b..7565ac8652 100644 --- a/Marlin/example_configurations/delta/generic/Configuration_adv.h +++ b/Marlin/example_configurations/delta/generic/Configuration_adv.h @@ -1199,7 +1199,7 @@ /** * Include capabilities in M115 output */ -//#define EXTENDED_CAPABILITIES_REPORT +#define EXTENDED_CAPABILITIES_REPORT /** * Volumetric extrusion default state diff --git a/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h index 334fba863b..7565ac8652 100644 --- a/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h @@ -1199,7 +1199,7 @@ /** * Include capabilities in M115 output */ -//#define EXTENDED_CAPABILITIES_REPORT +#define EXTENDED_CAPABILITIES_REPORT /** * Volumetric extrusion default state diff --git a/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h index d46820b121..d15fcff5bf 100644 --- a/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h @@ -1204,7 +1204,7 @@ /** * Include capabilities in M115 output */ -//#define EXTENDED_CAPABILITIES_REPORT +#define EXTENDED_CAPABILITIES_REPORT /** * Volumetric extrusion default state diff --git a/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h index 6440d1611d..173d6f986e 100644 --- a/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h @@ -1199,7 +1199,7 @@ /** * Include capabilities in M115 output */ -//#define EXTENDED_CAPABILITIES_REPORT +#define EXTENDED_CAPABILITIES_REPORT /** * Volumetric extrusion default state diff --git a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration_adv.h b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration_adv.h index d5082fdb8b..11857e0759 100644 --- a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration_adv.h +++ b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration_adv.h @@ -1206,7 +1206,7 @@ /** * Include capabilities in M115 output */ -//#define EXTENDED_CAPABILITIES_REPORT +#define EXTENDED_CAPABILITIES_REPORT /** * Volumetric extrusion default state diff --git a/Marlin/example_configurations/makibox/Configuration_adv.h b/Marlin/example_configurations/makibox/Configuration_adv.h index 026e2443a8..31e2d891fe 100644 --- a/Marlin/example_configurations/makibox/Configuration_adv.h +++ b/Marlin/example_configurations/makibox/Configuration_adv.h @@ -1197,7 +1197,7 @@ /** * Include capabilities in M115 output */ -//#define EXTENDED_CAPABILITIES_REPORT +#define EXTENDED_CAPABILITIES_REPORT /** * Volumetric extrusion default state diff --git a/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h b/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h index 249166ca10..6e0ce6e9e0 100644 --- a/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h +++ b/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h @@ -1197,7 +1197,7 @@ /** * Include capabilities in M115 output */ -//#define EXTENDED_CAPABILITIES_REPORT +#define EXTENDED_CAPABILITIES_REPORT /** * Volumetric extrusion default state diff --git a/Marlin/example_configurations/wt150/Configuration_adv.h b/Marlin/example_configurations/wt150/Configuration_adv.h index 245eeee210..b8dee77729 100644 --- a/Marlin/example_configurations/wt150/Configuration_adv.h +++ b/Marlin/example_configurations/wt150/Configuration_adv.h @@ -1200,7 +1200,7 @@ /** * Include capabilities in M115 output */ -//#define EXTENDED_CAPABILITIES_REPORT +#define EXTENDED_CAPABILITIES_REPORT /** * Volumetric extrusion default state From dd071a4a65708651ea890b15cc30c2c0dbb1e177 Mon Sep 17 00:00:00 2001 From: Brian Date: Wed, 7 Jun 2017 02:52:35 -0400 Subject: [PATCH 010/180] Enable AUTO_REPORT_TEMPERATURES by default --- Marlin/Configuration_adv.h | 2 +- Marlin/example_configurations/Cartesio/Configuration_adv.h | 2 +- Marlin/example_configurations/Felix/Configuration_adv.h | 2 +- .../FolgerTech-i3-2020/Configuration_adv.h | 2 +- Marlin/example_configurations/Hephestos/Configuration_adv.h | 2 +- Marlin/example_configurations/Hephestos_2/Configuration_adv.h | 2 +- Marlin/example_configurations/K8200/Configuration_adv.h | 2 +- Marlin/example_configurations/K8400/Configuration_adv.h | 2 +- Marlin/example_configurations/M150/Configuration_adv.h | 2 +- Marlin/example_configurations/RigidBot/Configuration_adv.h | 2 +- Marlin/example_configurations/SCARA/Configuration_adv.h | 2 +- Marlin/example_configurations/TAZ4/Configuration_adv.h | 2 +- Marlin/example_configurations/WITBOX/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 +- 23 files changed, 23 insertions(+), 23 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 2665bddb6f..d61851fc88 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1201,7 +1201,7 @@ /** * Auto-report temperatures with M155 S */ -//#define AUTO_REPORT_TEMPERATURES +#define AUTO_REPORT_TEMPERATURES /** * Include capabilities in M115 output diff --git a/Marlin/example_configurations/Cartesio/Configuration_adv.h b/Marlin/example_configurations/Cartesio/Configuration_adv.h index 42183ac74d..4007be0c88 100644 --- a/Marlin/example_configurations/Cartesio/Configuration_adv.h +++ b/Marlin/example_configurations/Cartesio/Configuration_adv.h @@ -1192,7 +1192,7 @@ /** * Auto-report temperatures with M155 S */ -//#define AUTO_REPORT_TEMPERATURES +#define AUTO_REPORT_TEMPERATURES /** * Include capabilities in M115 output diff --git a/Marlin/example_configurations/Felix/Configuration_adv.h b/Marlin/example_configurations/Felix/Configuration_adv.h index 28368b4280..da3d230faf 100644 --- a/Marlin/example_configurations/Felix/Configuration_adv.h +++ b/Marlin/example_configurations/Felix/Configuration_adv.h @@ -1192,7 +1192,7 @@ /** * Auto-report temperatures with M155 S */ -//#define AUTO_REPORT_TEMPERATURES +#define AUTO_REPORT_TEMPERATURES /** * Include capabilities in M115 output diff --git a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h index 5cee9c6a71..0827d3b078 100644 --- a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h +++ b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h @@ -1205,7 +1205,7 @@ /** * Auto-report temperatures with M155 S */ -//#define AUTO_REPORT_TEMPERATURES +#define AUTO_REPORT_TEMPERATURES /** * Include capabilities in M115 output diff --git a/Marlin/example_configurations/Hephestos/Configuration_adv.h b/Marlin/example_configurations/Hephestos/Configuration_adv.h index 52da5bfb49..349d7167ac 100644 --- a/Marlin/example_configurations/Hephestos/Configuration_adv.h +++ b/Marlin/example_configurations/Hephestos/Configuration_adv.h @@ -1192,7 +1192,7 @@ /** * Auto-report temperatures with M155 S */ -//#define AUTO_REPORT_TEMPERATURES +#define AUTO_REPORT_TEMPERATURES /** * Include capabilities in M115 output diff --git a/Marlin/example_configurations/Hephestos_2/Configuration_adv.h b/Marlin/example_configurations/Hephestos_2/Configuration_adv.h index 144f2e829f..ffcc13d3cb 100644 --- a/Marlin/example_configurations/Hephestos_2/Configuration_adv.h +++ b/Marlin/example_configurations/Hephestos_2/Configuration_adv.h @@ -1176,7 +1176,7 @@ /** * Auto-report temperatures with M155 S */ -//#define AUTO_REPORT_TEMPERATURES +#define AUTO_REPORT_TEMPERATURES /** * Include capabilities in M115 output diff --git a/Marlin/example_configurations/K8200/Configuration_adv.h b/Marlin/example_configurations/K8200/Configuration_adv.h index 894cc2c0b4..2867aeebbf 100644 --- a/Marlin/example_configurations/K8200/Configuration_adv.h +++ b/Marlin/example_configurations/K8200/Configuration_adv.h @@ -1205,7 +1205,7 @@ /** * Auto-report temperatures with M155 S */ -//#define AUTO_REPORT_TEMPERATURES +#define AUTO_REPORT_TEMPERATURES /** * Include capabilities in M115 output diff --git a/Marlin/example_configurations/K8400/Configuration_adv.h b/Marlin/example_configurations/K8400/Configuration_adv.h index 0a6208ab4c..76e1b03f81 100644 --- a/Marlin/example_configurations/K8400/Configuration_adv.h +++ b/Marlin/example_configurations/K8400/Configuration_adv.h @@ -1192,7 +1192,7 @@ /** * Auto-report temperatures with M155 S */ -//#define AUTO_REPORT_TEMPERATURES +#define AUTO_REPORT_TEMPERATURES /** * Include capabilities in M115 output diff --git a/Marlin/example_configurations/M150/Configuration_adv.h b/Marlin/example_configurations/M150/Configuration_adv.h index 5c46854c28..4877231b7c 100644 --- a/Marlin/example_configurations/M150/Configuration_adv.h +++ b/Marlin/example_configurations/M150/Configuration_adv.h @@ -1199,7 +1199,7 @@ /** * Auto-report temperatures with M155 S */ -//#define AUTO_REPORT_TEMPERATURES +#define AUTO_REPORT_TEMPERATURES /** * Include capabilities in M115 output diff --git a/Marlin/example_configurations/RigidBot/Configuration_adv.h b/Marlin/example_configurations/RigidBot/Configuration_adv.h index f973a648a7..745166ff87 100644 --- a/Marlin/example_configurations/RigidBot/Configuration_adv.h +++ b/Marlin/example_configurations/RigidBot/Configuration_adv.h @@ -1192,7 +1192,7 @@ /** * Auto-report temperatures with M155 S */ -//#define AUTO_REPORT_TEMPERATURES +#define AUTO_REPORT_TEMPERATURES /** * Include capabilities in M115 output diff --git a/Marlin/example_configurations/SCARA/Configuration_adv.h b/Marlin/example_configurations/SCARA/Configuration_adv.h index d3fab11d2e..46b888d814 100644 --- a/Marlin/example_configurations/SCARA/Configuration_adv.h +++ b/Marlin/example_configurations/SCARA/Configuration_adv.h @@ -1192,7 +1192,7 @@ /** * Auto-report temperatures with M155 S */ -//#define AUTO_REPORT_TEMPERATURES +#define AUTO_REPORT_TEMPERATURES /** * Include capabilities in M115 output diff --git a/Marlin/example_configurations/TAZ4/Configuration_adv.h b/Marlin/example_configurations/TAZ4/Configuration_adv.h index 72a6b1d8bc..04ae9af6f7 100644 --- a/Marlin/example_configurations/TAZ4/Configuration_adv.h +++ b/Marlin/example_configurations/TAZ4/Configuration_adv.h @@ -1192,7 +1192,7 @@ /** * Auto-report temperatures with M155 S */ -//#define AUTO_REPORT_TEMPERATURES +#define AUTO_REPORT_TEMPERATURES /** * Include capabilities in M115 output diff --git a/Marlin/example_configurations/WITBOX/Configuration_adv.h b/Marlin/example_configurations/WITBOX/Configuration_adv.h index 52da5bfb49..349d7167ac 100644 --- a/Marlin/example_configurations/WITBOX/Configuration_adv.h +++ b/Marlin/example_configurations/WITBOX/Configuration_adv.h @@ -1192,7 +1192,7 @@ /** * Auto-report temperatures with M155 S */ -//#define AUTO_REPORT_TEMPERATURES +#define AUTO_REPORT_TEMPERATURES /** * Include capabilities in M115 output 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 7782959a89..1c940ffffe 100644 --- a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h +++ b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h @@ -1197,7 +1197,7 @@ /** * Auto-report temperatures with M155 S */ -//#define AUTO_REPORT_TEMPERATURES +#define AUTO_REPORT_TEMPERATURES /** * Include capabilities in M115 output 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 392cde7c6b..24d99106ae 100644 --- a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h +++ b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h @@ -1196,7 +1196,7 @@ /** * Auto-report temperatures with M155 S */ -//#define AUTO_REPORT_TEMPERATURES +#define AUTO_REPORT_TEMPERATURES /** * Include capabilities in M115 output diff --git a/Marlin/example_configurations/delta/generic/Configuration_adv.h b/Marlin/example_configurations/delta/generic/Configuration_adv.h index 7565ac8652..f3f0694fe9 100644 --- a/Marlin/example_configurations/delta/generic/Configuration_adv.h +++ b/Marlin/example_configurations/delta/generic/Configuration_adv.h @@ -1194,7 +1194,7 @@ /** * Auto-report temperatures with M155 S */ -//#define AUTO_REPORT_TEMPERATURES +#define AUTO_REPORT_TEMPERATURES /** * Include capabilities in M115 output diff --git a/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h index 7565ac8652..f3f0694fe9 100644 --- a/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h @@ -1194,7 +1194,7 @@ /** * Auto-report temperatures with M155 S */ -//#define AUTO_REPORT_TEMPERATURES +#define AUTO_REPORT_TEMPERATURES /** * Include capabilities in M115 output diff --git a/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h index d15fcff5bf..9b258acf03 100644 --- a/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h @@ -1199,7 +1199,7 @@ /** * Auto-report temperatures with M155 S */ -//#define AUTO_REPORT_TEMPERATURES +#define AUTO_REPORT_TEMPERATURES /** * Include capabilities in M115 output diff --git a/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h index 173d6f986e..ccc7fcb61e 100644 --- a/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h @@ -1194,7 +1194,7 @@ /** * Auto-report temperatures with M155 S */ -//#define AUTO_REPORT_TEMPERATURES +#define AUTO_REPORT_TEMPERATURES /** * Include capabilities in M115 output diff --git a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration_adv.h b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration_adv.h index 11857e0759..71053244bc 100644 --- a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration_adv.h +++ b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration_adv.h @@ -1201,7 +1201,7 @@ /** * Auto-report temperatures with M155 S */ -//#define AUTO_REPORT_TEMPERATURES +#define AUTO_REPORT_TEMPERATURES /** * Include capabilities in M115 output diff --git a/Marlin/example_configurations/makibox/Configuration_adv.h b/Marlin/example_configurations/makibox/Configuration_adv.h index 31e2d891fe..e91d4ea72e 100644 --- a/Marlin/example_configurations/makibox/Configuration_adv.h +++ b/Marlin/example_configurations/makibox/Configuration_adv.h @@ -1192,7 +1192,7 @@ /** * Auto-report temperatures with M155 S */ -//#define AUTO_REPORT_TEMPERATURES +#define AUTO_REPORT_TEMPERATURES /** * Include capabilities in M115 output diff --git a/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h b/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h index 6e0ce6e9e0..643c6945a1 100644 --- a/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h +++ b/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h @@ -1192,7 +1192,7 @@ /** * Auto-report temperatures with M155 S */ -//#define AUTO_REPORT_TEMPERATURES +#define AUTO_REPORT_TEMPERATURES /** * Include capabilities in M115 output diff --git a/Marlin/example_configurations/wt150/Configuration_adv.h b/Marlin/example_configurations/wt150/Configuration_adv.h index b8dee77729..9f9cafc998 100644 --- a/Marlin/example_configurations/wt150/Configuration_adv.h +++ b/Marlin/example_configurations/wt150/Configuration_adv.h @@ -1195,7 +1195,7 @@ /** * Auto-report temperatures with M155 S */ -//#define AUTO_REPORT_TEMPERATURES +#define AUTO_REPORT_TEMPERATURES /** * Include capabilities in M115 output From b88957e0d4e9137c0352aa5def824574f1f05373 Mon Sep 17 00:00:00 2001 From: Tannoo Date: Wed, 7 Jun 2017 06:28:33 -0600 Subject: [PATCH 011/180] Leveling type in About Printer Show the Leveling system in use on the About Printer screen. --- Marlin/language_en.h | 15 +++++++++++++++ Marlin/ultralcd.cpp | 11 +++++++++++ 2 files changed, 26 insertions(+) diff --git a/Marlin/language_en.h b/Marlin/language_en.h index 6f79272d7d..654cfedf6e 100644 --- a/Marlin/language_en.h +++ b/Marlin/language_en.h @@ -688,6 +688,21 @@ #ifndef MSG_INFO_PRINTER_MENU #define MSG_INFO_PRINTER_MENU _UxGT("Printer Info") #endif +#ifndef MSG_3POINT_LEVELING + #define MSG_3POINT_LEVELING _UxGT("3-Point Leveling") +#endif +#ifndef MSG_LINEAR_LEVELING + #define MSG_LINEAR_LEVELING _UxGT("Linear Leveling") +#endif +#ifndef MSG_BILINEAR_LEVELING + #define MSG_BILINEAR_LEVELING _UxGT("Bilinear Leveling") +#endif +#ifndef MSG_UBL_LEVELING + #define MSG_UBL_LEVELING _UxGT("Unified Bed Leveling") +#endif +#ifndef MSG_MESH_LEVELING + #define MSG_MESH_LEVELING _UxGT("Mesh Leveling") +#endif #ifndef MSG_INFO_STATS_MENU #define MSG_INFO_STATS_MENU _UxGT("Printer Stats") #endif diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index 5b519493de..4dd267a564 100755 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -3356,6 +3356,17 @@ void kill_screen(const char* lcd_msg) { STATIC_ITEM(MACHINE_NAME, true); // My3DPrinter STATIC_ITEM(WEBSITE_URL, true); // www.my3dprinter.com STATIC_ITEM(MSG_INFO_EXTRUDERS ": " STRINGIFY(EXTRUDERS), true); // Extruders: 2 + #if ENABLED(AUTO_BED_LEVELING_3POINT) + STATIC_ITEM(MSG_3POINT_LEVELING, true); // 3-Point Leveling + #elif ENABLED(AUTO_BED_LEVELING_LINEAR) + STATIC_ITEM(MSG_LINEAR_LEVELING, true); // Linear Leveling + #elif ENABLED(AUTO_BED_LEVELING_BILINEAR) + STATIC_ITEM(MSG_BILINEAR_LEVELING, true); // Bi-linear Leveling + #elif ENABLED(AUTO_BED_LEVELING_UBL) + STATIC_ITEM(MSG_UBL_LEVELING, true); // Unified Bed Leveling + #elif ENABLED(MESH_BED_LEVELING) + STATIC_ITEM(MSG_MESH_LEVELING, true); // Mesh Leveling + #endif END_SCREEN(); } From 5d5ff36446a65630078a807a28475cf328a8a7d1 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 7 Jun 2017 10:21:34 -0500 Subject: [PATCH 012/180] Fix a compile error with _lcd_set_z_fade_height --- Marlin/ultralcd.cpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index 5b519493de..1512cd893b 100755 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -1731,7 +1731,10 @@ void kill_screen(const char* lcd_msg) { static bool _level_state; void _lcd_toggle_bed_leveling() { set_bed_leveling_enabled(_level_state); } - void _lcd_set_z_fade_height() { set_z_fade_height(planner.z_fade_height); } + + #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) + void _lcd_set_z_fade_height() { set_z_fade_height(planner.z_fade_height); } + #endif /** * Step 1: Bed Level entry-point From d28f5d8a78bcabbba725a33ecddc183389f1d108 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 6 Jun 2017 04:01:54 -0500 Subject: [PATCH 013/180] Fix: z_endstop_adj is never initialized --- Marlin/configuration_store.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/configuration_store.cpp b/Marlin/configuration_store.cpp index 0cef5c52a4..f1c1b82e2b 100644 --- a/Marlin/configuration_store.cpp +++ b/Marlin/configuration_store.cpp @@ -1192,7 +1192,7 @@ void MarlinSettings::reset() { #elif ENABLED(Z_DUAL_ENDSTOPS) - float z_endstop_adj = + z_endstop_adj = #ifdef Z_DUAL_ENDSTOPS_ADJUSTMENT Z_DUAL_ENDSTOPS_ADJUSTMENT #else From 19b62c14f034a39256fa7edddc5415e6c497420e Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 7 Jun 2017 09:53:34 -0500 Subject: [PATCH 014/180] Add a script so Travis can test for intentional failure --- buildroot/bin/build_marlin_fail | 7 +++++++ 1 file changed, 7 insertions(+) create mode 100755 buildroot/bin/build_marlin_fail diff --git a/buildroot/bin/build_marlin_fail b/buildroot/bin/build_marlin_fail new file mode 100755 index 0000000000..506426ebea --- /dev/null +++ b/buildroot/bin/build_marlin_fail @@ -0,0 +1,7 @@ +#!/usr/bin/env bash + +if arduino --verify --board arduino:avr:mega:cpu=atmega2560 Marlin/Marlin.ino ; then + return 1 +else + return 0 +fi From 4406fba9942f682dd59c8d96188ce5f48d31d980 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 7 Jun 2017 11:14:30 -0500 Subject: [PATCH 015/180] Fixes #6975 --- Marlin/Marlin_main.cpp | 13 ++++++------- 1 file changed, 6 insertions(+), 7 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index d88286c4df..1717026b3f 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -7918,20 +7918,19 @@ inline void gcode_M121() { endstops.enable_globally(false); } #ifdef PAUSE_PARK_X_POS + PAUSE_PARK_X_POS #endif + #if HOTENDS > 1 && DISABLED(DUAL_X_CARRIAGE) + + (active_extruder ? hotend_offset[X_AXIS][active_extruder] : 0) + #endif ; const float y_pos = parser.seen('Y') ? parser.value_linear_units() : 0 #ifdef PAUSE_PARK_Y_POS + PAUSE_PARK_Y_POS #endif + #if HOTENDS > 1 && DISABLED(DUAL_X_CARRIAGE) + + (active_extruder ? hotend_offset[Y_AXIS][active_extruder] : 0) + #endif ; - #if HOTENDS > 1 && DISABLED(DUAL_X_CARRIAGE) - if (active_extruder > 0) { - if (!parser.seen('X')) x_pos += hotend_offset[X_AXIS][active_extruder]; - if (!parser.seen('Y')) y_pos += hotend_offset[Y_AXIS][active_extruder]; - } - #endif - const bool job_running = print_job_timer.isRunning(); if (pause_print(retract, z_lift, x_pos, y_pos)) { From efc198f952a54323dbcb4d0c480d6fa9a64edb9b Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 5 Jun 2017 17:41:38 -0500 Subject: [PATCH 016/180] Spacing, const, comments --- Marlin/Conditionals_LCD.h | 2 +- Marlin/Configuration_adv.h | 12 ++--- Marlin/Marlin_main.cpp | 88 ++++++++++++---------------------- Marlin/buzzer.h | 2 +- Marlin/configuration_store.cpp | 8 ++-- Marlin/temperature.cpp | 2 +- Marlin/ultralcd_impl_HD44780.h | 63 ++++++++++++------------ 7 files changed, 73 insertions(+), 104 deletions(-) diff --git a/Marlin/Conditionals_LCD.h b/Marlin/Conditionals_LCD.h index 3c39512a93..b33499e6bf 100644 --- a/Marlin/Conditionals_LCD.h +++ b/Marlin/Conditionals_LCD.h @@ -243,7 +243,7 @@ /* Custom characters defined in the first 8 characters of the LCD */ #define LCD_BEDTEMP_CHAR 0x00 // Print only as a char. This will have 'unexpected' results when used in a string! #define LCD_DEGREE_CHAR 0x01 - #define LCD_STR_THERMOMETER "\x02" // Too many places use preprocessor string concatination to change this to a char right now. + #define LCD_STR_THERMOMETER "\x02" // Still used with string concatenation #define LCD_UPLEVEL_CHAR 0x03 #define LCD_REFRESH_CHAR 0x04 #define LCD_STR_FOLDER "\x05" diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 2665bddb6f..0db274d13b 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -225,13 +225,11 @@ */ //#define CASE_LIGHT_ENABLE #if ENABLED(CASE_LIGHT_ENABLE) - #define CASE_LIGHT_PIN 4 // can be defined here or in the pins_XXX.h file for your board - // pins_XXX.h file overrides this one - #define INVERT_CASE_LIGHT false // set to true if case light is ON when pin is at 0 - #define CASE_LIGHT_DEFAULT_ON true // set default power up state to on or off - #define CASE_LIGHT_DEFAULT_BRIGHTNESS 105 // set power up brightness 0-255 ( only used if on PWM - // and if CASE_LIGHT_DEFAULT is set to on - //#define MENU_ITEM_CASE_LIGHT // Uncomment to have a Case Light entry in main menu + //#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 //=========================================================================== diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 1717026b3f..c4866d89a5 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -458,7 +458,7 @@ volatile bool wait_for_heatup = true; volatile bool wait_for_user = false; #endif -const char axis_codes[XYZE] = {'X', 'Y', 'Z', 'E'}; +const char axis_codes[XYZE] = { 'X', 'Y', 'Z', 'E' }; // Number of characters read in the current line of serial input static int serial_count = 0; @@ -1394,7 +1394,7 @@ bool get_target_extruder_from_command(int code) { * * Callers must sync the planner position after calling this! */ -static void set_axis_is_at_home(AxisEnum axis) { +static void set_axis_is_at_home(const AxisEnum axis) { #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) { SERIAL_ECHOPAIR(">>> set_axis_is_at_home(", axis_codes[axis]); @@ -1496,7 +1496,7 @@ static void set_axis_is_at_home(AxisEnum axis) { /** * Some planner shorthand inline functions */ -inline float get_homing_bump_feedrate(AxisEnum axis) { +inline float get_homing_bump_feedrate(const AxisEnum axis) { int constexpr homing_bump_divisor[] = HOMING_BUMP_DIVISOR; int hbd = homing_bump_divisor[axis]; if (hbd < 1) { @@ -1507,20 +1507,19 @@ inline float get_homing_bump_feedrate(AxisEnum axis) { return homing_feedrate_mm_s[axis] / hbd; } -// -// line_to_current_position -// Move the planner to the current position from wherever it last moved -// (or from wherever it has been told it is located). -// +/** + * Move the planner to the current position from wherever it last moved + * (or from wherever it has been told it is located). + */ inline void line_to_current_position() { planner.buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], feedrate_mm_s, active_extruder); } -// -// line_to_destination -// Move the planner, not necessarily synced with current_position -// -inline void line_to_destination(float fr_mm_s) { +/** + * Move the planner to the position stored in the destination array, which is + * used by G0/G1/G2/G3/G5 and many other functions to set a destination. + */ +inline void line_to_destination(const float fr_mm_s) { planner.buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], fr_mm_s, active_extruder); } inline void line_to_destination() { line_to_destination(feedrate_mm_s); } @@ -2751,7 +2750,7 @@ static void clean_up_after_endstop_or_probe_move() { /** * Home an individual linear axis */ -static void do_homing_move(const AxisEnum axis, float distance, float fr_mm_s=0.0) { +static void do_homing_move(const AxisEnum axis, const float distance, const float fr_mm_s=0.0) { #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) { @@ -4907,7 +4906,7 @@ void home_all_axes() { gcode_G28(true); } if ( NEAR(current_position[X_AXIS], xProbe - (X_PROBE_OFFSET_FROM_EXTRUDER)) && NEAR(current_position[Y_AXIS], yProbe - (Y_PROBE_OFFSET_FROM_EXTRUDER)) ) { - float simple_z = current_position[Z_AXIS] - measured_z; + 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); @@ -7667,45 +7666,32 @@ void report_current_position() { #ifdef M114_DETAIL - static const char axis_char[XYZE] = {'X','Y','Z','E'}; - - void report_xyze(const float pos[XYZE], uint8_t n = 4, uint8_t precision = 3) { + void report_xyze(const float pos[XYZE], const uint8_t n = 4, const uint8_t precision = 3) { char str[12]; - for(uint8_t i=0; itick(); thermalManager.manage_heater(); diff --git a/Marlin/configuration_store.cpp b/Marlin/configuration_store.cpp index f1c1b82e2b..d9d71ce4b4 100644 --- a/Marlin/configuration_store.cpp +++ b/Marlin/configuration_store.cpp @@ -457,10 +457,10 @@ void MarlinSettings::postprocess() { #endif #if DISABLED(ULTIPANEL) - const int lcd_preheat_hotend_temp[2] = { PREHEAT_1_TEMP_HOTEND, PREHEAT_2_TEMP_HOTEND }, - lcd_preheat_bed_temp[2] = { PREHEAT_1_TEMP_BED, PREHEAT_2_TEMP_BED }, - lcd_preheat_fan_speed[2] = { PREHEAT_1_FAN_SPEED, PREHEAT_2_FAN_SPEED }; - #endif // !ULTIPANEL + constexpr int lcd_preheat_hotend_temp[2] = { PREHEAT_1_TEMP_HOTEND, PREHEAT_2_TEMP_HOTEND }, + lcd_preheat_bed_temp[2] = { PREHEAT_1_TEMP_BED, PREHEAT_2_TEMP_BED }, + lcd_preheat_fan_speed[2] = { PREHEAT_1_FAN_SPEED, PREHEAT_2_FAN_SPEED }; + #endif EEPROM_WRITE(lcd_preheat_hotend_temp); EEPROM_WRITE(lcd_preheat_bed_temp); diff --git a/Marlin/temperature.cpp b/Marlin/temperature.cpp index 40df64b67a..ea3a9a91f2 100644 --- a/Marlin/temperature.cpp +++ b/Marlin/temperature.cpp @@ -52,7 +52,7 @@ #endif #if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT) - static void* heater_ttbl_map[2] = {(void*)HEATER_0_TEMPTABLE, (void*)HEATER_1_TEMPTABLE }; + static void* heater_ttbl_map[2] = { (void*)HEATER_0_TEMPTABLE, (void*)HEATER_1_TEMPTABLE }; static uint8_t heater_ttbllen_map[2] = { HEATER_0_TEMPTABLE_LEN, HEATER_1_TEMPTABLE_LEN }; #else static void* heater_ttbl_map[HOTENDS] = ARRAY_BY_HOTENDS((void*)HEATER_0_TEMPTABLE, (void*)HEATER_1_TEMPTABLE, (void*)HEATER_2_TEMPTABLE, (void*)HEATER_3_TEMPTABLE, (void*)HEATER_4_TEMPTABLE); diff --git a/Marlin/ultralcd_impl_HD44780.h b/Marlin/ultralcd_impl_HD44780.h index d1ddd3ba1b..ed7d630b47 100644 --- a/Marlin/ultralcd_impl_HD44780.h +++ b/Marlin/ultralcd_impl_HD44780.h @@ -193,18 +193,19 @@ extern volatile uint8_t buttons; //an extended version of the last checked butt static void lcd_implementation_update_indicators(); #endif - -static void createChar_P(char c, PROGMEM byte *ptr) { +static void createChar_P(const char c, const byte * const ptr) { byte temp[8]; - int8_t i; - - for(i=0; i<8; i++) { + for (uint8_t i = 0; i < 8; i++) temp[i] = pgm_read_byte(&ptr[i]); - } lcd.createChar(c, temp); } -const static PROGMEM byte bedTemp[8] = { +static void lcd_set_custom_characters( + #if ENABLED(LCD_PROGRESS_BAR) + const bool info_screen_charset = true + #endif +) { + const static PROGMEM byte bedTemp[8] = { B00000, B11111, B10101, @@ -213,9 +214,9 @@ const static PROGMEM byte bedTemp[8] = { B11111, B00000, B00000 -}; + }; -const static PROGMEM byte degree[8] = { + const static PROGMEM byte degree[8] = { B01100, B10010, B10010, @@ -226,7 +227,7 @@ const static PROGMEM byte degree[8] = { B00000 }; -const static PROGMEM byte thermometer[8] = { + const static PROGMEM byte thermometer[8] = { B00100, B01010, B01010, @@ -237,7 +238,7 @@ const static PROGMEM byte thermometer[8] = { B01110 }; -const static PROGMEM byte uplevel[8] = { + const static PROGMEM byte uplevel[8] = { B00100, B01110, B11111, @@ -246,9 +247,9 @@ const static PROGMEM byte uplevel[8] = { B00000, B00000, B00000 -}; + }; -const static PROGMEM byte feedrate[8] = { + const static PROGMEM byte feedrate[8] = { B11100, B10000, B11000, @@ -257,9 +258,9 @@ const static PROGMEM byte feedrate[8] = { B00110, B00101, B00000 -}; + }; -const static PROGMEM byte clock[8] = { + const static PROGMEM byte clock[8] = { B00000, B01110, B10011, @@ -268,10 +269,10 @@ const static PROGMEM byte clock[8] = { B01110, B00000, B00000 -}; + }; -#if ENABLED(SDSUPPORT) - const static PROGMEM byte refresh[8] = { + #if ENABLED(SDSUPPORT) + const static PROGMEM byte refresh[8] = { B00000, B00110, B11001, @@ -280,8 +281,8 @@ const static PROGMEM byte clock[8] = { B10011, B01100, B00000, - }; - const static PROGMEM byte folder[8] = { + }; + const static PROGMEM byte folder[8] = { B00000, B11100, B11111, @@ -290,10 +291,10 @@ const static PROGMEM byte clock[8] = { B11111, B00000, B00000 - }; + }; - #if ENABLED(LCD_PROGRESS_BAR) - const static PROGMEM byte progress[3][8] = { { + #if ENABLED(LCD_PROGRESS_BAR) + const static PROGMEM byte progress[3][8] = { { B00000, B10000, B10000, @@ -321,14 +322,8 @@ const static PROGMEM byte clock[8] = { B10101, B00000 } }; + #endif #endif -#endif - -static void lcd_set_custom_characters( - #if ENABLED(LCD_PROGRESS_BAR) - const bool info_screen_charset = true - #endif -) { createChar_P(LCD_BEDTEMP_CHAR, bedTemp); createChar_P(LCD_DEGREE_CHAR, degree); @@ -638,10 +633,12 @@ FORCE_INLINE void _draw_heater_status(const int8_t heater, const char prefix, co #if ENABLED(LCD_PROGRESS_BAR) inline void lcd_draw_progress_bar(const uint8_t percent) { - int tix = (int)(percent * (LCD_WIDTH) * 3) / 100, - cel = tix / 3, rem = tix % 3, i = LCD_WIDTH; + const int tix = (int)(percent * (LCD_WIDTH) * 3) / 100, + cel = tix / 3, + rem = tix % 3; + uint8_t i = LCD_WIDTH; char msg[LCD_WIDTH + 1], b = ' '; - msg[i] = '\0'; + msg[LCD_WIDTH] = '\0'; while (i--) { if (i == cel - 1) b = LCD_STR_PROGRESS[2]; From e1c5a43247956688ed66043d5a405a4da5781aa1 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 6 Jun 2017 04:32:31 -0500 Subject: [PATCH 017/180] Cleanup stepper current control config options --- Marlin/Configuration_adv.h | 10 +++++----- .../Cartesio/Configuration_adv.h | 10 +++++----- .../example_configurations/Felix/Configuration_adv.h | 10 +++++----- .../FolgerTech-i3-2020/Configuration_adv.h | 10 +++++----- .../Hephestos/Configuration_adv.h | 10 +++++----- .../Hephestos_2/Configuration_adv.h | 11 +++++------ .../example_configurations/K8200/Configuration_adv.h | 10 +++++----- .../example_configurations/K8400/Configuration_adv.h | 10 +++++----- .../example_configurations/M150/Configuration_adv.h | 10 +++++----- .../RigidBot/Configuration_adv.h | 10 +++++----- .../example_configurations/SCARA/Configuration_adv.h | 10 +++++----- .../example_configurations/TAZ4/Configuration_adv.h | 10 +++++----- .../TinyBoy2/Configuration_adv.h | 10 +++++----- .../example_configurations/WITBOX/Configuration_adv.h | 10 +++++----- .../delta/FLSUN/auto_calibrate/Configuration_adv.h | 10 +++++----- .../delta/FLSUN/kossel_mini/Configuration_adv.h | 10 +++++----- .../delta/generic/Configuration_adv.h | 10 +++++----- .../delta/kossel_mini/Configuration_adv.h | 10 +++++----- .../delta/kossel_pro/Configuration_adv.h | 10 +++++----- .../delta/kossel_xl/Configuration_adv.h | 10 +++++----- .../gCreate_gMax1.5+/Configuration_adv.h | 10 +++++----- .../makibox/Configuration_adv.h | 8 ++++---- .../tvrrug/Round2/Configuration_adv.h | 10 +++++----- .../example_configurations/wt150/Configuration_adv.h | 8 ++++---- Marlin/pins.h | 6 +++--- 25 files changed, 121 insertions(+), 122 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 0db274d13b..0810194b20 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -419,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=========================== diff --git a/Marlin/example_configurations/Cartesio/Configuration_adv.h b/Marlin/example_configurations/Cartesio/Configuration_adv.h index 42183ac74d..844c8468f1 100644 --- a/Marlin/example_configurations/Cartesio/Configuration_adv.h +++ b/Marlin/example_configurations/Cartesio/Configuration_adv.h @@ -419,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=========================== diff --git a/Marlin/example_configurations/Felix/Configuration_adv.h b/Marlin/example_configurations/Felix/Configuration_adv.h index 28368b4280..1889d6883f 100644 --- a/Marlin/example_configurations/Felix/Configuration_adv.h +++ b/Marlin/example_configurations/Felix/Configuration_adv.h @@ -419,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=========================== diff --git a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h index 5cee9c6a71..e365927d3f 100644 --- a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h +++ b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h @@ -419,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=========================== diff --git a/Marlin/example_configurations/Hephestos/Configuration_adv.h b/Marlin/example_configurations/Hephestos/Configuration_adv.h index 52da5bfb49..20b20b6d23 100644 --- a/Marlin/example_configurations/Hephestos/Configuration_adv.h +++ b/Marlin/example_configurations/Hephestos/Configuration_adv.h @@ -419,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=========================== diff --git a/Marlin/example_configurations/Hephestos_2/Configuration_adv.h b/Marlin/example_configurations/Hephestos_2/Configuration_adv.h index 144f2e829f..0ea3be30f6 100644 --- a/Marlin/example_configurations/Hephestos_2/Configuration_adv.h +++ b/Marlin/example_configurations/Hephestos_2/Configuration_adv.h @@ -419,17 +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 {150, 170, 180, 190, 180} // Values 0-255 (bq ZUM Mega 3D (default): X = 150 [~1.17A]; Y = 170 [~1.33A]; Z = 180 [~1.41A]; E0 = 190 [~1.49A]) - -//#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 } // Default drive percent - X, Y, Z, E axis +//#define PWM_MOTOR_CURRENT { 1300, 1300, 1250 } // Values in milliamps +#define DIGIPOT_MOTOR_CURRENT { 150, 170, 180, 190, 180 } // Values 0-255 (bq ZUM Mega 3D (default): X = 150 [~1.17A]; Y = 170 [~1.33A]; Z = 180 [~1.41A]; E0 = 190 [~1.49A]) +//#define DAC_MOTOR_CURRENT_DEFAULT { 70, 80, 90, 80 } // Default drive percent - X, Y, Z, E axis // 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=========================== diff --git a/Marlin/example_configurations/K8200/Configuration_adv.h b/Marlin/example_configurations/K8200/Configuration_adv.h index 894cc2c0b4..0b72300d89 100644 --- a/Marlin/example_configurations/K8200/Configuration_adv.h +++ b/Marlin/example_configurations/K8200/Configuration_adv.h @@ -432,16 +432,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=========================== diff --git a/Marlin/example_configurations/K8400/Configuration_adv.h b/Marlin/example_configurations/K8400/Configuration_adv.h index 0a6208ab4c..f1d4c78477 100644 --- a/Marlin/example_configurations/K8400/Configuration_adv.h +++ b/Marlin/example_configurations/K8400/Configuration_adv.h @@ -419,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=========================== diff --git a/Marlin/example_configurations/M150/Configuration_adv.h b/Marlin/example_configurations/M150/Configuration_adv.h index 5c46854c28..adcee6867e 100644 --- a/Marlin/example_configurations/M150/Configuration_adv.h +++ b/Marlin/example_configurations/M150/Configuration_adv.h @@ -419,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=========================== diff --git a/Marlin/example_configurations/RigidBot/Configuration_adv.h b/Marlin/example_configurations/RigidBot/Configuration_adv.h index f973a648a7..1be574fce2 100644 --- a/Marlin/example_configurations/RigidBot/Configuration_adv.h +++ b/Marlin/example_configurations/RigidBot/Configuration_adv.h @@ -419,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=========================== diff --git a/Marlin/example_configurations/SCARA/Configuration_adv.h b/Marlin/example_configurations/SCARA/Configuration_adv.h index d3fab11d2e..3f31e9d944 100644 --- a/Marlin/example_configurations/SCARA/Configuration_adv.h +++ b/Marlin/example_configurations/SCARA/Configuration_adv.h @@ -419,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=========================== diff --git a/Marlin/example_configurations/TAZ4/Configuration_adv.h b/Marlin/example_configurations/TAZ4/Configuration_adv.h index 72a6b1d8bc..75988b6149 100644 --- a/Marlin/example_configurations/TAZ4/Configuration_adv.h +++ b/Marlin/example_configurations/TAZ4/Configuration_adv.h @@ -419,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=========================== diff --git a/Marlin/example_configurations/TinyBoy2/Configuration_adv.h b/Marlin/example_configurations/TinyBoy2/Configuration_adv.h index b6e6175fb8..ba0eae98a7 100644 --- a/Marlin/example_configurations/TinyBoy2/Configuration_adv.h +++ b/Marlin/example_configurations/TinyBoy2/Configuration_adv.h @@ -419,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=========================== diff --git a/Marlin/example_configurations/WITBOX/Configuration_adv.h b/Marlin/example_configurations/WITBOX/Configuration_adv.h index 52da5bfb49..20b20b6d23 100644 --- a/Marlin/example_configurations/WITBOX/Configuration_adv.h +++ b/Marlin/example_configurations/WITBOX/Configuration_adv.h @@ -419,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=========================== 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 7782959a89..80c2d36c6a 100644 --- a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h +++ b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h @@ -421,16 +421,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=========================== 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 392cde7c6b..8930283f6c 100644 --- a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h +++ b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h @@ -421,16 +421,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=========================== diff --git a/Marlin/example_configurations/delta/generic/Configuration_adv.h b/Marlin/example_configurations/delta/generic/Configuration_adv.h index 7565ac8652..c3df2ecccc 100644 --- a/Marlin/example_configurations/delta/generic/Configuration_adv.h +++ b/Marlin/example_configurations/delta/generic/Configuration_adv.h @@ -421,16 +421,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=========================== diff --git a/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h index 7565ac8652..c3df2ecccc 100644 --- a/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h @@ -421,16 +421,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=========================== diff --git a/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h index d15fcff5bf..2d811234f1 100644 --- a/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h @@ -426,16 +426,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=========================== diff --git a/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h index 173d6f986e..5639207b23 100644 --- a/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h @@ -421,16 +421,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=========================== diff --git a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration_adv.h b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration_adv.h index 11857e0759..0b6ae047d6 100644 --- a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration_adv.h +++ b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration_adv.h @@ -419,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=========================== diff --git a/Marlin/example_configurations/makibox/Configuration_adv.h b/Marlin/example_configurations/makibox/Configuration_adv.h index 31e2d891fe..d36902e802 100644 --- a/Marlin/example_configurations/makibox/Configuration_adv.h +++ b/Marlin/example_configurations/makibox/Configuration_adv.h @@ -419,13 +419,13 @@ * 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 4 // 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.7, 1.7, 1.7, 1.7 } // 5DPRINT diff --git a/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h b/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h index 6e0ce6e9e0..3314a56cfa 100644 --- a/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h +++ b/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h @@ -419,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=========================== diff --git a/Marlin/example_configurations/wt150/Configuration_adv.h b/Marlin/example_configurations/wt150/Configuration_adv.h index b8dee77729..48454db668 100644 --- a/Marlin/example_configurations/wt150/Configuration_adv.h +++ b/Marlin/example_configurations/wt150/Configuration_adv.h @@ -419,13 +419,13 @@ * 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 5 // 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 {0.68, 0.68, 1.18, 1.27, 1.27} diff --git a/Marlin/pins.h b/Marlin/pins.h index 703df17427..e4c5e4f5e1 100644 --- a/Marlin/pins.h +++ b/Marlin/pins.h @@ -20,8 +20,8 @@ * */ -#ifndef PINS_H -#define PINS_H +#ifndef __PINS_H__ +#define __PINS_H__ #if MB(GEN7_CUSTOM) #include "pins_GEN7_CUSTOM.h" @@ -570,4 +570,4 @@ #define SS_PIN AVR_SS_PIN #endif -#endif // __PINS_H +#endif // __PINS_H__ From 45c74406cf8eb4a294c1c2690aa50706cdf1b784 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 5 Jun 2017 17:45:28 -0500 Subject: [PATCH 018/180] Recover 32 bytes of SRAM in Marlin bootscreen code --- Marlin/ultralcd_impl_HD44780.h | 19 +++++++------------ 1 file changed, 7 insertions(+), 12 deletions(-) diff --git a/Marlin/ultralcd_impl_HD44780.h b/Marlin/ultralcd_impl_HD44780.h index ed7d630b47..e281cacaac 100644 --- a/Marlin/ultralcd_impl_HD44780.h +++ b/Marlin/ultralcd_impl_HD44780.h @@ -440,7 +440,7 @@ void lcd_printPGM_utf(const char *str, uint8_t n=LCD_WIDTH) { } void bootscreen() { - byte top_left[8] = { + const static PROGMEM byte corner[4][8] = { { B00000, B00000, B00000, @@ -449,8 +449,7 @@ void lcd_printPGM_utf(const char *str, uint8_t n=LCD_WIDTH) { B00010, B00100, B00100 - }; - byte top_right[8] = { + }, { B00000, B00000, B00000, @@ -459,8 +458,7 @@ void lcd_printPGM_utf(const char *str, uint8_t n=LCD_WIDTH) { B01100, B00100, B00100 - }; - byte botom_left[8] = { + }, { B00100, B00010, B00001, @@ -469,8 +467,7 @@ void lcd_printPGM_utf(const char *str, uint8_t n=LCD_WIDTH) { B00000, B00000, B00000 - }; - byte botom_right[8] = { + }, { B00100, B01000, B10000, @@ -479,11 +476,9 @@ void lcd_printPGM_utf(const char *str, uint8_t n=LCD_WIDTH) { B00000, B00000, B00000 - }; - lcd.createChar(0, top_left); - lcd.createChar(1, top_right); - lcd.createChar(2, botom_left); - lcd.createChar(3, botom_right); + } }; + for (uint8_t i = 0; i < 4; i++) + createChar_P(i, corner[i]); lcd.clear(); From 97e13a30ba1aff0af84f7847f27bd5c05eeb7b5f Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 5 Jun 2017 18:32:14 -0500 Subject: [PATCH 019/180] Save over 100 bytes SRAM in pin_is_protected --- Marlin/Marlin_main.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index c4866d89a5..5315772cdb 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -660,8 +660,8 @@ static bool send_ok[BUFSIZE]; #define host_keepalive() NOOP #endif -static inline float pgm_read_any(const float *p) { return pgm_read_float_near(p); } -static inline signed char pgm_read_any(const signed char *p) { return pgm_read_byte_near(p); } +FORCE_INLINE float pgm_read_any(const float *p) { return pgm_read_float_near(p); } +FORCE_INLINE signed char pgm_read_any(const signed char *p) { return pgm_read_byte_near(p); } #define XYZ_CONSTS_FROM_CONFIG(type, array, CONFIG) \ static const PROGMEM type array##_P[XYZ] = { X_##CONFIG, Y_##CONFIG, Z_##CONFIG }; \ @@ -6270,10 +6270,10 @@ inline void gcode_M31() { /** * Sensitive pin test for M42, M226 */ -static bool pin_is_protected(uint8_t pin) { - static const int sensitive_pins[] = SENSITIVE_PINS; +static bool pin_is_protected(const int8_t pin) { + static const int8_t sensitive_pins[] PROGMEM = SENSITIVE_PINS; for (uint8_t i = 0; i < COUNT(sensitive_pins); i++) - if (sensitive_pins[i] == pin) return true; + if (pin == (int8_t)pgm_read_byte(&sensitive_pins[i])) return true; return false; } From e6d10f6ddd51dd8e7296c39aa576bd8b26eb1423 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 5 Jun 2017 18:49:16 -0500 Subject: [PATCH 020/180] Spend 48b PROGMEM to save 16b SRAM ...by moving `homing_feedrate_mm_s` to PROGMEM. --- Marlin/Marlin_main.cpp | 30 ++++++++++++++++-------------- 1 file changed, 16 insertions(+), 14 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 5315772cdb..73990e71e5 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -389,7 +389,7 @@ static const char *injected_commands_P = NULL; * Feed rates are often configured with mm/m * but the planner and stepper like mm/s units. */ -float constexpr homing_feedrate_mm_s[] = { +static const float homing_feedrate_mm_s[] PROGMEM = { #if ENABLED(DELTA) MMM_TO_MMS(HOMING_FEEDRATE_Z), MMM_TO_MMS(HOMING_FEEDRATE_Z), #else @@ -397,6 +397,8 @@ float constexpr homing_feedrate_mm_s[] = { #endif MMM_TO_MMS(HOMING_FEEDRATE_Z), 0 }; +FORCE_INLINE float homing_feedrate(const AxisEnum a) { return pgm_read_float(&homing_feedrate_mm_s[a]); } + float feedrate_mm_s = MMM_TO_MMS(1500.0); static float saved_feedrate_mm_s; int feedrate_percentage = 100, saved_feedrate_percentage, @@ -1504,7 +1506,7 @@ inline float get_homing_bump_feedrate(const AxisEnum axis) { SERIAL_ECHO_START; SERIAL_ECHOLNPGM("Warning: Homing Bump Divisor < 1"); } - return homing_feedrate_mm_s[axis] / hbd; + return homing_feedrate(axis) / hbd; } /** @@ -1631,7 +1633,7 @@ void do_blocking_move_to(const float &x, const float &y, const float &z, const f // If Z needs to raise, do it before moving XY if (destination[Z_AXIS] < z) { destination[Z_AXIS] = z; - prepare_uninterpolated_move_to_destination(fr_mm_s ? fr_mm_s : homing_feedrate_mm_s[Z_AXIS]); + prepare_uninterpolated_move_to_destination(fr_mm_s ? fr_mm_s : homing_feedrate(Z_AXIS)); } destination[X_AXIS] = x; @@ -1641,14 +1643,14 @@ void do_blocking_move_to(const float &x, const float &y, const float &z, const f // If Z needs to lower, do it after moving XY if (destination[Z_AXIS] > z) { destination[Z_AXIS] = z; - prepare_uninterpolated_move_to_destination(fr_mm_s ? fr_mm_s : homing_feedrate_mm_s[Z_AXIS]); + prepare_uninterpolated_move_to_destination(fr_mm_s ? fr_mm_s : homing_feedrate(Z_AXIS)); } #else // If Z needs to raise, do it before moving XY if (current_position[Z_AXIS] < z) { - feedrate_mm_s = fr_mm_s ? fr_mm_s : homing_feedrate_mm_s[Z_AXIS]; + feedrate_mm_s = fr_mm_s ? fr_mm_s : homing_feedrate(Z_AXIS); current_position[Z_AXIS] = z; line_to_current_position(); } @@ -1660,7 +1662,7 @@ void do_blocking_move_to(const float &x, const float &y, const float &z, const f // If Z needs to lower, do it after moving XY if (current_position[Z_AXIS] > z) { - feedrate_mm_s = fr_mm_s ? fr_mm_s : homing_feedrate_mm_s[Z_AXIS]; + feedrate_mm_s = fr_mm_s ? fr_mm_s : homing_feedrate(Z_AXIS); current_position[Z_AXIS] = z; line_to_current_position(); } @@ -2778,11 +2780,11 @@ static void do_homing_move(const AxisEnum axis, const float distance, const floa SYNC_PLAN_POSITION_KINEMATIC(); current_position[axis] = distance; inverse_kinematics(current_position); - planner.buffer_line(delta[A_AXIS], delta[B_AXIS], delta[C_AXIS], current_position[E_AXIS], fr_mm_s ? fr_mm_s : homing_feedrate_mm_s[axis], active_extruder); + planner.buffer_line(delta[A_AXIS], delta[B_AXIS], delta[C_AXIS], current_position[E_AXIS], fr_mm_s ? fr_mm_s : homing_feedrate(axis), active_extruder); #else sync_plan_position(); current_position[axis] = distance; - planner.buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], fr_mm_s ? fr_mm_s : homing_feedrate_mm_s[axis], active_extruder); + planner.buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], fr_mm_s ? fr_mm_s : homing_feedrate(axis), active_extruder); #endif stepper.synchronize(); @@ -3397,7 +3399,7 @@ inline void gcode_G4() { const float mlx = max_length(X_AXIS), mly = max_length(Y_AXIS), mlratio = mlx > mly ? mly / mlx : mlx / mly, - fr_mm_s = min(homing_feedrate_mm_s[X_AXIS], homing_feedrate_mm_s[Y_AXIS]) * sqrt(sq(mlratio) + 1.0); + fr_mm_s = min(homing_feedrate(X_AXIS), homing_feedrate(Y_AXIS)) * sqrt(sq(mlratio) + 1.0); do_blocking_move_to_xy(1.5 * mlx * x_axis_home_dir, 1.5 * mly * home_dir(Y_AXIS), fr_mm_s); endstops.hit_on_purpose(); // clear endstop hit flags @@ -3540,7 +3542,7 @@ inline void gcode_G4() { // Move all carriages together linearly until an endstop is hit. current_position[X_AXIS] = current_position[Y_AXIS] = current_position[Z_AXIS] = (Z_MAX_LENGTH + 10); - feedrate_mm_s = homing_feedrate_mm_s[X_AXIS]; + feedrate_mm_s = homing_feedrate(X_AXIS); line_to_current_position(); stepper.synchronize(); endstops.hit_on_purpose(); // clear endstop hit flags @@ -3853,7 +3855,7 @@ void home_all_axes() { gcode_G28(true); } const float old_feedrate_mm_s = feedrate_mm_s; #if MANUAL_PROBE_HEIGHT > 0 - feedrate_mm_s = homing_feedrate_mm_s[Z_AXIS]; + feedrate_mm_s = homing_feedrate(Z_AXIS); current_position[Z_AXIS] = LOGICAL_Z_POSITION(Z_MIN_POS) + MANUAL_PROBE_HEIGHT; line_to_current_position(); #endif @@ -3864,7 +3866,7 @@ void home_all_axes() { gcode_G28(true); } line_to_current_position(); #if MANUAL_PROBE_HEIGHT > 0 - feedrate_mm_s = homing_feedrate_mm_s[Z_AXIS]; + feedrate_mm_s = homing_feedrate(Z_AXIS); current_position[Z_AXIS] = LOGICAL_Z_POSITION(Z_MIN_POS); // just slightly over the bed line_to_current_position(); #endif @@ -3900,7 +3902,7 @@ void home_all_axes() { gcode_G28(true); } #if ENABLED(MESH_G28_REST_ORIGIN) current_position[Z_AXIS] = LOGICAL_Z_POSITION(Z_MIN_POS); set_destination_to_current(); - line_to_destination(homing_feedrate_mm_s[Z_AXIS]); + line_to_destination(homing_feedrate(Z_AXIS)); stepper.synchronize(); #endif } @@ -5502,7 +5504,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.seen('F')) feedrate_mm_s = homing_feedrate_mm_s[i]; + if (!parser.seen('F')) feedrate_mm_s = homing_feedrate(i); // If G38.2 fails throw an error if (!G38_run_probe() && is_38_2) { SERIAL_ERROR_START; From 2a41f0ff84a7f8afe4942997e980cc73ba3e0339 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 6 Jun 2017 02:30:39 -0500 Subject: [PATCH 021/180] Save 28b PROGMEM in ultralcd.cpp (line_to_current) --- Marlin/ultralcd.cpp | 35 ++++++++++++++++------------------- 1 file changed, 16 insertions(+), 19 deletions(-) diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index 1512cd893b..7f2c80e11b 100755 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -686,8 +686,13 @@ void kill_screen(const char* lcd_msg) { else lcd_buzz(20, 440); } - inline void line_to_current(AxisEnum axis) { - planner.buffer_line_kinematic(current_position, MMM_TO_MMS(manual_feedrate_mm_m[axis]), active_extruder); + inline void line_to_current_z() { + planner.buffer_line_kinematic(current_position, MMM_TO_MMS(manual_feedrate_mm_m[Z_AXIS]), active_extruder); + } + + inline void line_to_z(const float &z) { + current_position[Z_AXIS] = z; + line_to_current_z(); } #if ENABLED(SDSUPPORT) @@ -1521,8 +1526,7 @@ void kill_screen(const char* lcd_msg) { // void _lcd_after_probing() { #if MANUAL_PROBE_HEIGHT > 0 - current_position[Z_AXIS] = LOGICAL_Z_POSITION(Z_MIN_POS) + MANUAL_PROBE_HEIGHT; - line_to_current(Z_AXIS); + line_to_z(LOGICAL_Z_POSITION(Z_MIN_POS) + MANUAL_PROBE_HEIGHT); #endif // Display "Done" screen and wait for moves to complete #if MANUAL_PROBE_HEIGHT > 0 || ENABLED(MESH_BED_LEVELING) @@ -1539,15 +1543,13 @@ 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 - current_position[Z_AXIS] = LOGICAL_Z_POSITION(Z_MIN_POS) + MANUAL_PROBE_HEIGHT; - line_to_current(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 - current_position[Z_AXIS] = LOGICAL_Z_POSITION(Z_MIN_POS); - line_to_current(Z_AXIS); + line_to_z(LOGICAL_Z_POSITION(Z_MIN_POS)); #endif lcd_synchronize(); } @@ -1629,10 +1631,8 @@ void kill_screen(const char* lcd_msg) { // if (encoderPosition) { refresh_cmd_timeout(); - current_position[Z_AXIS] += float((int32_t)encoderPosition) * (MBL_Z_STEP); - NOLESS(current_position[Z_AXIS], -(LCD_PROBE_Z_RANGE) * 0.5); - NOMORE(current_position[Z_AXIS], (LCD_PROBE_Z_RANGE) * 0.5); - line_to_current(Z_AXIS); + const float z = current_position[Z_AXIS] + float((int32_t)encoderPosition) * (MBL_Z_STEP); + line_to_z(constrain(z, -(LCD_PROBE_Z_RANGE) * 0.5, (LCD_PROBE_Z_RANGE) * 0.5)); lcdDrawUpdate = LCDVIEW_CALL_REDRAW_NEXT; encoderPosition = 0; } @@ -2299,15 +2299,13 @@ void kill_screen(const char* lcd_msg) { reset_bed_level(); // After calibration bed-level data is no longer valid #endif - current_position[Z_AXIS] = max(Z_HOMING_HEIGHT, Z_CLEARANCE_BETWEEN_PROBES) + (DELTA_PRINTABLE_RADIUS) / 5; - line_to_current(Z_AXIS); + line_to_z(max(Z_HOMING_HEIGHT, Z_CLEARANCE_BETWEEN_PROBES) + (DELTA_PRINTABLE_RADIUS) / 5); current_position[X_AXIS] = a < 0 ? LOGICAL_X_POSITION(X_HOME_POS) : cos(RADIANS(a)) * delta_calibration_radius; current_position[Y_AXIS] = a < 0 ? LOGICAL_Y_POSITION(Y_HOME_POS) : sin(RADIANS(a)) * delta_calibration_radius; - line_to_current(Z_AXIS); + line_to_current_z(); - current_position[Z_AXIS] = 4.0; - line_to_current(Z_AXIS); + line_to_z(4.0); lcd_synchronize(); @@ -2536,8 +2534,7 @@ void kill_screen(const char* lcd_msg) { #if ENABLED(DELTA) #define _MOVE_XY_ALLOWED (current_position[Z_AXIS] <= delta_clip_start_height) void lcd_lower_z_to_clip_height() { - current_position[Z_AXIS] = delta_clip_start_height; - line_to_current(Z_AXIS); + line_to_z(delta_clip_start_height); lcd_synchronize(); } #else From 36cc03a9b48ef66e592068f6fee5d982d20ef503 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 6 Jun 2017 02:58:31 -0500 Subject: [PATCH 022/180] Save 224b PROGMEM, 48b SRAM in get_homing_bump_feedrate --- Marlin/Marlin_main.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 73990e71e5..ec0152aa09 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -1499,8 +1499,8 @@ static void set_axis_is_at_home(const AxisEnum axis) { * Some planner shorthand inline functions */ inline float get_homing_bump_feedrate(const AxisEnum axis) { - int constexpr homing_bump_divisor[] = HOMING_BUMP_DIVISOR; - int hbd = homing_bump_divisor[axis]; + const uint8_t homing_bump_divisor[] PROGMEM = HOMING_BUMP_DIVISOR; + uint8_t hbd = pgm_read_byte(&homing_bump_divisor[axis]); if (hbd < 1) { hbd = 10; SERIAL_ECHO_START; From 4134a6b526fa6c9bbdc60b89bd6d9037df8a1fa7 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 6 Jun 2017 04:03:01 -0500 Subject: [PATCH 023/180] Save 88b PROGMEM, 48 bytes SRAM in settings.reset --- Marlin/configuration_store.cpp | 14 +++++++------- 1 file changed, 7 insertions(+), 7 deletions(-) diff --git a/Marlin/configuration_store.cpp b/Marlin/configuration_store.cpp index d9d71ce4b4..90e5efc551 100644 --- a/Marlin/configuration_store.cpp +++ b/Marlin/configuration_store.cpp @@ -1125,12 +1125,12 @@ void MarlinSettings::postprocess() { * M502 - Reset Configuration */ void MarlinSettings::reset() { - const float tmp1[] = DEFAULT_AXIS_STEPS_PER_UNIT, tmp2[] = DEFAULT_MAX_FEEDRATE; - const uint32_t tmp3[] = DEFAULT_MAX_ACCELERATION; + static const float tmp1[] PROGMEM = DEFAULT_AXIS_STEPS_PER_UNIT, tmp2[] PROGMEM = DEFAULT_MAX_FEEDRATE; + static const uint32_t tmp3[] PROGMEM = DEFAULT_MAX_ACCELERATION; LOOP_XYZE_N(i) { - planner.axis_steps_per_mm[i] = tmp1[i < COUNT(tmp1) ? i : COUNT(tmp1) - 1]; - planner.max_feedrate_mm_s[i] = tmp2[i < COUNT(tmp2) ? i : COUNT(tmp2) - 1]; - planner.max_acceleration_mm_per_s2[i] = tmp3[i < COUNT(tmp3) ? i : COUNT(tmp3) - 1]; + planner.axis_steps_per_mm[i] = pgm_read_float(&tmp1[i < COUNT(tmp1) ? i : COUNT(tmp1) - 1]); + planner.max_feedrate_mm_s[i] = pgm_read_float(&tmp2[i < COUNT(tmp2) ? i : COUNT(tmp2) - 1]); + planner.max_acceleration_mm_per_s2[i] = pgm_read_float(&tmp3[i < COUNT(tmp3) ? i : COUNT(tmp3) - 1]); } planner.acceleration = DEFAULT_ACCELERATION; @@ -1265,9 +1265,9 @@ void MarlinSettings::reset() { endstops.enable_globally( #if ENABLED(ENDSTOPS_ALWAYS_ON_DEFAULT) - (true) + true #else - (false) + false #endif ); From c9e3caf928eb9024b735f682a869c86d1d2ea524 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 6 Jun 2017 06:10:10 -0500 Subject: [PATCH 024/180] Save lots of PROGMEM, ~20b SRAM with DIGIPOT_I2C --- Marlin/Marlin_main.cpp | 2 +- Marlin/SanityCheck.h | 10 +++++++ Marlin/digipot_mcp4018.cpp | 57 ++++++++++++++++++++++++-------------- Marlin/digipot_mcp4451.cpp | 12 ++++---- 4 files changed, 53 insertions(+), 28 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index ec0152aa09..4bbd804984 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -782,7 +782,7 @@ extern "C" { #endif // !SDSUPPORT #if ENABLED(DIGIPOT_I2C) - extern void digipot_i2c_set_current(int channel, float current); + extern void digipot_i2c_set_current(uint8_t channel, float current); extern void digipot_i2c_init(); #endif diff --git a/Marlin/SanityCheck.h b/Marlin/SanityCheck.h index 83dabc975e..88f05d9dd1 100644 --- a/Marlin/SanityCheck.h +++ b/Marlin/SanityCheck.h @@ -1165,6 +1165,16 @@ static_assert(1 >= 0 #error "Enable STEALTHCHOP to use HYBRID_THRESHOLD." #endif +/** + * Digipot requirement + */ +#if ENABLED(DIGIPOT_MCP4018) + #if !defined(DIGIPOTS_I2C_SDA_X) || !defined(DIGIPOTS_I2C_SDA_Y) || !defined(DIGIPOTS_I2C_SDA_Z) \ + || !defined(DIGIPOTS_I2C_SDA_E0) || !defined(DIGIPOTS_I2C_SDA_E1) + #error "DIGIPOT_MCP4018 requires DIGIPOTS_I2C_SDA_* pins to be defined." + #endif +#endif + /** * Require 4 or more elements in per-axis initializers */ diff --git a/Marlin/digipot_mcp4018.cpp b/Marlin/digipot_mcp4018.cpp index a14419c4d6..a13302b034 100644 --- a/Marlin/digipot_mcp4018.cpp +++ b/Marlin/digipot_mcp4018.cpp @@ -24,6 +24,7 @@ #if ENABLED(DIGIPOT_I2C) && ENABLED(DIGIPOT_MCP4018) +#include "enum.h" #include "Stream.h" #include "utility/twi.h" #include //https://github.com/stawel/SlowSoftI2CMaster @@ -38,31 +39,47 @@ #define DIGIPOT_A4988_Itripmax(Vref) ((Vref)/(8.0*DIGIPOT_A4988_Rsx)) -#define DIGIPOT_A4988_FACTOR (DIGIPOT_A4988_MAX_VALUE/DIGIPOT_A4988_Itripmax(DIGIPOT_A4988_Vrefmax)) +#define DIGIPOT_A4988_FACTOR ((DIGIPOT_A4988_MAX_VALUE)/DIGIPOT_A4988_Itripmax(DIGIPOT_A4988_Vrefmax)) //TODO: MAX_CURRENT -0.5A ?? (currently set to 2A, max possible current 2.5A) #define DIGIPOT_A4988_MAX_CURRENT (DIGIPOT_A4988_Itripmax(DIGIPOT_A4988_Vrefmax) - 0.5) -static byte current_to_wiper(float current) { - return byte(ceil(float((DIGIPOT_A4988_FACTOR * current)))); +static byte current_to_wiper(const float current) { + return byte(ceil(float(DIGIPOT_A4988_FACTOR) * current)); } -static uint8_t sda_pins[DIGIPOT_I2C_NUM_CHANNELS] = { - DIGIPOTS_I2C_SDA_X, - DIGIPOTS_I2C_SDA_Y, - DIGIPOTS_I2C_SDA_Z, - DIGIPOTS_I2C_SDA_E0, - DIGIPOTS_I2C_SDA_E1, +const uint8_t sda_pins[DIGIPOT_I2C_NUM_CHANNELS] = { + DIGIPOTS_I2C_SDA_X + #if DIGIPOT_I2C_NUM_CHANNELS > 1 + , DIGIPOTS_I2C_SDA_Y + #if DIGIPOT_I2C_NUM_CHANNELS > 2 + , DIGIPOTS_I2C_SDA_Z + #if DIGIPOT_I2C_NUM_CHANNELS > 3 + , DIGIPOTS_I2C_SDA_E0 + #if DIGIPOT_I2C_NUM_CHANNELS > 4 + , DIGIPOTS_I2C_SDA_E1 + #endif + #endif + #endif + #endif }; static SlowSoftI2CMaster pots[DIGIPOT_I2C_NUM_CHANNELS] = { - SlowSoftI2CMaster { sda_pins[0], DIGIPOTS_I2C_SCL }, - SlowSoftI2CMaster { sda_pins[1], DIGIPOTS_I2C_SCL }, - SlowSoftI2CMaster { sda_pins[2], DIGIPOTS_I2C_SCL }, - SlowSoftI2CMaster { sda_pins[3], DIGIPOTS_I2C_SCL }, - SlowSoftI2CMaster { sda_pins[4], DIGIPOTS_I2C_SCL } + SlowSoftI2CMaster { sda_pins[X_AXIS], DIGIPOTS_I2C_SCL } + #if DIGIPOT_I2C_NUM_CHANNELS > 1 + , SlowSoftI2CMaster { sda_pins[Y_AXIS], DIGIPOTS_I2C_SCL } + #if DIGIPOT_I2C_NUM_CHANNELS > 2 + , SlowSoftI2CMaster { sda_pins[Z_AXIS], DIGIPOTS_I2C_SCL } + #if DIGIPOT_I2C_NUM_CHANNELS > 3 + , SlowSoftI2CMaster { sda_pins[E_AXIS], DIGIPOTS_I2C_SCL } + #if DIGIPOT_I2C_NUM_CHANNELS > 4 + , SlowSoftI2CMaster { sda_pins[E_AXIS + 1], DIGIPOTS_I2C_SCL } + #endif + #endif + #endif + #endif }; -static void i2c_send(int channel, byte v) { +static void i2c_send(const uint8_t channel, const byte v) { if (WITHIN(channel, 0, DIGIPOT_I2C_NUM_CHANNELS - 1)) { pots[channel].i2c_start(((DIGIPOT_I2C_ADDRESS) << 1) | I2C_WRITE); pots[channel].i2c_write(v); @@ -71,21 +88,19 @@ static void i2c_send(int channel, byte v) { } // This is for the MCP4018 I2C based digipot -void digipot_i2c_set_current(int channel, float current) { - current = min(max(current, 0.0f), float(DIGIPOT_A4988_MAX_CURRENT)); - - i2c_send(channel, current_to_wiper(current)); +void digipot_i2c_set_current(uint8_t channel, float current) { + i2c_send(channel, current_to_wiper(min(max(current, 0.0f), float(DIGIPOT_A4988_MAX_CURRENT)))); } void digipot_i2c_init() { - const float digipot_motor_current[] = DIGIPOT_I2C_MOTOR_CURRENTS; + static const float digipot_motor_current[] PROGMEM = DIGIPOT_I2C_MOTOR_CURRENTS; for (uint8_t i = 0; i < DIGIPOT_I2C_NUM_CHANNELS; i++) pots[i].i2c_init(); // setup initial currents as defined in Configuration_adv.h for (uint8_t i = 0; i < COUNT(digipot_motor_current); i++) - digipot_i2c_set_current(i, digipot_motor_current[i]); + digipot_i2c_set_current(i, pgm_read_float(&digipot_motor_current[i])); } #endif // DIGIPOT_I2C && DIGIPOT_MCP4018 diff --git a/Marlin/digipot_mcp4451.cpp b/Marlin/digipot_mcp4451.cpp index 419d3a423f..6e94778cf2 100644 --- a/Marlin/digipot_mcp4451.cpp +++ b/Marlin/digipot_mcp4451.cpp @@ -37,11 +37,11 @@ #define DIGIPOT_I2C_MAX_CURRENT 2.5 #endif -static byte current_to_wiper(float current) { +static byte current_to_wiper(const float current) { return byte(ceil(float((DIGIPOT_I2C_FACTOR * current)))); } -static void i2c_send(byte addr, byte a, byte b) { +static void i2c_send(const byte addr, const byte a, const byte b) { Wire.beginTransmission(addr); Wire.write(a); Wire.write(b); @@ -49,7 +49,7 @@ static void i2c_send(byte addr, byte a, byte b) { } // This is for the MCP4451 I2C based digipot -void digipot_i2c_set_current(int channel, float current) { +void digipot_i2c_set_current(uint8_t channel, float current) { current = min((float) max(current, 0.0f), DIGIPOT_I2C_MAX_CURRENT); // these addresses are specific to Azteeg X3 Pro, can be set to others, // In this case first digipot is at address A0=0, A1= 0, second one is at A0=0, A1= 1 @@ -69,11 +69,11 @@ void digipot_i2c_set_current(int channel, float current) { } void digipot_i2c_init() { - const float digipot_motor_current[] = DIGIPOT_I2C_MOTOR_CURRENTS; + static const float digipot_motor_current[] PROGMEM = DIGIPOT_I2C_MOTOR_CURRENTS; Wire.begin(); // setup initial currents as defined in Configuration_adv.h - for (int i = 0; i < COUNT(digipot_motor_current); i++) - digipot_i2c_set_current(i, digipot_motor_current[i]); + for (uint8_t i = 0; i < COUNT(digipot_motor_current); i++) + digipot_i2c_set_current(i, pgm_read_float(&digipot_motor_current[i])); } #endif // DIGIPOT_I2C From b7dc4d9973f503026dae528949594d03861fede4 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 6 Jun 2017 06:33:06 -0500 Subject: [PATCH 025/180] Save 92b PROGMEM, 14b SRAM with extruder auto fan --- Marlin/temperature.cpp | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/Marlin/temperature.cpp b/Marlin/temperature.cpp index ea3a9a91f2..1244a55b1c 100644 --- a/Marlin/temperature.cpp +++ b/Marlin/temperature.cpp @@ -472,8 +472,8 @@ int Temperature::getHeaterPower(int heater) { #if HAS_AUTO_FAN void Temperature::checkExtruderAutoFans() { - constexpr int8_t fanPin[] = { E0_AUTO_FAN_PIN, E1_AUTO_FAN_PIN, E2_AUTO_FAN_PIN, E3_AUTO_FAN_PIN, E4_AUTO_FAN_PIN }; - constexpr int fanBit[] = { + static const int8_t fanPin[] PROGMEM = { E0_AUTO_FAN_PIN, E1_AUTO_FAN_PIN, E2_AUTO_FAN_PIN, E3_AUTO_FAN_PIN, E4_AUTO_FAN_PIN }; + static const uint8_t fanBit[] PROGMEM = { 0, AUTO_1_IS_0 ? 0 : 1, AUTO_2_IS_0 ? 0 : AUTO_2_IS_1 ? 1 : 2, @@ -482,20 +482,20 @@ int Temperature::getHeaterPower(int heater) { }; uint8_t fanState = 0; - HOTEND_LOOP() { + HOTEND_LOOP() if (current_temperature[e] > EXTRUDER_AUTO_FAN_TEMPERATURE) - SBI(fanState, fanBit[e]); - } + SBI(fanState, pgm_read_byte(&fanBit[e])); uint8_t fanDone = 0; for (uint8_t f = 0; f < COUNT(fanPin); f++) { - int8_t pin = fanPin[f]; - if (pin >= 0 && !TEST(fanDone, fanBit[f])) { - uint8_t newFanSpeed = TEST(fanState, fanBit[f]) ? EXTRUDER_AUTO_FAN_SPEED : 0; + int8_t pin = pgm_read_byte(&fanPin[f]); + const uint8_t bit = pgm_read_byte(&fanBit[f]); + if (pin >= 0 && !TEST(fanDone, bit)) { + uint8_t newFanSpeed = TEST(fanState, bit) ? EXTRUDER_AUTO_FAN_SPEED : 0; // this idiom allows both digital and PWM fan outputs (see M42 handling). digitalWrite(pin, newFanSpeed); analogWrite(pin, newFanSpeed); - SBI(fanDone, fanBit[f]); + SBI(fanDone, bit); } } } From 6bb05c45433876f9be80fe23886c1282752f9311 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 6 Jun 2017 07:18:46 -0500 Subject: [PATCH 026/180] Save 20b in smart_fill_mesh with PROGMEM --- Marlin/ubl_G29.cpp | 37 +++++++++++++++++++++++-------------- 1 file changed, 23 insertions(+), 14 deletions(-) diff --git a/Marlin/ubl_G29.cpp b/Marlin/ubl_G29.cpp index 28a1cb3bd1..ab0ac32cb3 100644 --- a/Marlin/ubl_G29.cpp +++ b/Marlin/ubl_G29.cpp @@ -1593,24 +1593,33 @@ typedef struct { uint8_t sx, ex, sy, ey; bool yfirst; } smart_fill_info; void unified_bed_leveling::smart_fill_mesh() { - const smart_fill_info info[] = { - { 0, GRID_MAX_POINTS_X, 0, GRID_MAX_POINTS_Y - 2, false }, // Bottom of the mesh looking up - { 0, GRID_MAX_POINTS_X, GRID_MAX_POINTS_Y - 1, 0, false }, // Top of the mesh looking down - { 0, GRID_MAX_POINTS_X - 2, 0, GRID_MAX_POINTS_Y, true }, // Left side of the mesh looking right - { GRID_MAX_POINTS_X - 1, 0, 0, GRID_MAX_POINTS_Y, true } // Right side of the mesh looking left - }; + static const smart_fill_info + info0 PROGMEM = { 0, GRID_MAX_POINTS_X, 0, GRID_MAX_POINTS_Y - 2, false }, // Bottom of the mesh looking up + info1 PROGMEM = { 0, GRID_MAX_POINTS_X, GRID_MAX_POINTS_Y - 1, 0, false }, // Top of the mesh looking down + info2 PROGMEM = { 0, GRID_MAX_POINTS_X - 2, 0, GRID_MAX_POINTS_Y, true }, // Left side of the mesh looking right + info3 PROGMEM = { GRID_MAX_POINTS_X - 1, 0, 0, GRID_MAX_POINTS_Y, true }; // Right side of the mesh looking left + static const smart_fill_info * const info[] PROGMEM = { &info0, &info1, &info2, &info3 }; + + // static const smart_fill_info info[] PROGMEM = { + // { 0, GRID_MAX_POINTS_X, 0, GRID_MAX_POINTS_Y - 2, false } PROGMEM, // Bottom of the mesh looking up + // { 0, GRID_MAX_POINTS_X, GRID_MAX_POINTS_Y - 1, 0, false } PROGMEM, // Top of the mesh looking down + // { 0, GRID_MAX_POINTS_X - 2, 0, GRID_MAX_POINTS_Y, true } PROGMEM, // Left side of the mesh looking right + // { GRID_MAX_POINTS_X - 1, 0, 0, GRID_MAX_POINTS_Y, true } PROGMEM // Right side of the mesh looking left + // }; for (uint8_t i = 0; i < COUNT(info); ++i) { - const smart_fill_info &f = info[i]; - if (f.yfirst) { - const int8_t dir = f.ex > f.sx ? 1 : -1; - for (uint8_t y = f.sy; y != f.ey; ++y) - for (uint8_t x = f.sx; x != f.ex; x += dir) + const smart_fill_info *f = (smart_fill_info*)pgm_read_word(&info[i]); + const int8_t sx = pgm_read_word(&f->sx), sy = pgm_read_word(&f->sy), + ex = pgm_read_word(&f->ex), ey = pgm_read_word(&f->ey); + if (pgm_read_byte(&f->yfirst)) { + const int8_t dir = ex > sx ? 1 : -1; + for (uint8_t y = sy; y != ey; ++y) + for (uint8_t x = sx; x != ex; x += dir) if (smart_fill_one(x, y, dir, 0)) break; } else { - const int8_t dir = f.ey > f.sy ? 1 : -1; - for (uint8_t x = f.sx; x != f.ex; ++x) - for (uint8_t y = f.sy; y != f.ey; y += dir) + const int8_t dir = ey > sy ? 1 : -1; + for (uint8_t x = sx; x != ex; ++x) + for (uint8_t y = sy; y != ey; y += dir) if (smart_fill_one(x, y, 0, dir)) break; } } From 9128d9ab45b4f73a8b7d3f21ae84691619da21e5 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 6 Jun 2017 07:19:27 -0500 Subject: [PATCH 027/180] Improve sanity checks with static_assert, organize --- Marlin/SanityCheck.h | 364 +++++++++++++++++++++++-------------------- 1 file changed, 199 insertions(+), 165 deletions(-) diff --git a/Marlin/SanityCheck.h b/Marlin/SanityCheck.h index 88f05d9dd1..440144cf8f 100644 --- a/Marlin/SanityCheck.h +++ b/Marlin/SanityCheck.h @@ -270,23 +270,6 @@ #endif #endif -/** - * Delta requirements - */ -#if ENABLED(DELTA) - #if DISABLED(USE_XMAX_PLUG) && DISABLED(USE_YMAX_PLUG) && DISABLED(USE_ZMAX_PLUG) - #error "You probably want to use Max Endstops for DELTA!" - #elif ENABLED(ENABLE_LEVELING_FADE_HEIGHT) && DISABLED(AUTO_BED_LEVELING_BILINEAR) && !UBL_DELTA - #error "ENABLE_LEVELING_FADE_HEIGHT on DELTA requires AUTO_BED_LEVELING_BILINEAR or AUTO_BED_LEVELING_UBL." - #elif ABL_GRID - #if (GRID_MAX_POINTS_X & 1) == 0 || (GRID_MAX_POINTS_Y & 1) == 0 - #error "DELTA requires GRID_MAX_POINTS_X and GRID_MAX_POINTS_Y to be odd numbers." - #elif GRID_MAX_POINTS_X < 3 - #error "DELTA requires GRID_MAX_POINTS_X and GRID_MAX_POINTS_Y to be 3 or higher." - #endif - #endif -#endif - /** * Babystepping */ @@ -430,44 +413,57 @@ #endif /** - * Allow only one bed leveling option to be defined + * Kinematics + */ + +/** + * Allow only one kinematic type to be defined */ static_assert(1 >= 0 - #if ENABLED(AUTO_BED_LEVELING_LINEAR) + #if ENABLED(DELTA) + 1 #endif - #if ENABLED(AUTO_BED_LEVELING_3POINT) + #if ENABLED(MORGAN_SCARA) + 1 #endif - #if ENABLED(AUTO_BED_LEVELING_BILINEAR) + #if ENABLED(MAKERARM_SCARA) + 1 #endif - #if ENABLED(AUTO_BED_LEVELING_UBL) + #if ENABLED(COREXY) + 1 #endif - #if ENABLED(MESH_BED_LEVELING) + #if ENABLED(COREXZ) + 1 #endif - , "Select only one of: MESH_BED_LEVELING, AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_3POINT, AUTO_BED_LEVELING_BILINEAR or AUTO_BED_LEVELING_UBL." + #if ENABLED(COREYZ) + + 1 + #endif + #if ENABLED(COREYX) + + 1 + #endif + #if ENABLED(COREZX) + + 1 + #endif + #if ENABLED(COREZY) + + 1 + #endif + , "Please enable only one of DELTA, MORGAN_SCARA, MAKERARM_SCARA, COREXY, COREYX, COREXZ, COREZX, COREYZ, or COREZY." ); /** - * Mesh Bed Leveling + * Delta requirements */ -#if ENABLED(MESH_BED_LEVELING) - #if ENABLED(DELTA) - #error "MESH_BED_LEVELING does not yet support DELTA printers." - #elif GRID_MAX_POINTS_X > 9 || GRID_MAX_POINTS_Y > 9 - #error "GRID_MAX_POINTS_X and GRID_MAX_POINTS_Y must be less than 10 for MBL." - #endif -#endif - -/** - * Unified Bed Leveling - */ -#if ENABLED(AUTO_BED_LEVELING_UBL) - #if IS_SCARA - #error "AUTO_BED_LEVELING_UBL does not yet support SCARA printers." +#if ENABLED(DELTA) + #if DISABLED(USE_XMAX_PLUG) && DISABLED(USE_YMAX_PLUG) && DISABLED(USE_ZMAX_PLUG) + #error "You probably want to use Max Endstops for DELTA!" + #elif ENABLED(ENABLE_LEVELING_FADE_HEIGHT) && DISABLED(AUTO_BED_LEVELING_BILINEAR) && !UBL_DELTA + #error "ENABLE_LEVELING_FADE_HEIGHT on DELTA requires AUTO_BED_LEVELING_BILINEAR or AUTO_BED_LEVELING_UBL." + #elif ABL_GRID + #if (GRID_MAX_POINTS_X & 1) == 0 || (GRID_MAX_POINTS_Y & 1) == 0 + #error "DELTA requires GRID_MAX_POINTS_X and GRID_MAX_POINTS_Y to be odd numbers." + #elif GRID_MAX_POINTS_X < 3 + #error "DELTA requires GRID_MAX_POINTS_X and GRID_MAX_POINTS_Y to be 3 or higher." + #endif #endif #endif @@ -503,7 +499,6 @@ static_assert(1 >= 0 , "Please enable only one probe option: PROBE_MANUALLY, FIX_MOUNTED_PROBE, BLTOUCH, SOLENOID_PROBE, Z_PROBE_ALLEN_KEY, Z_PROBE_SLED, or Z Servo." ); - #if PROBE_SELECTED /** @@ -593,6 +588,114 @@ static_assert(1 >= 0 #endif +/** + * Allow only one bed leveling option to be defined + */ +static_assert(1 >= 0 + #if ENABLED(AUTO_BED_LEVELING_LINEAR) + + 1 + #endif + #if ENABLED(AUTO_BED_LEVELING_3POINT) + + 1 + #endif + #if ENABLED(AUTO_BED_LEVELING_BILINEAR) + + 1 + #endif + #if ENABLED(AUTO_BED_LEVELING_UBL) + + 1 + #endif + #if ENABLED(MESH_BED_LEVELING) + + 1 + #endif + , "Select only one of: MESH_BED_LEVELING, AUTO_BED_LEVELING_LINEAR, AUTO_BED_LEVELING_3POINT, AUTO_BED_LEVELING_BILINEAR or AUTO_BED_LEVELING_UBL." +); + +/** + * Bed Leveling Requirements + */ + +#if ENABLED(AUTO_BED_LEVELING_UBL) + + /** + * Unified Bed Leveling + */ + + #if IS_SCARA + #error "AUTO_BED_LEVELING_UBL does not yet support SCARA printers." + #elif DISABLED(EEPROM_SETTINGS) + #error "AUTO_BED_LEVELING_UBL requires EEPROM_SETTINGS. Please update your configuration." + #elif !WITHIN(GRID_MAX_POINTS_X, 3, 15) || !WITHIN(GRID_MAX_POINTS_Y, 3, 15) + #error "GRID_MAX_POINTS_[XY] must be a whole number between 3 and 15." + #else + static_assert(WITHIN(UBL_PROBE_PT_1_X, MIN_PROBE_X, MAX_PROBE_X), "UBL_PROBE_PT_1_X can't be reached by the Z probe."); + static_assert(WITHIN(UBL_PROBE_PT_2_X, MIN_PROBE_X, MAX_PROBE_X), "UBL_PROBE_PT_2_X can't be reached by the Z probe."); + static_assert(WITHIN(UBL_PROBE_PT_3_X, MIN_PROBE_X, MAX_PROBE_X), "UBL_PROBE_PT_3_X can't be reached by the Z probe."); + static_assert(WITHIN(UBL_PROBE_PT_1_Y, MIN_PROBE_Y, MAX_PROBE_Y), "UBL_PROBE_PT_1_Y can't be reached by the Z probe."); + static_assert(WITHIN(UBL_PROBE_PT_2_Y, MIN_PROBE_Y, MAX_PROBE_Y), "UBL_PROBE_PT_2_Y can't be reached by the Z probe."); + static_assert(WITHIN(UBL_PROBE_PT_3_Y, MIN_PROBE_Y, MAX_PROBE_Y), "UBL_PROBE_PT_3_Y can't be reached by the Z probe."); + #endif + +#elif HAS_ABL + + /** + * Auto Bed Leveling + */ + + #if ENABLED(USE_RAW_KINEMATICS) + #error "USE_RAW_KINEMATICS is not compatible with AUTO_BED_LEVELING" + #endif + + /** + * Delta and SCARA have limited bed leveling options + */ + #if IS_SCARA && DISABLED(AUTO_BED_LEVELING_BILINEAR) + #error "Only AUTO_BED_LEVELING_BILINEAR currently supports SCARA bed leveling." + #endif + + /** + * Check auto bed leveling probe points + */ + #if ABL_GRID + + #ifdef DELTA_PROBEABLE_RADIUS + static_assert(LEFT_PROBE_BED_POSITION >= -DELTA_PROBEABLE_RADIUS, "LEFT_PROBE_BED_POSITION must be within DELTA_PROBEABLE_RADIUS."); + static_assert(RIGHT_PROBE_BED_POSITION <= DELTA_PROBEABLE_RADIUS, "RIGHT_PROBE_BED_POSITION must be within DELTA_PROBEABLE_RADIUS."); + static_assert(FRONT_PROBE_BED_POSITION >= -DELTA_PROBEABLE_RADIUS, "FRONT_PROBE_BED_POSITION must be within DELTA_PROBEABLE_RADIUS."); + static_assert(BACK_PROBE_BED_POSITION <= DELTA_PROBEABLE_RADIUS, "BACK_PROBE_BED_POSITION must be within DELTA_PROBEABLE_RADIUS."); + #else + static_assert(LEFT_PROBE_BED_POSITION < RIGHT_PROBE_BED_POSITION, "LEFT_PROBE_BED_POSITION must be less than RIGHT_PROBE_BED_POSITION."); + static_assert(FRONT_PROBE_BED_POSITION < BACK_PROBE_BED_POSITION, "FRONT_PROBE_BED_POSITION must be less than BACK_PROBE_BED_POSITION."); + static_assert(LEFT_PROBE_BED_POSITION >= MIN_PROBE_X, "LEFT_PROBE_BED_POSITION can't be reached by the Z probe."); + static_assert(RIGHT_PROBE_BED_POSITION <= MAX_PROBE_X, "RIGHT_PROBE_BED_POSITION can't be reached by the Z probe."); + static_assert(FRONT_PROBE_BED_POSITION >= MIN_PROBE_Y, "FRONT_PROBE_BED_POSITION can't be reached by the Z probe."); + static_assert(BACK_PROBE_BED_POSITION <= MAX_PROBE_Y, "BACK_PROBE_BED_POSITION can't be reached by the Z probe."); + #endif + + #else // AUTO_BED_LEVELING_3POINT + + static_assert(WITHIN(ABL_PROBE_PT_1_X, MIN_PROBE_X, MAX_PROBE_X), "ABL_PROBE_PT_1_X can't be reached by the Z probe."); + static_assert(WITHIN(ABL_PROBE_PT_2_X, MIN_PROBE_X, MAX_PROBE_X), "ABL_PROBE_PT_2_X can't be reached by the Z probe."); + static_assert(WITHIN(ABL_PROBE_PT_3_X, MIN_PROBE_X, MAX_PROBE_X), "ABL_PROBE_PT_3_X can't be reached by the Z probe."); + static_assert(WITHIN(ABL_PROBE_PT_1_Y, MIN_PROBE_Y, MAX_PROBE_Y), "ABL_PROBE_PT_1_Y can't be reached by the Z probe."); + static_assert(WITHIN(ABL_PROBE_PT_2_Y, MIN_PROBE_Y, MAX_PROBE_Y), "ABL_PROBE_PT_2_Y can't be reached by the Z probe."); + static_assert(WITHIN(ABL_PROBE_PT_3_Y, MIN_PROBE_Y, MAX_PROBE_Y), "ABL_PROBE_PT_3_Y can't be reached by the Z probe."); + + #endif // AUTO_BED_LEVELING_3POINT + +#elif ENABLED(MESH_BED_LEVELING) + + /** + * Mesh Bed Leveling + */ + + #if ENABLED(DELTA) + #error "MESH_BED_LEVELING does not yet support DELTA printers." + #elif GRID_MAX_POINTS_X > 9 || GRID_MAX_POINTS_Y > 9 + #error "GRID_MAX_POINTS_X and GRID_MAX_POINTS_Y must be less than 10 for MBL." + #endif + +#endif + /** * LCD_BED_LEVELING requirements */ @@ -630,83 +733,6 @@ static_assert(1 >= 0 #endif #endif // Z_SAFE_HOMING -/** - * Auto Bed Leveling - */ -#if HAS_ABL - - #if ENABLED(USE_RAW_KINEMATICS) - #error "USE_RAW_KINEMATICS is not compatible with AUTO_BED_LEVELING" - #endif - - /** - * Delta and SCARA have limited bed leveling options - */ - #if IS_SCARA && DISABLED(AUTO_BED_LEVELING_BILINEAR) - #error "Only AUTO_BED_LEVELING_BILINEAR currently supports SCARA bed leveling." - #endif - - /** - * Check auto bed leveling sub-options, especially probe points - */ - #if ABL_GRID - #ifndef DELTA_PROBEABLE_RADIUS - #if LEFT_PROBE_BED_POSITION > RIGHT_PROBE_BED_POSITION - #error "LEFT_PROBE_BED_POSITION must be less than RIGHT_PROBE_BED_POSITION." - #elif FRONT_PROBE_BED_POSITION > BACK_PROBE_BED_POSITION - #error "FRONT_PROBE_BED_POSITION must be less than BACK_PROBE_BED_POSITION." - #endif - #if LEFT_PROBE_BED_POSITION < MIN_PROBE_X - #error "The given LEFT_PROBE_BED_POSITION can't be reached by the Z probe." - #elif RIGHT_PROBE_BED_POSITION > MAX_PROBE_X - #error "The given RIGHT_PROBE_BED_POSITION can't be reached by the Z probe." - #elif FRONT_PROBE_BED_POSITION < MIN_PROBE_Y - #error "The given FRONT_PROBE_BED_POSITION can't be reached by the Z probe." - #elif BACK_PROBE_BED_POSITION > MAX_PROBE_Y - #error "The given BACK_PROBE_BED_POSITION can't be reached by the Z probe." - #endif - #endif - #elif ENABLED(AUTO_BED_LEVELING_UBL) - #if DISABLED(EEPROM_SETTINGS) - #error "AUTO_BED_LEVELING_UBL requires EEPROM_SETTINGS. Please update your configuration." - #elif !WITHIN(GRID_MAX_POINTS_X, 3, 15) || !WITHIN(GRID_MAX_POINTS_Y, 3, 15) - #error "GRID_MAX_POINTS_[XY] must be a whole number between 3 and 15." - #endif - #if IS_CARTESIAN - #if !WITHIN(GRID_MAX_POINTS_X, 3, 15) || !WITHIN(GRID_MAX_POINTS_Y, 3, 15) - #error "GRID_MAX_POINTS_[XY] must be a whole number between 3 and 15." - #elif !WITHIN(UBL_PROBE_PT_1_X, MIN_PROBE_X, MAX_PROBE_X) - #error "The given UBL_PROBE_PT_1_X can't be reached by the Z probe." - #elif !WITHIN(UBL_PROBE_PT_2_X, MIN_PROBE_X, MAX_PROBE_X) - #error "The given UBL_PROBE_PT_2_X can't be reached by the Z probe." - #elif !WITHIN(UBL_PROBE_PT_3_X, MIN_PROBE_X, MAX_PROBE_X) - #error "The given UBL_PROBE_PT_3_X can't be reached by the Z probe." - #elif !WITHIN(UBL_PROBE_PT_1_Y, MIN_PROBE_Y, MAX_PROBE_Y) - #error "The given UBL_PROBE_PT_1_Y can't be reached by the Z probe." - #elif !WITHIN(UBL_PROBE_PT_2_Y, MIN_PROBE_Y, MAX_PROBE_Y) - #error "The given UBL_PROBE_PT_2_Y can't be reached by the Z probe." - #elif !WITHIN(UBL_PROBE_PT_3_Y, MIN_PROBE_Y, MAX_PROBE_Y) - #error "The given UBL_PROBE_PT_3_Y can't be reached by the Z probe." - #endif - #endif - #else // AUTO_BED_LEVELING_3POINT - #if !WITHIN(ABL_PROBE_PT_1_X, MIN_PROBE_X, MAX_PROBE_X) - #error "The given ABL_PROBE_PT_1_X can't be reached by the Z probe." - #elif !WITHIN(ABL_PROBE_PT_2_X, MIN_PROBE_X, MAX_PROBE_X) - #error "The given ABL_PROBE_PT_2_X can't be reached by the Z probe." - #elif !WITHIN(ABL_PROBE_PT_3_X, MIN_PROBE_X, MAX_PROBE_X) - #error "The given ABL_PROBE_PT_3_X can't be reached by the Z probe." - #elif !WITHIN(ABL_PROBE_PT_1_Y, MIN_PROBE_Y, MAX_PROBE_Y) - #error "The given ABL_PROBE_PT_1_Y can't be reached by the Z probe." - #elif !WITHIN(ABL_PROBE_PT_2_Y, MIN_PROBE_Y, MAX_PROBE_Y) - #error "The given ABL_PROBE_PT_2_Y can't be reached by the Z probe." - #elif !WITHIN(ABL_PROBE_PT_3_Y, MIN_PROBE_Y, MAX_PROBE_Y) - #error "The given ABL_PROBE_PT_3_Y can't be reached by the Z probe." - #endif - #endif // AUTO_BED_LEVELING_3POINT - -#endif // HAS_ABL - /** * Advance Extrusion */ @@ -739,40 +765,6 @@ static_assert(1 >= 0 #error "Only enable one SAV_3DGLCD display type: U8GLIB_SSD1306 or U8GLIB_SH1106." #endif -/** - * Don't set more than one kinematic type - */ -static_assert(1 >= 0 - #if ENABLED(DELTA) - + 1 - #endif - #if ENABLED(MORGAN_SCARA) - + 1 - #endif - #if ENABLED(MAKERARM_SCARA) - + 1 - #endif - #if ENABLED(COREXY) - + 1 - #endif - #if ENABLED(COREXZ) - + 1 - #endif - #if ENABLED(COREYZ) - + 1 - #endif - #if ENABLED(COREYX) - + 1 - #endif - #if ENABLED(COREZX) - + 1 - #endif - #if ENABLED(COREZY) - + 1 - #endif - , "Please enable only one of DELTA, MORGAN_SCARA, MAKERARM_SCARA, COREXY, COREYX, COREXZ, COREZX, COREYZ, or COREZY." -); - /** * Allen Key * Deploying the Allen Key probe uses big moves in z direction. Too dangerous for an unhomed z-axis. @@ -1147,22 +1139,64 @@ static_assert(1 >= 0 , "Please select no more than one LCD controller option." ); -#if ENABLED(HAVE_TMC2130) && !( \ - ENABLED( X_IS_TMC2130 ) \ - || ENABLED( X2_IS_TMC2130 ) \ - || ENABLED( Y_IS_TMC2130 ) \ - || ENABLED( Y2_IS_TMC2130 ) \ - || ENABLED( Z_IS_TMC2130 ) \ - || ENABLED( Z2_IS_TMC2130 ) \ - || ENABLED( E0_IS_TMC2130 ) \ - || ENABLED( E1_IS_TMC2130 ) \ - || ENABLED( E2_IS_TMC2130 ) \ - || ENABLED( E3_IS_TMC2130 ) ) - #error "Choose at least one TMC2130 stepper." +/** + * Make sure HAVE_TMCDRIVER is warranted + */ +#if ENABLED(HAVE_TMCDRIVER) && !( \ + ENABLED( X_IS_TMC ) \ + || ENABLED( X2_IS_TMC ) \ + || ENABLED( Y_IS_TMC ) \ + || ENABLED( Y2_IS_TMC ) \ + || ENABLED( Z_IS_TMC ) \ + || ENABLED( Z2_IS_TMC ) \ + || ENABLED( E0_IS_TMC ) \ + || ENABLED( E1_IS_TMC ) \ + || ENABLED( E2_IS_TMC ) \ + || ENABLED( E3_IS_TMC ) \ + || ENABLED( E4_IS_TMC ) \ + ) + #error "HAVE_TMCDRIVER requires at least one TMC stepper to be set." #endif -#if ENABLED(HYBRID_THRESHOLD) && DISABLED(STEALTHCHOP) - #error "Enable STEALTHCHOP to use HYBRID_THRESHOLD." +/** + * Make sure HAVE_TMC2130 is warranted + */ +#if ENABLED(HAVE_TMC2130) + #if !( ENABLED( X_IS_TMC2130 ) \ + || ENABLED( X2_IS_TMC2130 ) \ + || ENABLED( Y_IS_TMC2130 ) \ + || ENABLED( Y2_IS_TMC2130 ) \ + || ENABLED( Z_IS_TMC2130 ) \ + || ENABLED( Z2_IS_TMC2130 ) \ + || ENABLED( E0_IS_TMC2130 ) \ + || ENABLED( E1_IS_TMC2130 ) \ + || ENABLED( E2_IS_TMC2130 ) \ + || ENABLED( E3_IS_TMC2130 ) \ + || ENABLED( E4_IS_TMC2130 ) \ + ) + #error "HAVE_TMC2130 requires at least one TMC2130 stepper to be set." + #elif ENABLED(HYBRID_THRESHOLD) && DISABLED(STEALTHCHOP) + #error "Enable STEALTHCHOP to use HYBRID_THRESHOLD." + #endif +#endif + +/** + * Make sure HAVE_L6470DRIVER is warranted + */ +#if ENABLED(HAVE_L6470DRIVER) && !( \ + ENABLED( X_IS_L6470 ) \ + || ENABLED( X2_IS_L6470 ) \ + || ENABLED( Y_IS_L6470 ) \ + || ENABLED( Y2_IS_L6470 ) \ + || ENABLED( Z_IS_L6470 ) \ + || ENABLED( Z2_IS_L6470 ) \ + || ENABLED( E0_IS_L6470 ) \ + || ENABLED( E1_IS_L6470 ) \ + || ENABLED( E2_IS_L6470 ) \ + || ENABLED( E3_IS_L6470 ) \ + || ENABLED( E4_IS_L6470 ) \ + ) + #error "HAVE_L6470DRIVER requires at least one L6470 stepper to be set." #endif /** From dac29e0f7526e9ca5e59b8827e4530a02fb48212 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 7 Jun 2017 06:14:24 -0500 Subject: [PATCH 028/180] Cleaner failure of UBL without EEPROM --- Marlin/Marlin_main.cpp | 51 +++++++++++++++++++++++++----------------- 1 file changed, 30 insertions(+), 21 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 4bbd804984..f66d1c6d4f 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -8866,25 +8866,43 @@ void quickstop_stepper() { inline void gcode_M420() { #if ENABLED(AUTO_BED_LEVELING_UBL) + // L to load a mesh from the EEPROM if (parser.seen('L')) { - const int8_t storage_slot = parser.has_value() ? parser.value_int() : ubl.state.storage_slot; - const int16_t a = settings.calc_num_meshes(); - if (!a) { + #if ENABLED(EEPROM_SETTINGS) + const int8_t storage_slot = parser.has_value() ? parser.value_int() : ubl.state.storage_slot; + const int16_t a = settings.calc_num_meshes(); + + if (!a) { + SERIAL_PROTOCOLLNPGM("?EEPROM storage not available."); + return; + } + + if (!WITHIN(storage_slot, 0, a - 1)) { + SERIAL_PROTOCOLLNPGM("?Invalid storage slot."); + SERIAL_PROTOCOLLNPAIR("?Use 0 to ", a - 1); + return; + } + + settings.load_mesh(storage_slot); + ubl.state.storage_slot = storage_slot; + + #else + SERIAL_PROTOCOLLNPGM("?EEPROM storage not available."); return; - } - if (!WITHIN(storage_slot, 0, a - 1)) { - SERIAL_PROTOCOLLNPGM("?Invalid storage slot."); - SERIAL_PROTOCOLLNPAIR("?Use 0 to ", a - 1); - return; - } - - settings.load_mesh(storage_slot); - ubl.state.storage_slot = storage_slot; + #endif } + + // L to load a mesh from the EEPROM + if (parser.seen('L') || parser.seen('V')) { + ubl.display_map(0); // Currently only supports one map type + SERIAL_ECHOLNPAIR("UBL_MESH_VALID = ", UBL_MESH_VALID); + SERIAL_ECHOLNPAIR("ubl.state.storage_slot = ", ubl.state.storage_slot); + } + #endif // AUTO_BED_LEVELING_UBL // V to print the matrix or mesh @@ -8906,15 +8924,6 @@ void quickstop_stepper() { #endif } - #if ENABLED(AUTO_BED_LEVELING_UBL) - // L to load a mesh from the EEPROM - if (parser.seen('L') || parser.seen('V')) { - ubl.display_map(0); // Currently only supports one map type - SERIAL_ECHOLNPAIR("UBL_MESH_VALID = ", UBL_MESH_VALID); - SERIAL_ECHOLNPAIR("ubl.state.storage_slot = ", ubl.state.storage_slot); - } - #endif - bool to_enable = false; if (parser.seen('S')) { to_enable = parser.value_bool(); From a27b08e6af12782c17e19ba9d87198048b988aee Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 7 Jun 2017 07:12:19 -0500 Subject: [PATCH 029/180] Various code style tweaks --- Marlin/G26_Mesh_Validation_Tool.cpp | 16 ++--- Marlin/Marlin_main.cpp | 100 ++++++++++++++++------------ Marlin/ubl.h | 5 +- Marlin/ubl_motion.cpp | 18 +++-- 4 files changed, 76 insertions(+), 63 deletions(-) diff --git a/Marlin/G26_Mesh_Validation_Tool.cpp b/Marlin/G26_Mesh_Validation_Tool.cpp index 5c8802ef41..d8cc62e0ea 100644 --- a/Marlin/G26_Mesh_Validation_Tool.cpp +++ b/Marlin/G26_Mesh_Validation_Tool.cpp @@ -252,8 +252,8 @@ // Move nozzle to the specified height for the first layer set_destination_to_current(); destination[Z_AXIS] = g26_layer_height; - move_to(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], 0.0); - move_to(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], g26_ooze_amount); + move_to(destination, 0.0); + move_to(destination, g26_ooze_amount); has_control_of_lcd_panel = true; //debug_current_and_destination(PSTR("Starting G26 Mesh Validation Pattern.")); @@ -368,14 +368,14 @@ destination[Z_AXIS] = Z_CLEARANCE_BETWEEN_PROBES; //debug_current_and_destination(PSTR("ready to do Z-Raise.")); - move_to(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], 0); // Raise the nozzle + move_to(destination, 0); // Raise the nozzle //debug_current_and_destination(PSTR("done doing Z-Raise.")); destination[X_AXIS] = g26_x_pos; // Move back to the starting position destination[Y_AXIS] = g26_y_pos; //destination[Z_AXIS] = Z_CLEARANCE_BETWEEN_PROBES; // Keep the nozzle where it is - move_to(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], 0); // Move back to the starting position + move_to(destination, 0); // Move back to the starting position //debug_current_and_destination(PSTR("done doing X/Y move.")); has_control_of_lcd_panel = false; // Give back control of the LCD Panel! @@ -554,16 +554,16 @@ } - void unified_bed_leveling::retract_filament(float where[XYZE]) { + void unified_bed_leveling::retract_filament(const float where[XYZE]) { if (!g26_retracted) { // Only retract if we are not already retracted! g26_retracted = true; - move_to(where[X_AXIS], where[Y_AXIS], where[Z_AXIS], -1.0 * g26_retraction_multiplier); + move_to(where, -1.0 * g26_retraction_multiplier); } } - void unified_bed_leveling::recover_filament(float where[XYZE]) { + void unified_bed_leveling::recover_filament(const float where[XYZE]) { if (g26_retracted) { // Only un-retract if we are retracted. - move_to(where[X_AXIS], where[Y_AXIS], where[Z_AXIS], 1.2 * g26_retraction_multiplier); + move_to(where, 1.2 * g26_retraction_multiplier); g26_retracted = false; } } diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index f66d1c6d4f..5a1d1504d1 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -1561,16 +1561,16 @@ inline void set_destination_to_current() { COPY(destination, current_position); * Plan a move to (X, Y, Z) and set the current_position * The final current_position may not be the one that was requested */ -void do_blocking_move_to(const float &x, const float &y, const float &z, const float &fr_mm_s /*=0.0*/) { +void do_blocking_move_to(const float &lx, const float &ly, const float &lz, const float &fr_mm_s/*=0.0*/) { const float old_feedrate_mm_s = feedrate_mm_s; #if ENABLED(DEBUG_LEVELING_FEATURE) - if (DEBUGGING(LEVELING)) print_xyz(PSTR(">>> do_blocking_move_to"), NULL, x, y, z); + if (DEBUGGING(LEVELING)) print_xyz(PSTR(">>> do_blocking_move_to"), NULL, lx, ly, lz); #endif #if ENABLED(DELTA) - if (!position_is_reachable_xy(x, y)) return; + if (!position_is_reachable_xy(lx, ly)) return; feedrate_mm_s = fr_mm_s ? fr_mm_s : XY_PROBE_FEEDRATE_MM_S; @@ -1582,10 +1582,10 @@ void do_blocking_move_to(const float &x, const float &y, const float &z, const f // when in the danger zone if (current_position[Z_AXIS] > delta_clip_start_height) { - if (z > delta_clip_start_height) { // staying in the danger zone - destination[X_AXIS] = x; // move directly (uninterpolated) - destination[Y_AXIS] = y; - destination[Z_AXIS] = z; + if (lz > delta_clip_start_height) { // staying in the danger zone + destination[X_AXIS] = lx; // move directly (uninterpolated) + destination[Y_AXIS] = ly; + destination[Z_AXIS] = lz; prepare_uninterpolated_move_to_destination(); // set_current_to_destination #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) DEBUG_POS("danger zone move", current_position); @@ -1601,23 +1601,23 @@ void do_blocking_move_to(const float &x, const float &y, const float &z, const f } } - if (z > current_position[Z_AXIS]) { // raising? - destination[Z_AXIS] = z; + if (lz > current_position[Z_AXIS]) { // raising? + destination[Z_AXIS] = lz; prepare_uninterpolated_move_to_destination(); // set_current_to_destination #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) DEBUG_POS("z raise move", current_position); #endif } - destination[X_AXIS] = x; - destination[Y_AXIS] = y; + destination[X_AXIS] = lx; + destination[Y_AXIS] = ly; prepare_move_to_destination(); // set_current_to_destination #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) DEBUG_POS("xy move", current_position); #endif - if (z < current_position[Z_AXIS]) { // lowering? - destination[Z_AXIS] = z; + if (lz < current_position[Z_AXIS]) { // lowering? + destination[Z_AXIS] = lz; prepare_uninterpolated_move_to_destination(); // set_current_to_destination #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) DEBUG_POS("z lower move", current_position); @@ -1626,44 +1626,44 @@ void do_blocking_move_to(const float &x, const float &y, const float &z, const f #elif IS_SCARA - if (!position_is_reachable_xy(x, y)) return; + if (!position_is_reachable_xy(lx, ly)) return; set_destination_to_current(); // If Z needs to raise, do it before moving XY - if (destination[Z_AXIS] < z) { - destination[Z_AXIS] = z; + if (destination[Z_AXIS] < lz) { + destination[Z_AXIS] = lz; prepare_uninterpolated_move_to_destination(fr_mm_s ? fr_mm_s : homing_feedrate(Z_AXIS)); } - destination[X_AXIS] = x; - destination[Y_AXIS] = y; + destination[X_AXIS] = lx; + destination[Y_AXIS] = ly; prepare_uninterpolated_move_to_destination(fr_mm_s ? fr_mm_s : XY_PROBE_FEEDRATE_MM_S); // If Z needs to lower, do it after moving XY - if (destination[Z_AXIS] > z) { - destination[Z_AXIS] = z; + if (destination[Z_AXIS] > lz) { + destination[Z_AXIS] = lz; prepare_uninterpolated_move_to_destination(fr_mm_s ? fr_mm_s : homing_feedrate(Z_AXIS)); } #else // If Z needs to raise, do it before moving XY - if (current_position[Z_AXIS] < z) { + if (current_position[Z_AXIS] < lz) { feedrate_mm_s = fr_mm_s ? fr_mm_s : homing_feedrate(Z_AXIS); - current_position[Z_AXIS] = z; + current_position[Z_AXIS] = lz; line_to_current_position(); } feedrate_mm_s = fr_mm_s ? fr_mm_s : XY_PROBE_FEEDRATE_MM_S; - current_position[X_AXIS] = x; - current_position[Y_AXIS] = y; + current_position[X_AXIS] = lx; + current_position[Y_AXIS] = ly; line_to_current_position(); // If Z needs to lower, do it after moving XY - if (current_position[Z_AXIS] > z) { + if (current_position[Z_AXIS] > lz) { feedrate_mm_s = fr_mm_s ? fr_mm_s : homing_feedrate(Z_AXIS); - current_position[Z_AXIS] = z; + current_position[Z_AXIS] = lz; line_to_current_position(); } @@ -1677,14 +1677,14 @@ void do_blocking_move_to(const float &x, const float &y, const float &z, const f if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("<<< do_blocking_move_to"); #endif } -void do_blocking_move_to_x(const float &x, const float &fr_mm_s/*=0.0*/) { - do_blocking_move_to(x, current_position[Y_AXIS], current_position[Z_AXIS], fr_mm_s); +void do_blocking_move_to_x(const float &lx, const float &fr_mm_s/*=0.0*/) { + do_blocking_move_to(lx, current_position[Y_AXIS], current_position[Z_AXIS], fr_mm_s); } -void do_blocking_move_to_z(const float &z, const float &fr_mm_s/*=0.0*/) { - do_blocking_move_to(current_position[X_AXIS], current_position[Y_AXIS], z, fr_mm_s); +void do_blocking_move_to_z(const float &lz, const float &fr_mm_s/*=0.0*/) { + do_blocking_move_to(current_position[X_AXIS], current_position[Y_AXIS], lz, fr_mm_s); } -void do_blocking_move_to_xy(const float &x, const float &y, const float &fr_mm_s/*=0.0*/) { - do_blocking_move_to(x, y, current_position[Z_AXIS], fr_mm_s); +void do_blocking_move_to_xy(const float &lx, const float &ly, const float &fr_mm_s/*=0.0*/) { + do_blocking_move_to(lx, ly, current_position[Z_AXIS], fr_mm_s); } // @@ -1719,7 +1719,7 @@ static void clean_up_after_endstop_or_probe_move() { /** * Raise Z to a minimum height to make room for a probe to move */ - inline void do_probe_raise(float z_raise) { + inline void do_probe_raise(const float z_raise) { #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) { SERIAL_ECHOPAIR("do_probe_raise(", z_raise); @@ -1801,6 +1801,10 @@ static void clean_up_after_endstop_or_probe_move() { #elif ENABLED(Z_PROBE_ALLEN_KEY) + FORCE_INLINE void do_blocking_move_to(const float logical[XYZ], const float &fr_mm_s) { + do_blocking_move_to(logical[X_AXIS], logical[Y_AXIS], logical[Z_AXIS], fr_mm_s); + } + void run_deploy_moves_script() { #if defined(Z_PROBE_ALLEN_KEY_DEPLOY_1_X) || defined(Z_PROBE_ALLEN_KEY_DEPLOY_1_Y) || defined(Z_PROBE_ALLEN_KEY_DEPLOY_1_Z) #ifndef Z_PROBE_ALLEN_KEY_DEPLOY_1_X @@ -1815,7 +1819,8 @@ static void clean_up_after_endstop_or_probe_move() { #ifndef Z_PROBE_ALLEN_KEY_DEPLOY_1_FEEDRATE #define Z_PROBE_ALLEN_KEY_DEPLOY_1_FEEDRATE 0.0 #endif - do_blocking_move_to(Z_PROBE_ALLEN_KEY_DEPLOY_1_X, Z_PROBE_ALLEN_KEY_DEPLOY_1_Y, Z_PROBE_ALLEN_KEY_DEPLOY_1_Z, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_DEPLOY_1_FEEDRATE)); + const float deploy_1[] = { Z_PROBE_ALLEN_KEY_DEPLOY_1_X, Z_PROBE_ALLEN_KEY_DEPLOY_1_Y, Z_PROBE_ALLEN_KEY_DEPLOY_1_Z }; + do_blocking_move_to(deploy_1, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_DEPLOY_1_FEEDRATE)); #endif #if defined(Z_PROBE_ALLEN_KEY_DEPLOY_2_X) || defined(Z_PROBE_ALLEN_KEY_DEPLOY_2_Y) || defined(Z_PROBE_ALLEN_KEY_DEPLOY_2_Z) #ifndef Z_PROBE_ALLEN_KEY_DEPLOY_2_X @@ -1830,7 +1835,8 @@ static void clean_up_after_endstop_or_probe_move() { #ifndef Z_PROBE_ALLEN_KEY_DEPLOY_2_FEEDRATE #define Z_PROBE_ALLEN_KEY_DEPLOY_2_FEEDRATE 0.0 #endif - do_blocking_move_to(Z_PROBE_ALLEN_KEY_DEPLOY_2_X, Z_PROBE_ALLEN_KEY_DEPLOY_2_Y, Z_PROBE_ALLEN_KEY_DEPLOY_2_Z, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_DEPLOY_2_FEEDRATE)); + const float deploy_2[] = { Z_PROBE_ALLEN_KEY_DEPLOY_2_X, Z_PROBE_ALLEN_KEY_DEPLOY_2_Y, Z_PROBE_ALLEN_KEY_DEPLOY_2_Z }; + do_blocking_move_to(deploy_2, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_DEPLOY_2_FEEDRATE)); #endif #if defined(Z_PROBE_ALLEN_KEY_DEPLOY_3_X) || defined(Z_PROBE_ALLEN_KEY_DEPLOY_3_Y) || defined(Z_PROBE_ALLEN_KEY_DEPLOY_3_Z) #ifndef Z_PROBE_ALLEN_KEY_DEPLOY_3_X @@ -1845,7 +1851,8 @@ static void clean_up_after_endstop_or_probe_move() { #ifndef Z_PROBE_ALLEN_KEY_DEPLOY_3_FEEDRATE #define Z_PROBE_ALLEN_KEY_DEPLOY_3_FEEDRATE 0.0 #endif - do_blocking_move_to(Z_PROBE_ALLEN_KEY_DEPLOY_3_X, Z_PROBE_ALLEN_KEY_DEPLOY_3_Y, Z_PROBE_ALLEN_KEY_DEPLOY_3_Z, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_DEPLOY_3_FEEDRATE)); + const float deploy_3[] = { Z_PROBE_ALLEN_KEY_DEPLOY_3_X, Z_PROBE_ALLEN_KEY_DEPLOY_3_Y, Z_PROBE_ALLEN_KEY_DEPLOY_3_Z }; + do_blocking_move_to(deploy_3, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_DEPLOY_3_FEEDRATE)); #endif #if defined(Z_PROBE_ALLEN_KEY_DEPLOY_4_X) || defined(Z_PROBE_ALLEN_KEY_DEPLOY_4_Y) || defined(Z_PROBE_ALLEN_KEY_DEPLOY_4_Z) #ifndef Z_PROBE_ALLEN_KEY_DEPLOY_4_X @@ -1860,7 +1867,8 @@ static void clean_up_after_endstop_or_probe_move() { #ifndef Z_PROBE_ALLEN_KEY_DEPLOY_4_FEEDRATE #define Z_PROBE_ALLEN_KEY_DEPLOY_4_FEEDRATE 0.0 #endif - do_blocking_move_to(Z_PROBE_ALLEN_KEY_DEPLOY_4_X, Z_PROBE_ALLEN_KEY_DEPLOY_4_Y, Z_PROBE_ALLEN_KEY_DEPLOY_4_Z, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_DEPLOY_4_FEEDRATE)); + const float deploy_4[] = { Z_PROBE_ALLEN_KEY_DEPLOY_4_X, Z_PROBE_ALLEN_KEY_DEPLOY_4_Y, Z_PROBE_ALLEN_KEY_DEPLOY_4_Z }; + do_blocking_move_to(deploy_4, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_DEPLOY_4_FEEDRATE)); #endif #if defined(Z_PROBE_ALLEN_KEY_DEPLOY_5_X) || defined(Z_PROBE_ALLEN_KEY_DEPLOY_5_Y) || defined(Z_PROBE_ALLEN_KEY_DEPLOY_5_Z) #ifndef Z_PROBE_ALLEN_KEY_DEPLOY_5_X @@ -1875,7 +1883,8 @@ static void clean_up_after_endstop_or_probe_move() { #ifndef Z_PROBE_ALLEN_KEY_DEPLOY_5_FEEDRATE #define Z_PROBE_ALLEN_KEY_DEPLOY_5_FEEDRATE 0.0 #endif - do_blocking_move_to(Z_PROBE_ALLEN_KEY_DEPLOY_5_X, Z_PROBE_ALLEN_KEY_DEPLOY_5_Y, Z_PROBE_ALLEN_KEY_DEPLOY_5_Z, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_DEPLOY_5_FEEDRATE)); + const float deploy_5[] = { Z_PROBE_ALLEN_KEY_DEPLOY_5_X, Z_PROBE_ALLEN_KEY_DEPLOY_5_Y, Z_PROBE_ALLEN_KEY_DEPLOY_5_Z }; + do_blocking_move_to(deploy_5, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_DEPLOY_5_FEEDRATE)); #endif } @@ -1893,7 +1902,8 @@ static void clean_up_after_endstop_or_probe_move() { #ifndef Z_PROBE_ALLEN_KEY_STOW_1_FEEDRATE #define Z_PROBE_ALLEN_KEY_STOW_1_FEEDRATE 0.0 #endif - do_blocking_move_to(Z_PROBE_ALLEN_KEY_STOW_1_X, Z_PROBE_ALLEN_KEY_STOW_1_Y, Z_PROBE_ALLEN_KEY_STOW_1_Z, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_STOW_1_FEEDRATE)); + const float stow_1[] = { Z_PROBE_ALLEN_KEY_STOW_1_X, Z_PROBE_ALLEN_KEY_STOW_1_Y, Z_PROBE_ALLEN_KEY_STOW_1_Z }; + do_blocking_move_to(stow_1, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_STOW_1_FEEDRATE)); #endif #if defined(Z_PROBE_ALLEN_KEY_STOW_2_X) || defined(Z_PROBE_ALLEN_KEY_STOW_2_Y) || defined(Z_PROBE_ALLEN_KEY_STOW_2_Z) #ifndef Z_PROBE_ALLEN_KEY_STOW_2_X @@ -1908,7 +1918,8 @@ static void clean_up_after_endstop_or_probe_move() { #ifndef Z_PROBE_ALLEN_KEY_STOW_2_FEEDRATE #define Z_PROBE_ALLEN_KEY_STOW_2_FEEDRATE 0.0 #endif - do_blocking_move_to(Z_PROBE_ALLEN_KEY_STOW_2_X, Z_PROBE_ALLEN_KEY_STOW_2_Y, Z_PROBE_ALLEN_KEY_STOW_2_Z, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_STOW_2_FEEDRATE)); + const float stow_2[] = { Z_PROBE_ALLEN_KEY_STOW_2_X, Z_PROBE_ALLEN_KEY_STOW_2_Y, Z_PROBE_ALLEN_KEY_STOW_2_Z }; + do_blocking_move_to(stow_2, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_STOW_2_FEEDRATE)); #endif #if defined(Z_PROBE_ALLEN_KEY_STOW_3_X) || defined(Z_PROBE_ALLEN_KEY_STOW_3_Y) || defined(Z_PROBE_ALLEN_KEY_STOW_3_Z) #ifndef Z_PROBE_ALLEN_KEY_STOW_3_X @@ -1923,7 +1934,8 @@ static void clean_up_after_endstop_or_probe_move() { #ifndef Z_PROBE_ALLEN_KEY_STOW_3_FEEDRATE #define Z_PROBE_ALLEN_KEY_STOW_3_FEEDRATE 0.0 #endif - do_blocking_move_to(Z_PROBE_ALLEN_KEY_STOW_3_X, Z_PROBE_ALLEN_KEY_STOW_3_Y, Z_PROBE_ALLEN_KEY_STOW_3_Z, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_STOW_3_FEEDRATE)); + const float stow_3[] = { Z_PROBE_ALLEN_KEY_STOW_3_X, Z_PROBE_ALLEN_KEY_STOW_3_Y, Z_PROBE_ALLEN_KEY_STOW_3_Z }; + do_blocking_move_to(stow_3, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_STOW_3_FEEDRATE)); #endif #if defined(Z_PROBE_ALLEN_KEY_STOW_4_X) || defined(Z_PROBE_ALLEN_KEY_STOW_4_Y) || defined(Z_PROBE_ALLEN_KEY_STOW_4_Z) #ifndef Z_PROBE_ALLEN_KEY_STOW_4_X @@ -1938,7 +1950,8 @@ static void clean_up_after_endstop_or_probe_move() { #ifndef Z_PROBE_ALLEN_KEY_STOW_4_FEEDRATE #define Z_PROBE_ALLEN_KEY_STOW_4_FEEDRATE 0.0 #endif - do_blocking_move_to(Z_PROBE_ALLEN_KEY_STOW_4_X, Z_PROBE_ALLEN_KEY_STOW_4_Y, Z_PROBE_ALLEN_KEY_STOW_4_Z, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_STOW_4_FEEDRATE)); + const float stow_4[] = { Z_PROBE_ALLEN_KEY_STOW_4_X, Z_PROBE_ALLEN_KEY_STOW_4_Y, Z_PROBE_ALLEN_KEY_STOW_4_Z }; + do_blocking_move_to(stow_4, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_STOW_4_FEEDRATE)); #endif #if defined(Z_PROBE_ALLEN_KEY_STOW_5_X) || defined(Z_PROBE_ALLEN_KEY_STOW_5_Y) || defined(Z_PROBE_ALLEN_KEY_STOW_5_Z) #ifndef Z_PROBE_ALLEN_KEY_STOW_5_X @@ -1953,7 +1966,8 @@ static void clean_up_after_endstop_or_probe_move() { #ifndef Z_PROBE_ALLEN_KEY_STOW_5_FEEDRATE #define Z_PROBE_ALLEN_KEY_STOW_5_FEEDRATE 0.0 #endif - do_blocking_move_to(Z_PROBE_ALLEN_KEY_STOW_5_X, Z_PROBE_ALLEN_KEY_STOW_5_Y, Z_PROBE_ALLEN_KEY_STOW_5_Z, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_STOW_5_FEEDRATE)); + const float stow_5[] = { Z_PROBE_ALLEN_KEY_STOW_5_X, Z_PROBE_ALLEN_KEY_STOW_5_Y, Z_PROBE_ALLEN_KEY_STOW_5_Z }; + do_blocking_move_to(stow_5, MMM_TO_MMS(Z_PROBE_ALLEN_KEY_STOW_5_FEEDRATE)); #endif } diff --git a/Marlin/ubl.h b/Marlin/ubl.h index 29ee83c358..d060f8f6b0 100644 --- a/Marlin/ubl.h +++ b/Marlin/ubl.h @@ -138,10 +138,11 @@ static bool look_for_lines_to_connect(); static bool turn_on_heaters(); static bool prime_nozzle(); - static void retract_filament(float where[XYZE]); - static void recover_filament(float where[XYZE]); + static void retract_filament(const float where[XYZE]); + static void recover_filament(const float where[XYZE]); static void print_line_from_here_to_there(const float&, const float&, const float&, const float&, const float&, const float&); static void move_to(const float&, const float&, const float&, const float&); + inline static void move_to(const float where[XYZE], const float &de) { move_to(where[X_AXIS], where[Y_AXIS], where[Z_AXIS], de); } #endif public: diff --git a/Marlin/ubl_motion.cpp b/Marlin/ubl_motion.cpp index 3eccee9b52..396251fb79 100644 --- a/Marlin/ubl_motion.cpp +++ b/Marlin/ubl_motion.cpp @@ -67,19 +67,17 @@ const float de = destination[E_AXIS] - current_position[E_AXIS]; - if (de == 0.0) return; + if (de == 0.0) return; // Printing moves only - const float dx = current_position[X_AXIS] - destination[X_AXIS], - dy = current_position[Y_AXIS] - destination[Y_AXIS], + const float dx = destination[X_AXIS] - current_position[X_AXIS], + dy = destination[Y_AXIS] - current_position[Y_AXIS], xy_dist = HYPOT(dx, dy); - if (xy_dist == 0.0) - return; - else { - SERIAL_ECHOPGM(" fpmm="); - const float fpmm = de / xy_dist; - SERIAL_ECHO_F(fpmm, 6); - } + if (xy_dist == 0.0) return; + + SERIAL_ECHOPGM(" fpmm="); + const float fpmm = de / xy_dist; + SERIAL_ECHO_F(fpmm, 6); SERIAL_ECHOPGM(" current=( "); SERIAL_ECHO_F(current_position[X_AXIS], 6); From e556ab1dff267245af93def2196469bc2b12739e Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 7 Jun 2017 09:40:07 -0500 Subject: [PATCH 030/180] Find three-point leveling points on Delta --- Marlin/Configuration.h | 6 ++++-- .../Cartesio/Configuration.h | 6 ++++-- .../example_configurations/Felix/Configuration.h | 6 ++++-- .../Felix/DUAL/Configuration.h | 6 ++++-- .../FolgerTech-i3-2020/Configuration.h | 6 ++++-- .../Hephestos/Configuration.h | 6 ++++-- .../Hephestos_2/Configuration.h | 6 ++++-- .../example_configurations/K8200/Configuration.h | 6 ++++-- .../example_configurations/K8400/Configuration.h | 6 ++++-- .../K8400/Dual-head/Configuration.h | 6 ++++-- .../example_configurations/M150/Configuration.h | 6 ++++-- .../RepRapWorld/Megatronics/Configuration.h | 6 ++++-- .../RigidBot/Configuration.h | 6 ++++-- .../example_configurations/SCARA/Configuration.h | 6 ++++-- .../example_configurations/TAZ4/Configuration.h | 6 ++++-- .../TinyBoy2/Configuration.h | 6 ++++-- .../WITBOX/Configuration.h | 6 ++++-- .../adafruit/ST7565/Configuration.h | 6 ++++-- .../delta/FLSUN/auto_calibrate/Configuration.h | 16 ++++++++++------ .../delta/FLSUN/kossel_mini/Configuration.h | 16 ++++++++++------ .../delta/generic/Configuration.h | 16 ++++++++++------ .../delta/kossel_mini/Configuration.h | 16 ++++++++++------ .../delta/kossel_pro/Configuration.h | 16 ++++++++++------ .../delta/kossel_xl/Configuration.h | 16 ++++++++++------ .../gCreate_gMax1.5+/Configuration.h | 6 ++++-- .../makibox/Configuration.h | 6 ++++-- .../tvrrug/Round2/Configuration.h | 6 ++++-- .../example_configurations/wt150/Configuration.h | 6 ++++-- 28 files changed, 148 insertions(+), 80 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 8b4735df1f..2ab907bafc 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -881,12 +881,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 diff --git a/Marlin/example_configurations/Cartesio/Configuration.h b/Marlin/example_configurations/Cartesio/Configuration.h index b3b487ed44..0ded77ad5c 100644 --- a/Marlin/example_configurations/Cartesio/Configuration.h +++ b/Marlin/example_configurations/Cartesio/Configuration.h @@ -878,12 +878,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 diff --git a/Marlin/example_configurations/Felix/Configuration.h b/Marlin/example_configurations/Felix/Configuration.h index 95ee044ec1..6956cfda03 100644 --- a/Marlin/example_configurations/Felix/Configuration.h +++ b/Marlin/example_configurations/Felix/Configuration.h @@ -862,12 +862,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 diff --git a/Marlin/example_configurations/Felix/DUAL/Configuration.h b/Marlin/example_configurations/Felix/DUAL/Configuration.h index 86e386e15f..183759c6d7 100644 --- a/Marlin/example_configurations/Felix/DUAL/Configuration.h +++ b/Marlin/example_configurations/Felix/DUAL/Configuration.h @@ -862,12 +862,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 diff --git a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h index ee45fa7bd5..370c0b2573 100644 --- a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h +++ b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h @@ -884,12 +884,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 10 - #define UBL_PROBE_PT_1_X 45 // These set the probe locations for when UBL does a 3-Point leveling - #define UBL_PROBE_PT_1_Y 170 // of the mesh. + + #define UBL_PROBE_PT_1_X 45 // Probing points for 3-Point leveling of the mesh + #define UBL_PROBE_PT_1_Y 170 #define UBL_PROBE_PT_2_X 45 #define UBL_PROBE_PT_2_Y 25 #define UBL_PROBE_PT_3_X 180 #define UBL_PROBE_PT_3_Y 25 + #define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation #define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle diff --git a/Marlin/example_configurations/Hephestos/Configuration.h b/Marlin/example_configurations/Hephestos/Configuration.h index affcb9c27b..dca9646126 100644 --- a/Marlin/example_configurations/Hephestos/Configuration.h +++ b/Marlin/example_configurations/Hephestos/Configuration.h @@ -870,12 +870,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 diff --git a/Marlin/example_configurations/Hephestos_2/Configuration.h b/Marlin/example_configurations/Hephestos_2/Configuration.h index cd0bae630a..98416e2c79 100644 --- a/Marlin/example_configurations/Hephestos_2/Configuration.h +++ b/Marlin/example_configurations/Hephestos_2/Configuration.h @@ -873,12 +873,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 diff --git a/Marlin/example_configurations/K8200/Configuration.h b/Marlin/example_configurations/K8200/Configuration.h index 6f5ce58ac1..369d315305 100644 --- a/Marlin/example_configurations/K8200/Configuration.h +++ b/Marlin/example_configurations/K8200/Configuration.h @@ -909,12 +909,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 diff --git a/Marlin/example_configurations/K8400/Configuration.h b/Marlin/example_configurations/K8400/Configuration.h index 5cc90ad08e..6b7a39efbe 100644 --- a/Marlin/example_configurations/K8400/Configuration.h +++ b/Marlin/example_configurations/K8400/Configuration.h @@ -880,12 +880,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 diff --git a/Marlin/example_configurations/K8400/Dual-head/Configuration.h b/Marlin/example_configurations/K8400/Dual-head/Configuration.h index 8c22763f7d..cfa443311d 100644 --- a/Marlin/example_configurations/K8400/Dual-head/Configuration.h +++ b/Marlin/example_configurations/K8400/Dual-head/Configuration.h @@ -880,12 +880,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 diff --git a/Marlin/example_configurations/M150/Configuration.h b/Marlin/example_configurations/M150/Configuration.h index 7a1a0eaf49..3c85ce9ab5 100644 --- a/Marlin/example_configurations/M150/Configuration.h +++ b/Marlin/example_configurations/M150/Configuration.h @@ -907,12 +907,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 diff --git a/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h b/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h index b887f6bce0..61ecc112a0 100644 --- a/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h +++ b/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h @@ -880,12 +880,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 diff --git a/Marlin/example_configurations/RigidBot/Configuration.h b/Marlin/example_configurations/RigidBot/Configuration.h index 92276ee9ec..7648087a05 100644 --- a/Marlin/example_configurations/RigidBot/Configuration.h +++ b/Marlin/example_configurations/RigidBot/Configuration.h @@ -878,12 +878,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 diff --git a/Marlin/example_configurations/SCARA/Configuration.h b/Marlin/example_configurations/SCARA/Configuration.h index 45a9c37b34..162536f06c 100644 --- a/Marlin/example_configurations/SCARA/Configuration.h +++ b/Marlin/example_configurations/SCARA/Configuration.h @@ -895,12 +895,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 diff --git a/Marlin/example_configurations/TAZ4/Configuration.h b/Marlin/example_configurations/TAZ4/Configuration.h index a22b6987ad..de5eee2a07 100644 --- a/Marlin/example_configurations/TAZ4/Configuration.h +++ b/Marlin/example_configurations/TAZ4/Configuration.h @@ -899,12 +899,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 diff --git a/Marlin/example_configurations/TinyBoy2/Configuration.h b/Marlin/example_configurations/TinyBoy2/Configuration.h index ace689cef3..d893a920df 100644 --- a/Marlin/example_configurations/TinyBoy2/Configuration.h +++ b/Marlin/example_configurations/TinyBoy2/Configuration.h @@ -936,12 +936,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 diff --git a/Marlin/example_configurations/WITBOX/Configuration.h b/Marlin/example_configurations/WITBOX/Configuration.h index 15432ef96b..1389cdc9e9 100644 --- a/Marlin/example_configurations/WITBOX/Configuration.h +++ b/Marlin/example_configurations/WITBOX/Configuration.h @@ -870,12 +870,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 diff --git a/Marlin/example_configurations/adafruit/ST7565/Configuration.h b/Marlin/example_configurations/adafruit/ST7565/Configuration.h index 8e6735ecd2..ef71b3b561 100644 --- a/Marlin/example_configurations/adafruit/ST7565/Configuration.h +++ b/Marlin/example_configurations/adafruit/ST7565/Configuration.h @@ -880,12 +880,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 diff --git a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h index f52882ee83..6a824599ef 100644 --- a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h +++ b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h @@ -999,12 +999,16 @@ #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_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 _PX(R,A) (R) * cos(RADIANS(A)) + #define _PY(R,A) (R) * sin(RADIANS(A)) + #define UBL_PROBE_PT_1_X _PX(DELTA_PROBEABLE_RADIUS, 0) // Probing points for 3-Point leveling of the mesh + #define UBL_PROBE_PT_1_Y _PY(DELTA_PROBEABLE_RADIUS, 0) + #define UBL_PROBE_PT_2_X _PX(DELTA_PROBEABLE_RADIUS, 120) + #define UBL_PROBE_PT_2_Y _PY(DELTA_PROBEABLE_RADIUS, 120) + #define UBL_PROBE_PT_3_X _PX(DELTA_PROBEABLE_RADIUS, 240) + #define UBL_PROBE_PT_3_Y _PY(DELTA_PROBEABLE_RADIUS, 240) + #define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation #define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle diff --git a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h index 43cad5d57d..f29cc903b8 100644 --- a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h +++ b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h @@ -1001,12 +1001,16 @@ #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_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 _PX(R,A) (R) * cos(RADIANS(A)) + #define _PY(R,A) (R) * sin(RADIANS(A)) + #define UBL_PROBE_PT_1_X _PX(DELTA_PROBEABLE_RADIUS, 0) // Probing points for 3-Point leveling of the mesh + #define UBL_PROBE_PT_1_Y _PY(DELTA_PROBEABLE_RADIUS, 0) + #define UBL_PROBE_PT_2_X _PX(DELTA_PROBEABLE_RADIUS, 120) + #define UBL_PROBE_PT_2_Y _PY(DELTA_PROBEABLE_RADIUS, 120) + #define UBL_PROBE_PT_3_X _PX(DELTA_PROBEABLE_RADIUS, 240) + #define UBL_PROBE_PT_3_Y _PY(DELTA_PROBEABLE_RADIUS, 240) + #define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation #define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle diff --git a/Marlin/example_configurations/delta/generic/Configuration.h b/Marlin/example_configurations/delta/generic/Configuration.h index d6e183dc9e..5fb5d6747c 100644 --- a/Marlin/example_configurations/delta/generic/Configuration.h +++ b/Marlin/example_configurations/delta/generic/Configuration.h @@ -990,12 +990,16 @@ #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_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 _PX(R,A) (R) * cos(RADIANS(A)) + #define _PY(R,A) (R) * sin(RADIANS(A)) + #define UBL_PROBE_PT_1_X _PX(DELTA_PROBEABLE_RADIUS, 0) // Probing points for 3-Point leveling of the mesh + #define UBL_PROBE_PT_1_Y _PY(DELTA_PROBEABLE_RADIUS, 0) + #define UBL_PROBE_PT_2_X _PX(DELTA_PROBEABLE_RADIUS, 120) + #define UBL_PROBE_PT_2_Y _PY(DELTA_PROBEABLE_RADIUS, 120) + #define UBL_PROBE_PT_3_X _PX(DELTA_PROBEABLE_RADIUS, 240) + #define UBL_PROBE_PT_3_Y _PY(DELTA_PROBEABLE_RADIUS, 240) + #define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation #define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle diff --git a/Marlin/example_configurations/delta/kossel_mini/Configuration.h b/Marlin/example_configurations/delta/kossel_mini/Configuration.h index 71ce72e190..26d45ed197 100644 --- a/Marlin/example_configurations/delta/kossel_mini/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_mini/Configuration.h @@ -993,12 +993,16 @@ #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_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 _PX(R,A) (R) * cos(RADIANS(A)) + #define _PY(R,A) (R) * sin(RADIANS(A)) + #define UBL_PROBE_PT_1_X _PX(DELTA_PROBEABLE_RADIUS, 0) // Probing points for 3-Point leveling of the mesh + #define UBL_PROBE_PT_1_Y _PY(DELTA_PROBEABLE_RADIUS, 0) + #define UBL_PROBE_PT_2_X _PX(DELTA_PROBEABLE_RADIUS, 120) + #define UBL_PROBE_PT_2_Y _PY(DELTA_PROBEABLE_RADIUS, 120) + #define UBL_PROBE_PT_3_X _PX(DELTA_PROBEABLE_RADIUS, 240) + #define UBL_PROBE_PT_3_Y _PY(DELTA_PROBEABLE_RADIUS, 240) + #define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation #define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle diff --git a/Marlin/example_configurations/delta/kossel_pro/Configuration.h b/Marlin/example_configurations/delta/kossel_pro/Configuration.h index 9bed47b50d..5028ad3bea 100644 --- a/Marlin/example_configurations/delta/kossel_pro/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_pro/Configuration.h @@ -998,12 +998,16 @@ #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_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 _PX(R,A) (R) * cos(RADIANS(A)) + #define _PY(R,A) (R) * sin(RADIANS(A)) + #define UBL_PROBE_PT_1_X _PX(DELTA_PROBEABLE_RADIUS, 0) // Probing points for 3-Point leveling of the mesh + #define UBL_PROBE_PT_1_Y _PY(DELTA_PROBEABLE_RADIUS, 0) + #define UBL_PROBE_PT_2_X _PX(DELTA_PROBEABLE_RADIUS, 120) + #define UBL_PROBE_PT_2_Y _PY(DELTA_PROBEABLE_RADIUS, 120) + #define UBL_PROBE_PT_3_X _PX(DELTA_PROBEABLE_RADIUS, 240) + #define UBL_PROBE_PT_3_Y _PY(DELTA_PROBEABLE_RADIUS, 240) + #define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation #define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle diff --git a/Marlin/example_configurations/delta/kossel_xl/Configuration.h b/Marlin/example_configurations/delta/kossel_xl/Configuration.h index 39c44e47ce..52733e783d 100644 --- a/Marlin/example_configurations/delta/kossel_xl/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_xl/Configuration.h @@ -1056,12 +1056,16 @@ #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_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 _PX(R,A) (R) * cos(RADIANS(A)) + #define _PY(R,A) (R) * sin(RADIANS(A)) + #define UBL_PROBE_PT_1_X _PX(DELTA_PROBEABLE_RADIUS, 0) // Probing points for 3-Point leveling of the mesh + #define UBL_PROBE_PT_1_Y _PY(DELTA_PROBEABLE_RADIUS, 0) + #define UBL_PROBE_PT_2_X _PX(DELTA_PROBEABLE_RADIUS, 120) + #define UBL_PROBE_PT_2_Y _PY(DELTA_PROBEABLE_RADIUS, 120) + #define UBL_PROBE_PT_3_X _PX(DELTA_PROBEABLE_RADIUS, 240) + #define UBL_PROBE_PT_3_Y _PY(DELTA_PROBEABLE_RADIUS, 240) + #define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation #define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle diff --git a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h index b193acca60..63b605cebb 100644 --- a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h +++ b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h @@ -896,12 +896,14 @@ #define UBL_MESH_INSET 45 // 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 53 // These set the probe locations for when UBL does a 3-Point leveling - #define UBL_PROBE_PT_1_Y 323 // of the mesh. + + #define UBL_PROBE_PT_1_X 53 // Probing points for 3-Point leveling of the mesh + #define UBL_PROBE_PT_1_Y 323 #define UBL_PROBE_PT_2_X 53 #define UBL_PROBE_PT_2_Y 63 #define UBL_PROBE_PT_3_X 348 #define UBL_PROBE_PT_3_Y 211 + #define UBL_G26_MESH_VALIDATION // Enable G26 mesh validation #define UBL_MESH_EDIT_MOVES_Z // Sophisticated users prefer no movement of nozzle diff --git a/Marlin/example_configurations/makibox/Configuration.h b/Marlin/example_configurations/makibox/Configuration.h index bdb1d20469..8f22295bec 100644 --- a/Marlin/example_configurations/makibox/Configuration.h +++ b/Marlin/example_configurations/makibox/Configuration.h @@ -883,12 +883,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 diff --git a/Marlin/example_configurations/tvrrug/Round2/Configuration.h b/Marlin/example_configurations/tvrrug/Round2/Configuration.h index 75a450d36a..e6010071ca 100644 --- a/Marlin/example_configurations/tvrrug/Round2/Configuration.h +++ b/Marlin/example_configurations/tvrrug/Round2/Configuration.h @@ -875,12 +875,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 diff --git a/Marlin/example_configurations/wt150/Configuration.h b/Marlin/example_configurations/wt150/Configuration.h index 26e24c7035..81430e8ffa 100644 --- a/Marlin/example_configurations/wt150/Configuration.h +++ b/Marlin/example_configurations/wt150/Configuration.h @@ -885,12 +885,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 From 707707d71aa592b119cbf01b9e57d97060657cc1 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 7 Jun 2017 16:06:25 -0500 Subject: [PATCH 031/180] Fix LCD status message padding --- Marlin/ultralcd.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index 7f2c80e11b..627f4dd499 100755 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -4165,7 +4165,7 @@ void pad_message_string() { // pad with spaces to fill up the line while (j++ < LCD_WIDTH) lcd_status_message[i++] = ' '; // chop off at the edge - lcd_status_message[i] = '\0'; + lcd_status_message[--i] = '\0'; } } From c2eff60d3fb6b0ca85f8795e760bd4b8a0515fbf Mon Sep 17 00:00:00 2001 From: Kai Date: Thu, 8 Jun 2017 09:19:04 +0200 Subject: [PATCH 032/180] Fix for #6980 Line 7830 prevented successfull compilation when #define CASE_LIGHT_ENABLE is uncommented --- Marlin/Marlin_main.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 5a1d1504d1..8e4853e9a2 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -7827,7 +7827,6 @@ inline void gcode_M115() { // CASE LIGHTS (M355) #if HAS_CASE_LIGHT SERIAL_PROTOCOLLNPGM("Cap:TOGGLE_LIGHTS:1"); - bool USEABLE_HARDWARE_PWM(uint8_t pin); if (USEABLE_HARDWARE_PWM(CASE_LIGHT_PIN)) { SERIAL_PROTOCOLLNPGM("Cap:CASE_LIGHT_BRIGHTNESS:1"); } From abb6b8ad54c62ddbf74779cf7a5c142adee4c1e6 Mon Sep 17 00:00:00 2001 From: Kai Date: Thu, 8 Jun 2017 17:04:52 +0200 Subject: [PATCH 033/180] update language_de.h (#6986) There was quite a lot to translate this time. I'm not absolutely confident with the whole UBL stuff and it's a PITA to translate. I don't use any kind of levelling myself as i just have a perfectly level cast aluminium plate as bed. So maybe someone who really uses it might take a closer look at it after it's merged. --- Marlin/language_de.h | 73 ++++++++++++++++++++++++++++++++++++++++---- 1 file changed, 67 insertions(+), 6 deletions(-) diff --git a/Marlin/language_de.h b/Marlin/language_de.h index 1a6cb71f4d..1a3080def8 100644 --- a/Marlin/language_de.h +++ b/Marlin/language_de.h @@ -43,6 +43,8 @@ #define MSG_MAIN _UxGT("Hauptmenü") #define MSG_AUTOSTART _UxGT("Autostart") #define MSG_DISABLE_STEPPERS _UxGT("Motoren deaktivieren") // M84 +#define MSG_DEBUG_MENU _UxGT("Debug Menu") +#define MSG_PROGRESS_BAR_TEST _UxGT("Fortschrittb. Test") #define MSG_AUTO_HOME _UxGT("Home") // G28 #define MSG_AUTO_HOME_X _UxGT("Home X") #define MSG_AUTO_HOME_Y _UxGT("Home Y") @@ -74,6 +76,7 @@ #define MSG_MOVE_AXIS _UxGT("Bewegen") #define MSG_BED_LEVELING _UxGT("Bett nivellieren") #define MSG_LEVEL_BED _UxGT("Bett nivellieren") +#define MSG_USER_MENU _UxGT("Benutzer Menü") #define MSG_MOVING _UxGT("In Bewegung...") #define MSG_FREE_XY _UxGT("Abstand XY") #define MSG_MOVE_X _UxGT("X") @@ -110,6 +113,7 @@ #define MSG_VMAX _UxGT("V max ") // space by purpose #define MSG_VMIN _UxGT("V min") #define MSG_VTRAV_MIN _UxGT("V min Leerfahrt") +#define MSG_ACCELERATION _UxGT("Beschleunigung") #define MSG_AMAX _UxGT("A max ") // space by purpose #define MSG_A_RETRACT _UxGT("A Retract") #define MSG_A_TRAVEL _UxGT("A Leerfahrt") @@ -130,9 +134,10 @@ #define MSG_FILAMENT_DIAM _UxGT("D Fil.") #define MSG_ADVANCE_K _UxGT("Advance Faktor") #define MSG_CONTRAST _UxGT("LCD Kontrast") -#define MSG_STORE_EEPROM _UxGT("EPROM speichern") -#define MSG_LOAD_EEPROM _UxGT("EPROM laden") +#define MSG_STORE_EEPROM _UxGT("Konfig. speichern") +#define MSG_LOAD_EEPROM _UxGT("Konfig. laden") #define MSG_RESTORE_FAILSAFE _UxGT("Standardkonfiguration") +#define MSG_INIT_EEPROM _UxGT("EEPROM initialisieren") #define MSG_REFRESH _UxGT("Aktualisieren") #define MSG_WATCH _UxGT("Info") #define MSG_PREPARE _UxGT("Vorbereitung") @@ -144,6 +149,7 @@ #define MSG_NO_CARD _UxGT("Keine SD-Karte") #define MSG_DWELL _UxGT("Warten...") #define MSG_USERWAIT _UxGT("Warte auf Nutzer") +#define MSG_PRINT_PAUSED _UxGT("Druck pausiert") #define MSG_RESUMING _UxGT("Druckfortsetzung") #define MSG_PRINT_ABORTED _UxGT("Druck abgebrochen") #define MSG_NO_MOVE _UxGT("Motoren eingeschaltet") @@ -163,6 +169,8 @@ #define MSG_ZPROBE_OUT _UxGT("Sensor ausserhalb") #define MSG_BLTOUCH_SELFTEST _UxGT("BLTouch Test") #define MSG_BLTOUCH_RESET _UxGT("BLTouch Reset") +#define MSG_BLTOUCH_DEPLOY _UxGT("BLTouch ausfahren") +#define MSG_BLTOUCH_STOW _UxGT("BLTouch einfahren") #define MSG_HOME _UxGT("Vorher") // Used as MSG_HOME " " MSG_X MSG_Y MSG_Z " " MSG_FIRST #define MSG_FIRST _UxGT("homen") #define MSG_ZPROBE_ZOFFSET _UxGT("Z Versatz") @@ -194,11 +202,14 @@ #define MSG_DELTA_CALIBRATE_CENTER _UxGT("Kalibriere Mitte") #define MSG_DELTA_AUTO_CALIBRATE _UxGT("Autom. Kalibrierung") #define MSG_DELTA_HEIGHT_CALIBRATE _UxGT("Delta Höhe setzen") -#define MSG_DEBUG_MENU _UxGT("Debug Menu") -#define MSG_PROGRESS_BAR_TEST _UxGT("Fortschrittb. Test") #define MSG_INFO_MENU _UxGT("Über den Drucker") #define MSG_INFO_PRINTER_MENU _UxGT("Drucker Info") +#define MSG_3POINT_LEVELING _UxGT("3-Punkt Nivellierung") +#define MSG_LINEAR_LEVELING _UxGT("Lineare Nivellierung") +#define MSG_BILINEAR_LEVELING _UxGT("Bilineare Nivell.") +#define MSG_UBL_LEVELING _UxGT("Unified Bed Leveling") +#define MSG_MESH_LEVELING _UxGT("Netz Nivellierung") #define MSG_INFO_STATS_MENU _UxGT("Drucker Stat.") #define MSG_INFO_BOARD_MENU _UxGT("Board Info") #define MSG_INFO_THERMISTOR_MENU _UxGT("Thermistoren") @@ -206,6 +217,56 @@ #define MSG_INFO_BAUDRATE _UxGT("Baud") #define MSG_INFO_PROTOCOL _UxGT("Protokoll") #define MSG_CASE_LIGHT _UxGT("Licht") +#define MSG_CASE_LIGHT_BRIGHTNESS _UxGT("Helligkeit") + +#if ENABLED(AUTO_BED_LEVELING_UBL) + #define MSG_UBL_UNHOMED _UxGT("Erst XYZ homen") + #define MSG_UBL_TOOLS _UxGT("UBL Tools") + #define MSG_UBL_LEVEL_BED _UxGT("Unified Bed Leveling") + #define MSG_UBL_MANUAL_MESH _UxGT("Netz manuell erst.") + #define MSG_UBL_ACTIVATE_MESH _UxGT("UBL aktivieren") + #define MSG_UBL_DEACTIVATE_MESH _UxGT("UBL deaktivieren") + #define MSG_UBL_SET_BED_TEMP _UxGT("Bett Temp.") + #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_EDIT_CUSTOM_MESH _UxGT("Eigenes Netz bearb.") + #define MSG_UBL_BUILD_CUSTOM_MESH _UxGT("Eigenes Netz erst.") + #define MSG_UBL_BUILD_MESH_MENU _UxGT("Netz erstellen") + #define MSG_UBL_BUILD_PLA_MESH _UxGT("Netz erstellen PLA") + #define MSG_UBL_BUILD_ABS_MESH _UxGT("Netz erstellen ABS") + #define MSG_UBL_BUILD_COLD_MESH _UxGT("Netz erstellen kalt") + #define MSG_UBL_MESH_HEIGHT_ADJUST _UxGT("Netz Höhe einst.") + #define MSG_UBL_MESH_HEIGHT_AMOUNT _UxGT("Height Amount") + #define MSG_UBL_VALIDATE_MESH_MENU _UxGT("Netz validieren") + #define MSG_UBL_VALIDATE_PLA_MESH _UxGT("Netz validieren PLA") + #define MSG_UBL_VALIDATE_ABS_MESH _UxGT("Netz validieren ABS") + #define MSG_UBL_VALIDATE_CUSTOM_MESH _UxGT("Eigenes Netz validieren") + #define MSG_UBL_CONTINUE_MESH _UxGT("Netzerst. forts.") + #define MSG_UBL_MESH_LEVELING _UxGT("Netz Nivellierung") + #define MSG_UBL_3POINT_MESH_LEVELING _UxGT("3-Punkt Nivellierung") + #define MSG_UBL_GRID_MESH_LEVELING _UxGT("Gitternetz Nivellierung") + #define MSG_UBL_MESH_LEVEL _UxGT("Netz nivellieren") + #define MSG_UBL_SIDE_POINTS _UxGT("Eckpunkte") + #define MSG_UBL_MAP_TYPE _UxGT("Kartentyp") + #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_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") + #define MSG_UBL_MANUAL_FILLIN _UxGT("Manuelles Fill-in") + #define MSG_UBL_SMART_FILLIN _UxGT("Kluges Fill-in") + #define MSG_UBL_FILLIN_MESH _UxGT("Fill-in Netz") + #define MSG_UBL_INVALIDATE_ALL _UxGT("Alles annullieren") + #define MSG_UBL_INVALIDATE_CLOSEST _UxGT("Nächstlieg. ann.") + #define MSG_UBL_FINE_TUNE_ALL _UxGT("Feineinstellung Alle") + #define MSG_UBL_FINE_TUNE_CLOSEST _UxGT("Feineinst- Nächstl.") + #define MSG_UBL_STORAGE_MESH_MENU _UxGT("Netz Speicherplatz") + #define MSG_UBL_STORAGE_SLOT _UxGT("Memory Slot") + #define MSG_UBL_LOAD_MESH _UxGT("Bett Netz laden") + #define MSG_UBL_SAVE_MESH _UxGT("Bett Netz speichern") +#endif // AUTO_BED_LEVELING_UBL #if LCD_WIDTH >= 20 #define MSG_INFO_PRINT_COUNT _UxGT("Gesamte Drucke") @@ -229,8 +290,8 @@ #define MSG_DAC_PERCENT _UxGT("Treiber %") #define MSG_DAC_EEPROM_WRITE _UxGT("Werte speichern") -#define MSG_FILAMENT_CHANGE_HEADER _UxGT("PRINT PAUSED") -#define MSG_FILAMENT_CHANGE_OPTION_HEADER _UxGT("RESUME OPTIONS:") +#define MSG_FILAMENT_CHANGE_HEADER _UxGT("DRUCK PAUSIERT") +#define MSG_FILAMENT_CHANGE_OPTION_HEADER _UxGT("FORTS. OPTIONEN:") #define MSG_FILAMENT_CHANGE_OPTION_EXTRUDE _UxGT("Extrude mehr") #define MSG_FILAMENT_CHANGE_OPTION_RESUME _UxGT("Drucke weiter") #define MSG_FILAMENT_CHANGE_MINTEMP _UxGT("Min. Temperatur ist ") From 731c8e6372308157b804105de6e304406f6d2a4c Mon Sep 17 00:00:00 2001 From: Tannoo Date: Thu, 8 Jun 2017 09:09:39 -0600 Subject: [PATCH 034/180] Translatable Strings for ubl_G29 (#6990) --- Marlin/language_en.h | 33 +++++++++++++++++++++++++++++++++ Marlin/ubl_G29.cpp | 22 +++++++++++----------- 2 files changed, 44 insertions(+), 11 deletions(-) diff --git a/Marlin/language_en.h b/Marlin/language_en.h index 654cfedf6e..a0b9bb0a05 100644 --- a/Marlin/language_en.h +++ b/Marlin/language_en.h @@ -156,11 +156,17 @@ #ifndef MSG_LEVEL_BED #define MSG_LEVEL_BED _UxGT("Level bed") #endif +#ifndef MSG_EDITING_STOPPED + #define MSG_EDITING_STOPPED _UxGT("Mesh Editing Stopped") +#endif #ifndef MSG_USER_MENU #define MSG_USER_MENU _UxGT("Custom Commands") #endif #if ENABLED(AUTO_BED_LEVELING_UBL) + #ifndef MSG_UBL_DOING_G29 + #define MSG_UBL_DOING_G29 _UxGT("Doing G29 UBL!") + #endif #ifndef MSG_UBL_UNHOMED #define MSG_UBL_UNHOMED _UxGT("Home XYZ first") #endif @@ -173,6 +179,18 @@ #ifndef MSG_UBL_MANUAL_MESH #define MSG_UBL_MANUAL_MESH _UxGT("Manually Build Mesh") #endif + #ifndef MSG_UBL_BC_INSERT + #define MSG_UBL_BC_INSERT _UxGT("Place shim & measure") + #endif + #ifndef MSG_UBL_BC_INSERT2 + #define MSG_UBL_BC_INSERT2 _UxGT("Measure") + #endif + #ifndef MSG_UBL_BC_REMOVE + #define MSG_UBL_BC_REMOVE _UxGT("Remove & measure bed") + #endif + #ifndef MSG_UBL_MOVING_TO_NEXT + #define MSG_UBL_MOVING_TO_NEXT _UxGT("Moving to next") + #endif #ifndef MSG_UBL_ACTIVATE_MESH #define MSG_UBL_ACTIVATE_MESH _UxGT("Activate UBL") #endif @@ -194,6 +212,12 @@ #ifndef MSG_UBL_EDIT_CUSTOM_MESH #define MSG_UBL_EDIT_CUSTOM_MESH _UxGT("Edit Custom Mesh") #endif + #ifndef MSG_UBL_FINE_TUNE_MESH + #define MSG_UBL_FINE_TUNE_MESH _UxGT("Fine Tuning Mesh") + #endif + #ifndef MSG_UBL_DONE_EDITING_MESH + #define MSG_UBL_DONE_EDITING_MESH _UxGT("Done Editing Mesh") + #endif #ifndef MSG_UBL_BUILD_CUSTOM_MESH #define MSG_UBL_BUILD_CUSTOM_MESH _UxGT("Build Custom Mesh") #endif @@ -299,6 +323,15 @@ #ifndef MSG_UBL_SAVE_MESH #define MSG_UBL_SAVE_MESH _UxGT("Save Bed Mesh") #endif + #ifndef MSG_UBL_SAVE_ERROR + #define MSG_UBL_SAVE_ERROR _UxGT("save_UBL_active() error") + #endif + #ifndef MSG_UBL_RESTORE_ERROR + #define MSG_UBL_RESTORE_ERROR _UxGT("restore_UBL_active() error") + #endif + #ifndef MSG_UBL_Z_OFFSET_STOPPED + #define MSG_UBL_Z_OFFSET_STOPPED _UxGT("Z-Offset Stopped") + #endif #endif // AUTO_BED_LEVELING_UBL #ifndef MSG_MOVING diff --git a/Marlin/ubl_G29.cpp b/Marlin/ubl_G29.cpp index ab0ac32cb3..063475e9ed 100644 --- a/Marlin/ubl_G29.cpp +++ b/Marlin/ubl_G29.cpp @@ -713,7 +713,7 @@ if (ELAPSED(millis(), nxt)) { SERIAL_PROTOCOLLNPGM("\nZ-Offset Adjustment Stopped."); do_blocking_move_to_z(Z_CLEARANCE_DEPLOY_PROBE); - LCD_MESSAGEPGM("Z-Offset Stopped"); // TODO: Make translatable string + LCD_MESSAGEPGM(MSG_UBL_Z_OFFSET_STOPPED); restore_ubl_active_state_and_leave(); goto LEAVE; } @@ -971,7 +971,7 @@ stepper.synchronize(); SERIAL_PROTOCOLPGM("Place shim under nozzle"); - LCD_MESSAGEPGM("Place shim & measure"); // TODO: Make translatable string + LCD_MESSAGEPGM(MSG_UBL_BC_INSERT); lcd_return_to_status(); echo_and_take_a_measurement(); @@ -980,7 +980,7 @@ stepper.synchronize(); SERIAL_PROTOCOLPGM("Remove shim"); - LCD_MESSAGEPGM("Remove & measure bed"); // TODO: Make translatable string + LCD_MESSAGEPGM(MSG_UBL_BC_REMOVE); echo_and_take_a_measurement(); const float z2 = measure_point_with_encoder(); @@ -1029,7 +1029,7 @@ do_blocking_move_to_z(Z_CLEARANCE_BETWEEN_PROBES); - LCD_MESSAGEPGM("Moving to next"); // TODO: Make translatable string + LCD_MESSAGEPGM(MSG_UBL_MOVING_TO_NEXT); do_blocking_move_to_xy(xProbe, yProbe); do_blocking_move_to_z(z_clearance); @@ -1039,7 +1039,7 @@ if (do_ubl_mesh_map) display_map(g29_map_type); // show user where we're probing - serialprintPGM(parser.seen('B') ? PSTR("Place shim & measure") : PSTR("Measure")); // TODO: Make translatable strings + serialprintPGM(parser.seen('B') ? PSTR(MSG_UBL_BC_INSERT) : PSTR(MSG_UBL_BC_INSERT2)); const float z_step = 0.01; // existing behavior: 0.01mm per click, occasionally step //const float z_step = 1.0 / planner.axis_steps_per_mm[Z_AXIS]; // approx one step each click @@ -1097,7 +1097,7 @@ bool err_flag = false; #if ENABLED(NEWPANEL) - LCD_MESSAGEPGM("Doing G29 UBL!"); // TODO: Make translatable string + LCD_MESSAGEPGM(MSG_UBL_DOING_G29); lcd_quick_feedback(); #endif @@ -1207,7 +1207,7 @@ SERIAL_ECHOLNPGM("save_ubl_active_state_and_disabled() called multiple times in a row."); #if ENABLED(NEWPANEL) - LCD_MESSAGEPGM("save_UBL_active() error"); // TODO: Make translatable string + LCD_MESSAGEPGM(MSG_UBL_SAVE_ERROR); lcd_quick_feedback(); #endif @@ -1222,7 +1222,7 @@ SERIAL_ECHOLNPGM("restore_ubl_active_state_and_leave() called too many times."); #if ENABLED(NEWPANEL) - LCD_MESSAGEPGM("restore_UBL_active() error"); // TODO: Make translatable string + LCD_MESSAGEPGM(MSG_UBL_RESTORE_ERROR); lcd_quick_feedback(); #endif @@ -1476,7 +1476,7 @@ memset(not_done, 0xFF, sizeof(not_done)); - LCD_MESSAGEPGM("Fine Tuning Mesh"); // TODO: Make translatable string + LCD_MESSAGEPGM(MSG_UBL_FINE_TUNE_MESH); do_blocking_move_to_z(Z_CLEARANCE_BETWEEN_PROBES); do_blocking_move_to_xy(lx, ly); @@ -1538,7 +1538,7 @@ lcd_return_to_status(); //SERIAL_PROTOCOLLNPGM("\nFine Tuning of Mesh Stopped."); do_blocking_move_to_z(Z_CLEARANCE_BETWEEN_PROBES); - LCD_MESSAGEPGM("Mesh Editing Stopped"); // TODO: Make translatable string + LCD_MESSAGEPGM(MSG_EDITING_STOPPED); while (ubl_lcd_clicked()) idle(); @@ -1565,7 +1565,7 @@ do_blocking_move_to_xy(lx, ly); - LCD_MESSAGEPGM("Done Editing Mesh"); // TODO: Make translatable string + LCD_MESSAGEPGM(MSG_UBL_DONE_EDITING_MESH); SERIAL_ECHOLNPGM("Done Editing Mesh"); } #endif From 8d1d9040b6ff927417de7351c82ba4deecdbf8f3 Mon Sep 17 00:00:00 2001 From: Bob-the-Kuhn Date: Thu, 8 Jun 2017 14:59:21 -0500 Subject: [PATCH 035/180] add static --- 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 8e4853e9a2..6e6ded87c2 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -1499,7 +1499,7 @@ static void set_axis_is_at_home(const AxisEnum axis) { * Some planner shorthand inline functions */ inline float get_homing_bump_feedrate(const AxisEnum axis) { - const uint8_t homing_bump_divisor[] PROGMEM = HOMING_BUMP_DIVISOR; + static const uint8_t homing_bump_divisor[] PROGMEM = HOMING_BUMP_DIVISOR; uint8_t hbd = pgm_read_byte(&homing_bump_divisor[axis]); if (hbd < 1) { hbd = 10; From 28d72f48f1590d759b9eb0bc76c392dc27c4643b Mon Sep 17 00:00:00 2001 From: Bob-the-Kuhn Date: Thu, 8 Jun 2017 16:15:02 -0500 Subject: [PATCH 036/180] change to DWORD --- Marlin/configuration_store.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/configuration_store.cpp b/Marlin/configuration_store.cpp index 90e5efc551..eedee1deb2 100644 --- a/Marlin/configuration_store.cpp +++ b/Marlin/configuration_store.cpp @@ -1130,7 +1130,7 @@ void MarlinSettings::reset() { LOOP_XYZE_N(i) { planner.axis_steps_per_mm[i] = pgm_read_float(&tmp1[i < COUNT(tmp1) ? i : COUNT(tmp1) - 1]); planner.max_feedrate_mm_s[i] = pgm_read_float(&tmp2[i < COUNT(tmp2) ? i : COUNT(tmp2) - 1]); - planner.max_acceleration_mm_per_s2[i] = pgm_read_float(&tmp3[i < COUNT(tmp3) ? i : COUNT(tmp3) - 1]); + planner.max_acceleration_mm_per_s2[i] = pgm_read_dword_near(&tmp3[i < COUNT(tmp3) ? i : COUNT(tmp3) - 1]); } planner.acceleration = DEFAULT_ACCELERATION; From 2f55870edbebcbd52f51f72584342589656d63c1 Mon Sep 17 00:00:00 2001 From: bgort Date: Fri, 9 Jun 2017 08:06:23 -0400 Subject: [PATCH 037/180] [New Feature] I2C position encoder support (#6946) * [New Feature] I2C position encoder support I plan to continue improving/cleaning this up, as there areas that need work. * let the cleanups begin. * progress * more progress * comments, rename files, etc. * clean * Cleanups per thinkyhead * a few more cleanups * cleanups, bugfixes, etc. * remove unnecessary passes_test(), additional cleanups/optimizations * cleanups * misc. * Fix up I2CPEM.init() and a few other things. * organize, fix, rename, etc. * more optimization * a few more tweaks --- Marlin/Configuration_adv.h | 83 +++ Marlin/I2CPositionEncoder.cpp | 1101 +++++++++++++++++++++++++++++++++ Marlin/I2CPositionEncoder.h | 356 +++++++++++ Marlin/Marlin_main.cpp | 89 ++- Marlin/SanityCheck.h | 15 +- Marlin/enum.h | 36 +- Marlin/gcode.h | 19 + Marlin/macros.h | 2 + 8 files changed, 1684 insertions(+), 17 deletions(-) create mode 100644 Marlin/I2CPositionEncoder.cpp create mode 100644 Marlin/I2CPositionEncoder.h diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 2e567fd0e8..c8e30fffec 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1261,4 +1261,87 @@ #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 + #endif // CONFIGURATION_ADV_H diff --git a/Marlin/I2CPositionEncoder.cpp b/Marlin/I2CPositionEncoder.cpp new file mode 100644 index 0000000000..146776c863 --- /dev/null +++ b/Marlin/I2CPositionEncoder.cpp @@ -0,0 +1,1101 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (C) 2016, 2017 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +//todo: add support for multiple encoders on a single axis +//todo: add z axis auto-leveling +//todo: consolidate some of the related M codes? +//todo: add endstop-replacement mode? +//todo: try faster I2C speed; tweak TWI_FREQ (400000L, or faster?); or just TWBR = ((CPU_FREQ / 400000L) - 16) / 2; +//todo: consider Marlin-optimized Wire library; i.e. MarlinWire, like MarlinSerial + + +#include "MarlinConfig.h" + +#if ENABLED(I2C_POSITION_ENCODERS) + + #include "Marlin.h" + #include "temperature.h" + #include "stepper.h" + #include "I2CPositionEncoder.h" + #include "gcode.h" + + #include + + void I2CPositionEncoder::init(uint8_t address, AxisEnum axis) { + encoderAxis = axis; + i2cAddress = address; + + initialised++; + + SERIAL_ECHOPAIR("Seetting up encoder on ", axis_codes[encoderAxis]); + SERIAL_ECHOLNPAIR(" axis, addr = ", address); + + position = get_position(); + } + + void I2CPositionEncoder::update() { + if (!initialised || !homed || !active) return; //check encoder is set up and active + + position = get_position(); + + //we don't want to stop things just because the encoder missed a message, + //so we only care about responses that indicate bad magnetic strength + + if (!passes_test(false)) { //check encoder data is good + lastErrorTime = millis(); + /* + if (trusted) { //commented out as part of the note below + trusted = false; + SERIAL_ECHOPGM("Fault detected on "); + SERIAL_ECHO(axis_codes[encoderAxis]); + SERIAL_ECHOLNPGM(" axis encoder. Disengaging error correction until module is trusted again."); + } + */ + return; + } + + if (!trusted) { + /** + * This is commented out because it introduces error and can cause bad print quality. + * + * This code is intended to manage situations where the encoder has reported bad magnetic strength. + * This indicates that the magnetic strip was too far away from the sensor to reliably track position. + * When this happens, this code resets the offset based on where the printer thinks it is. This has been + * shown to introduce errors in actual position which result in drifting prints and poor print quality. + * Perhaps a better method would be to disable correction on the axis with a problem, report it to the + * user via the status leds on the encoder module and prompt the user to re-home the axis at which point + * the encoder would be re-enabled. + */ + + /* + // If the magnetic strength has been good for a certain time, start trusting the module again + + if (millis() - lastErrorTime > I2CPE_TIME_TRUSTED) { + trusted = true; + + SERIAL_ECHOPGM("Untrusted encoder module on "); + SERIAL_ECHO(axis_codes[encoderAxis]); + SERIAL_ECHOLNPGM(" axis has been fault-free for set duration, reinstating error correction."); + + //the encoder likely lost its place when the error occured, so we'll reset and use the printer's + //idea of where it the axis is to re-initialise + double position = stepper.get_axis_position_mm(encoderAxis); + long positionInTicks = position * get_ticks_unit(); + + //shift position from previous to current position + zeroOffset -= (positionInTicks - get_position()); + + #if defined(I2CPE_DEBUG) + SERIAL_ECHOPGM("Current position is "); + SERIAL_ECHOLN(position); + + SERIAL_ECHOPGM("Position in encoder ticks is "); + SERIAL_ECHOLN(positionInTicks); + + SERIAL_ECHOPGM("New zero-offset of "); + SERIAL_ECHOLN(zeroOffset); + + SERIAL_ECHOPGM("New position reads as "); + SERIAL_ECHO(get_position()); + SERIAL_ECHOPGM("("); + SERIAL_ECHO(mm_from_count(get_position())); + SERIAL_ECHOLNPGM(")"); + #endif + } + */ + return; + } + + lastPosition = position; + unsigned long positionTime = millis(); + + //only do error correction if setup and enabled + if (ec && ecMethod != I2CPE_ECM_NONE) { + + #if defined(I2CPE_EC_THRESH_PROPORTIONAL) + unsigned long distance = abs(position - lastPosition); + unsigned long deltaTime = positionTime - lastPositionTime; + unsigned long speed = distance / deltaTime; + float threshold = constrain((speed / 50), 1, 50) * ecThreshold; + #else + float threshold = get_error_correct_threshold(); + #endif + + //check error + #if ENABLED(I2CPE_ERR_ROLLING_AVERAGE) + double sum = 0, diffSum = 0; + + errIdx = (errIdx >= I2CPE_ERR_ARRAY_SIZE - 1) ? 0 : errIdx + 1; + err[errIdx] = get_axis_error_steps(false); + + LOOP_L_N(i, I2CPE_ERR_ARRAY_SIZE) { + sum += err[i]; + if (i) diffSum += abs(err[i-1] - err[i]); + } + + long error = (long)(sum/(I2CPE_ERR_ARRAY_SIZE + 1)); //calculate average for error + + #else + long error = get_axis_error_steps(false); + #endif + + //SERIAL_ECHOPGM("Axis err*r steps: "); + //SERIAL_ECHOLN(error); + + #if defined(I2CPE_ERR_THRESH_ABORT) + if (abs(error) > I2CPE_ERR_THRESH_ABORT * planner.axis_steps_per_mm[encoderAxis]) { + //kill("Significant Error"); + SERIAL_ECHOPGM("Axis error greater than set threshold, aborting!"); + SERIAL_ECHOLN(error); + safe_delay(5000); + } + #endif + + #if ENABLED(I2CPE_ERR_ROLLING_AVERAGE) + if (errIdx == 0) { + // in order to correct for "error" but avoid correcting for noise and non skips + // it must be > threshold and have a difference average of < 10 and be < 2000 steps + if (abs(error) > threshold * planner.axis_steps_per_mm[encoderAxis] && + diffSum < 10*(I2CPE_ERR_ARRAY_SIZE-1) && abs(error) < 2000) { //Check for persistent error (skip) + SERIAL_ECHO(axis_codes[encoderAxis]); + SERIAL_ECHOPAIR(" diffSum: ", diffSum/(I2CPE_ERR_ARRAY_SIZE-1)); + SERIAL_ECHOPAIR(" - err detected: ", error / planner.axis_steps_per_mm[encoderAxis]); + SERIAL_ECHOLNPGM("mm; correcting!"); + thermalManager.babystepsTodo[encoderAxis] = -lround(error); + } + } + #else + if (abs(error) > threshold * planner.axis_steps_per_mm[encoderAxis]) { + //SERIAL_ECHOLN(error); + //SERIAL_ECHOLN(position); + thermalManager.babystepsTodo[encoderAxis] = -lround(error/2); + } + #endif + + if (abs(error) > (I2CPE_ERR_CNT_THRESH * planner.axis_steps_per_mm[encoderAxis]) && millis() - lastErrorCountTime > I2CPE_ERR_CNT_DEBOUNCE_MS) { + SERIAL_ECHOPAIR("Large error on ", axis_codes[encoderAxis]); + SERIAL_ECHOPAIR(" axis. error: ", (int)error); + SERIAL_ECHOLNPAIR("; diffSum: ", diffSum); + errorCount++; + lastErrorCountTime = millis(); + } + } + + lastPositionTime = positionTime; + } + + void I2CPositionEncoder::set_homed() { + if (active) { + reset(); // Reset module's offset to zero (so current position is homed / zero) + delay(10); + + zeroOffset = get_raw_count(); + homed++; + trusted++; + + #if defined(I2CPE_DEBUG) + SERIAL_ECHO(axis_codes[encoderAxis]); + SERIAL_ECHOPAIR(" axis encoder homed, offset of ", zeroOffset); + SERIAL_ECHOLNPGM(" ticks."); + #endif + } + } + + bool I2CPositionEncoder::passes_test(bool report) { + if (H == I2CPE_MAG_SIG_GOOD) { + if (report) { + SERIAL_ECHO(axis_codes[encoderAxis]); + SERIAL_ECHOLNPGM(" axis encoder passes test; field strength good."); + } + return true; + } else if (H == I2CPE_MAG_SIG_MID) { + if (report) { + SERIAL_ECHOPAIR("Warning, ", axis_codes[encoderAxis]); + SERIAL_ECHOLNPGM(" axis encoder passes test; field strength fair."); + } + return true; + } else if (H == I2CPE_MAG_SIG_BAD) { + if (report) { + SERIAL_ECHOPAIR("Warning, ", axis_codes[encoderAxis]); + SERIAL_ECHOLNPGM(" axis magnetic strip not detected!"); + } + return false; + } + + if (report) { + SERIAL_ECHOPAIR("Warning, ", axis_codes[encoderAxis]); + SERIAL_ECHOLNPGM(" axis encoder not detected!"); + } + return false; + } + + double I2CPositionEncoder::get_axis_error_mm(bool report) { + double target, actual, error; + + target = stepper.get_axis_position_mm(encoderAxis); + actual = mm_from_count(position); + error = actual - target; + + if (abs(error) > 10000) error = 0; // ? + + if (report) { + SERIAL_ECHO(axis_codes[encoderAxis]); + SERIAL_ECHOPAIR(" axis target: ", target); + SERIAL_ECHOPAIR(", actual: ", actual); + SERIAL_ECHOLNPAIR(", error : ",error); + } + + return error; + } + + long I2CPositionEncoder::get_axis_error_steps(bool report) { + if (!active) { + if (report) { + SERIAL_ECHO(axis_codes[encoderAxis]); + SERIAL_ECHOLNPGM(" axis encoder not active!"); + } + return 0; + } + + float stepperTicksPerUnit; + long encoderTicks = position, encoderCountInStepperTicksScaled; + //long stepperTicks = stepper.position(encoderAxis); + + // With a rotary encoder we're concerned with ticks/rev; whereas with a linear we're concerned with ticks/mm + stepperTicksPerUnit = (type == I2CPE_ENC_TYPE_ROTARY) ? stepperTicks : planner.axis_steps_per_mm[encoderAxis]; + + //convert both 'ticks' into same units / base + encoderCountInStepperTicksScaled = lround((stepperTicksPerUnit * encoderTicks) / encoderTicksPerUnit); + + long target = stepper.position(encoderAxis), + error = (encoderCountInStepperTicksScaled - target); + + //suppress discontinuities (might be caused by bad I2C readings...?) + bool suppressOutput = (abs(error - errorPrev) > 100); + + if (report) { + SERIAL_ECHO(axis_codes[encoderAxis]); + SERIAL_ECHOPAIR(" axis target: ", target); + SERIAL_ECHOPAIR(", actual: ", encoderCountInStepperTicksScaled); + SERIAL_ECHOLNPAIR(", error : ", error); + + if (suppressOutput) SERIAL_ECHOLNPGM("Discontinuity detected, suppressing error."); + } + + errorPrev = error; + + return (suppressOutput ? 0 : error); + } + + long I2CPositionEncoder::get_raw_count() { + uint8_t index = 0; + i2cLong encoderCount; + + encoderCount.val = 0x00; + + if (Wire.requestFrom((int)i2cAddress, 3) != 3) { + //houston, we have a problem... + H = I2CPE_MAG_SIG_NF; + return 0; + } + + while (Wire.available()) + encoderCount.bval[index++] = (uint8_t)Wire.read(); + + //extract the magnetic strength + H = (B00000011 & (encoderCount.bval[2] >> 6)); + + //extract sign bit; sign = (encoderCount.bval[2] & B00100000); + //set all upper bits to the sign value to overwrite H + encoderCount.val = (encoderCount.bval[2] & B00100000) ? (encoderCount.val | 0xFFC00000) : (encoderCount.val & 0x003FFFFF); + + if (invert) encoderCount.val *= -1; + + return encoderCount.val; + } + + bool I2CPositionEncoder::test_axis() { + //only works on XYZ cartesian machines for the time being + if (!(encoderAxis == X_AXIS || encoderAxis == Y_AXIS || encoderAxis == Z_AXIS)) return false; + + int feedrate; + float startPosition, endPosition; + float startCoord[NUM_AXIS] = {0}, endCoord[NUM_AXIS] = {0}; + + startPosition = soft_endstop_min[encoderAxis] + 10; + endPosition = soft_endstop_max[encoderAxis] - 10; + + feedrate = (int)MMM_TO_MMS((encoderAxis == Z_AXIS) ? HOMING_FEEDRATE_Z : HOMING_FEEDRATE_XY); + + ec = false; + + LOOP_NA(i) { + startCoord[i] = stepper.get_axis_position_mm((AxisEnum)i); + endCoord[i] = stepper.get_axis_position_mm((AxisEnum)i); + } + + startCoord[encoderAxis] = startPosition; + endCoord[encoderAxis] = endPosition; + + stepper.synchronize(); + + planner.buffer_line(startCoord[X_AXIS],startCoord[Y_AXIS],startCoord[Z_AXIS], + stepper.get_axis_position_mm(E_AXIS), feedrate, 0); + stepper.synchronize(); + + // if the module isn't currently trusted, wait until it is (or until it should be if things are working) + if (!trusted) { + long startWaitingTime = millis(); + while (!trusted && millis() - startWaitingTime < I2CPE_TIME_TRUSTED) + safe_delay(500); + } + + if (trusted) { // if trusted, commence test + planner.buffer_line(endCoord[X_AXIS], endCoord[Y_AXIS], endCoord[Z_AXIS], + stepper.get_axis_position_mm(E_AXIS), feedrate, 0); + stepper.synchronize(); + } + + return trusted; + } + + void I2CPositionEncoder::calibrate_steps_mm(int iter) { + if (type != I2CPE_ENC_TYPE_LINEAR) { + SERIAL_ECHOLNPGM("Steps per mm calibration is only available using linear encoders."); + return; + } + + if (!(encoderAxis == X_AXIS || encoderAxis == Y_AXIS || encoderAxis == Z_AXIS)) { + SERIAL_ECHOLNPGM("Automatic steps / mm calibration not supported for this axis."); + return; + } + + float oldStepsMm, newStepsMm, + startDistance, endDistance, + travelDistance, travelledDistance, total = 0, + startCoord[NUM_AXIS] = {0}, endCoord[NUM_AXIS] = {0}; + + double feedrate; + + long startCount, stopCount; + + feedrate = MMM_TO_MMS((encoderAxis == Z_AXIS) ? HOMING_FEEDRATE_Z : HOMING_FEEDRATE_XY); + + bool oldec = ec; + ec = false; + + startDistance = 20; + endDistance = soft_endstop_max[encoderAxis] - 20; + travelDistance = endDistance - startDistance; + + LOOP_NA(i) { + startCoord[i] = stepper.get_axis_position_mm((AxisEnum)i); + endCoord[i] = stepper.get_axis_position_mm((AxisEnum)i); + } + + startCoord[encoderAxis] = startDistance; + endCoord[encoderAxis] = endDistance; + + LOOP_L_N(i, iter) { + stepper.synchronize(); + + planner.buffer_line(startCoord[X_AXIS],startCoord[Y_AXIS],startCoord[Z_AXIS], + stepper.get_axis_position_mm(E_AXIS), feedrate, 0); + stepper.synchronize(); + + delay(250); + startCount = get_position(); + + //do_blocking_move_to(endCoord[X_AXIS],endCoord[Y_AXIS],endCoord[Z_AXIS]); + + planner.buffer_line(endCoord[X_AXIS],endCoord[Y_AXIS],endCoord[Z_AXIS], + stepper.get_axis_position_mm(E_AXIS), feedrate, 0); + stepper.synchronize(); + + //Read encoder distance + delay(250); + stopCount = get_position(); + + travelledDistance = mm_from_count(abs(stopCount - startCount)); + + SERIAL_ECHOPAIR("Attempted to travel: ", travelDistance); + SERIAL_ECHOLNPGM("mm."); + + SERIAL_ECHOPAIR("Actually travelled: ", travelledDistance); + SERIAL_ECHOLNPGM("mm."); + + //Calculate new axis steps per unit + oldStepsMm = planner.axis_steps_per_mm[encoderAxis]; + newStepsMm = (oldStepsMm * travelDistance) / travelledDistance; + + SERIAL_ECHOLNPAIR("Old steps per mm: ", oldStepsMm); + SERIAL_ECHOLNPAIR("New steps per mm: ", newStepsMm); + + //Save new value + planner.axis_steps_per_mm[encoderAxis] = newStepsMm; + + if (iter > 1) { + total += newStepsMm; + + // swap start and end points so next loop runs from current position + float tempCoord = startCoord[encoderAxis]; + startCoord[encoderAxis] = endCoord[encoderAxis]; + endCoord[encoderAxis] = tempCoord; + } + } + + if (iter > 1) { + total /= (float)iter; + SERIAL_ECHOLNPAIR("Average steps per mm: ", total); + } + + ec = oldec; + + SERIAL_ECHOLNPGM("Calculated steps per mm has been set. Please save to EEPROM (M500) if you wish to keep these values."); + } + + void I2CPositionEncoder::reset() { + Wire.beginTransmission(i2cAddress); + Wire.write(I2CPE_RESET_COUNT); + Wire.endTransmission(); + + #if ENABLED(I2CPE_ERR_ROLLING_AVERAGE) + ZERO(err); + #endif + } + + void I2CPositionEncodersMgr::init() { + Wire.begin(); + + #if I2CPE_ENCODER_CNT > 0 + uint8_t i = 0; + + encoders[i].init(I2CPE_ENC_1_ADDR, I2CPE_ENC_1_AXIS); + + #if defined(I2CPE_ENC_1_TYPE) + encoders[i].set_type(I2CPE_ENC_1_TYPE); + #endif + #if defined(I2CPE_ENC_1_TICKS_UNIT) + encoders[i].set_ticks_unit(I2CPE_ENC_1_TICKS_UNIT); + #endif + #if defined(I2CPE_ENC_1_TICKS_REV) + encoders[i].set_stepper_ticks(I2CPE_ENC_1_TICKS_REV); + #endif + #if defined(I2CPE_ENC_1_INVERT) + encoders[i].set_inverted(I2CPE_ENC_1_INVERT); + #endif + #if defined(I2CPE_ENC_1_EC_METHOD) + encoders[i].set_ec_method(I2CPE_ENC_1_EC_METHOD); + #endif + #if defined(I2CPE_ENC_1_EC_THRESH) + encoders[i].set_ec_threshold(I2CPE_ENC_1_EC_THRESH); + #endif + + encoders[i].set_active(encoders[i].passes_test(true)); + + #if (I2CPE_ENC_1_AXIS == E_AXIS) + encoders[i].set_homed(); + #endif + #endif + + #if I2CPE_ENCODER_CNT > 1 + i++; + + encoders[i].init(I2CPE_ENC_2_ADDR, I2CPE_ENC_2_AXIS); + + #if defined(I2CPE_ENC_2_TYPE) + encoders[i].set_type(I2CPE_ENC_2_TYPE); + #endif + #if defined(I2CPE_ENC_2_TICKS_UNIT) + encoders[i].set_ticks_unit(I2CPE_ENC_2_TICKS_UNIT); + #endif + #if defined(I2CPE_ENC_2_TICKS_REV) + encoders[i].set_stepper_ticks(I2CPE_ENC_2_TICKS_REV); + #endif + #if defined(I2CPE_ENC_2_INVERT) + encoders[i].set_inverted(I2CPE_ENC_2_INVERT); + #endif + #if defined(I2CPE_ENC_2_EC_METHOD) + encoders[i].set_ec_method(I2CPE_ENC_2_EC_METHOD); + #endif + #if defined(I2CPE_ENC_2_EC_THRESH) + encoders[i].set_ec_threshold(I2CPE_ENC_2_EC_THRESH); + #endif + + encoders[i].set_active(encoders[i].passes_test(true)); + + #if (I2CPE_ENC_2_AXIS == E_AXIS) + encoders[i].set_homed(); + #endif + #endif + + #if I2CPE_ENCODER_CNT > 2 + i++; + + encoders[i].init(I2CPE_ENC_3_ADDR, I2CPE_ENC_3_AXIS); + + #if defined(I2CPE_ENC_3_TYPE) + encoders[i].set_type(I2CPE_ENC_3_TYPE); + #endif + #if defined(I2CPE_ENC_3_TICKS_UNIT) + encoders[i].set_ticks_unit(I2CPE_ENC_3_TICKS_UNIT); + #endif + #if defined(I2CPE_ENC_3_TICKS_REV) + encoders[i].set_stepper_ticks(I2CPE_ENC_3_TICKS_REV); + #endif + #if defined(I2CPE_ENC_3_INVERT) + encoders[i].set_inverted(I2CPE_ENC_3_INVERT); + #endif + #if defined(I2CPE_ENC_3_EC_METHOD) + encoders[i].set_ec_method(I2CPE_ENC_3_EC_METHOD); + #endif + #if defined(I2CPE_ENC_3_EC_THRESH) + encoders[i].set_ec_threshold(I2CPE_ENC_3_EC_THRESH); + #endif + + encoders[i].set_active(encoders[i].passes_test(true)); + + #if (I2CPE_ENC_3_AXIS == E_AXIS) + encoders[i].set_homed(); + #endif + #endif + + #if I2CPE_ENCODER_CNT > 3 + i++; + + encoders[i].init(I2CPE_ENC_4_ADDR, I2CPE_ENC_4_AXIS); + + #if defined(I2CPE_ENC_4_TYPE) + encoders[i].set_type(I2CPE_ENC_4_TYPE); + #endif + #if defined(I2CPE_ENC_4_TICKS_UNIT) + encoders[i].set_ticks_unit(I2CPE_ENC_4_TICKS_UNIT); + #endif + #if defined(I2CPE_ENC_4_TICKS_REV) + encoders[i].set_stepper_ticks(I2CPE_ENC_4_TICKS_REV); + #endif + #if defined(I2CPE_ENC_4_INVERT) + encoders[i].set_inverted(I2CPE_ENC_4_INVERT); + #endif + #if defined(I2CPE_ENC_4_EC_METHOD) + encoders[i].set_ec_method(I2CPE_ENC_4_EC_METHOD); + #endif + #if defined(I2CPE_ENC_4_EC_THRESH) + encoders[i].set_ec_threshold(I2CPE_ENC_4_EC_THRESH); + #endif + + encoders[i].set_active(encoders[i].passes_test(true)); + + #if (I2CPE_ENC_4_AXIS == E_AXIS) + encoders[i].set_homed(); + #endif + #endif + + #if I2CPE_ENCODER_CNT > 4 + i++; + + encoders[i].init(I2CPE_ENC_5_ADDR, I2CPE_ENC_5_AXIS); + + #if defined(I2CPE_ENC_5_TYPE) + encoders[i].set_type(I2CPE_ENC_5_TYPE); + #endif + #if defined(I2CPE_ENC_5_TICKS_UNIT) + encoders[i].set_ticks_unit(I2CPE_ENC_5_TICKS_UNIT); + #endif + #if defined(I2CPE_ENC_5_TICKS_REV) + encoders[i].set_stepper_ticks(I2CPE_ENC_5_TICKS_REV); + #endif + #if defined(I2CPE_ENC_5_INVERT) + encoders[i].set_inverted(I2CPE_ENC_5_INVERT); + #endif + #if defined(I2CPE_ENC_5_EC_METHOD) + encoders[i].set_ec_method(I2CPE_ENC_5_EC_METHOD); + #endif + #if defined(I2CPE_ENC_5_EC_THRESH) + encoders[i].set_ec_threshold(I2CPE_ENC_5_EC_THRESH); + #endif + + encoders[i].set_active(encoders[i].passes_test(true)); + + #if (I2CPE_ENC_5_AXIS == E_AXIS) + encoders[i].set_homed(); + #endif + #endif + + } + + void I2CPositionEncodersMgr::report_position(uint8_t idx, bool units, bool noOffset) { + CHECK_IDX + + if (units) { + SERIAL_ECHOLN(noOffset ? encoders[idx].mm_from_count(encoders[idx].get_raw_count()) : encoders[idx].get_position_mm()); + } else { + if (noOffset) { + long raw_count = encoders[idx].get_raw_count(); + SERIAL_ECHO(axis_codes[encoders[idx].get_axis()]); + SERIAL_ECHOPGM(" "); + + for (uint8_t j = 31; j > 0; j--) + SERIAL_ECHO((bool)(0x00000001 & (raw_count >> j))); + + SERIAL_ECHO((bool)(0x00000001 & (raw_count))); + SERIAL_ECHOLNPAIR(" ", raw_count); + } else + SERIAL_ECHOLN(encoders[idx].get_position()); + } + } + + void I2CPositionEncodersMgr::change_module_address(uint8_t oldaddr, uint8_t newaddr) { + // First check 'new' address is not in use + Wire.beginTransmission(newaddr); + if (!Wire.endTransmission()) { + SERIAL_ECHOPAIR("?There is already a device with that address on the I2C bus! (", newaddr); + SERIAL_ECHOLNPGM(")"); + return; + } + + // Now check that we can find the module on the oldaddr address + Wire.beginTransmission(oldaddr); + if (Wire.endTransmission()) { + SERIAL_ECHOPAIR("?No module detected at this address! (", oldaddr); + SERIAL_ECHOLNPGM(")"); + return; + } + + SERIAL_ECHOPAIR("Module found at ", oldaddr); + SERIAL_ECHOLNPAIR(", changing address to ", newaddr); + + // Change the modules address + Wire.beginTransmission(oldaddr); + Wire.write(I2CPE_SET_ADDR); + Wire.write(newaddr); + Wire.endTransmission(); + + SERIAL_ECHOLNPGM("Address changed, resetting and waiting for confirmation.."); + + // Wait for the module to reset (can probably be improved by polling address with a timeout). + safe_delay(I2CPE_REBOOT_TIME); + + // Look for the module at the new address. + Wire.beginTransmission(newaddr); + if (Wire.endTransmission()) { + SERIAL_ECHOLNPGM("Address change failed! Check encoder module."); + return; + } + + SERIAL_ECHOLNPGM("Address change successful!"); + + // Now, if this module is configured, find which encoder instance it's supposed to correspond to + // and enable it (it will likely have failed initialisation on power-up, before the address change). + int8_t idx = idx_from_addr(newaddr); + if (idx >= 0 && !encoders[idx].get_active()) { + SERIAL_ECHO(axis_codes[encoders[idx].get_axis()]); + SERIAL_ECHOLNPGM(" axis encoder was not detected on printer startup. Trying again."); + encoders[idx].set_active(encoders[idx].passes_test(true)); + } + } + + void I2CPositionEncodersMgr::report_module_firmware(uint8_t address) { + // First check there is a module + Wire.beginTransmission(address); + if (Wire.endTransmission()) { + SERIAL_ECHOPAIR("?No module detected at this address! (", address); + SERIAL_ECHOLNPGM(")"); + return; + } + + SERIAL_ECHOPAIR("Requesting version info from module at address ", address); + SERIAL_ECHOPGM(":\n"); + + Wire.beginTransmission(address); + Wire.write(I2CPE_SET_REPORT_MODE); + Wire.write(I2CPE_REPORT_VERSION); + Wire.endTransmission(); + + // Read value + if (Wire.requestFrom((int)address, 32)) { + char c; + while (Wire.available() > 0 && (c = (char)Wire.read()) > 0) + SERIAL_ECHO(c); + SERIAL_EOL; + } + + // Set module back to normal (distance) mode + Wire.beginTransmission((int)address); + Wire.write(I2CPE_SET_REPORT_MODE); + Wire.write(I2CPE_REPORT_DISTANCE); + Wire.endTransmission(); + } + + int8_t I2CPositionEncodersMgr::parse() { + I2CPE_addr = 0; + + if (parser.seen('A')) { + if (!parser.has_value()) { + SERIAL_PROTOCOLLNPGM("?A seen, but no address specified! [30-200]"); + return I2CPE_PARSE_ERR; + }; + + I2CPE_addr = parser.value_byte(); + + if (!WITHIN(I2CPE_addr, 30, 200)) { // reserve the first 30 and last 55 + SERIAL_PROTOCOLLNPGM("?Address out of range. [30-200]"); + return I2CPE_PARSE_ERR; + } + + I2CPE_idx = idx_from_addr(I2CPE_addr); + + if (!WITHIN(I2CPE_idx, 0, I2CPE_ENCODER_CNT - 1)) { + SERIAL_PROTOCOLLNPGM("?No device with this address!"); + return I2CPE_PARSE_ERR; + } + } else if (parser.seenval('I')) { + if (!parser.has_value()) { + SERIAL_PROTOCOLLNPAIR("?I seen, but no index specified! [0-", I2CPE_ENCODER_CNT - 1); + SERIAL_ECHOLNPGM("]"); + return I2CPE_PARSE_ERR; + }; + + I2CPE_idx = parser.value_byte(); + + if (!WITHIN(I2CPE_idx, 0, I2CPE_ENCODER_CNT - 1)) { + SERIAL_PROTOCOLLNPAIR("?Index out of range. [0-", I2CPE_ENCODER_CNT - 1); + SERIAL_ECHOLNPGM("]"); + return I2CPE_PARSE_ERR; + } + + I2CPE_addr = encoders[I2CPE_idx].get_address(); + } else { + I2CPE_idx = -1; + } + + I2CPE_anyaxis = parser.seen_axis(); + + return I2CPE_PARSE_OK; + }; + + /** + * M860: Report the position(s) of position encoder module(s). + * + * A Module I2C address. [30, 200]. + * I Module index. [0, I2CPE_ENCODER_CNT - 1] + * O Include homed zero-offset in returned position. + * U Units in mm or raw step count. + * + * If A or I not specified: + * X Report on X axis encoder, if present. + * Y Report on Y axis encoder, if present. + * Z Report on Z axis encoder, if present. + * E Report on E axis encoder, if present. + * + */ + void I2CPositionEncodersMgr::M860() { + if (parse()) return; + + bool hasU = parser.seen('U'), hasO = parser.seen('O'); + + if (I2CPE_idx < 0) { + int8_t idx; + LOOP_XYZE(i) { + if ((!I2CPE_anyaxis || parser.seen(axis_codes[i])) && ((idx = idx_from_axis(AxisEnum(i))) >= 0)) + report_position((uint8_t)idx, hasU, hasO); + } + } else report_position((uint8_t)I2CPE_idx, hasU, hasO); + } + + /** + * M861: Report the status of position encoder modules. + * + * A Module I2C address. [30, 200]. + * I Module index. [0, I2CPE_ENCODER_CNT - 1] + * + * If A or I not specified: + * X Report on X axis encoder, if present. + * Y Report on Y axis encoder, if present. + * Z Report on Z axis encoder, if present. + * E Report on E axis encoder, if present. + * + */ + void I2CPositionEncodersMgr::M861() { + if (parse()) return; + + if (I2CPE_idx < 0) { + int8_t idx; + LOOP_XYZE(i) { + if ((!I2CPE_anyaxis || parser.seen(axis_codes[i])) && ((idx = idx_from_axis(AxisEnum(i))) >= 0)) + report_status((uint8_t)idx); + } + } else report_status((uint8_t)I2CPE_idx); + } + + /** + * M862: Perform an axis continuity test for position encoder + * modules. + * + * A Module I2C address. [30, 200]. + * I Module index. [0, I2CPE_ENCODER_CNT - 1] + * + * If A or I not specified: + * X Report on X axis encoder, if present. + * Y Report on Y axis encoder, if present. + * Z Report on Z axis encoder, if present. + * E Report on E axis encoder, if present. + * + */ + void I2CPositionEncodersMgr::M862() { + if (parse()) return; + + if (I2CPE_idx < 0) { + int8_t idx; + LOOP_XYZE(i) { + if ((!I2CPE_anyaxis || parser.seen(axis_codes[i])) && ((idx = idx_from_axis(AxisEnum(i))) >= 0)) + test_axis((uint8_t)idx); + } + } else test_axis((uint8_t)I2CPE_idx); + } + + /** + * M863: Perform steps-per-mm calibration for + * position encoder modules. + * + * A Module I2C address. [30, 200]. + * I Module index. [0, I2CPE_ENCODER_CNT - 1] + * P Number of rePeats/iterations. + * + * If A or I not specified: + * X Report on X axis encoder, if present. + * Y Report on Y axis encoder, if present. + * Z Report on Z axis encoder, if present. + * E Report on E axis encoder, if present. + * + */ + void I2CPositionEncodersMgr::M863() { + if (parse()) return; + + int iterations = parser.seenval('P') ? constrain(parser.value_byte(), 1, 10) : 1; + + if (I2CPE_idx < 0) { + int8_t idx; + LOOP_XYZE(i) { + if ((!I2CPE_anyaxis || parser.seen(axis_codes[i])) && ((idx = idx_from_axis(AxisEnum(i))) >= 0)) + calibrate_steps_mm((uint8_t)idx, iterations); + } + } else calibrate_steps_mm((uint8_t)I2CPE_idx, iterations); + } + + /** + * M864: Change position encoder module I2C address. + * + * A Module current/old I2C address. If not present, + * assumes default address (030). [30, 200]. + * N Module new I2C address. [30, 200]. + * + * If N not specified: + * X Use I2CPE_PRESET_ADDR_X (030). + * Y Use I2CPE_PRESET_ADDR_Y (031). + * Z Use I2CPE_PRESET_ADDR_Z (032). + * E Use I2CPE_PRESET_ADDR_E (033). + */ + void I2CPositionEncodersMgr::M864() { + uint8_t newAddress; + + if (parse()) return; + + if (!I2CPE_addr) I2CPE_addr = I2CPE_PRESET_ADDR_X; + + if (parser.seen('N')) { + if (!parser.has_value()) { + SERIAL_PROTOCOLLNPGM("?N seen, but no address specified! [30-200]"); + return; + }; + + newAddress = parser.value_byte(); + + if (!WITHIN(newAddress, 30, 200)) { + SERIAL_PROTOCOLLNPGM("?New address out of range. [30-200]"); + return; + } + } else if (!I2CPE_anyaxis) { + SERIAL_PROTOCOLLNPGM("?You must specify N or [XYZE]."); + return; + } else { + if (parser.seen('X')) newAddress = I2CPE_PRESET_ADDR_X; + else if (parser.seen('Y')) newAddress = I2CPE_PRESET_ADDR_Y; + else if (parser.seen('Z')) newAddress = I2CPE_PRESET_ADDR_Z; + else if (parser.seen('E')) newAddress = I2CPE_PRESET_ADDR_E; + else return; + } + + SERIAL_ECHOPAIR("Changing module at address ", I2CPE_addr); + SERIAL_ECHOLNPAIR(" to address ", newAddress); + + change_module_address(I2CPE_addr, newAddress); + } + + /** + * M865: Check position encoder module firmware version. + * + * A Module I2C address. [30, 200]. + * I Module index. [0, I2CPE_ENCODER_CNT - 1]. + * + * If A or I not specified: + * X Check X axis encoder, if present. + * Y Check Y axis encoder, if present. + * Z Check Z axis encoder, if present. + * E Check E axis encoder, if present. + */ + void I2CPositionEncodersMgr::M865() { + if (parse()) return; + + if (!I2CPE_addr) { + int8_t idx; + LOOP_XYZE(i) { + if ((!I2CPE_anyaxis || parser.seen(axis_codes[i])) && ((idx = idx_from_axis(AxisEnum(i))) >= 0)) + report_module_firmware(encoders[idx].get_address()); + } + } else report_module_firmware(I2CPE_addr); + } + + /** + * M866: Report or reset position encoder module error + * count. + * + * A Module I2C address. [30, 200]. + * I Module index. [0, I2CPE_ENCODER_CNT - 1]. + * R Reset error counter. + * + * If A or I not specified: + * X Act on X axis encoder, if present. + * Y Act on Y axis encoder, if present. + * Z Act on Z axis encoder, if present. + * E Act on E axis encoder, if present. + */ + void I2CPositionEncodersMgr::M866() { + if (parse()) return; + + bool hasR = parser.seen('R'); + + if (I2CPE_idx < 0) { + int8_t idx; + LOOP_XYZE(i) { + if ((!I2CPE_anyaxis || parser.seen(axis_codes[i])) && ((idx = idx_from_axis(AxisEnum(i))) >= 0)) { + if (hasR) reset_error_count((uint8_t)idx, AxisEnum(i)); + else report_error_count((uint8_t)idx, AxisEnum(i)); + } + } + } else { + if (hasR) reset_error_count((uint8_t)I2CPE_idx, encoders[I2CPE_idx].get_axis()); + else report_error_count((uint8_t)I2CPE_idx, encoders[I2CPE_idx].get_axis()); + } + } + + /** + * M867: Enable/disable or toggle error correction for position encoder modules. + * + * A Module I2C address. [30, 200]. + * I Module index. [0, I2CPE_ENCODER_CNT - 1]. + * S<1|0> Enable/disable error correction. 1 enables, 0 disables. If not + * supplied, toggle. + * + * If A or I not specified: + * X Act on X axis encoder, if present. + * Y Act on Y axis encoder, if present. + * Z Act on Z axis encoder, if present. + * E Act on E axis encoder, if present. + */ + void I2CPositionEncodersMgr::M867() { + if (parse()) return; + + int8_t onoff = parser.seenval('S') ? parser.value_int() : -1; + + if (I2CPE_idx < 0) { + int8_t idx; + LOOP_XYZE(i) { + if ((!I2CPE_anyaxis || parser.seen(axis_codes[i])) && ((idx = idx_from_axis(AxisEnum(i))) >= 0)) { + if (onoff == -1) enable_ec((uint8_t)idx, !encoders[idx].get_ec_enabled(), AxisEnum(i)); + else enable_ec((uint8_t)idx, (bool)onoff, AxisEnum(i)); + } + } + } else { + if (onoff == -1) enable_ec((uint8_t)I2CPE_idx, !encoders[I2CPE_idx].get_ec_enabled(), encoders[I2CPE_idx].get_axis()); + else enable_ec((uint8_t)I2CPE_idx, (bool)onoff, encoders[I2CPE_idx].get_axis()); + } + } + + /** + * M868: Report or set position encoder module error correction + * threshold. + * + * A Module I2C address. [30, 200]. + * I Module index. [0, I2CPE_ENCODER_CNT - 1]. + * T New error correction threshold. + * + * If A not specified: + * X Act on X axis encoder, if present. + * Y Act on Y axis encoder, if present. + * Z Act on Z axis encoder, if present. + * E Act on E axis encoder, if present. + */ + void I2CPositionEncodersMgr::M868() { + if (parse()) return; + + float newThreshold = parser.seenval('T') ? parser.value_float() : -9999; + + if (I2CPE_idx < 0) { + int8_t idx; + LOOP_XYZE(i) { + if ((!I2CPE_anyaxis || parser.seen(axis_codes[i])) && ((idx = idx_from_axis(AxisEnum(i))) >= 0)) { + if (newThreshold != -9999) set_ec_threshold((uint8_t)idx, newThreshold, encoders[idx].get_axis()); + else get_ec_threshold((uint8_t)idx, encoders[idx].get_axis()); + } + } + } else { + if (newThreshold != -9999) set_ec_threshold((uint8_t)I2CPE_idx, newThreshold, encoders[I2CPE_idx].get_axis()); + else get_ec_threshold((uint8_t)I2CPE_idx, encoders[I2CPE_idx].get_axis()); + } + } + + /** + * M869: Report position encoder module error. + * + * A Module I2C address. [30, 200]. + * I Module index. [0, I2CPE_ENCODER_CNT - 1]. + * + * If A not specified: + * X Act on X axis encoder, if present. + * Y Act on Y axis encoder, if present. + * Z Act on Z axis encoder, if present. + * E Act on E axis encoder, if present. + */ + void I2CPositionEncodersMgr::M869() { + if (parse()) return; + + if (I2CPE_idx < 0) { + int8_t idx; + LOOP_XYZE(i) { + if ((!I2CPE_anyaxis || parser.seen(axis_codes[i])) && ((idx = idx_from_axis(AxisEnum(i))) >= 0)) + report_error((uint8_t)idx); + } + } else report_error((uint8_t)I2CPE_idx); + } + +#endif diff --git a/Marlin/I2CPositionEncoder.h b/Marlin/I2CPositionEncoder.h new file mode 100644 index 0000000000..a4b7eb3adb --- /dev/null +++ b/Marlin/I2CPositionEncoder.h @@ -0,0 +1,356 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (C) 2016, 2017 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +#ifndef I2CPOSENC_H +#define I2CPOSENC_H + +#include "MarlinConfig.h" + +#if ENABLED(I2C_POSITION_ENCODERS) + + #include "enum.h" + #include "macros.h" + #include "types.h" + #include + + //=========== Advanced / Less-Common Encoder Configuration Settings ========== + + #define I2CPE_EC_THRESH_PROPORTIONAL // if enabled adjusts the error correction threshold + // proportional to the current speed of the axis allows + // for very small error margin at low speeds without + // stuttering due to reading latency at high speeds + + #define I2CPE_DEBUG // enable encoder-related debug serial echos + + #define I2CPE_REBOOT_TIME 5000 // time we wait for an encoder module to reboot + // after changing address. + + #define I2CPE_MAG_SIG_GOOD 0 + #define I2CPE_MAG_SIG_MID 1 + #define I2CPE_MAG_SIG_BAD 2 + #define I2CPE_MAG_SIG_NF 255 + + #define I2CPE_REQ_REPORT 0 + #define I2CPE_RESET_COUNT 1 + #define I2CPE_SET_ADDR 2 + #define I2CPE_SET_REPORT_MODE 3 + #define I2CPE_CLEAR_EEPROM 4 + + #define I2CPE_LED_PAR_MODE 10 + #define I2CPE_LED_PAR_BRT 11 + #define I2CPE_LED_PAR_RATE 14 + + #define I2CPE_REPORT_DISTANCE 0 + #define I2CPE_REPORT_STRENGTH 1 + #define I2CPE_REPORT_VERSION 2 + + // Default I2C addresses + #define I2CPE_PRESET_ADDR_X 30 + #define I2CPE_PRESET_ADDR_Y 31 + #define I2CPE_PRESET_ADDR_Z 32 + #define I2CPE_PRESET_ADDR_E 33 + + #define I2CPE_DEF_AXIS X_AXIS + #define I2CPE_DEF_ADDR I2CPE_PRESET_ADDR_X + + // Error event counter; tracks how many times there is an error exceeding a certain threshold + #define I2CPE_ERR_CNT_THRESH 3.00 + #define I2CPE_ERR_CNT_DEBOUNCE_MS 2000 + + #if ENABLED(I2CPE_ERR_ROLLING_AVERAGE) + #define I2CPE_ERR_ARRAY_SIZE 32 + #endif + + // Error Correction Methods + #define I2CPE_ECM_NONE 0 + #define I2CPE_ECM_MICROSTEP 1 + #define I2CPE_ECM_PLANNER 2 + #define I2CPE_ECM_STALLDETECT 3 + + // Encoder types + #define I2CPE_ENC_TYPE_ROTARY 0 + #define I2CPE_ENC_TYPE_LINEAR 1 + + // Parser + #define I2CPE_PARSE_ERR 1 + #define I2CPE_PARSE_OK 0 + + #define LOOP_PE(VAR) LOOP_L_N(VAR, I2CPE_ENCODER_CNT) + #define CHECK_IDX if (!WITHIN(idx, 0, I2CPE_ENCODER_CNT - 1)) return; + + extern const char axis_codes[XYZE]; + + typedef union { + volatile long val = 0; + uint8_t bval[4]; + } i2cLong; + + class I2CPositionEncoder { + private: + AxisEnum encoderAxis = I2CPE_DEF_AXIS; + + uint8_t i2cAddress = I2CPE_DEF_ADDR, + ecMethod = I2CPE_DEF_EC_METHOD, + type = I2CPE_DEF_TYPE, + H = I2CPE_MAG_SIG_NF; // Magnetic field strength + + int encoderTicksPerUnit = I2CPE_DEF_ENC_TICKS_UNIT, + stepperTicks = I2CPE_DEF_TICKS_REV; + + float ecThreshold = I2CPE_DEF_EC_THRESH; + + bool homed = false, + trusted = false, + initialised = false, + active = false, + invert = false, + ec = true; + + int errorCount = 0, + errorPrev = 0; + + float axisOffset = 0; + + long axisOffsetTicks = 0, + zeroOffset = 0, + lastPosition = 0, + position; + + unsigned long lastPositionTime = 0, + lastErrorCountTime = 0, + lastErrorTime; + + //double positionMm; //calculate + + #if ENABLED(I2CPE_ERR_ROLLING_AVERAGE) + uint8_t errIdx = 0; + int err[I2CPE_ERR_ARRAY_SIZE] = {0}; + #endif + + public: + void init(uint8_t address, AxisEnum axis); + void reset(); + + void update(); + + void set_homed(); + + long get_raw_count(); + + FORCE_INLINE double mm_from_count(long count) { + if (type == I2CPE_ENC_TYPE_LINEAR) return count / encoderTicksPerUnit; + else if (type == I2CPE_ENC_TYPE_ROTARY) + return (count * stepperTicks) / (encoderTicksPerUnit * planner.axis_steps_per_mm[encoderAxis]); + return -1; + } + + FORCE_INLINE double get_position_mm() { return mm_from_count(get_position()); } + FORCE_INLINE long get_position() { return get_raw_count() - zeroOffset - axisOffsetTicks; } + + long get_axis_error_steps(bool report); + double get_axis_error_mm(bool report); + + void calibrate_steps_mm(int iter); + + bool passes_test(bool report); + + bool test_axis(void); + + FORCE_INLINE int get_error_count(void) { return errorCount; } + FORCE_INLINE void set_error_count(int newCount) { errorCount = newCount; } + + FORCE_INLINE uint8_t get_address() { return i2cAddress; } + FORCE_INLINE void set_address(uint8_t addr) { i2cAddress = addr; } + + FORCE_INLINE bool get_active(void) { return active; } + FORCE_INLINE void set_active(bool a) { active = a; } + + FORCE_INLINE void set_inverted(bool i) { invert = i; } + + FORCE_INLINE AxisEnum get_axis() { return encoderAxis; } + + FORCE_INLINE bool get_ec_enabled() { return ec; } + FORCE_INLINE void set_ec_enabled(bool enabled) { ec = enabled; } + + FORCE_INLINE uint8_t get_ec_method() { return ecMethod; } + FORCE_INLINE void set_ec_method(byte method) { ecMethod = method; } + + FORCE_INLINE float get_ec_threshold() { return ecThreshold; } + FORCE_INLINE void set_ec_threshold(float newThreshold) { ecThreshold = newThreshold; } + + FORCE_INLINE int get_encoder_ticks_mm() { + if (type == I2CPE_ENC_TYPE_LINEAR) return encoderTicksPerUnit; + else if (type == I2CPE_ENC_TYPE_ROTARY) + return (int)((encoderTicksPerUnit / stepperTicks) * planner.axis_steps_per_mm[encoderAxis]); + return 0; + } + + FORCE_INLINE int get_ticks_unit() { return encoderTicksPerUnit; } + FORCE_INLINE void set_ticks_unit(int ticks) { encoderTicksPerUnit = ticks; } + + FORCE_INLINE uint8_t get_type() { return type; } + FORCE_INLINE void set_type(byte newType) { type = newType; } + + FORCE_INLINE int get_stepper_ticks() { return stepperTicks; } + FORCE_INLINE void set_stepper_ticks(int ticks) { stepperTicks = ticks; } + + FORCE_INLINE float get_axis_offset() { return axisOffset; } + FORCE_INLINE void set_axis_offset(float newOffset) { + axisOffset = newOffset; + axisOffsetTicks = (long)(axisOffset * get_encoder_ticks_mm()); + } + + FORCE_INLINE void set_current_position(float newPositionMm) { + set_axis_offset(get_position_mm() - newPositionMm + axisOffset); + } + }; + + class I2CPositionEncodersMgr { + private: + bool I2CPE_anyaxis; + uint8_t I2CPE_addr; + int8_t I2CPE_idx; + + public: + void init(void); + + // consider only updating one endoder per call / tick if encoders become too time intensive + void update(void) { LOOP_PE(i) encoders[i].update(); } + + void homed(AxisEnum axis) { + LOOP_PE(i) + if (encoders[i].get_axis() == axis) encoders[i].set_homed(); + } + + void report_position(uint8_t idx, bool units, bool noOffset); + + void report_status(uint8_t idx) { + CHECK_IDX + SERIAL_ECHOPAIR("Encoder ",idx); + SERIAL_ECHOPGM(": "); + encoders[idx].get_raw_count(); + encoders[idx].passes_test(true); + } + + void report_error(uint8_t idx) { + CHECK_IDX + encoders[idx].get_axis_error_steps(true); + } + + void test_axis(uint8_t idx) { + CHECK_IDX + encoders[idx].test_axis(); + } + + void calibrate_steps_mm(uint8_t idx, int iterations) { + CHECK_IDX + encoders[idx].calibrate_steps_mm(iterations); + } + + void change_module_address(uint8_t oldaddr, uint8_t newaddr); + void report_module_firmware(uint8_t address); + + void report_error_count(uint8_t idx, AxisEnum axis) { + CHECK_IDX + SERIAL_ECHOPAIR("Error count on ", axis_codes[axis]); + SERIAL_ECHOLNPAIR(" axis is ", encoders[idx].get_error_count()); + } + + void reset_error_count(uint8_t idx, AxisEnum axis) { + CHECK_IDX + encoders[idx].set_error_count(0); + SERIAL_ECHOPAIR("Error count on ", axis_codes[axis]); + SERIAL_ECHOLNPGM(" axis has been reset."); + } + + void enable_ec(uint8_t idx, bool enabled, AxisEnum axis) { + CHECK_IDX + encoders[idx].set_ec_enabled(enabled); + SERIAL_ECHOPAIR("Error correction on ", axis_codes[axis]); + SERIAL_ECHOPGM(" axis is "); + serialprintPGM(encoders[idx].get_ec_enabled() ? PSTR("en") : PSTR("dis")); + SERIAL_ECHOLNPGM("abled."); + } + + void set_ec_threshold(uint8_t idx, float newThreshold, AxisEnum axis) { + CHECK_IDX + encoders[idx].set_ec_threshold(newThreshold); + SERIAL_ECHOPAIR("Error correct threshold for ", axis_codes[axis]); + SERIAL_ECHOPAIR_F(" axis set to ", newThreshold); + SERIAL_ECHOLNPGM("mm."); + } + + void get_ec_threshold(uint8_t idx, AxisEnum axis) { + CHECK_IDX + float threshold = encoders[idx].get_ec_threshold(); + SERIAL_ECHOPAIR("Error correct threshold for ", axis_codes[axis]); + SERIAL_ECHOPAIR_F(" axis is ", threshold); + SERIAL_ECHOLNPGM("mm."); + } + + int8_t idx_from_axis(AxisEnum axis) { + LOOP_PE(i) + if (encoders[i].get_axis() == axis) return i; + + return -1; + } + + int8_t idx_from_addr(uint8_t addr) { + LOOP_PE(i) + if (encoders[i].get_address() == addr) return i; + + return -1; + } + + int8_t parse(); + + void M860(); + void M861(); + void M862(); + void M863(); + void M864(); + void M865(); + void M866(); + void M867(); + void M868(); + void M869(); + + I2CPositionEncoder encoders[I2CPE_ENCODER_CNT]; + }; + + extern I2CPositionEncodersMgr I2CPEM; + + FORCE_INLINE void gcode_M860() { I2CPEM.M860(); } + FORCE_INLINE void gcode_M861() { I2CPEM.M861(); } + FORCE_INLINE void gcode_M862() { I2CPEM.M862(); } + FORCE_INLINE void gcode_M863() { I2CPEM.M863(); } + FORCE_INLINE void gcode_M864() { I2CPEM.M864(); } + FORCE_INLINE void gcode_M865() { I2CPEM.M865(); } + FORCE_INLINE void gcode_M866() { I2CPEM.M866(); } + FORCE_INLINE void gcode_M867() { I2CPEM.M867(); } + FORCE_INLINE void gcode_M868() { I2CPEM.M868(); } + FORCE_INLINE void gcode_M869() { I2CPEM.M869(); } + +#endif //I2C_POSITION_ENCODERS +#endif //I2CPOSENC_H + + diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 6e6ded87c2..1e0ef1554a 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -200,6 +200,16 @@ * M666 - Set delta endstop adjustment. (Requires DELTA) * M605 - Set dual x-carriage movement mode: "M605 S [X] [R]". (Requires DUAL_X_CARRIAGE) * M851 - Set Z probe's Z offset in current units. (Negative = below the nozzle.) + * M860 - Report the position of position encoder modules. + * M861 - Report the status of position encoder modules. + * M862 - Perform an axis continuity test for position encoder modules. + * M863 - Perform steps-per-mm calibration for position encoder modules. + * M864 - Change position encoder module I2C address. + * M865 - Check position encoder module firmware version. + * M866 - Report or reset position encoder module error count. + * M867 - Enable/disable or toggle error correction for position encoder modules. + * M868 - Report or set position encoder module error correction threshold. + * M869 - Report position encoder module error. * M900 - Get and/or Set advance K factor and WH/D ratio. (Requires LIN_ADVANCE) * M906 - Set or get motor current in milliamps using axis codes X, Y, Z, E. Report values if no axis codes given. (Requires HAVE_TMC2130) * M907 - Set digital trimpot motor current using axis codes. (Requires a board with digital trimpots) @@ -286,6 +296,10 @@ #include "twibus.h" #endif +#if ENABLED(I2C_POSITION_ENCODERS) + #include "I2CPositionEncoder.h" +#endif + #if ENABLED(ENDSTOP_INTERRUPTS_FEATURE) #include "endstop_interrupts.h" #endif @@ -662,6 +676,12 @@ static bool send_ok[BUFSIZE]; #define host_keepalive() NOOP #endif +#if ENABLED(I2C_POSITION_ENCODERS) + I2CPositionEncodersMgr I2CPEM; + uint8_t blockBufferIndexRef = 0; + millis_t lastUpdateMillis; +#endif + FORCE_INLINE float pgm_read_any(const float *p) { return pgm_read_float_near(p); } FORCE_INLINE signed char pgm_read_any(const signed char *p) { return pgm_read_byte_near(p); } @@ -1493,6 +1513,10 @@ static void set_axis_is_at_home(const AxisEnum axis) { SERIAL_EOL; } #endif + + #if ENABLED(I2C_POSITION_ENCODERS) + I2CPEM.homed(axis); + #endif } /** @@ -5609,6 +5633,11 @@ inline void gcode_G92() { #if HAS_POSITION_SHIFT position_shift[i] += v - p; // Offset the coordinate space update_software_endstops((AxisEnum)i); + + #if ENABLED(I2C_POSITION_ENCODERS) + I2CPEM.encoders[I2CPEM.idx_from_axis((AxisEnum) i)].set_axis_offset(position_shift[i]); + #endif + #endif } #endif @@ -10904,6 +10933,50 @@ void process_next_command() { break; #endif + #if ENABLED(I2C_POSITION_ENCODERS) + + case 860: // M860 Report encoder module position + gcode_M860(); + break; + + case 861: // M861 Report encoder module status + gcode_M861(); + break; + + case 862: // M862 Perform axis test + gcode_M862(); + break; + + case 863: // M863 Calibrate steps/mm + gcode_M863(); + break; + + case 864: // M864 Change module address + gcode_M864(); + break; + + case 865: // M865 Check module firmware version + gcode_M865(); + break; + + case 866: // M866 Report axis error count + gcode_M866(); + break; + + case 867: // M867 Toggle error correction + gcode_M867(); + break; + + case 868: // M868 Set error correction threshold + gcode_M868(); + break; + + case 869: // M869 Report axis error + gcode_M869(); + break; + + #endif // I2C_POSITION_ENCODERS + case 999: // M999: Restart after being Stopped gcode_M999(); break; @@ -12200,7 +12273,7 @@ void disable_all_steppers() { const bool has_days = (elapsed.value > 60*60*24L); (void)elapsed.toDigital(timestamp, has_days); SERIAL_ECHO(timestamp); - SERIAL_ECHO(": "); + SERIAL_ECHOPGM(": "); SERIAL_ECHO(axisID); SERIAL_ECHOLNPGM(" driver overtemperature warning!"); } @@ -12495,6 +12568,16 @@ void idle( #if HAS_BUZZER && DISABLED(LCD_USE_I2C_BUZZER) buzzer.tick(); #endif + + #if ENABLED(I2C_POSITION_ENCODERS) + if (planner.blocks_queued() && + ( (blockBufferIndexRef != planner.block_buffer_head) || + ((lastUpdateMillis + I2CPE_MIN_UPD_TIME_MS) < millis())) ) { + blockBufferIndexRef = planner.block_buffer_head; + I2CPEM.update(); + lastUpdateMillis = millis(); + } + #endif } /** @@ -12739,6 +12822,10 @@ void setup() { set_bltouch_deployed(false); #endif + #if ENABLED(I2C_POSITION_ENCODERS) + I2CPEM.init(); + #endif + #if ENABLED(EXPERIMENTAL_I2CBUS) && I2C_SLAVE_ADDRESS > 0 i2c.onReceive(i2c_on_receive); i2c.onRequest(i2c_on_request); diff --git a/Marlin/SanityCheck.h b/Marlin/SanityCheck.h index 440144cf8f..7260c0e5b2 100644 --- a/Marlin/SanityCheck.h +++ b/Marlin/SanityCheck.h @@ -270,11 +270,24 @@ #endif #endif +/** + * I2C Position Encoders + */ +#if ENABLED(I2C_POSITION_ENCODERS) + #if DISABLED(BABYSTEPPING) + #error "I2C_POSITION_ENCODERS requires BABYSTEPPING." + #endif + + #if I2CPE_ENCODER_CNT > 5 || I2CPE_ENCODER_CNT < 1 + #error "I2CPE_ENCODER_CNT must be between 1 and 5." + #endif +#endif + /** * Babystepping */ #if ENABLED(BABYSTEPPING) - #if DISABLED(ULTRA_LCD) + #if DISABLED(ULTRA_LCD) && DISABLED(I2C_POSITION_ENCODERS) #error "BABYSTEPPING requires an LCD controller." #elif ENABLED(SCARA) #error "BABYSTEPPING is not implemented for SCARA yet." diff --git a/Marlin/enum.h b/Marlin/enum.h index 999164187f..764e154cd0 100644 --- a/Marlin/enum.h +++ b/Marlin/enum.h @@ -34,23 +34,29 @@ * between X_AXIS and X Head movement, like CoreXY bots */ enum AxisEnum { - NO_AXIS = -1, - X_AXIS = 0, - A_AXIS = 0, - Y_AXIS = 1, - B_AXIS = 1, - Z_AXIS = 2, - C_AXIS = 2, - E_AXIS = 3, - X_HEAD = 4, - Y_HEAD = 5, - Z_HEAD = 6, - ALL_AXES = 100 + NO_AXIS = -1, + X_AXIS = 0, + A_AXIS = 0, + Y_AXIS = 1, + B_AXIS = 1, + Z_AXIS = 2, + C_AXIS = 2, + E_AXIS = 3, + X_HEAD = 4, + Y_HEAD = 5, + Z_HEAD = 6, + ALL_AXES = 100 }; -#define LOOP_XYZ(VAR) for (uint8_t VAR=X_AXIS; VAR<=Z_AXIS; VAR++) -#define LOOP_XYZE(VAR) for (uint8_t VAR=X_AXIS; VAR<=E_AXIS; VAR++) -#define LOOP_XYZE_N(VAR) for (uint8_t VAR=X_AXIS; VAR> 3], (L - 'A') & 0x7) + #else // Code is found in the string. If not found, value_ptr is unchanged. @@ -139,6 +145,12 @@ public: return b; } + static volatile bool seen_any() { + return *command_args == '\0'; + } + + #define SEEN_TEST(L) !!strchr(command_args, L) + #endif // FASTER_GCODE_PARSER // Populate all fields by parsing a single line of GCode @@ -148,6 +160,13 @@ public: // Code value pointer was set FORCE_INLINE static bool has_value() { return value_ptr != NULL; } + // Seen and has value + FORCE_INLINE static bool seenval(const char c) { return seen(c) && has_value(); } + + static volatile bool seen_axis() { + return SEEN_TEST('X') || SEEN_TEST('Y') || SEEN_TEST('Z') || SEEN_TEST('E'); + } + // Float removes 'E' to prevent scientific notation interpretation inline static float value_float() { if (value_ptr) { diff --git a/Marlin/macros.h b/Marlin/macros.h index 0fb057441d..f1575cad12 100644 --- a/Marlin/macros.h +++ b/Marlin/macros.h @@ -108,6 +108,8 @@ #define HYPOT2(x,y) (sq(x)+sq(y)) #define HYPOT(x,y) sqrt(HYPOT2(x,y)) +#define SIGN(a) ((a>0)-(a<0)) + // Macros to contrain values #define NOLESS(v,n) do{ if (v < n) v = n; }while(0) #define NOMORE(v,n) do{ if (v > n) v = n; }while(0) From 5b270417ed86eca5a5aea4edb69ee167fba10607 Mon Sep 17 00:00:00 2001 From: Diederik van der Pant Date: Fri, 9 Jun 2017 14:17:47 +0200 Subject: [PATCH 038/180] added shift register pins for reprapworld keypad v1.1 I recently upgraded my Marlin to V1.1.x and decided to publish my fix to make marlin compile properly when #define board megatronics 2 in combination with #define reprapworld keypad v1.1. It was previously described in the comments of a closed pull request. MarlinFirmware#472. All the buttons on the keypad are now operational. --- Marlin/pins_MEGATRONICS_2.h | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/Marlin/pins_MEGATRONICS_2.h b/Marlin/pins_MEGATRONICS_2.h index 0cbb769453..6db1489bf9 100644 --- a/Marlin/pins_MEGATRONICS_2.h +++ b/Marlin/pins_MEGATRONICS_2.h @@ -131,6 +131,12 @@ #define BTN_EN2 59 #define BTN_ENC 43 +// Buttons that are attached using shift register of reprapworld keypad v1.1 +#define SHIFT_CLK 63 +#define SHIFT_LD 42 +#define SHIFT_OUT 17 +#define SHIFT_EN 17 + // // M3/M4/M5 - Spindle/Laser Control // From 1c107b3949edf551f974f494a9e1fc92d35f37e4 Mon Sep 17 00:00:00 2001 From: Bob-the-Kuhn Date: Fri, 9 Jun 2017 11:53:36 -0500 Subject: [PATCH 039/180] delete problem line --- Marlin/Configuration.h | 1 - Marlin/example_configurations/Cartesio/Configuration.h | 1 - Marlin/example_configurations/Felix/Configuration.h | 1 - Marlin/example_configurations/Felix/DUAL/Configuration.h | 1 - Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h | 1 - Marlin/example_configurations/Hephestos/Configuration.h | 1 - Marlin/example_configurations/Hephestos_2/Configuration.h | 1 - Marlin/example_configurations/K8200/Configuration.h | 1 - Marlin/example_configurations/K8400/Configuration.h | 1 - Marlin/example_configurations/K8400/Dual-head/Configuration.h | 1 - Marlin/example_configurations/M150/Configuration.h | 1 - .../RepRapWorld/Megatronics/Configuration.h | 1 - Marlin/example_configurations/RigidBot/Configuration.h | 1 - Marlin/example_configurations/SCARA/Configuration.h | 1 - Marlin/example_configurations/TAZ4/Configuration.h | 1 - Marlin/example_configurations/TinyBoy2/Configuration.h | 1 - Marlin/example_configurations/WITBOX/Configuration.h | 1 - Marlin/example_configurations/adafruit/ST7565/Configuration.h | 1 - .../delta/FLSUN/auto_calibrate/Configuration.h | 1 - .../delta/FLSUN/kossel_mini/Configuration.h | 1 - Marlin/example_configurations/delta/generic/Configuration.h | 1 - Marlin/example_configurations/delta/kossel_mini/Configuration.h | 1 - Marlin/example_configurations/delta/kossel_pro/Configuration.h | 1 - Marlin/example_configurations/delta/kossel_xl/Configuration.h | 1 - Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h | 1 - Marlin/example_configurations/makibox/Configuration.h | 1 - Marlin/example_configurations/tvrrug/Round2/Configuration.h | 1 - Marlin/example_configurations/wt150/Configuration.h | 1 - 28 files changed, 28 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 2ab907bafc..cc422b6525 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -566,7 +566,6 @@ * */ //#define Z_MIN_PROBE_ENDSTOP -//#define Z_MIN_PROBE_PIN Z_MAX_PIN /** * Probe Type diff --git a/Marlin/example_configurations/Cartesio/Configuration.h b/Marlin/example_configurations/Cartesio/Configuration.h index 0ded77ad5c..13929a9543 100644 --- a/Marlin/example_configurations/Cartesio/Configuration.h +++ b/Marlin/example_configurations/Cartesio/Configuration.h @@ -563,7 +563,6 @@ * */ //#define Z_MIN_PROBE_ENDSTOP -//#define Z_MIN_PROBE_PIN Z_MAX_PIN /** * Probe Type diff --git a/Marlin/example_configurations/Felix/Configuration.h b/Marlin/example_configurations/Felix/Configuration.h index 6956cfda03..d2fd786a5d 100644 --- a/Marlin/example_configurations/Felix/Configuration.h +++ b/Marlin/example_configurations/Felix/Configuration.h @@ -547,7 +547,6 @@ * */ //#define Z_MIN_PROBE_ENDSTOP -//#define Z_MIN_PROBE_PIN Z_MAX_PIN /** * Probe Type diff --git a/Marlin/example_configurations/Felix/DUAL/Configuration.h b/Marlin/example_configurations/Felix/DUAL/Configuration.h index 183759c6d7..5189616aad 100644 --- a/Marlin/example_configurations/Felix/DUAL/Configuration.h +++ b/Marlin/example_configurations/Felix/DUAL/Configuration.h @@ -547,7 +547,6 @@ * */ //#define Z_MIN_PROBE_ENDSTOP -//#define Z_MIN_PROBE_PIN Z_MAX_PIN /** * Probe Type diff --git a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h index 370c0b2573..8d72fcc27c 100644 --- a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h +++ b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h @@ -571,7 +571,6 @@ * */ //#define Z_MIN_PROBE_ENDSTOP -//#define Z_MIN_PROBE_PIN Z_MAX_PIN /** * Probe Type diff --git a/Marlin/example_configurations/Hephestos/Configuration.h b/Marlin/example_configurations/Hephestos/Configuration.h index dca9646126..ae0e3a89a5 100644 --- a/Marlin/example_configurations/Hephestos/Configuration.h +++ b/Marlin/example_configurations/Hephestos/Configuration.h @@ -555,7 +555,6 @@ * */ #define Z_MIN_PROBE_ENDSTOP -//#define Z_MIN_PROBE_PIN Z_MAX_PIN /** * Probe Type diff --git a/Marlin/example_configurations/Hephestos_2/Configuration.h b/Marlin/example_configurations/Hephestos_2/Configuration.h index 98416e2c79..aab15d09a7 100644 --- a/Marlin/example_configurations/Hephestos_2/Configuration.h +++ b/Marlin/example_configurations/Hephestos_2/Configuration.h @@ -558,7 +558,6 @@ * */ //#define Z_MIN_PROBE_ENDSTOP -//#define Z_MIN_PROBE_PIN Z_MAX_PIN /** * Probe Type diff --git a/Marlin/example_configurations/K8200/Configuration.h b/Marlin/example_configurations/K8200/Configuration.h index 369d315305..2efae18109 100644 --- a/Marlin/example_configurations/K8200/Configuration.h +++ b/Marlin/example_configurations/K8200/Configuration.h @@ -594,7 +594,6 @@ * */ //#define Z_MIN_PROBE_ENDSTOP -//#define Z_MIN_PROBE_PIN Z_MAX_PIN /** * Probe Type diff --git a/Marlin/example_configurations/K8400/Configuration.h b/Marlin/example_configurations/K8400/Configuration.h index 6b7a39efbe..8c2ed2be9f 100644 --- a/Marlin/example_configurations/K8400/Configuration.h +++ b/Marlin/example_configurations/K8400/Configuration.h @@ -565,7 +565,6 @@ * */ //#define Z_MIN_PROBE_ENDSTOP -//#define Z_MIN_PROBE_PIN Z_MAX_PIN /** * Probe Type diff --git a/Marlin/example_configurations/K8400/Dual-head/Configuration.h b/Marlin/example_configurations/K8400/Dual-head/Configuration.h index cfa443311d..7236ab4968 100644 --- a/Marlin/example_configurations/K8400/Dual-head/Configuration.h +++ b/Marlin/example_configurations/K8400/Dual-head/Configuration.h @@ -565,7 +565,6 @@ * */ //#define Z_MIN_PROBE_ENDSTOP -//#define Z_MIN_PROBE_PIN Z_MAX_PIN /** * Probe Type diff --git a/Marlin/example_configurations/M150/Configuration.h b/Marlin/example_configurations/M150/Configuration.h index 3c85ce9ab5..7b5321be9e 100644 --- a/Marlin/example_configurations/M150/Configuration.h +++ b/Marlin/example_configurations/M150/Configuration.h @@ -584,7 +584,6 @@ * */ //#define Z_MIN_PROBE_ENDSTOP -//#define Z_MIN_PROBE_PIN Z_MAX_PIN /** * Probe Type diff --git a/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h b/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h index 61ecc112a0..409684ed8c 100644 --- a/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h +++ b/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h @@ -565,7 +565,6 @@ * */ //#define Z_MIN_PROBE_ENDSTOP -//#define Z_MIN_PROBE_PIN Z_MAX_PIN /** * Probe Type diff --git a/Marlin/example_configurations/RigidBot/Configuration.h b/Marlin/example_configurations/RigidBot/Configuration.h index 7648087a05..ef09f47067 100644 --- a/Marlin/example_configurations/RigidBot/Configuration.h +++ b/Marlin/example_configurations/RigidBot/Configuration.h @@ -563,7 +563,6 @@ * */ //#define Z_MIN_PROBE_ENDSTOP -//#define Z_MIN_PROBE_PIN Z_MAX_PIN /** * Probe Type diff --git a/Marlin/example_configurations/SCARA/Configuration.h b/Marlin/example_configurations/SCARA/Configuration.h index 162536f06c..9af3cecde5 100644 --- a/Marlin/example_configurations/SCARA/Configuration.h +++ b/Marlin/example_configurations/SCARA/Configuration.h @@ -580,7 +580,6 @@ * */ //#define Z_MIN_PROBE_ENDSTOP -//#define Z_MIN_PROBE_PIN Z_MAX_PIN /** * Probe Type diff --git a/Marlin/example_configurations/TAZ4/Configuration.h b/Marlin/example_configurations/TAZ4/Configuration.h index de5eee2a07..4660946752 100644 --- a/Marlin/example_configurations/TAZ4/Configuration.h +++ b/Marlin/example_configurations/TAZ4/Configuration.h @@ -584,7 +584,6 @@ * */ //#define Z_MIN_PROBE_ENDSTOP -//#define Z_MIN_PROBE_PIN Z_MAX_PIN /** * Probe Type diff --git a/Marlin/example_configurations/TinyBoy2/Configuration.h b/Marlin/example_configurations/TinyBoy2/Configuration.h index d893a920df..4fefe85d6c 100644 --- a/Marlin/example_configurations/TinyBoy2/Configuration.h +++ b/Marlin/example_configurations/TinyBoy2/Configuration.h @@ -616,7 +616,6 @@ * */ //#define Z_MIN_PROBE_ENDSTOP -//#define Z_MIN_PROBE_PIN Z_MAX_PIN /** * Probe Type diff --git a/Marlin/example_configurations/WITBOX/Configuration.h b/Marlin/example_configurations/WITBOX/Configuration.h index 1389cdc9e9..187fb948a6 100644 --- a/Marlin/example_configurations/WITBOX/Configuration.h +++ b/Marlin/example_configurations/WITBOX/Configuration.h @@ -555,7 +555,6 @@ * */ //#define Z_MIN_PROBE_ENDSTOP -//#define Z_MIN_PROBE_PIN Z_MAX_PIN /** * Probe Type diff --git a/Marlin/example_configurations/adafruit/ST7565/Configuration.h b/Marlin/example_configurations/adafruit/ST7565/Configuration.h index ef71b3b561..0f608c7a1d 100644 --- a/Marlin/example_configurations/adafruit/ST7565/Configuration.h +++ b/Marlin/example_configurations/adafruit/ST7565/Configuration.h @@ -565,7 +565,6 @@ * */ //#define Z_MIN_PROBE_ENDSTOP -//#define Z_MIN_PROBE_PIN Z_MAX_PIN /** * Probe Type diff --git a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h index 6a824599ef..df495943d6 100644 --- a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h +++ b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h @@ -633,7 +633,6 @@ * */ //#define Z_MIN_PROBE_ENDSTOP // A3K leave disabled! -//#define Z_MIN_PROBE_PIN Z_MAX_PIN /** * Probe Type diff --git a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h index f29cc903b8..453b0a603f 100644 --- a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h +++ b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h @@ -640,7 +640,6 @@ * */ //#define Z_MIN_PROBE_ENDSTOP // A3K leave disabled! -//#define Z_MIN_PROBE_PIN Z_MAX_PIN /** * Probe Type diff --git a/Marlin/example_configurations/delta/generic/Configuration.h b/Marlin/example_configurations/delta/generic/Configuration.h index 5fb5d6747c..d005b0876b 100644 --- a/Marlin/example_configurations/delta/generic/Configuration.h +++ b/Marlin/example_configurations/delta/generic/Configuration.h @@ -629,7 +629,6 @@ * */ #define Z_MIN_PROBE_ENDSTOP -//#define Z_MIN_PROBE_PIN Z_MAX_PIN /** * Probe Type diff --git a/Marlin/example_configurations/delta/kossel_mini/Configuration.h b/Marlin/example_configurations/delta/kossel_mini/Configuration.h index 26d45ed197..edc6ca7905 100644 --- a/Marlin/example_configurations/delta/kossel_mini/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_mini/Configuration.h @@ -629,7 +629,6 @@ * */ //#define Z_MIN_PROBE_ENDSTOP -//#define Z_MIN_PROBE_PIN Z_MAX_PIN /** * Probe Type diff --git a/Marlin/example_configurations/delta/kossel_pro/Configuration.h b/Marlin/example_configurations/delta/kossel_pro/Configuration.h index 5028ad3bea..42675f9fff 100644 --- a/Marlin/example_configurations/delta/kossel_pro/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_pro/Configuration.h @@ -622,7 +622,6 @@ * */ //#define Z_MIN_PROBE_ENDSTOP -//#define Z_MIN_PROBE_PIN Z_MAX_PIN /** * Probe Type diff --git a/Marlin/example_configurations/delta/kossel_xl/Configuration.h b/Marlin/example_configurations/delta/kossel_xl/Configuration.h index 52733e783d..1427f5adbb 100644 --- a/Marlin/example_configurations/delta/kossel_xl/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_xl/Configuration.h @@ -641,7 +641,6 @@ * */ #define Z_MIN_PROBE_ENDSTOP -//#define Z_MIN_PROBE_PIN Z_MAX_PIN /** * Probe Type diff --git a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h index 63b605cebb..63a698a6c3 100644 --- a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h +++ b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h @@ -580,7 +580,6 @@ * */ //#define Z_MIN_PROBE_ENDSTOP -//#define Z_MIN_PROBE_PIN Z_MAX_PIN /** * Probe Type diff --git a/Marlin/example_configurations/makibox/Configuration.h b/Marlin/example_configurations/makibox/Configuration.h index 8f22295bec..a13bb2ed53 100644 --- a/Marlin/example_configurations/makibox/Configuration.h +++ b/Marlin/example_configurations/makibox/Configuration.h @@ -568,7 +568,6 @@ * */ //#define Z_MIN_PROBE_ENDSTOP -//#define Z_MIN_PROBE_PIN Z_MAX_PIN /** * Probe Type diff --git a/Marlin/example_configurations/tvrrug/Round2/Configuration.h b/Marlin/example_configurations/tvrrug/Round2/Configuration.h index e6010071ca..046a8a5e2b 100644 --- a/Marlin/example_configurations/tvrrug/Round2/Configuration.h +++ b/Marlin/example_configurations/tvrrug/Round2/Configuration.h @@ -560,7 +560,6 @@ * */ //#define Z_MIN_PROBE_ENDSTOP -//#define Z_MIN_PROBE_PIN Z_MAX_PIN /** * Probe Type diff --git a/Marlin/example_configurations/wt150/Configuration.h b/Marlin/example_configurations/wt150/Configuration.h index 81430e8ffa..52fa225197 100644 --- a/Marlin/example_configurations/wt150/Configuration.h +++ b/Marlin/example_configurations/wt150/Configuration.h @@ -570,7 +570,6 @@ * */ //#define Z_MIN_PROBE_ENDSTOP -//#define Z_MIN_PROBE_PIN Z_MAX_PIN /** * Probe Type From 897bc2ac1fa295eea47bcc6ce62135015c4adf5a Mon Sep 17 00:00:00 2001 From: Thomas Moore Date: Fri, 9 Jun 2017 15:19:08 -0500 Subject: [PATCH 040/180] Updates for ensure_safe_temperature (#6963) * Updates for ensure_safe_temperature * M600 fixes --- Marlin/Marlin_main.cpp | 76 ++++++++++++++++++------------------------ 1 file changed, 33 insertions(+), 43 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 1e0ef1554a..c01686105f 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -5871,15 +5871,41 @@ inline void gcode_M17() { } } + static void ensure_safe_temperature() { + bool heaters_heating = true; + + wait_for_heatup = true; // M108 will clear this + while (wait_for_heatup && heaters_heating) { + idle(); + heaters_heating = false; + HOTEND_LOOP() { + if (thermalManager.degTargetHotend(e) && abs(thermalManager.degHotend(e) - thermalManager.degTargetHotend(e)) > 3) { + heaters_heating = true; + #if ENABLED(ULTIPANEL) + lcd_advanced_pause_show_message(ADVANCED_PAUSE_MESSAGE_WAIT_FOR_NOZZLES_TO_HEAT); + #endif + break; + } + } + } + } + static bool pause_print(const float &retract, const float &z_lift, const float &x_pos, const float &y_pos, const float &unload_length = 0 , int8_t max_beep_count = 0, bool show_lcd = false ) { if (move_away_flag) return false; // already paused - if (!DEBUGGING(DRYRUN) && thermalManager.tooColdToExtrude(active_extruder) && unload_length > 0) { - SERIAL_ERROR_START; - SERIAL_ERRORLNPGM(MSG_TOO_COLD_FOR_M600); - return false; + if (!DEBUGGING(DRYRUN) && unload_length != 0) { + #if ENABLED(PREVENT_COLD_EXTRUSION) + if (!thermalManager.allow_cold_extrude && + thermalManager.degTargetHotend(active_extruder) < thermalManager.extrude_min_temp) { + SERIAL_ERROR_START; + SERIAL_ERRORLNPGM(MSG_TOO_COLD_FOR_M600); + return false; + } + #endif + + ensure_safe_temperature(); // wait for extruder to heat up before unloading } // Indicate that the printer is paused @@ -5965,25 +5991,6 @@ inline void gcode_M17() { return true; } - static void ensure_safe_temperature() { - bool did_show = false; - wait_for_heatup = true; - while (wait_for_heatup) { - idle(); - wait_for_heatup = false; - HOTEND_LOOP() { - if (thermalManager.degTargetHotend(e) && abs(thermalManager.degHotend(e) - thermalManager.degTargetHotend(e)) > 3) { - wait_for_heatup = true; - if (!did_show) { // Show "wait for heating" - lcd_advanced_pause_show_message(ADVANCED_PAUSE_MESSAGE_WAIT_FOR_NOZZLES_TO_HEAT); - did_show = true; - } - break; - } - } - } - } - static void wait_for_filament_reload(int8_t max_beep_count = 0) { bool nozzle_timed_out = false; @@ -6000,7 +6007,8 @@ inline void gcode_M17() { nozzle_timed_out |= thermalManager.is_heater_idle(e); #if ENABLED(ULTIPANEL) - if (nozzle_timed_out) ensure_safe_temperature(); + if (nozzle_timed_out) + lcd_advanced_pause_show_message(ADVANCED_PAUSE_MESSAGE_CLICK_TO_HEAT_NOZZLE); #endif idle(true); @@ -6019,23 +6027,7 @@ inline void gcode_M17() { thermalManager.reset_heater_idle_timer(e); } - #if ENABLED(ULTIPANEL) - // Show "wait for heating" - lcd_advanced_pause_show_message(ADVANCED_PAUSE_MESSAGE_WAIT_FOR_NOZZLES_TO_HEAT); - #endif - - wait_for_heatup = true; - while (wait_for_heatup) { - idle(); - wait_for_heatup = false; - HOTEND_LOOP() { - const int16_t target_temp = thermalManager.degTargetHotend(e); - if (target_temp && abs(thermalManager.degHotend(e) - target_temp) > 3) { - wait_for_heatup = true; - break; - } - } - } + if (nozzle_timed_out) ensure_safe_temperature(); #if HAS_BUZZER filament_change_beep(max_beep_count, true); @@ -9248,8 +9240,6 @@ inline void gcode_M503() { */ inline void gcode_M600() { - ensure_safe_temperature(); - // 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 From 761df686bd3d432ed85d44fe47ffef7f1662c064 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 9 Jun 2017 10:23:48 -0500 Subject: [PATCH 041/180] Minor cleanup in gcode.h --- Marlin/gcode.h | 10 +++------- 1 file changed, 3 insertions(+), 7 deletions(-) diff --git a/Marlin/gcode.h b/Marlin/gcode.h index fe5d930122..3001b8b2e0 100644 --- a/Marlin/gcode.h +++ b/Marlin/gcode.h @@ -128,9 +128,7 @@ public: return b; } - static volatile bool seen_any() { - return codebits[3] || codebits[2] || codebits[1] || codebits[0]; - } + static volatile bool seen_any() { return codebits[3] || codebits[2] || codebits[1] || codebits[0]; } #define SEEN_TEST(L) TEST(codebits[(L - 'A') >> 3], (L - 'A') & 0x7) @@ -145,9 +143,7 @@ public: return b; } - static volatile bool seen_any() { - return *command_args == '\0'; - } + static volatile bool seen_any() { return *command_args == '\0'; } #define SEEN_TEST(L) !!strchr(command_args, L) @@ -207,7 +203,7 @@ public: #if ENABLED(INCH_MODE_SUPPORT) - inline static void set_input_linear_units(LinearUnit units) { + inline static void set_input_linear_units(const LinearUnit units) { switch (units) { case LINEARUNIT_INCH: linear_unit_factor = 25.4; From d91710e9aaf4aa57d09a2f5cd718252828d278ce Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 9 Jun 2017 10:23:25 -0500 Subject: [PATCH 042/180] Followup for UBL translated strings --- Marlin/language_en.h | 338 +++++++++++++++++++++---------------------- 1 file changed, 168 insertions(+), 170 deletions(-) diff --git a/Marlin/language_en.h b/Marlin/language_en.h index a0b9bb0a05..56a0e5642b 100644 --- a/Marlin/language_en.h +++ b/Marlin/language_en.h @@ -163,176 +163,174 @@ #define MSG_USER_MENU _UxGT("Custom Commands") #endif -#if ENABLED(AUTO_BED_LEVELING_UBL) - #ifndef MSG_UBL_DOING_G29 - #define MSG_UBL_DOING_G29 _UxGT("Doing G29 UBL!") - #endif - #ifndef MSG_UBL_UNHOMED - #define MSG_UBL_UNHOMED _UxGT("Home XYZ first") - #endif - #ifndef MSG_UBL_TOOLS - #define MSG_UBL_TOOLS _UxGT("UBL Tools") - #endif - #ifndef MSG_UBL_LEVEL_BED - #define MSG_UBL_LEVEL_BED _UxGT("Unified Bed Leveling") - #endif - #ifndef MSG_UBL_MANUAL_MESH - #define MSG_UBL_MANUAL_MESH _UxGT("Manually Build Mesh") - #endif - #ifndef MSG_UBL_BC_INSERT - #define MSG_UBL_BC_INSERT _UxGT("Place shim & measure") - #endif - #ifndef MSG_UBL_BC_INSERT2 - #define MSG_UBL_BC_INSERT2 _UxGT("Measure") - #endif - #ifndef MSG_UBL_BC_REMOVE - #define MSG_UBL_BC_REMOVE _UxGT("Remove & measure bed") - #endif - #ifndef MSG_UBL_MOVING_TO_NEXT - #define MSG_UBL_MOVING_TO_NEXT _UxGT("Moving to next") - #endif - #ifndef MSG_UBL_ACTIVATE_MESH - #define MSG_UBL_ACTIVATE_MESH _UxGT("Activate UBL") - #endif - #ifndef MSG_UBL_DEACTIVATE_MESH - #define MSG_UBL_DEACTIVATE_MESH _UxGT("Deactivate UBL") - #endif - #ifndef MSG_UBL_SET_BED_TEMP - #define MSG_UBL_SET_BED_TEMP _UxGT("Bed Temp") - #endif - #ifndef MSG_UBL_CUSTOM_BED_TEMP - #define MSG_UBL_CUSTOM_BED_TEMP MSG_UBL_SET_BED_TEMP - #endif - #ifndef MSG_UBL_SET_HOTEND_TEMP - #define MSG_UBL_SET_HOTEND_TEMP _UxGT("Hotend Temp") - #endif - #ifndef MSG_UBL_CUSTOM_HOTEND_TEMP - #define MSG_UBL_CUSTOM_HOTEND_TEMP MSG_UBL_SET_HOTEND_TEMP - #endif - #ifndef MSG_UBL_EDIT_CUSTOM_MESH - #define MSG_UBL_EDIT_CUSTOM_MESH _UxGT("Edit Custom Mesh") - #endif - #ifndef MSG_UBL_FINE_TUNE_MESH - #define MSG_UBL_FINE_TUNE_MESH _UxGT("Fine Tuning Mesh") - #endif - #ifndef MSG_UBL_DONE_EDITING_MESH - #define MSG_UBL_DONE_EDITING_MESH _UxGT("Done Editing Mesh") - #endif - #ifndef MSG_UBL_BUILD_CUSTOM_MESH - #define MSG_UBL_BUILD_CUSTOM_MESH _UxGT("Build Custom Mesh") - #endif - #ifndef MSG_UBL_BUILD_MESH_MENU - #define MSG_UBL_BUILD_MESH_MENU _UxGT("Build Mesh") - #endif - #ifndef MSG_UBL_BUILD_PLA_MESH - #define MSG_UBL_BUILD_PLA_MESH _UxGT("Build PLA Mesh") - #endif - #ifndef MSG_UBL_BUILD_ABS_MESH - #define MSG_UBL_BUILD_ABS_MESH _UxGT("Build ABS Mesh") - #endif - #ifndef MSG_UBL_BUILD_COLD_MESH - #define MSG_UBL_BUILD_COLD_MESH _UxGT("Build Cold Mesh") - #endif - #ifndef MSG_UBL_MESH_HEIGHT_ADJUST - #define MSG_UBL_MESH_HEIGHT_ADJUST _UxGT("Adjust Mesh Height") - #endif - #ifndef MSG_UBL_MESH_HEIGHT_AMOUNT - #define MSG_UBL_MESH_HEIGHT_AMOUNT _UxGT("Height Amount") - #endif - #ifndef MSG_UBL_VALIDATE_MESH_MENU - #define MSG_UBL_VALIDATE_MESH_MENU _UxGT("Validate Mesh") - #endif - #ifndef MSG_UBL_VALIDATE_PLA_MESH - #define MSG_UBL_VALIDATE_PLA_MESH _UxGT("Validate PLA Mesh") - #endif - #ifndef MSG_UBL_VALIDATE_ABS_MESH - #define MSG_UBL_VALIDATE_ABS_MESH _UxGT("Validate ABS Mesh") - #endif - #ifndef MSG_UBL_VALIDATE_CUSTOM_MESH - #define MSG_UBL_VALIDATE_CUSTOM_MESH _UxGT("Validate Custom Mesh") - #endif - #ifndef MSG_UBL_CONTINUE_MESH - #define MSG_UBL_CONTINUE_MESH _UxGT("Continue Bed Mesh") - #endif - #ifndef MSG_UBL_MESH_LEVELING - #define MSG_UBL_MESH_LEVELING _UxGT("Mesh Leveling") - #endif - #ifndef MSG_UBL_3POINT_MESH_LEVELING - #define MSG_UBL_3POINT_MESH_LEVELING _UxGT("3-Point Leveling") - #endif - #ifndef MSG_UBL_GRID_MESH_LEVELING - #define MSG_UBL_GRID_MESH_LEVELING _UxGT("Grid Mesh Leveling") - #endif - #ifndef MSG_UBL_MESH_LEVEL - #define MSG_UBL_MESH_LEVEL _UxGT("Level Mesh") - #endif - #ifndef MSG_UBL_SIDE_POINTS - #define MSG_UBL_SIDE_POINTS _UxGT("Side Points") - #endif - #ifndef MSG_UBL_MAP_TYPE - #define MSG_UBL_MAP_TYPE _UxGT("Map Type") - #endif - #ifndef MSG_UBL_OUTPUT_MAP - #define MSG_UBL_OUTPUT_MAP _UxGT("Output Mesh Map") - #endif - #ifndef MSG_UBL_OUTPUT_MAP_HOST - #define MSG_UBL_OUTPUT_MAP_HOST _UxGT("Output for Host") - #endif - #ifndef MSG_UBL_OUTPUT_MAP_CSV - #define MSG_UBL_OUTPUT_MAP_CSV _UxGT("Output for CSV") - #endif - #ifndef MSG_UBL_INFO_UBL - #define MSG_UBL_INFO_UBL _UxGT("Output UBL Info") - #endif - #ifndef MSG_UBL_EDIT_MESH_MENU - #define MSG_UBL_EDIT_MESH_MENU _UxGT("Edit Mesh") - #endif - #ifndef MSG_UBL_FILLIN_AMOUNT - #define MSG_UBL_FILLIN_AMOUNT _UxGT("Fill-in Amount") - #endif - #ifndef MSG_UBL_MANUAL_FILLIN - #define MSG_UBL_MANUAL_FILLIN _UxGT("Manual Fill-in") - #endif - #ifndef MSG_UBL_SMART_FILLIN - #define MSG_UBL_SMART_FILLIN _UxGT("Smart Fill-in") - #endif - #ifndef MSG_UBL_FILLIN_MESH - #define MSG_UBL_FILLIN_MESH _UxGT("Fill-in Mesh") - #endif - #ifndef MSG_UBL_INVALIDATE_ALL - #define MSG_UBL_INVALIDATE_ALL _UxGT("Invalidate All") - #endif - #ifndef MSG_UBL_INVALIDATE_CLOSEST - #define MSG_UBL_INVALIDATE_CLOSEST _UxGT("Invalidate Closest") - #endif - #ifndef MSG_UBL_FINE_TUNE_ALL - #define MSG_UBL_FINE_TUNE_ALL _UxGT("Fine Tune All") - #endif - #ifndef MSG_UBL_FINE_TUNE_CLOSEST - #define MSG_UBL_FINE_TUNE_CLOSEST _UxGT("Fine Tune Closest") - #endif - #ifndef MSG_UBL_STORAGE_MESH_MENU - #define MSG_UBL_STORAGE_MESH_MENU _UxGT("Mesh Storage") - #endif - #ifndef MSG_UBL_STORAGE_SLOT - #define MSG_UBL_STORAGE_SLOT _UxGT("Memory Slot") - #endif - #ifndef MSG_UBL_LOAD_MESH - #define MSG_UBL_LOAD_MESH _UxGT("Load Bed Mesh") - #endif - #ifndef MSG_UBL_SAVE_MESH - #define MSG_UBL_SAVE_MESH _UxGT("Save Bed Mesh") - #endif - #ifndef MSG_UBL_SAVE_ERROR - #define MSG_UBL_SAVE_ERROR _UxGT("save_UBL_active() error") - #endif - #ifndef MSG_UBL_RESTORE_ERROR - #define MSG_UBL_RESTORE_ERROR _UxGT("restore_UBL_active() error") - #endif - #ifndef MSG_UBL_Z_OFFSET_STOPPED - #define MSG_UBL_Z_OFFSET_STOPPED _UxGT("Z-Offset Stopped") - #endif -#endif // AUTO_BED_LEVELING_UBL +#ifndef MSG_UBL_DOING_G29 + #define MSG_UBL_DOING_G29 _UxGT("Doing G29") +#endif +#ifndef MSG_UBL_UNHOMED + #define MSG_UBL_UNHOMED _UxGT("Home XYZ first") +#endif +#ifndef MSG_UBL_TOOLS + #define MSG_UBL_TOOLS _UxGT("UBL Tools") +#endif +#ifndef MSG_UBL_LEVEL_BED + #define MSG_UBL_LEVEL_BED _UxGT("Unified Bed Leveling") +#endif +#ifndef MSG_UBL_MANUAL_MESH + #define MSG_UBL_MANUAL_MESH _UxGT("Manually Build Mesh") +#endif +#ifndef MSG_UBL_BC_INSERT + #define MSG_UBL_BC_INSERT _UxGT("Place shim & measure") +#endif +#ifndef MSG_UBL_BC_INSERT2 + #define MSG_UBL_BC_INSERT2 _UxGT("Measure") +#endif +#ifndef MSG_UBL_BC_REMOVE + #define MSG_UBL_BC_REMOVE _UxGT("Remove & measure bed") +#endif +#ifndef MSG_UBL_MOVING_TO_NEXT + #define MSG_UBL_MOVING_TO_NEXT _UxGT("Moving to next") +#endif +#ifndef MSG_UBL_ACTIVATE_MESH + #define MSG_UBL_ACTIVATE_MESH _UxGT("Activate UBL") +#endif +#ifndef MSG_UBL_DEACTIVATE_MESH + #define MSG_UBL_DEACTIVATE_MESH _UxGT("Deactivate UBL") +#endif +#ifndef MSG_UBL_SET_BED_TEMP + #define MSG_UBL_SET_BED_TEMP _UxGT("Bed Temp") +#endif +#ifndef MSG_UBL_CUSTOM_BED_TEMP + #define MSG_UBL_CUSTOM_BED_TEMP MSG_UBL_SET_BED_TEMP +#endif +#ifndef MSG_UBL_SET_HOTEND_TEMP + #define MSG_UBL_SET_HOTEND_TEMP _UxGT("Hotend Temp") +#endif +#ifndef MSG_UBL_CUSTOM_HOTEND_TEMP + #define MSG_UBL_CUSTOM_HOTEND_TEMP MSG_UBL_SET_HOTEND_TEMP +#endif +#ifndef MSG_UBL_EDIT_CUSTOM_MESH + #define MSG_UBL_EDIT_CUSTOM_MESH _UxGT("Edit Custom Mesh") +#endif +#ifndef MSG_UBL_FINE_TUNE_MESH + #define MSG_UBL_FINE_TUNE_MESH _UxGT("Fine Tuning Mesh") +#endif +#ifndef MSG_UBL_DONE_EDITING_MESH + #define MSG_UBL_DONE_EDITING_MESH _UxGT("Done Editing Mesh") +#endif +#ifndef MSG_UBL_BUILD_CUSTOM_MESH + #define MSG_UBL_BUILD_CUSTOM_MESH _UxGT("Build Custom Mesh") +#endif +#ifndef MSG_UBL_BUILD_MESH_MENU + #define MSG_UBL_BUILD_MESH_MENU _UxGT("Build Mesh") +#endif +#ifndef MSG_UBL_BUILD_PLA_MESH + #define MSG_UBL_BUILD_PLA_MESH _UxGT("Build PLA Mesh") +#endif +#ifndef MSG_UBL_BUILD_ABS_MESH + #define MSG_UBL_BUILD_ABS_MESH _UxGT("Build ABS Mesh") +#endif +#ifndef MSG_UBL_BUILD_COLD_MESH + #define MSG_UBL_BUILD_COLD_MESH _UxGT("Build Cold Mesh") +#endif +#ifndef MSG_UBL_MESH_HEIGHT_ADJUST + #define MSG_UBL_MESH_HEIGHT_ADJUST _UxGT("Adjust Mesh Height") +#endif +#ifndef MSG_UBL_MESH_HEIGHT_AMOUNT + #define MSG_UBL_MESH_HEIGHT_AMOUNT _UxGT("Height Amount") +#endif +#ifndef MSG_UBL_VALIDATE_MESH_MENU + #define MSG_UBL_VALIDATE_MESH_MENU _UxGT("Validate Mesh") +#endif +#ifndef MSG_UBL_VALIDATE_PLA_MESH + #define MSG_UBL_VALIDATE_PLA_MESH _UxGT("Validate PLA Mesh") +#endif +#ifndef MSG_UBL_VALIDATE_ABS_MESH + #define MSG_UBL_VALIDATE_ABS_MESH _UxGT("Validate ABS Mesh") +#endif +#ifndef MSG_UBL_VALIDATE_CUSTOM_MESH + #define MSG_UBL_VALIDATE_CUSTOM_MESH _UxGT("Validate Custom Mesh") +#endif +#ifndef MSG_UBL_CONTINUE_MESH + #define MSG_UBL_CONTINUE_MESH _UxGT("Continue Bed Mesh") +#endif +#ifndef MSG_UBL_MESH_LEVELING + #define MSG_UBL_MESH_LEVELING _UxGT("Mesh Leveling") +#endif +#ifndef MSG_UBL_3POINT_MESH_LEVELING + #define MSG_UBL_3POINT_MESH_LEVELING _UxGT("3-Point Leveling") +#endif +#ifndef MSG_UBL_GRID_MESH_LEVELING + #define MSG_UBL_GRID_MESH_LEVELING _UxGT("Grid Mesh Leveling") +#endif +#ifndef MSG_UBL_MESH_LEVEL + #define MSG_UBL_MESH_LEVEL _UxGT("Level Mesh") +#endif +#ifndef MSG_UBL_SIDE_POINTS + #define MSG_UBL_SIDE_POINTS _UxGT("Side Points") +#endif +#ifndef MSG_UBL_MAP_TYPE + #define MSG_UBL_MAP_TYPE _UxGT("Map Type") +#endif +#ifndef MSG_UBL_OUTPUT_MAP + #define MSG_UBL_OUTPUT_MAP _UxGT("Output Mesh Map") +#endif +#ifndef MSG_UBL_OUTPUT_MAP_HOST + #define MSG_UBL_OUTPUT_MAP_HOST _UxGT("Output for Host") +#endif +#ifndef MSG_UBL_OUTPUT_MAP_CSV + #define MSG_UBL_OUTPUT_MAP_CSV _UxGT("Output for CSV") +#endif +#ifndef MSG_UBL_INFO_UBL + #define MSG_UBL_INFO_UBL _UxGT("Output UBL Info") +#endif +#ifndef MSG_UBL_EDIT_MESH_MENU + #define MSG_UBL_EDIT_MESH_MENU _UxGT("Edit Mesh") +#endif +#ifndef MSG_UBL_FILLIN_AMOUNT + #define MSG_UBL_FILLIN_AMOUNT _UxGT("Fill-in Amount") +#endif +#ifndef MSG_UBL_MANUAL_FILLIN + #define MSG_UBL_MANUAL_FILLIN _UxGT("Manual Fill-in") +#endif +#ifndef MSG_UBL_SMART_FILLIN + #define MSG_UBL_SMART_FILLIN _UxGT("Smart Fill-in") +#endif +#ifndef MSG_UBL_FILLIN_MESH + #define MSG_UBL_FILLIN_MESH _UxGT("Fill-in Mesh") +#endif +#ifndef MSG_UBL_INVALIDATE_ALL + #define MSG_UBL_INVALIDATE_ALL _UxGT("Invalidate All") +#endif +#ifndef MSG_UBL_INVALIDATE_CLOSEST + #define MSG_UBL_INVALIDATE_CLOSEST _UxGT("Invalidate Closest") +#endif +#ifndef MSG_UBL_FINE_TUNE_ALL + #define MSG_UBL_FINE_TUNE_ALL _UxGT("Fine Tune All") +#endif +#ifndef MSG_UBL_FINE_TUNE_CLOSEST + #define MSG_UBL_FINE_TUNE_CLOSEST _UxGT("Fine Tune Closest") +#endif +#ifndef MSG_UBL_STORAGE_MESH_MENU + #define MSG_UBL_STORAGE_MESH_MENU _UxGT("Mesh Storage") +#endif +#ifndef MSG_UBL_STORAGE_SLOT + #define MSG_UBL_STORAGE_SLOT _UxGT("Memory Slot") +#endif +#ifndef MSG_UBL_LOAD_MESH + #define MSG_UBL_LOAD_MESH _UxGT("Load Bed Mesh") +#endif +#ifndef MSG_UBL_SAVE_MESH + #define MSG_UBL_SAVE_MESH _UxGT("Save Bed Mesh") +#endif +#ifndef MSG_UBL_SAVE_ERROR + #define MSG_UBL_SAVE_ERROR _UxGT("Err: UBL Save") +#endif +#ifndef MSG_UBL_RESTORE_ERROR + #define MSG_UBL_RESTORE_ERROR _UxGT("Err: UBL Restore") +#endif +#ifndef MSG_UBL_Z_OFFSET_STOPPED + #define MSG_UBL_Z_OFFSET_STOPPED _UxGT("Z-Offset Stopped") +#endif #ifndef MSG_MOVING #define MSG_MOVING _UxGT("Moving...") From e94f79cceabc4b13f4447260227d6db837dcaf02 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 9 Jun 2017 10:51:23 -0500 Subject: [PATCH 043/180] Patch some serial macros --- Marlin/G26_Mesh_Validation_Tool.cpp | 6 +- Marlin/I2CPositionEncoder.cpp | 2 +- Marlin/M100_Free_Mem_Chk.cpp | 8 +- Marlin/Marlin_main.cpp | 256 ++++++++++++++-------------- Marlin/cardreader.cpp | 32 ++-- Marlin/configuration_store.cpp | 66 +++---- Marlin/endstops.cpp | 4 +- Marlin/gcode.cpp | 6 +- Marlin/pinsDebug.h | 4 +- Marlin/planner.cpp | 8 +- Marlin/printcounter.cpp | 6 +- Marlin/serial.h | 10 +- Marlin/stepper.cpp | 2 +- Marlin/stepper.h | 2 +- Marlin/stepper_dac.cpp | 4 +- Marlin/temperature.cpp | 36 ++-- Marlin/twibus.cpp | 8 +- Marlin/ubl.cpp | 12 +- Marlin/ubl.h | 10 +- Marlin/ubl_G29.cpp | 50 +++--- Marlin/ubl_motion.cpp | 4 +- Marlin/ultralcd.cpp | 4 +- Marlin/vector_3.cpp | 4 +- Marlin/watchdog.cpp | 2 +- 24 files changed, 273 insertions(+), 273 deletions(-) diff --git a/Marlin/G26_Mesh_Validation_Tool.cpp b/Marlin/G26_Mesh_Validation_Tool.cpp index d8cc62e0ea..afbf2b1103 100644 --- a/Marlin/G26_Mesh_Validation_Tool.cpp +++ b/Marlin/G26_Mesh_Validation_Tool.cpp @@ -288,7 +288,7 @@ SERIAL_ECHOPAIR(" Doing circle at: (xi=", xi); SERIAL_ECHOPAIR(", yi=", yi); SERIAL_CHAR(')'); - SERIAL_EOL; + SERIAL_EOL(); } start_angle = 0.0; // assume it is going to be a full circle @@ -467,7 +467,7 @@ SERIAL_ECHOPAIR(") -> (ex=", ex); SERIAL_ECHOPAIR(", ey=", ey); SERIAL_CHAR(')'); - SERIAL_EOL; + SERIAL_EOL(); //debug_current_and_destination(PSTR("Connecting horizontal line.")); } @@ -501,7 +501,7 @@ SERIAL_ECHOPAIR(") -> (ex=", ex); SERIAL_ECHOPAIR(", ey=", ey); SERIAL_CHAR(')'); - SERIAL_EOL; + SERIAL_EOL(); debug_current_and_destination(PSTR("Connecting vertical line.")); } print_line_from_here_to_there(LOGICAL_X_POSITION(sx), LOGICAL_Y_POSITION(sy), g26_layer_height, LOGICAL_X_POSITION(ex), LOGICAL_Y_POSITION(ey), g26_layer_height); diff --git a/Marlin/I2CPositionEncoder.cpp b/Marlin/I2CPositionEncoder.cpp index 146776c863..212e34f752 100644 --- a/Marlin/I2CPositionEncoder.cpp +++ b/Marlin/I2CPositionEncoder.cpp @@ -736,7 +736,7 @@ char c; while (Wire.available() > 0 && (c = (char)Wire.read()) > 0) SERIAL_ECHO(c); - SERIAL_EOL; + SERIAL_EOL(); } // Set module back to normal (distance) mode diff --git a/Marlin/M100_Free_Mem_Chk.cpp b/Marlin/M100_Free_Mem_Chk.cpp index cfc001de2f..be418b049e 100644 --- a/Marlin/M100_Free_Mem_Chk.cpp +++ b/Marlin/M100_Free_Mem_Chk.cpp @@ -130,7 +130,7 @@ int16_t count_test_bytes(const char * const ptr) { } SERIAL_CHAR(ccc); } - SERIAL_EOL; + SERIAL_EOL(); ptr += 16; safe_delay(25); idle(); @@ -200,7 +200,7 @@ void free_memory_pool_report(char * const ptr, const int16_t size) { *addr = i; SERIAL_ECHOPAIR("\nCorrupting address: ", hex_address(addr)); } - SERIAL_EOL; + SERIAL_EOL(); } } #endif // M100_FREE_MEMORY_CORRUPTOR @@ -229,7 +229,7 @@ void init_free_memory(char *ptr, int16_t size) { if (ptr[i] != TEST_BYTE) { SERIAL_ECHOPAIR("? address : ", hex_address(ptr + i)); SERIAL_ECHOLNPAIR("=", hex_byte(ptr[i])); - SERIAL_EOL; + SERIAL_EOL(); } } } @@ -323,7 +323,7 @@ int check_for_free_memory_corruption(const char * const title) { SERIAL_ECHOPGM(" return="); if (block_cnt == 1) { SERIAL_CHAR('0'); // if the block_cnt is 1, nothing has broken up the free memory - SERIAL_EOL; // area and it is appropriate to say 'no corruption'. + SERIAL_EOL(); // area and it is appropriate to say 'no corruption'. return 0; } SERIAL_ECHOLNPGM("true"); diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index c01686105f..df12d05513 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -734,7 +734,7 @@ void report_current_position_detail(); SERIAL_CHAR(')'); if (suffix) {serialprintPGM(suffix);} //won't compile for Teensy with the previous construction - else SERIAL_EOL; + else SERIAL_EOL(); } void print_xyz(const char* prefix, const char* suffix, const float xyz[]) { @@ -868,10 +868,10 @@ inline bool _enqueuecommand(const char* cmd, bool say_ok=false) { */ bool enqueue_and_echo_command(const char* cmd, bool say_ok/*=false*/) { if (_enqueuecommand(cmd, say_ok)) { - SERIAL_ECHO_START; + SERIAL_ECHO_START(); SERIAL_ECHOPAIR(MSG_ENQUEUEING, cmd); SERIAL_CHAR('"'); - SERIAL_EOL; + SERIAL_EOL(); return true; } return false; @@ -1010,7 +1010,7 @@ void servo_init() { #endif // HAS_COLOR_LEDS void gcode_line_error(const char* err, bool doFlush = true) { - SERIAL_ERROR_START; + SERIAL_ERROR_START(); serialprintPGM(err); SERIAL_ERRORLN(gcode_LastN); //Serial.println(gcode_N); @@ -1206,7 +1206,7 @@ inline void get_serial_commands() { card.checkautostart(true); } else if (n == -1) { - SERIAL_ERROR_START; + SERIAL_ERROR_START(); SERIAL_ECHOLNPGM(MSG_SD_ERR_READ); } if (sd_char == '#') stop_buffering = true; @@ -1261,7 +1261,7 @@ void get_available_commands() { bool get_target_extruder_from_command(int code) { if (parser.seen('T')) { if (parser.value_byte() >= EXTRUDERS) { - SERIAL_ECHO_START; + SERIAL_ECHO_START(); SERIAL_CHAR('M'); SERIAL_ECHO(code); SERIAL_ECHOLNPAIR(" " MSG_INVALID_EXTRUDER " ", parser.value_byte()); @@ -1421,7 +1421,7 @@ static void set_axis_is_at_home(const AxisEnum axis) { if (DEBUGGING(LEVELING)) { SERIAL_ECHOPAIR(">>> set_axis_is_at_home(", axis_codes[axis]); SERIAL_CHAR(')'); - SERIAL_EOL; + SERIAL_EOL(); } #endif @@ -1510,7 +1510,7 @@ static void set_axis_is_at_home(const AxisEnum axis) { DEBUG_POS("", current_position); SERIAL_ECHOPAIR("<<< set_axis_is_at_home(", axis_codes[axis]); SERIAL_CHAR(')'); - SERIAL_EOL; + SERIAL_EOL(); } #endif @@ -1527,7 +1527,7 @@ inline float get_homing_bump_feedrate(const AxisEnum axis) { uint8_t hbd = pgm_read_byte(&homing_bump_divisor[axis]); if (hbd < 1) { hbd = 10; - SERIAL_ECHO_START; + SERIAL_ECHO_START(); SERIAL_ECHOLNPGM("Warning: Homing Bump Divisor < 1"); } return homing_feedrate(axis) / hbd; @@ -1748,7 +1748,7 @@ static void clean_up_after_endstop_or_probe_move() { if (DEBUGGING(LEVELING)) { SERIAL_ECHOPAIR("do_probe_raise(", z_raise); SERIAL_CHAR(')'); - SERIAL_EOL; + SERIAL_EOL(); } #endif @@ -1777,7 +1777,7 @@ static void clean_up_after_endstop_or_probe_move() { zz = z && !axis_homed[Z_AXIS]; #endif if (xx || yy || zz) { - SERIAL_ECHO_START; + SERIAL_ECHO_START(); SERIAL_ECHOPGM(MSG_HOME " "); if (xx) SERIAL_ECHOPGM(MSG_X); if (yy) SERIAL_ECHOPGM(MSG_Y); @@ -1811,7 +1811,7 @@ static void clean_up_after_endstop_or_probe_move() { if (DEBUGGING(LEVELING)) { SERIAL_ECHOPAIR("dock_sled(", stow); SERIAL_CHAR(')'); - SERIAL_EOL; + SERIAL_EOL(); } #endif @@ -2054,7 +2054,7 @@ static void clean_up_after_endstop_or_probe_move() { // (Measured completion time was 0.65 seconds // after reset, deploy, and stow sequence) if (TEST_BLTOUCH()) { // If it still claims to be triggered... - SERIAL_ERROR_START; + SERIAL_ERROR_START(); SERIAL_ERRORLNPGM(MSG_STOP_BLTOUCH); stop(); // punt! } @@ -2066,7 +2066,7 @@ static void clean_up_after_endstop_or_probe_move() { if (DEBUGGING(LEVELING)) { SERIAL_ECHOPAIR("set_bltouch_deployed(", deploy); SERIAL_CHAR(')'); - SERIAL_EOL; + SERIAL_EOL(); } #endif } @@ -2098,7 +2098,7 @@ static void clean_up_after_endstop_or_probe_move() { // 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_ERROR_START(); SERIAL_ERRORLNPGM(MSG_STOP_BLTOUCH); stop(); // punt! return true; @@ -2111,7 +2111,7 @@ static void clean_up_after_endstop_or_probe_move() { #define _AUE_ARGS #endif if (axis_unhomed_error(_AUE_ARGS)) { - SERIAL_ERROR_START; + SERIAL_ERROR_START(); SERIAL_ERRORLNPGM(MSG_STOP_UNHOMED); stop(); return true; @@ -2159,7 +2159,7 @@ static void clean_up_after_endstop_or_probe_move() { if (_TRIGGERED_WHEN_STOWED_TEST == deploy) { // State hasn't changed? if (IsRunning()) { - SERIAL_ERROR_START; + SERIAL_ERROR_START(); SERIAL_ERRORLNPGM("Z-Probe failed"); LCD_ALERTMESSAGEPGM("Err: ZPROBE"); } @@ -2323,7 +2323,7 @@ static void clean_up_after_endstop_or_probe_move() { SERIAL_PROTOCOL_F(y, 3); SERIAL_PROTOCOLPGM(" Z: "); SERIAL_PROTOCOL_F(measured_z, 3); - SERIAL_EOL; + SERIAL_EOL(); } #if ENABLED(DEBUG_LEVELING_FEATURE) @@ -2523,7 +2523,7 @@ static void clean_up_after_endstop_or_probe_move() { SERIAL_PROTOCOLCHAR(' '); SERIAL_PROTOCOL((int)x); } - SERIAL_EOL; + SERIAL_EOL(); #endif #ifdef SCAD_MESH_OUTPUT SERIAL_PROTOCOLLNPGM("measured_z = ["); // open 2D array @@ -2561,12 +2561,12 @@ static void clean_up_after_endstop_or_probe_move() { SERIAL_PROTOCOLCHAR(']'); // close sub-array if (y < sy - 1) SERIAL_PROTOCOLCHAR(','); #endif - SERIAL_EOL; + SERIAL_EOL(); } #ifdef SCAD_MESH_OUTPUT SERIAL_PROTOCOLPGM("];"); // close 2D array #endif - SERIAL_EOL; + SERIAL_EOL(); } #endif @@ -2596,7 +2596,7 @@ static void clean_up_after_endstop_or_probe_move() { #endif return; // Don't overwrite good values. } - SERIAL_EOL; + SERIAL_EOL(); // Get X neighbors, Y neighbors, and XY neighbors const uint8_t x1 = x + xdir, y1 = y + ydir, x2 = x1 + xdir, y2 = y1 + ydir; @@ -2798,7 +2798,7 @@ static void do_homing_move(const AxisEnum axis, const float distance, const floa SERIAL_ECHOPAIR(", ", distance); SERIAL_ECHOPAIR(", ", fr_mm_s); SERIAL_CHAR(')'); - SERIAL_EOL; + SERIAL_EOL(); } #endif @@ -2841,7 +2841,7 @@ static void do_homing_move(const AxisEnum axis, const float distance, const floa if (DEBUGGING(LEVELING)) { SERIAL_ECHOPAIR("<<< do_homing_move(", axis_codes[axis]); SERIAL_CHAR(')'); - SERIAL_EOL; + SERIAL_EOL(); } #endif } @@ -2896,7 +2896,7 @@ static void homeaxis(const AxisEnum axis) { if (DEBUGGING(LEVELING)) { SERIAL_ECHOPAIR(">>> homeaxis(", axis_codes[axis]); SERIAL_CHAR(')'); - SERIAL_EOL; + SERIAL_EOL(); } #endif @@ -3029,7 +3029,7 @@ static void homeaxis(const AxisEnum axis) { if (DEBUGGING(LEVELING)) { SERIAL_ECHOPAIR("<<< homeaxis(", axis_codes[axis]); SERIAL_CHAR(')'); - SERIAL_EOL; + SERIAL_EOL(); } #endif } // homeaxis() @@ -3176,15 +3176,15 @@ void gcode_get_destination() { switch (busy_state) { case IN_HANDLER: case IN_PROCESS: - SERIAL_ECHO_START; + SERIAL_ECHO_START(); SERIAL_ECHOLNPGM(MSG_BUSY_PROCESSING); break; case PAUSED_FOR_USER: - SERIAL_ECHO_START; + SERIAL_ECHO_START(); SERIAL_ECHOLNPGM(MSG_BUSY_PAUSED_FOR_USER); break; case PAUSED_FOR_INPUT: - SERIAL_ECHO_START; + SERIAL_ECHO_START(); SERIAL_ECHOLNPGM(MSG_BUSY_PAUSED_FOR_INPUT); break; default: @@ -3302,7 +3302,7 @@ inline void gcode_G0_G1( } else { // Bad arguments - SERIAL_ERROR_START; + SERIAL_ERROR_START(); SERIAL_ERRORLNPGM(MSG_ERR_ARC_ARGS); } } @@ -3543,7 +3543,7 @@ inline void gcode_G4() { else SERIAL_ECHOLNPGM(" (disabled)"); - SERIAL_EOL; + SERIAL_EOL(); #elif ENABLED(MESH_BED_LEVELING) @@ -3557,7 +3557,7 @@ inline void gcode_G4() { else SERIAL_ECHOPGM(" (disabled)"); - SERIAL_EOL; + SERIAL_EOL(); #endif // MESH_BED_LEVELING } @@ -3613,7 +3613,7 @@ inline void gcode_G4() { // Disallow Z homing if X or Y are unknown if (!axis_known_position[X_AXIS] || !axis_known_position[Y_AXIS]) { LCD_MESSAGEPGM(MSG_ERR_Z_HOMING); - SERIAL_ECHO_START; + SERIAL_ECHO_START(); SERIAL_ECHOLNPGM(MSG_ERR_Z_HOMING); return; } @@ -3652,7 +3652,7 @@ inline void gcode_G4() { } else { LCD_MESSAGEPGM(MSG_ZPROBE_OUT); - SERIAL_ECHO_START; + SERIAL_ECHO_START(); SERIAL_ECHOLNPGM(MSG_ZPROBE_OUT); } @@ -4300,14 +4300,14 @@ void home_all_axes() { gcode_G28(true); } if (parser.seen('W')) { if (!leveling_is_valid()) { - SERIAL_ERROR_START; + SERIAL_ERROR_START(); SERIAL_ERRORLNPGM("No bilinear grid"); return; } const float z = parser.seen('Z') && parser.has_value() ? parser.value_float() : NAN; if (!isnan(z) || !WITHIN(z, -10, 10)) { - SERIAL_ERROR_START; + SERIAL_ERROR_START(); SERIAL_ERRORLNPGM("Bad Z value"); return; } @@ -4837,11 +4837,11 @@ void home_all_axes() { gcode_G28(true); } SERIAL_PROTOCOL_F(plane_equation_coefficients[1], 8); SERIAL_PROTOCOLPGM(" d: "); SERIAL_PROTOCOL_F(plane_equation_coefficients[2], 8); - SERIAL_EOL; + SERIAL_EOL(); if (verbose_level > 2) { SERIAL_PROTOCOLPGM("Mean of sampled points: "); SERIAL_PROTOCOL_F(mean, 8); - SERIAL_EOL; + SERIAL_EOL(); } } @@ -4887,9 +4887,9 @@ void home_all_axes() { gcode_G28(true); } SERIAL_PROTOCOLCHAR(' '); SERIAL_PROTOCOL_F(diff, 5); } // xx - SERIAL_EOL; + SERIAL_EOL(); } // yy - SERIAL_EOL; + SERIAL_EOL(); if (verbose_level > 3) { SERIAL_PROTOCOLLNPGM("\nCorrected Bed Height vs. Bed Topology:"); @@ -4911,9 +4911,9 @@ void home_all_axes() { gcode_G28(true); } SERIAL_PROTOCOLCHAR(' '); SERIAL_PROTOCOL_F(diff, 5); } // xx - SERIAL_EOL; + SERIAL_EOL(); } // yy - SERIAL_EOL; + SERIAL_EOL(); } } //do_topography_map @@ -5163,7 +5163,7 @@ void home_all_axes() { gcode_G28(true); } SERIAL_PROTOCOLPGM("Checking... AC"); if (verbose_level == 0) SERIAL_PROTOCOLPGM(" (DRY-RUN)"); - SERIAL_EOL; + SERIAL_EOL(); LCD_MESSAGEPGM("Checking... AC"); // TODO: Make translatable string SERIAL_PROTOCOLPAIR(".Height:", DELTA_HEIGHT + home_offset[Z_AXIS]); @@ -5179,7 +5179,7 @@ void home_all_axes() { gcode_G28(true); } SERIAL_PROTOCOL_F(endstop_adj[C_AXIS], 2); SERIAL_PROTOCOLPAIR(" Radius:", delta_radius); } - SERIAL_EOL; + SERIAL_EOL(); if (_7p_calibration && towers_set) { SERIAL_PROTOCOLPGM(".Tower angle : Tx:"); if (delta_tower_angle_trim[A_AXIS] >= 0) SERIAL_CHAR('+'); @@ -5188,7 +5188,7 @@ void home_all_axes() { gcode_G28(true); } if (delta_tower_angle_trim[B_AXIS] >= 0) SERIAL_CHAR('+'); SERIAL_PROTOCOL_F(delta_tower_angle_trim[B_AXIS], 2); SERIAL_PROTOCOLPGM(" Tz:+0.00"); - SERIAL_EOL; + SERIAL_EOL(); } #if ENABLED(Z_PROBE_SLED) @@ -5356,7 +5356,7 @@ void home_all_axes() { gcode_G28(true); } if (z_at_pt[9] >= 0) SERIAL_CHAR('+'); SERIAL_PROTOCOL_F(z_at_pt[9], 2); } - if (!_4p_opposite_points) SERIAL_EOL; + if (!_4p_opposite_points) SERIAL_EOL(); if ((_4p_opposite_points) || _7p_calibration) { if (_7p_calibration) { SERIAL_CHAR('.'); @@ -5371,7 +5371,7 @@ void home_all_axes() { gcode_G28(true); } SERIAL_PROTOCOLPGM(" xy:"); if (z_at_pt[3] >= 0) SERIAL_CHAR('+'); SERIAL_PROTOCOL_F(z_at_pt[3], 2); - SERIAL_EOL; + SERIAL_EOL(); } } if (test_precision != 0.0) { // !forced end @@ -5384,7 +5384,7 @@ void home_all_axes() { gcode_G28(true); } SERIAL_PROTOCOLPGM("std dev:"); SERIAL_PROTOCOL_F(zero_std_dev, 3); } - SERIAL_EOL; + SERIAL_EOL(); LCD_MESSAGEPGM("Calibration OK"); // TODO: Make translatable string } else { // !end iterations @@ -5395,7 +5395,7 @@ void home_all_axes() { gcode_G28(true); } SERIAL_PROTOCOL_SP(36); SERIAL_PROTOCOLPGM("std dev:"); SERIAL_PROTOCOL_F(zero_std_dev, 3); - SERIAL_EOL; + SERIAL_EOL(); lcd_setstatus(mess); } SERIAL_PROTOCOLPAIR(".Height:", DELTA_HEIGHT + home_offset[Z_AXIS]); @@ -5411,7 +5411,7 @@ void home_all_axes() { gcode_G28(true); } SERIAL_PROTOCOL_F(endstop_adj[C_AXIS], 2); SERIAL_PROTOCOLPAIR(" Radius:", delta_radius); } - SERIAL_EOL; + SERIAL_EOL(); if (_7p_calibration && towers_set) { SERIAL_PROTOCOLPGM(".Tower angle : Tx:"); if (delta_tower_angle_trim[A_AXIS] >= 0) SERIAL_CHAR('+'); @@ -5420,11 +5420,11 @@ void home_all_axes() { gcode_G28(true); } if (delta_tower_angle_trim[B_AXIS] >= 0) SERIAL_CHAR('+'); SERIAL_PROTOCOL_F(delta_tower_angle_trim[B_AXIS], 2); SERIAL_PROTOCOLPGM(" Tz:+0.00"); - SERIAL_EOL; + SERIAL_EOL(); } if (zero_std_dev >= test_precision || zero_std_dev <= calibration_precision) serialprintPGM(save_message); - SERIAL_EOL; + SERIAL_EOL(); } else { // forced end if (verbose_level == 0) { @@ -5432,15 +5432,15 @@ void home_all_axes() { gcode_G28(true); } SERIAL_PROTOCOL_SP(39); SERIAL_PROTOCOLPGM("std dev:"); SERIAL_PROTOCOL_F(zero_std_dev, 3); - SERIAL_EOL; + SERIAL_EOL(); } else { SERIAL_PROTOCOLLNPGM("Calibration OK"); LCD_MESSAGEPGM("Calibration OK"); // TODO: Make translatable string SERIAL_PROTOCOLPAIR(".Height:", DELTA_HEIGHT + home_offset[Z_AXIS]); - SERIAL_EOL; + SERIAL_EOL(); serialprintPGM(save_message); - SERIAL_EOL; + SERIAL_EOL(); } } @@ -5545,7 +5545,7 @@ void home_all_axes() { gcode_G28(true); } if (!parser.seen('F')) feedrate_mm_s = homing_feedrate(i); // If G38.2 fails throw an error if (!G38_run_probe() && is_38_2) { - SERIAL_ERROR_START; + SERIAL_ERROR_START(); SERIAL_ERRORLNPGM("Failed to reach target"); } break; @@ -5685,7 +5685,7 @@ inline void gcode_G92() { #else if (!hasP && !hasS && args && *args) { - SERIAL_ECHO_START; + SERIAL_ECHO_START(); SERIAL_ECHOLN(args); } @@ -5899,7 +5899,7 @@ inline void gcode_M17() { #if ENABLED(PREVENT_COLD_EXTRUSION) if (!thermalManager.allow_cold_extrude && thermalManager.degTargetHotend(active_extruder) < thermalManager.extrude_min_temp) { - SERIAL_ERROR_START; + SERIAL_ERROR_START(); SERIAL_ERRORLNPGM(MSG_TOO_COLD_FOR_M600); return false; } @@ -6232,7 +6232,7 @@ inline void gcode_M31() { elapsed.toString(buffer); lcd_setstatus(buffer); - SERIAL_ECHO_START; + SERIAL_ECHO_START(); SERIAL_ECHOLNPAIR("Print time: ", buffer); } @@ -6330,7 +6330,7 @@ inline void gcode_M42() { if (pin_number < 0) return; if (pin_is_protected(pin_number)) { - SERIAL_ERROR_START; + SERIAL_ERROR_START(); SERIAL_ERRORLNPGM(MSG_ERR_PROTECTED_PIN); return; } @@ -6391,12 +6391,12 @@ inline void gcode_M42() { inline void servo_probe_test() { #if !(NUM_SERVOS > 0 && HAS_SERVO_0) - SERIAL_ERROR_START; + SERIAL_ERROR_START(); SERIAL_ERRORLNPGM("SERVO not setup"); #elif !HAS_Z_SERVO_ENDSTOP - SERIAL_ERROR_START; + SERIAL_ERROR_START(); SERIAL_ERRORLNPGM("Z_ENDSTOP_SERVO_NR not setup"); #else @@ -6832,7 +6832,7 @@ inline void gcode_M42() { SERIAL_PROTOCOLPGM(" range: "); SERIAL_PROTOCOL_F(max-min, 3); } - SERIAL_EOL; + SERIAL_EOL(); } } @@ -6841,7 +6841,7 @@ inline void gcode_M42() { if (STOW_PROBE()) return; SERIAL_PROTOCOLPGM("Finished!"); - SERIAL_EOL; + SERIAL_EOL(); if (verbose_level > 0) { SERIAL_PROTOCOLPGM("Mean: "); @@ -6852,13 +6852,13 @@ inline void gcode_M42() { SERIAL_PROTOCOL_F(max, 3); SERIAL_PROTOCOLPGM(" Range: "); SERIAL_PROTOCOL_F(max-min, 3); - SERIAL_EOL; + SERIAL_EOL(); } SERIAL_PROTOCOLPGM("Standard Deviation: "); SERIAL_PROTOCOL_F(sigma, 6); - SERIAL_EOL; - SERIAL_EOL; + SERIAL_EOL(); + SERIAL_EOL(); clean_up_after_endstop_or_probe_move(); @@ -7014,11 +7014,11 @@ inline void gcode_M105() { SERIAL_PROTOCOLPGM(MSG_OK); print_heaterstates(); #else // !HAS_TEMP_HOTEND && !HAS_TEMP_BED - SERIAL_ERROR_START; + SERIAL_ERROR_START(); SERIAL_ERRORLNPGM(MSG_ERR_NO_THERMISTORS); #endif - SERIAL_EOL; + SERIAL_EOL(); } #if ENABLED(AUTO_REPORT_TEMPERATURES) && (HAS_TEMP_HOTEND || HAS_TEMP_BED) @@ -7041,7 +7041,7 @@ inline void gcode_M105() { if (auto_report_temp_interval && ELAPSED(millis(), next_temp_report_ms)) { next_temp_report_ms = millis() + 1000UL * auto_report_temp_interval; print_heaterstates(); - SERIAL_EOL; + SERIAL_EOL(); } } @@ -7194,7 +7194,7 @@ inline void gcode_M109() { SERIAL_PROTOCOLLNPGM("?"); } #else - SERIAL_EOL; + SERIAL_EOL(); #endif } @@ -7327,7 +7327,7 @@ inline void gcode_M109() { SERIAL_PROTOCOLLNPGM("?"); } #else - SERIAL_EOL; + SERIAL_EOL(); #endif } @@ -7407,7 +7407,7 @@ inline void gcode_M111() { #endif }; - SERIAL_ECHO_START; + SERIAL_ECHO_START(); SERIAL_ECHOPGM(MSG_DEBUG_PREFIX); if (marlin_debug_flags) { uint8_t comma = 0; @@ -7421,7 +7421,7 @@ inline void gcode_M111() { else { SERIAL_ECHOPGM(MSG_DEBUG_OFF); } - SERIAL_EOL; + SERIAL_EOL(); } #if ENABLED(HOST_KEEPALIVE_FEATURE) @@ -7437,7 +7437,7 @@ inline void gcode_M111() { NOMORE(host_keepalive_interval, 60); } else { - SERIAL_ECHO_START; + SERIAL_ECHO_START(); SERIAL_ECHOLNPAIR("M113 S", (unsigned long)host_keepalive_interval); } } @@ -7491,7 +7491,7 @@ inline void gcode_M140() { inline void gcode_M145() { uint8_t material = parser.seen('S') ? (uint8_t)parser.value_int() : 0; if (material >= COUNT(lcd_preheat_hotend_temp)) { - SERIAL_ERROR_START; + SERIAL_ERROR_START(); SERIAL_ERRORLNPGM(MSG_ERR_MATERIAL_INDEX); } else { @@ -7697,7 +7697,7 @@ void report_current_position() { #if IS_SCARA SERIAL_PROTOCOLPAIR("SCARA Theta:", stepper.get_axis_position_degrees(A_AXIS)); SERIAL_PROTOCOLLNPAIR(" Psi+Theta:", stepper.get_axis_position_degrees(B_AXIS)); - SERIAL_EOL; + SERIAL_EOL(); #endif } @@ -7711,7 +7711,7 @@ void report_current_position() { SERIAL_CHAR(':'); SERIAL_PROTOCOL(dtostrf(pos[i], 8, precision, str)); } - SERIAL_EOL; + SERIAL_EOL(); } inline void report_xyz(const float pos[XYZ]) { report_xyze(pos, 3); } @@ -8214,7 +8214,7 @@ inline void gcode_M205() { if (sumAPX == 1) home_offset[A_AXIS] = parser.value_float(); else if (sumAPX > 1) { - SERIAL_ERROR_START; + SERIAL_ERROR_START(); SERIAL_ERRORLNPGM("Only one of A, P, or X is allowed."); return; } @@ -8224,7 +8224,7 @@ inline void gcode_M205() { if (sumBTY == 1) home_offset[B_AXIS] = parser.value_float(); else if (sumBTY > 1) { - SERIAL_ERROR_START; + SERIAL_ERROR_START(); SERIAL_ERRORLNPGM("Only one of B, T, or Y is allowed."); return; } @@ -8296,7 +8296,7 @@ inline void gcode_M205() { * Usage: M211 S1 to enable, M211 S0 to disable, M211 alone for report */ inline void gcode_M211() { - SERIAL_ECHO_START; + SERIAL_ECHO_START(); #if HAS_SOFTWARE_ENDSTOPS if (parser.seen('S')) soft_endstops_enabled = parser.value_bool(); SERIAL_ECHOPGM(MSG_SOFT_ENDSTOPS); @@ -8335,7 +8335,7 @@ inline void gcode_M211() { if (parser.seen('Z')) hotend_offset[Z_AXIS][target_extruder] = parser.value_linear_units(); #endif - SERIAL_ECHO_START; + SERIAL_ECHO_START(); SERIAL_ECHOPGM(MSG_HOTEND_OFFSET); HOTEND_LOOP() { SERIAL_CHAR(' '); @@ -8347,7 +8347,7 @@ inline void gcode_M211() { SERIAL_ECHO(hotend_offset[Z_AXIS][e]); #endif } - SERIAL_EOL; + SERIAL_EOL(); } #endif // HOTENDS > 1 @@ -8447,7 +8447,7 @@ inline void gcode_M226() { i2c.relay(bytes); } else { - SERIAL_ERROR_START; + SERIAL_ERROR_START(); SERIAL_ERRORLN("Bad i2c request"); } } @@ -8466,13 +8466,13 @@ inline void gcode_M226() { if (parser.seen('S')) MOVE_SERVO(servo_index, parser.value_int()); else { - SERIAL_ECHO_START; + SERIAL_ECHO_START(); SERIAL_ECHOPAIR(" Servo ", servo_index); SERIAL_ECHOLNPAIR(": ", servo[servo_index].read()); } } else { - SERIAL_ERROR_START; + SERIAL_ERROR_START(); SERIAL_ECHOPAIR("Servo ", servo_index); SERIAL_ECHOLNPGM(" out of range"); } @@ -8528,7 +8528,7 @@ inline void gcode_M226() { #endif thermalManager.updatePID(); - SERIAL_ECHO_START; + SERIAL_ECHO_START(); #if ENABLED(PID_PARAMS_PER_HOTEND) SERIAL_ECHOPAIR(" e:", e); // specify extruder in serial output #endif // PID_PARAMS_PER_HOTEND @@ -8539,10 +8539,10 @@ inline void gcode_M226() { //Kc does not have scaling applied above, or in resetting defaults SERIAL_ECHOPAIR(" c:", PID_PARAM(Kc, e)); #endif - SERIAL_EOL; + SERIAL_EOL(); } else { - SERIAL_ERROR_START; + SERIAL_ERROR_START(); SERIAL_ERRORLN(MSG_INVALID_EXTRUDER); } } @@ -8558,7 +8558,7 @@ inline void gcode_M226() { thermalManager.updatePID(); - SERIAL_ECHO_START; + SERIAL_ECHO_START(); SERIAL_ECHOPAIR(" p:", thermalManager.bedKp); SERIAL_ECHOPAIR(" i:", unscalePID_i(thermalManager.bedKi)); SERIAL_ECHOLNPAIR(" d:", unscalePID_d(thermalManager.bedKd)); @@ -8611,7 +8611,7 @@ inline void gcode_M226() { if (parser.seen('C')) set_lcd_contrast(parser.value_int()); SERIAL_PROTOCOLPGM("lcd contrast value: "); SERIAL_PROTOCOL(lcd_contrast); - SERIAL_EOL; + SERIAL_EOL(); } #endif // HAS_LCD_CONTRAST @@ -8644,7 +8644,7 @@ inline void gcode_M226() { thermalManager.allow_cold_extrude = (thermalManager.extrude_min_temp == 0) || parser.value_bool(); else if (!seen_S) { // Report current state - SERIAL_ECHO_START; + SERIAL_ECHO_START(); SERIAL_ECHOPAIR("Cold extrudes are ", (thermalManager.allow_cold_extrude ? "en" : "dis")); SERIAL_ECHOPAIR("abled (min temp ", thermalManager.extrude_min_temp); SERIAL_ECHOLNPGM("C)"); @@ -8678,7 +8678,7 @@ inline void gcode_M303() { KEEPALIVE_STATE(IN_HANDLER); #else - SERIAL_ERROR_START; + SERIAL_ERROR_START(); SERIAL_ERRORLNPGM(MSG_ERR_M303_DISABLED); #endif } @@ -8767,7 +8767,7 @@ inline void gcode_M303() { break; #endif default: - SERIAL_ECHO_START; + SERIAL_ECHO_START(); SERIAL_ECHOLNPGM(MSG_INVALID_SOLENOID); break; } @@ -8971,11 +8971,11 @@ void quickstop_stepper() { const bool new_status = leveling_is_active(); if (to_enable && !new_status) { - SERIAL_ERROR_START; + SERIAL_ERROR_START(); SERIAL_ERRORLNPGM(MSG_ERR_M420_FAILED); } - SERIAL_ECHO_START; + SERIAL_ECHO_START(); SERIAL_ECHOLNPAIR("Bed Leveling ", new_status ? MSG_ON : MSG_OFF); } #endif @@ -8999,11 +8999,11 @@ void quickstop_stepper() { const bool hasZ = parser.seen('Z'), hasQ = !hasZ && parser.seen('Q'); if (int(hasI && hasJ) + int(hasX && hasY) != 1 || !(hasZ || hasQ)) { - SERIAL_ERROR_START; + SERIAL_ERROR_START(); SERIAL_ERRORLNPGM(MSG_ERR_M421_PARAMETERS); } else if (ix < 0 || iy < 0) { - SERIAL_ERROR_START; + SERIAL_ERROR_START(); SERIAL_ERRORLNPGM(MSG_ERR_MESH_XY); } else @@ -9027,11 +9027,11 @@ void quickstop_stepper() { const bool hasZ = parser.seen('Z'), hasQ = !hasZ && parser.seen('Q'); if (!hasI || !hasJ || !(hasZ || hasQ)) { - SERIAL_ERROR_START; + SERIAL_ERROR_START(); SERIAL_ERRORLNPGM(MSG_ERR_M421_PARAMETERS); } else if (!WITHIN(ix, 0, GRID_MAX_POINTS_X - 1) || !WITHIN(iy, 0, GRID_MAX_POINTS_Y - 1)) { - SERIAL_ERROR_START; + SERIAL_ERROR_START(); SERIAL_ERRORLNPGM(MSG_ERR_MESH_XY); } else { @@ -9067,11 +9067,11 @@ void quickstop_stepper() { } if (int(hasC) + int(hasI && hasJ) != 1 || !(hasZ || hasQ)) { - SERIAL_ERROR_START; + SERIAL_ERROR_START(); SERIAL_ERRORLNPGM(MSG_ERR_M421_PARAMETERS); } else if (!WITHIN(ix, 0, GRID_MAX_POINTS_X - 1) || !WITHIN(iy, 0, GRID_MAX_POINTS_Y - 1)) { - SERIAL_ERROR_START; + SERIAL_ERROR_START(); SERIAL_ERRORLNPGM(MSG_ERR_MESH_XY); } else @@ -9103,7 +9103,7 @@ void quickstop_stepper() { set_home_offset((AxisEnum)i, diff); } else { - SERIAL_ERROR_START; + SERIAL_ERROR_START(); SERIAL_ERRORLNPGM(MSG_ERR_M428_TOO_FAR); LCD_ALERTMESSAGEPGM("Err: Too far!"); BUZZ(200, 40); @@ -9202,7 +9202,7 @@ inline void gcode_M503() { } inline void gcode_M851() { - SERIAL_ECHO_START; + SERIAL_ECHO_START(); SERIAL_ECHOPGM(MSG_ZPROBE_ZOFFSET " "); if (parser.seen('Z')) { const float value = parser.value_linear_units(); @@ -9217,7 +9217,7 @@ inline void gcode_M503() { else SERIAL_ECHOPAIR(": ", zprobe_zoffset); - SERIAL_EOL; + SERIAL_EOL(); } #endif // HAS_BED_PROBE @@ -9327,7 +9327,7 @@ inline void gcode_M503() { case DXC_DUPLICATION_MODE: if (parser.seen('X')) duplicate_extruder_x_offset = max(parser.value_linear_units(), X2_MIN_POS - x_home_pos(0)); if (parser.seen('R')) duplicate_extruder_temp_offset = parser.value_celsius_diff(); - SERIAL_ECHO_START; + SERIAL_ECHO_START(); SERIAL_ECHOPGM(MSG_HOTEND_OFFSET); SERIAL_CHAR(' '); SERIAL_ECHO(hotend_offset[X_AXIS][0]); @@ -9352,7 +9352,7 @@ inline void gcode_M503() { inline void gcode_M605() { stepper.synchronize(); extruder_duplication_enabled = parser.seen('S') && parser.value_int() == (int)DXC_DUPLICATION_MODE; - SERIAL_ECHO_START; + SERIAL_ECHO_START(); SERIAL_ECHOLNPAIR(MSG_DUPLICATION_MODE, extruder_duplication_enabled ? MSG_ON : MSG_OFF); } @@ -9382,12 +9382,12 @@ inline void gcode_M503() { } if (newR >= 0) planner.advance_ed_ratio = newR; - SERIAL_ECHO_START; + SERIAL_ECHO_START(); SERIAL_ECHOPAIR("Advance K=", planner.extruder_advance_k); SERIAL_ECHOPGM(" E/D="); const float ratio = planner.advance_ed_ratio; if (ratio) SERIAL_ECHO(ratio); else SERIAL_ECHOPGM("Auto"); - SERIAL_EOL; + SERIAL_EOL(); } #endif // LIN_ADVANCE @@ -9407,7 +9407,7 @@ inline void gcode_M503() { SERIAL_CHAR(name); SERIAL_ECHOPGM(" axis temperature prewarn triggered: "); serialprintPGM(st.getOTPW() ? PSTR("true") : PSTR("false")); - SERIAL_EOL; + SERIAL_EOL(); } static void tmc2130_clear_otpw(TMC2130Stepper &st, const char name) { st.clear_otpw(); @@ -9690,7 +9690,7 @@ inline void gcode_M355() { if (args) update_case_light(); // always report case light status - SERIAL_ECHO_START; + SERIAL_ECHO_START(); if (!case_light_on) { SERIAL_ECHOLN("Case light: off"); } @@ -9700,7 +9700,7 @@ inline void gcode_M355() { } #else - SERIAL_ERROR_START; + SERIAL_ERROR_START(); SERIAL_ERRORLNPGM(MSG_ERR_M355_NONE); #endif // HAS_CASE_LIGHT } @@ -9799,7 +9799,7 @@ inline void gcode_M999() { #endif inline void invalid_extruder_error(const uint8_t &e) { - SERIAL_ECHO_START; + SERIAL_ECHO_START(); SERIAL_CHAR('T'); SERIAL_ECHO_F(e, DEC); SERIAL_ECHOLN(MSG_INVALID_EXTRUDER); @@ -10120,7 +10120,7 @@ void tool_change(const uint8_t tmp_extruder, const float fr_mm_s/*=0.0*/, bool n #endif // HOTENDS <= 1 - SERIAL_ECHO_START; + SERIAL_ECHO_START(); SERIAL_ECHOLNPAIR(MSG_ACTIVE_EXTRUDER, (int)active_extruder); #endif // !MIXING_EXTRUDER || MIXING_VIRTUAL_TOOLS <= 1 @@ -10138,7 +10138,7 @@ inline void gcode_T(uint8_t tmp_extruder) { if (DEBUGGING(LEVELING)) { SERIAL_ECHOPAIR(">>> gcode_T(", tmp_extruder); SERIAL_CHAR(')'); - SERIAL_EOL; + SERIAL_EOL(); DEBUG_POS("BEFORE", current_position); } #endif @@ -10173,7 +10173,7 @@ void process_next_command() { char * const current_command = command_queue[cmd_queue_index_r]; if (DEBUGGING(ECHO)) { - SERIAL_ECHO_START; + SERIAL_ECHO_START(); SERIAL_ECHOLN(current_command); #if ENABLED(M100_FREE_MEMORY_WATCHER) SERIAL_ECHOPAIR("slot:", cmd_queue_index_r); @@ -11021,7 +11021,7 @@ void ok_to_send() { SERIAL_PROTOCOLPGM(" P"); SERIAL_PROTOCOL(int(BLOCK_BUFFER_SIZE - planner.movesplanned() - 1)); SERIAL_PROTOCOLPGM(" B"); SERIAL_PROTOCOL(BUFSIZE - commands_in_queue); #endif - SERIAL_EOL; + SERIAL_EOL(); } #if HAS_SOFTWARE_ENDSTOPS @@ -11813,13 +11813,13 @@ void prepare_move_to_destination() { if (destination[E_AXIS] != current_position[E_AXIS]) { if (thermalManager.tooColdToExtrude(active_extruder)) { current_position[E_AXIS] = destination[E_AXIS]; // Behave as if the move really took place, but ignore E part - SERIAL_ECHO_START; + SERIAL_ECHO_START(); SERIAL_ECHOLNPGM(MSG_ERR_COLD_EXTRUDE_STOP); } #if ENABLED(PREVENT_LENGTHY_EXTRUDE) if (labs(destination[E_AXIS] - current_position[E_AXIS]) > EXTRUDE_MAXLENGTH) { current_position[E_AXIS] = destination[E_AXIS]; // Behave as if the move really took place, but ignore E part - SERIAL_ECHO_START; + SERIAL_ECHO_START(); SERIAL_ECHOLNPGM(MSG_ERR_LONG_EXTRUDE_STOP); } #endif @@ -12300,7 +12300,7 @@ void disable_all_steppers() { #endif } } - SERIAL_EOL; + SERIAL_EOL(); #endif } @@ -12373,7 +12373,7 @@ void manage_inactivity(bool ignore_stepper_queue/*=false*/) { const millis_t ms = millis(); if (max_inactive_time && ELAPSED(ms, previous_cmd_ms + max_inactive_time)) { - SERIAL_ERROR_START; + SERIAL_ERROR_START(); SERIAL_ECHOLNPAIR(MSG_KILL_INACTIVE_TIME, parser.command_ptr); kill(PSTR(MSG_KILLED)); } @@ -12424,7 +12424,7 @@ void manage_inactivity(bool ignore_stepper_queue/*=false*/) { // KILL the machine // ---------------------------------------------------------------- if (killCount >= KILL_DELAY) { - SERIAL_ERROR_START; + SERIAL_ERROR_START(); SERIAL_ERRORLNPGM(MSG_KILL_BUTTON); kill(PSTR(MSG_KILLED)); } @@ -12575,7 +12575,7 @@ void idle( * After this the machine will need to be reset. */ void kill(const char* lcd_msg) { - SERIAL_ERROR_START; + SERIAL_ERROR_START(); SERIAL_ERRORLNPGM(MSG_ERR_KILLED); thermalManager.disable_all_heaters(); @@ -12618,7 +12618,7 @@ void stop() { if (IsRunning()) { Stopped_gcode_LastN = gcode_LastN; // Save last g_code for restart - SERIAL_ERROR_START; + SERIAL_ERROR_START(); SERIAL_ERRORLNPGM(MSG_ERR_STOPPED); LCD_MESSAGEPGM(MSG_STOPPED); safe_delay(350); // allow enough time for messages to get out before stopping @@ -12666,7 +12666,7 @@ void setup() { MYSERIAL.begin(BAUDRATE); SERIAL_PROTOCOLLNPGM("start"); - SERIAL_ECHO_START; + SERIAL_ECHO_START(); // Check startup - does nothing if bootloader sets MCUSR to 0 byte mcu = MCUSR; @@ -12680,17 +12680,17 @@ void setup() { SERIAL_ECHOPGM(MSG_MARLIN); SERIAL_CHAR(' '); SERIAL_ECHOLNPGM(SHORT_BUILD_VERSION); - SERIAL_EOL; + SERIAL_EOL(); #if defined(STRING_DISTRIBUTION_DATE) && defined(STRING_CONFIG_H_AUTHOR) - SERIAL_ECHO_START; + SERIAL_ECHO_START(); SERIAL_ECHOPGM(MSG_CONFIGURATION_VER); SERIAL_ECHOPGM(STRING_DISTRIBUTION_DATE); SERIAL_ECHOLNPGM(MSG_AUTHOR STRING_CONFIG_H_AUTHOR); SERIAL_ECHOLNPGM("Compiled: " __DATE__); #endif - SERIAL_ECHO_START; + SERIAL_ECHO_START(); SERIAL_ECHOPAIR(MSG_FREE_MEMORY, freeMemory()); SERIAL_ECHOLNPAIR(MSG_PLANNER_BUFFER_BYTES, (int)sizeof(block_t)*BLOCK_BUFFER_SIZE); diff --git a/Marlin/cardreader.cpp b/Marlin/cardreader.cpp index 5681660d25..0f40202912 100644 --- a/Marlin/cardreader.cpp +++ b/Marlin/cardreader.cpp @@ -109,7 +109,7 @@ void CardReader::lsDive(const char *prepend, SdFile parent, const char * const m SdFile dir; if (!dir.open(parent, lfilename, O_READ)) { if (lsAction == LS_SerialPrint) { - SERIAL_ECHO_START; + SERIAL_ECHO_START(); SERIAL_ECHOPGM(MSG_SD_CANT_OPEN_SUBDIR); SERIAL_ECHOLN(lfilename); } @@ -208,8 +208,8 @@ void CardReader::ls() { // Open the sub-item as the new dive parent SdFile dir; if (!dir.open(diveDir, segment, O_READ)) { - SERIAL_EOL; - SERIAL_ECHO_START; + SERIAL_EOL(); + SERIAL_ECHO_START(); SERIAL_ECHOPGM(MSG_SD_CANT_OPEN_SUBDIR); SERIAL_ECHO(segment); break; @@ -220,7 +220,7 @@ void CardReader::ls() { } // while i SD_PROCEDURE_DEPTH - 1) { - SERIAL_ERROR_START; + SERIAL_ERROR_START(); SERIAL_ERRORPGM("trying to call sub-gcode files with too many levels. MAX level is:"); SERIAL_ERRORLN(SD_PROCEDURE_DEPTH); kill(PSTR(MSG_KILLED)); @@ -341,7 +341,7 @@ void CardReader::openFile(char* name, bool read, bool push_current/*=false*/) { // Store current filename and position getAbsFilename(proc_filenames[file_subcall_ctr]); - SERIAL_ECHO_START; + SERIAL_ECHO_START(); SERIAL_ECHOPAIR("SUBROUTINE CALL target:\"", name); SERIAL_ECHOPAIR("\" parent:\"", proc_filenames[file_subcall_ctr]); SERIAL_ECHOLNPAIR("\" pos", sdpos); @@ -358,7 +358,7 @@ void CardReader::openFile(char* name, bool read, bool push_current/*=false*/) { } if (doing) { - SERIAL_ECHO_START; + SERIAL_ECHO_START(); SERIAL_ECHOPGM("Now "); SERIAL_ECHO(doing == 1 ? "doing" : "fresh"); SERIAL_ECHOLNPAIR(" file: ", name); @@ -421,14 +421,14 @@ void CardReader::openFile(char* name, bool read, bool push_current/*=false*/) { else { SERIAL_PROTOCOLPAIR(MSG_SD_OPEN_FILE_FAIL, fname); SERIAL_PROTOCOLCHAR('.'); - SERIAL_EOL; + SERIAL_EOL(); } } else { //write if (!file.open(curDir, fname, O_CREAT | O_APPEND | O_WRITE | O_TRUNC)) { SERIAL_PROTOCOLPAIR(MSG_SD_OPEN_FILE_FAIL, fname); SERIAL_PROTOCOLCHAR('.'); - SERIAL_EOL; + SERIAL_EOL(); } else { saving = true; @@ -462,7 +462,7 @@ void CardReader::removeFile(char* name) { if (!myDir.open(curDir, subdirname, O_READ)) { SERIAL_PROTOCOLPAIR("open failed, File: ", subdirname); SERIAL_PROTOCOLCHAR('.'); - SERIAL_EOL; + SERIAL_EOL(); return; } else { @@ -526,7 +526,7 @@ void CardReader::write_command(char *buf) { end[3] = '\0'; file.write(begin); if (file.writeError) { - SERIAL_ERROR_START; + SERIAL_ERROR_START(); SERIAL_ERRORLNPGM(MSG_SD_ERR_WRITE_TO_FILE); } } @@ -617,7 +617,7 @@ void CardReader::chdir(const char * relpath) { if (workDir.isOpen()) parent = &workDir; if (!newfile.open(*parent, relpath, O_READ)) { - SERIAL_ECHO_START; + SERIAL_ECHO_START(); SERIAL_ECHOPGM(MSG_SD_CANT_ENTER_SUBDIR); SERIAL_ECHOLN(relpath); } diff --git a/Marlin/configuration_store.cpp b/Marlin/configuration_store.cpp index eedee1deb2..2e48701c70 100644 --- a/Marlin/configuration_store.cpp +++ b/Marlin/configuration_store.cpp @@ -247,7 +247,7 @@ void MarlinSettings::postprocess() { #define EEPROM_SKIP(VAR) eeprom_index += sizeof(VAR) #define EEPROM_WRITE(VAR) write_data(eeprom_index, (uint8_t*)&VAR, sizeof(VAR), &working_crc) #define EEPROM_READ(VAR) read_data(eeprom_index, (uint8_t*)&VAR, sizeof(VAR), &working_crc) - #define EEPROM_ASSERT(TST,ERR) if (!(TST)) do{ SERIAL_ERROR_START; SERIAL_ERRORLNPGM(ERR); eeprom_read_error = true; }while(0) + #define EEPROM_ASSERT(TST,ERR) if (!(TST)) do{ SERIAL_ERROR_START(); SERIAL_ERRORLNPGM(ERR); eeprom_read_error = true; }while(0) const char version[4] = EEPROM_VERSION; @@ -267,7 +267,7 @@ void MarlinSettings::postprocess() { if (v != eeprom_read_byte(p)) { eeprom_write_byte(p, v); if (eeprom_read_byte(p) != v) { - SERIAL_ECHO_START; + SERIAL_ECHO_START(); SERIAL_ECHOLNPGM(MSG_ERR_EEPROM_WRITE); eeprom_error = true; return; @@ -638,7 +638,7 @@ void MarlinSettings::postprocess() { EEPROM_WRITE(final_crc); // Report storage size - SERIAL_ECHO_START; + SERIAL_ECHO_START(); SERIAL_ECHOPAIR("Settings Stored (", eeprom_size - (EEPROM_OFFSET)); SERIAL_ECHOPAIR(" bytes; crc ", final_crc); SERIAL_ECHOLNPGM(")"); @@ -672,7 +672,7 @@ void MarlinSettings::postprocess() { stored_ver[0] = '?'; stored_ver[1] = '\0'; } - SERIAL_ECHO_START; + SERIAL_ECHO_START(); SERIAL_ECHOPGM("EEPROM version mismatch "); SERIAL_ECHOPAIR("(EEPROM=", stored_ver); SERIAL_ECHOLNPGM(" Marlin=" EEPROM_VERSION ")"); @@ -981,14 +981,14 @@ void MarlinSettings::postprocess() { if (working_crc == stored_crc) { postprocess(); - SERIAL_ECHO_START; + SERIAL_ECHO_START(); SERIAL_ECHO(version); SERIAL_ECHOPAIR(" stored settings retrieved (", eeprom_index - (EEPROM_OFFSET)); SERIAL_ECHOPAIR(" bytes; crc ", working_crc); SERIAL_ECHOLNPGM(")"); } else { - SERIAL_ERROR_START; + SERIAL_ERROR_START(); SERIAL_ERRORPGM("EEPROM CRC mismatch - (stored) "); SERIAL_ERROR(stored_crc); SERIAL_ERRORPGM(" != "); @@ -1004,7 +1004,7 @@ void MarlinSettings::postprocess() { ubl.report_state(); if (!ubl.sanity_check()) { - SERIAL_EOL; + SERIAL_EOL(); ubl.echo_name(); SERIAL_ECHOLNPGM(" initialized.\n"); } @@ -1059,7 +1059,7 @@ void MarlinSettings::postprocess() { SERIAL_PROTOCOLPAIR("E2END=", E2END); SERIAL_PROTOCOLPAIR(" meshes_end=", meshes_end); SERIAL_PROTOCOLLNPAIR(" slot=", slot); - SERIAL_EOL; + SERIAL_EOL(); return; } @@ -1114,7 +1114,7 @@ void MarlinSettings::postprocess() { #else // !EEPROM_SETTINGS bool MarlinSettings::save() { - SERIAL_ERROR_START; + SERIAL_ERROR_START(); SERIAL_ERRORLNPGM("EEPROM disabled"); return false; } @@ -1315,13 +1315,13 @@ void MarlinSettings::reset() { postprocess(); - SERIAL_ECHO_START; + SERIAL_ECHO_START(); SERIAL_ECHOLNPGM("Hardcoded Default Settings Loaded"); } #if DISABLED(DISABLE_M503) - #define CONFIG_ECHO_START do{ if (!forReplay) SERIAL_ECHO_START; }while(0) + #define CONFIG_ECHO_START do{ if (!forReplay) SERIAL_ECHO_START(); }while(0) /** * M503 - Report current settings in RAM @@ -1365,7 +1365,7 @@ void MarlinSettings::reset() { #endif - SERIAL_EOL; + SERIAL_EOL(); /** * Volumetric extrusion M200 @@ -1374,30 +1374,30 @@ void MarlinSettings::reset() { CONFIG_ECHO_START; SERIAL_ECHOPGM("Filament settings:"); if (volumetric_enabled) - SERIAL_EOL; + SERIAL_EOL(); else SERIAL_ECHOLNPGM(" Disabled"); } CONFIG_ECHO_START; SERIAL_ECHOPAIR(" M200 D", filament_size[0]); - SERIAL_EOL; + SERIAL_EOL(); #if EXTRUDERS > 1 CONFIG_ECHO_START; SERIAL_ECHOPAIR(" M200 T1 D", filament_size[1]); - SERIAL_EOL; + SERIAL_EOL(); #if EXTRUDERS > 2 CONFIG_ECHO_START; SERIAL_ECHOPAIR(" M200 T2 D", filament_size[2]); - SERIAL_EOL; + SERIAL_EOL(); #if EXTRUDERS > 3 CONFIG_ECHO_START; SERIAL_ECHOPAIR(" M200 T3 D", filament_size[3]); - SERIAL_EOL; + SERIAL_EOL(); #if EXTRUDERS > 4 CONFIG_ECHO_START; SERIAL_ECHOPAIR(" M200 T4 D", filament_size[4]); - SERIAL_EOL; + SERIAL_EOL(); #endif // EXTRUDERS > 4 #endif // EXTRUDERS > 3 #endif // EXTRUDERS > 2 @@ -1419,7 +1419,7 @@ void MarlinSettings::reset() { #if DISABLED(DISTINCT_E_FACTORS) SERIAL_ECHOPAIR(" E", VOLUMETRIC_UNIT(planner.axis_steps_per_mm[E_AXIS])); #endif - SERIAL_EOL; + SERIAL_EOL(); #if ENABLED(DISTINCT_E_FACTORS) CONFIG_ECHO_START; for (uint8_t i = 0; i < E_STEPPERS; i++) { @@ -1439,7 +1439,7 @@ void MarlinSettings::reset() { #if DISABLED(DISTINCT_E_FACTORS) SERIAL_ECHOPAIR(" E", VOLUMETRIC_UNIT(planner.max_feedrate_mm_s[E_AXIS])); #endif - SERIAL_EOL; + SERIAL_EOL(); #if ENABLED(DISTINCT_E_FACTORS) CONFIG_ECHO_START; for (uint8_t i = 0; i < E_STEPPERS; i++) { @@ -1459,7 +1459,7 @@ void MarlinSettings::reset() { #if DISABLED(DISTINCT_E_FACTORS) SERIAL_ECHOPAIR(" E", VOLUMETRIC_UNIT(planner.max_acceleration_mm_per_s2[E_AXIS])); #endif - SERIAL_EOL; + SERIAL_EOL(); #if ENABLED(DISTINCT_E_FACTORS) CONFIG_ECHO_START; for (uint8_t i = 0; i < E_STEPPERS; i++) { @@ -1514,7 +1514,7 @@ void MarlinSettings::reset() { #if ENABLED(DUAL_X_CARRIAGE) || ENABLED(SWITCHING_NOZZLE) SERIAL_ECHOPAIR(" Z", LINEAR_UNIT(hotend_offset[Z_AXIS][e])); #endif - SERIAL_EOL; + SERIAL_EOL(); } #endif @@ -1529,7 +1529,7 @@ void MarlinSettings::reset() { #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) SERIAL_ECHOPAIR(" Z", LINEAR_UNIT(planner.z_fade_height)); #endif - SERIAL_EOL; + SERIAL_EOL(); for (uint8_t py = 0; py < GRID_MAX_POINTS_Y; py++) { for (uint8_t px = 0; px < GRID_MAX_POINTS_X; px++) { CONFIG_ECHO_START; @@ -1537,7 +1537,7 @@ void MarlinSettings::reset() { SERIAL_ECHOPAIR(" Y", (int)py + 1); SERIAL_ECHOPGM(" Z"); SERIAL_PROTOCOL_F(LINEAR_UNIT(mbl.z_values[px][py]), 5); - SERIAL_EOL; + SERIAL_EOL(); } } @@ -1553,17 +1553,17 @@ void MarlinSettings::reset() { #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) SERIAL_ECHOPAIR(" Z", planner.z_fade_height); #endif - SERIAL_EOL; + SERIAL_EOL(); if (!forReplay) { - SERIAL_EOL; + SERIAL_EOL(); ubl.report_state(); SERIAL_ECHOLNPAIR("\nActive Mesh Slot: ", ubl.state.storage_slot); SERIAL_ECHOPGM("z_offset: "); SERIAL_ECHO_F(ubl.state.z_offset, 6); - SERIAL_EOL; + SERIAL_EOL(); SERIAL_ECHOPAIR("EEPROM can hold ", calc_num_meshes()); SERIAL_ECHOLNPGM(" meshes.\n"); @@ -1580,7 +1580,7 @@ void MarlinSettings::reset() { #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) SERIAL_ECHOPAIR(" Z", LINEAR_UNIT(planner.z_fade_height)); #endif - SERIAL_EOL; + SERIAL_EOL(); #endif @@ -1606,7 +1606,7 @@ void MarlinSettings::reset() { SERIAL_ECHOPAIR(" X", LINEAR_UNIT(delta_tower_angle_trim[A_AXIS])); SERIAL_ECHOPAIR(" Y", LINEAR_UNIT(delta_tower_angle_trim[B_AXIS])); SERIAL_ECHOPAIR(" Z", 0.00); - SERIAL_EOL; + SERIAL_EOL(); #elif ENABLED(Z_DUAL_ENDSTOPS) if (!forReplay) { CONFIG_ECHO_START; @@ -1649,7 +1649,7 @@ void MarlinSettings::reset() { SERIAL_ECHOPAIR(" C", PID_PARAM(Kc, e)); if (e == 0) SERIAL_ECHOPAIR(" L", lpq_len); #endif - SERIAL_EOL; + SERIAL_EOL(); } } else @@ -1664,7 +1664,7 @@ void MarlinSettings::reset() { SERIAL_ECHOPAIR(" C", PID_PARAM(Kc, 0)); SERIAL_ECHOPAIR(" L", lpq_len); #endif - SERIAL_EOL; + SERIAL_EOL(); } #endif // PIDTEMP @@ -1673,7 +1673,7 @@ void MarlinSettings::reset() { SERIAL_ECHOPAIR(" M304 P", thermalManager.bedKp); SERIAL_ECHOPAIR(" I", unscalePID_i(thermalManager.bedKi)); SERIAL_ECHOPAIR(" D", unscalePID_d(thermalManager.bedKd)); - SERIAL_EOL; + SERIAL_EOL(); #endif #endif // PIDTEMP || PIDTEMPBED @@ -1773,7 +1773,7 @@ void MarlinSettings::reset() { #if ENABLED(E3_IS_TMC2130) SERIAL_ECHOPAIR(" E3", stepperE3.getCurrent()); #endif - SERIAL_EOL; + SERIAL_EOL(); #endif /** diff --git a/Marlin/endstops.cpp b/Marlin/endstops.cpp index 9a4a9c84b5..1d98ec9d45 100644 --- a/Marlin/endstops.cpp +++ b/Marlin/endstops.cpp @@ -161,7 +161,7 @@ void Endstops::report_state() { #define ENDSTOP_HIT_TEST_Y() _ENDSTOP_HIT_TEST(Y,'Y') #define ENDSTOP_HIT_TEST_Z() _ENDSTOP_HIT_TEST(Z,'Z') - SERIAL_ECHO_START; + SERIAL_ECHO_START(); SERIAL_ECHOPGM(MSG_ENDSTOPS_HIT); ENDSTOP_HIT_TEST_X(); ENDSTOP_HIT_TEST_Y(); @@ -171,7 +171,7 @@ void Endstops::report_state() { #define P_AXIS Z_AXIS if (TEST(endstop_hit_bits, Z_MIN_PROBE)) _ENDSTOP_HIT_ECHO(P, 'P'); #endif - SERIAL_EOL; + SERIAL_EOL(); #if ENABLED(ULTRA_LCD) lcd_status_printf_P(0, PSTR(MSG_LCD_ENDSTOPS " %c %c %c %c"), chrX, chrY, chrZ, chrP); diff --git a/Marlin/gcode.cpp b/Marlin/gcode.cpp index d23db21f70..02aaf68a3a 100644 --- a/Marlin/gcode.cpp +++ b/Marlin/gcode.cpp @@ -203,7 +203,7 @@ void GCodeParser::parse(char *p) { } #if ENABLED(DEBUG_GCODE_PARSER) - if (debug) SERIAL_EOL; + if (debug) SERIAL_EOL(); #endif #if ENABLED(FASTER_GCODE_PARSER) @@ -229,10 +229,10 @@ void GCodeParser::parse(char *p) { } void GCodeParser::unknown_command_error() { - SERIAL_ECHO_START; + SERIAL_ECHO_START(); SERIAL_ECHOPAIR(MSG_UNKNOWN_COMMAND, command_ptr); SERIAL_CHAR('"'); - SERIAL_EOL; + SERIAL_EOL(); } #if ENABLED(DEBUG_GCODE_PARSER) diff --git a/Marlin/pinsDebug.h b/Marlin/pinsDebug.h index 18062b79ee..dafd51e357 100644 --- a/Marlin/pinsDebug.h +++ b/Marlin/pinsDebug.h @@ -452,7 +452,7 @@ inline void report_pin_state_extended(int8_t pin, bool ignore, bool extended = t } if (!multi_name_pin && extended) pwm_details(pin); // report PWM capabilities only on the first pass & only if doing an extended report } - SERIAL_EOL; + SERIAL_EOL(); } // end of IF } // end of for loop @@ -483,7 +483,7 @@ inline void report_pin_state_extended(int8_t pin, bool ignore, bool extended = t } //if (!pwm_status(pin)) SERIAL_CHAR(' '); // add padding if it's not a PWM pin if (extended) pwm_details(pin); // report PWM capabilities only if doing an extended report - SERIAL_EOL; + SERIAL_EOL(); } } diff --git a/Marlin/planner.cpp b/Marlin/planner.cpp index f23410e777..dee6eaad02 100644 --- a/Marlin/planner.cpp +++ b/Marlin/planner.cpp @@ -740,7 +740,7 @@ void Planner::_buffer_line(const float &a, const float &b, const float &c, const #endif SERIAL_ECHOPAIR(" (", dc); SERIAL_CHAR(')'); - SERIAL_EOL; + SERIAL_EOL(); //*/ // DRYRUN ignores all temperature constraints and assures that the extruder is instantly satisfied @@ -766,7 +766,7 @@ void Planner::_buffer_line(const float &a, const float &b, const float &c, const position_float[E_AXIS] = e; de_float = 0; #endif - SERIAL_ECHO_START; + SERIAL_ECHO_START(); SERIAL_ECHOLNPGM(MSG_ERR_COLD_EXTRUDE_STOP); } #if ENABLED(PREVENT_LENGTHY_EXTRUDE) @@ -777,7 +777,7 @@ void Planner::_buffer_line(const float &a, const float &b, const float &c, const position_float[E_AXIS] = e; de_float = 0; #endif - SERIAL_ECHO_START; + SERIAL_ECHO_START(); SERIAL_ECHOLNPGM(MSG_ERR_LONG_EXTRUDE_STOP); } #endif @@ -1420,7 +1420,7 @@ void Planner::_buffer_line(const float &a, const float &b, const float &c, const block->advance_rate = block->advance = 0; /** - SERIAL_ECHO_START; + SERIAL_ECHO_START(); SERIAL_ECHOPGM("advance :"); SERIAL_ECHO(block->advance/256.0); SERIAL_ECHOPGM("advance rate :"); diff --git a/Marlin/printcounter.cpp b/Marlin/printcounter.cpp index 09f31f783e..6edc0ac8cc 100644 --- a/Marlin/printcounter.cpp +++ b/Marlin/printcounter.cpp @@ -108,7 +108,7 @@ void PrintCounter::showStats() { SERIAL_ECHO(this->data.totalPrints - this->data.finishedPrints - ((this->isRunning() || this->isPaused()) ? 1 : 0)); - SERIAL_EOL; + SERIAL_EOL(); SERIAL_PROTOCOLPGM(MSG_STATS); elapsed = this->data.printTime; @@ -135,14 +135,14 @@ void PrintCounter::showStats() { SERIAL_CHAR(')'); #endif - SERIAL_EOL; + SERIAL_EOL(); SERIAL_PROTOCOLPGM(MSG_STATS); SERIAL_ECHOPGM("Filament used: "); SERIAL_ECHO(this->data.filamentUsed / 1000); SERIAL_ECHOPGM("m"); - SERIAL_EOL; + SERIAL_EOL(); } void PrintCounter::tick() { diff --git a/Marlin/serial.h b/Marlin/serial.h index b57e7b1b67..08a4c08c6d 100644 --- a/Marlin/serial.h +++ b/Marlin/serial.h @@ -41,18 +41,18 @@ extern const char echomagic[] PROGMEM; extern const char errormagic[] PROGMEM; #define SERIAL_CHAR(x) (MYSERIAL.write(x)) -#define SERIAL_EOL SERIAL_CHAR('\n') +#define SERIAL_EOL() SERIAL_CHAR('\n') #define SERIAL_PROTOCOLCHAR(x) SERIAL_CHAR(x) #define SERIAL_PROTOCOL(x) (MYSERIAL.print(x)) #define SERIAL_PROTOCOL_F(x,y) (MYSERIAL.print(x,y)) #define SERIAL_PROTOCOLPGM(x) (serialprintPGM(PSTR(x))) -#define SERIAL_PROTOCOLLN(x) do{ MYSERIAL.print(x); SERIAL_EOL; }while(0) +#define SERIAL_PROTOCOLLN(x) do{ MYSERIAL.print(x); SERIAL_EOL(); }while(0) #define SERIAL_PROTOCOLLNPGM(x) (serialprintPGM(PSTR(x "\n"))) #define SERIAL_PROTOCOLPAIR(name, value) (serial_echopair_P(PSTR(name),(value))) -#define SERIAL_PROTOCOLLNPAIR(name, value) do{ SERIAL_PROTOCOLPAIR(name, value); SERIAL_EOL; }while(0) +#define SERIAL_PROTOCOLLNPAIR(name, value) do{ SERIAL_PROTOCOLPAIR(name, value); SERIAL_EOL(); }while(0) -#define SERIAL_ECHO_START (serialprintPGM(echomagic)) +#define SERIAL_ECHO_START() (serialprintPGM(echomagic)) #define SERIAL_ECHO(x) SERIAL_PROTOCOL(x) #define SERIAL_ECHOPGM(x) SERIAL_PROTOCOLPGM(x) #define SERIAL_ECHOLN(x) SERIAL_PROTOCOLLN(x) @@ -61,7 +61,7 @@ extern const char errormagic[] PROGMEM; #define SERIAL_ECHOLNPAIR(name, value) SERIAL_PROTOCOLLNPAIR(name, value) #define SERIAL_ECHO_F(x,y) SERIAL_PROTOCOL_F(x,y) -#define SERIAL_ERROR_START (serialprintPGM(errormagic)) +#define SERIAL_ERROR_START() (serialprintPGM(errormagic)) #define SERIAL_ERROR(x) SERIAL_PROTOCOL(x) #define SERIAL_ERRORPGM(x) SERIAL_PROTOCOLPGM(x) #define SERIAL_ERRORLN(x) SERIAL_PROTOCOLLN(x) diff --git a/Marlin/stepper.cpp b/Marlin/stepper.cpp index d2d4d09d0d..4b9167b668 100644 --- a/Marlin/stepper.cpp +++ b/Marlin/stepper.cpp @@ -1305,7 +1305,7 @@ void Stepper::report_positions() { #endif SERIAL_PROTOCOL(zpos); - SERIAL_EOL; + SERIAL_EOL(); } #if ENABLED(BABYSTEPPING) diff --git a/Marlin/stepper.h b/Marlin/stepper.h index ec6772eeb5..429e8f1d7a 100644 --- a/Marlin/stepper.h +++ b/Marlin/stepper.h @@ -369,7 +369,7 @@ class Stepper { } #endif - // SERIAL_ECHO_START; + // SERIAL_ECHO_START(); // SERIAL_ECHOPGM("advance :"); // SERIAL_ECHO(current_block->advance/256.0); // SERIAL_ECHOPGM("advance rate :"); diff --git a/Marlin/stepper_dac.cpp b/Marlin/stepper_dac.cpp index 5a908dc8c5..0e7b8c8137 100644 --- a/Marlin/stepper_dac.cpp +++ b/Marlin/stepper_dac.cpp @@ -103,9 +103,9 @@ void dac_print_values() { if (!dac_present) return; - SERIAL_ECHO_START; + SERIAL_ECHO_START(); SERIAL_ECHOLNPGM("Stepper current values in % (Amps):"); - SERIAL_ECHO_START; + SERIAL_ECHO_START(); SERIAL_ECHOPAIR(" X:", dac_perc(X_AXIS)); SERIAL_ECHOPAIR(" (", dac_amps(X_AXIS)); SERIAL_ECHOPAIR(") Y:", dac_perc(Y_AXIS)); diff --git a/Marlin/temperature.cpp b/Marlin/temperature.cpp index 1244a55b1c..911e7b6942 100644 --- a/Marlin/temperature.cpp +++ b/Marlin/temperature.cpp @@ -389,7 +389,7 @@ uint8_t Temperature::soft_pwm_amount[HOTENDS], if (ELAPSED(ms, temp_ms + 2000UL)) { #if HAS_TEMP_HOTEND || HAS_TEMP_BED print_heaterstates(); - SERIAL_EOL; + SERIAL_EOL(); #endif temp_ms = ms; @@ -404,17 +404,17 @@ uint8_t Temperature::soft_pwm_amount[HOTENDS], #if HAS_PID_FOR_BOTH const char* estring = hotend < 0 ? "bed" : ""; - SERIAL_PROTOCOLPAIR("#define DEFAULT_", estring); SERIAL_PROTOCOLPAIR("Kp ", workKp); SERIAL_EOL; - SERIAL_PROTOCOLPAIR("#define DEFAULT_", estring); SERIAL_PROTOCOLPAIR("Ki ", workKi); SERIAL_EOL; - SERIAL_PROTOCOLPAIR("#define DEFAULT_", estring); SERIAL_PROTOCOLPAIR("Kd ", workKd); SERIAL_EOL; + SERIAL_PROTOCOLPAIR("#define DEFAULT_", estring); SERIAL_PROTOCOLPAIR("Kp ", workKp); SERIAL_EOL(); + SERIAL_PROTOCOLPAIR("#define DEFAULT_", estring); SERIAL_PROTOCOLPAIR("Ki ", workKi); SERIAL_EOL(); + SERIAL_PROTOCOLPAIR("#define DEFAULT_", estring); SERIAL_PROTOCOLPAIR("Kd ", workKd); SERIAL_EOL(); #elif ENABLED(PIDTEMP) - SERIAL_PROTOCOLPAIR("#define DEFAULT_Kp ", workKp); SERIAL_EOL; - SERIAL_PROTOCOLPAIR("#define DEFAULT_Ki ", workKi); SERIAL_EOL; - SERIAL_PROTOCOLPAIR("#define DEFAULT_Kd ", workKd); SERIAL_EOL; + SERIAL_PROTOCOLPAIR("#define DEFAULT_Kp ", workKp); SERIAL_EOL(); + SERIAL_PROTOCOLPAIR("#define DEFAULT_Ki ", workKi); SERIAL_EOL(); + SERIAL_PROTOCOLPAIR("#define DEFAULT_Kd ", workKd); SERIAL_EOL(); #else - SERIAL_PROTOCOLPAIR("#define DEFAULT_bedKp ", workKp); SERIAL_EOL; - SERIAL_PROTOCOLPAIR("#define DEFAULT_bedKi ", workKi); SERIAL_EOL; - SERIAL_PROTOCOLPAIR("#define DEFAULT_bedKd ", workKd); SERIAL_EOL; + SERIAL_PROTOCOLPAIR("#define DEFAULT_bedKp ", workKp); SERIAL_EOL(); + SERIAL_PROTOCOLPAIR("#define DEFAULT_bedKi ", workKi); SERIAL_EOL(); + SERIAL_PROTOCOLPAIR("#define DEFAULT_bedKd ", workKd); SERIAL_EOL(); #endif #define _SET_BED_PID() do { \ @@ -508,7 +508,7 @@ int Temperature::getHeaterPower(int heater) { void Temperature::_temp_error(int e, const char* serial_msg, const char* lcd_msg) { static bool killed = false; if (IsRunning()) { - SERIAL_ERROR_START; + SERIAL_ERROR_START(); serialprintPGM(serial_msg); SERIAL_ERRORPGM(MSG_STOPPED_HEATER); if (e >= 0) SERIAL_ERRORLN((int)e); else SERIAL_ERRORLNPGM(MSG_HEATER_BED); @@ -619,7 +619,7 @@ float Temperature::get_pid_output(int e) { #endif // PID_OPENLOOP #if ENABLED(PID_DEBUG) - SERIAL_ECHO_START; + SERIAL_ECHO_START(); SERIAL_ECHOPAIR(MSG_PID_DEBUG, HOTEND_INDEX); SERIAL_ECHOPAIR(MSG_PID_DEBUG_INPUT, current_temperature[HOTEND_INDEX]); SERIAL_ECHOPAIR(MSG_PID_DEBUG_OUTPUT, pid_output); @@ -629,7 +629,7 @@ float Temperature::get_pid_output(int e) { #if ENABLED(PID_EXTRUSION_SCALING) SERIAL_ECHOPAIR(MSG_PID_DEBUG_CTERM, cTerm[HOTEND_INDEX]); #endif - SERIAL_EOL; + SERIAL_EOL(); #endif // PID_DEBUG #else /* PID off */ @@ -670,7 +670,7 @@ float Temperature::get_pid_output(int e) { #endif // PID_OPENLOOP #if ENABLED(PID_BED_DEBUG) - SERIAL_ECHO_START; + SERIAL_ECHO_START(); SERIAL_ECHOPGM(" PID_BED_DEBUG "); SERIAL_ECHOPGM(": Input "); SERIAL_ECHO(current_temperature_bed); @@ -854,7 +854,7 @@ float Temperature::analog2temp(int raw, uint8_t e) { if (e >= HOTENDS) #endif { - SERIAL_ERROR_START; + SERIAL_ERROR_START(); SERIAL_ERROR((int)e); SERIAL_ERRORLNPGM(MSG_INVALID_EXTRUDER_NUM); kill(PSTR(MSG_KILLED)); @@ -1278,7 +1278,7 @@ void Temperature::init() { static float tr_target_temperature[HOTENDS + 1] = { 0.0 }; /** - SERIAL_ECHO_START; + SERIAL_ECHO_START(); SERIAL_ECHOPGM("Thermal Thermal Runaway Running. Heater ID: "); if (heater_id < 0) SERIAL_ECHOPGM("bed"); else SERIAL_ECHO(heater_id); SERIAL_ECHOPAIR(" ; State:", *state); @@ -1289,7 +1289,7 @@ void Temperature::init() { SERIAL_ECHOPAIR(" ; Idle Timeout:", heater_idle_timeout_exceeded[heater_id]); else SERIAL_ECHOPAIR(" ; Idle Timeout:", bed_idle_timeout_exceeded); - SERIAL_EOL; + SERIAL_EOL(); */ int heater_index = heater_id >= 0 ? heater_id : HOTENDS; @@ -1457,7 +1457,7 @@ void Temperature::disable_all_heaters() { WRITE(MAX6675_SS, 1); // disable TT_MAX6675 if (max6675_temp & MAX6675_ERROR_MASK) { - SERIAL_ERROR_START; + SERIAL_ERROR_START(); SERIAL_ERRORPGM("Temp measurement error! "); #if MAX6675_ERROR_MASK == 7 SERIAL_ERRORPGM("MAX31855 "); diff --git a/Marlin/twibus.cpp b/Marlin/twibus.cpp index d4822f1d26..4e29ef8830 100644 --- a/Marlin/twibus.cpp +++ b/Marlin/twibus.cpp @@ -43,7 +43,7 @@ void TWIBus::reset() { void TWIBus::address(const uint8_t adr) { if (!WITHIN(adr, 8, 127)) { - SERIAL_ECHO_START; + SERIAL_ECHO_START(); SERIAL_ECHOLNPGM("Bad I2C address (8-127)"); } @@ -90,7 +90,7 @@ void TWIBus::send() { // static void TWIBus::echoprefix(uint8_t bytes, const char prefix[], uint8_t adr) { - SERIAL_ECHO_START; + SERIAL_ECHO_START(); serialprintPGM(prefix); SERIAL_ECHOPAIR(": from:", adr); SERIAL_ECHOPAIR(" bytes:", bytes); @@ -101,13 +101,13 @@ void TWIBus::echoprefix(uint8_t bytes, const char prefix[], uint8_t adr) { void TWIBus::echodata(uint8_t bytes, const char prefix[], uint8_t adr) { echoprefix(bytes, prefix, adr); while (bytes-- && Wire.available()) SERIAL_CHAR(Wire.read()); - SERIAL_EOL; + SERIAL_EOL(); } void TWIBus::echobuffer(const char prefix[], uint8_t adr) { echoprefix(this->buffer_s, prefix, adr); for (uint8_t i = 0; i < this->buffer_s; i++) SERIAL_CHAR(this->buffer[i]); - SERIAL_EOL; + SERIAL_EOL(); } bool TWIBus::request(const uint8_t bytes) { diff --git a/Marlin/ubl.cpp b/Marlin/ubl.cpp index e243c6d88a..e116296591 100644 --- a/Marlin/ubl.cpp +++ b/Marlin/ubl.cpp @@ -116,11 +116,11 @@ serial_echo_xy(0, GRID_MAX_POINTS_Y - 1); SERIAL_ECHO_SP(spaces + 3); serial_echo_xy(GRID_MAX_POINTS_X - 1, GRID_MAX_POINTS_Y - 1); - SERIAL_EOL; + SERIAL_EOL(); serial_echo_xy(UBL_MESH_MIN_X, UBL_MESH_MAX_Y); SERIAL_ECHO_SP(spaces); serial_echo_xy(UBL_MESH_MAX_X, UBL_MESH_MAX_Y); - SERIAL_EOL; + SERIAL_EOL(); } const float current_xi = get_cell_index_x(current_position[X_AXIS] + (MESH_X_DIST) / 2.0), @@ -154,10 +154,10 @@ SERIAL_CHAR(' '); } } - SERIAL_EOL; + SERIAL_EOL(); if (j && map0) { // we want the (0,0) up tight against the block of numbers SERIAL_CHAR(' '); - SERIAL_EOL; + SERIAL_EOL(); } } @@ -165,11 +165,11 @@ serial_echo_xy(UBL_MESH_MIN_X, UBL_MESH_MIN_Y); SERIAL_ECHO_SP(spaces + 4); serial_echo_xy(UBL_MESH_MAX_X, UBL_MESH_MIN_Y); - SERIAL_EOL; + SERIAL_EOL(); serial_echo_xy(0, 0); SERIAL_ECHO_SP(spaces + 5); serial_echo_xy(GRID_MAX_POINTS_X - 1, 0); - SERIAL_EOL; + SERIAL_EOL(); } } diff --git a/Marlin/ubl.h b/Marlin/ubl.h index d060f8f6b0..21f83c1131 100644 --- a/Marlin/ubl.h +++ b/Marlin/ubl.h @@ -256,7 +256,7 @@ SERIAL_ECHOPAIR(",x1_i=", x1_i); SERIAL_ECHOPAIR(",yi=", yi); SERIAL_CHAR(')'); - SERIAL_EOL; + SERIAL_EOL(); return NAN; } @@ -276,7 +276,7 @@ SERIAL_ECHOPAIR(", xi=", xi); SERIAL_ECHOPAIR(", y1_i=", y1_i); SERIAL_CHAR(')'); - SERIAL_EOL; + SERIAL_EOL(); return NAN; } @@ -301,7 +301,7 @@ SERIAL_ECHOPAIR("? in get_z_correction(lx0=", lx0); SERIAL_ECHOPAIR(", ly0=", ly0); SERIAL_CHAR(')'); - SERIAL_EOL; + SERIAL_EOL(); #if ENABLED(ULTRA_LCD) strcpy(lcd_status_message, "get_z_correction() indexes out of range."); @@ -336,7 +336,7 @@ if (DEBUGGING(MESH_ADJUST)) { SERIAL_ECHOPGM(" >>>---> "); SERIAL_ECHO_F(z0, 6); - SERIAL_EOL; + SERIAL_EOL(); } #endif @@ -352,7 +352,7 @@ SERIAL_CHAR(','); SERIAL_ECHO(ly0); SERIAL_CHAR(')'); - SERIAL_EOL; + SERIAL_EOL(); } #endif } diff --git a/Marlin/ubl_G29.cpp b/Marlin/ubl_G29.cpp index 063475e9ed..64a3820f19 100644 --- a/Marlin/ubl_G29.cpp +++ b/Marlin/ubl_G29.cpp @@ -406,7 +406,7 @@ } if (isnan(z1) || isnan(z2) || isnan(z3)) { // probe_pt will return NAN if unreachable - SERIAL_ERROR_START; + SERIAL_ERROR_START(); SERIAL_ERRORLNPGM("Attempt to probe off the bed."); goto LEAVE; } @@ -643,7 +643,7 @@ SERIAL_ECHO_F(z_values[x][y], 6); SERIAL_ECHOPAIR(" ; X ", LOGICAL_X_POSITION(mesh_index_to_xpos(x))); SERIAL_ECHOPAIR(", Y ", LOGICAL_Y_POSITION(mesh_index_to_ypos(y))); - SERIAL_EOL; + SERIAL_EOL(); } return; } @@ -766,12 +766,12 @@ SERIAL_ECHOLNPAIR("# of samples: ", n); SERIAL_ECHOPGM("Mean Mesh Height: "); SERIAL_ECHO_F(mean, 6); - SERIAL_EOL; + SERIAL_EOL(); const float sigma = sqrt(sum_of_diff_squared / (n + 1)); SERIAL_ECHOPGM("Standard Deviation: "); SERIAL_ECHO_F(sigma, 6); - SERIAL_EOL; + SERIAL_EOL(); if (g29_c_flag) for (uint8_t x = 0; x < GRID_MAX_POINTS_X; x++) @@ -892,17 +892,17 @@ if (DEBUGGING(LEVELING)) { SERIAL_ECHOPGM("d from 1st point: "); SERIAL_ECHO_F(d, 6); - SERIAL_EOL; + SERIAL_EOL(); t = normal.x * (UBL_PROBE_PT_2_X) + normal.y * (UBL_PROBE_PT_2_Y); d = t + normal.z * z2; SERIAL_ECHOPGM("d from 2nd point: "); SERIAL_ECHO_F(d, 6); - SERIAL_EOL; + SERIAL_EOL(); t = normal.x * (UBL_PROBE_PT_3_X) + normal.y * (UBL_PROBE_PT_3_Y); d = t + normal.z * z3; SERIAL_ECHOPGM("d from 3rd point: "); SERIAL_ECHO_F(d, 6); - SERIAL_EOL; + SERIAL_EOL(); } #endif @@ -1080,7 +1080,7 @@ if (g29_verbose_level > 2) { SERIAL_PROTOCOLPGM("Mesh Point Measured at: "); SERIAL_PROTOCOL_F(z_values[location.x_index][location.y_index], 6); - SERIAL_EOL; + SERIAL_EOL(); } } while (location.x_index >= 0 && location.y_index >= 0); @@ -1244,7 +1244,7 @@ SERIAL_PROTOCOLPAIR("Mesh ", state.storage_slot); SERIAL_PROTOCOLPGM(" Loaded."); } - SERIAL_EOL; + SERIAL_EOL(); safe_delay(50); SERIAL_PROTOCOLLNPAIR("UBL object count: ", (int)ubl_cnt); @@ -1252,13 +1252,13 @@ #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) SERIAL_PROTOCOL("planner.z_fade_height : "); SERIAL_PROTOCOL_F(planner.z_fade_height, 4); - SERIAL_EOL; + SERIAL_EOL(); #endif #if HAS_BED_PROBE SERIAL_PROTOCOLPGM("zprobe_zoffset: "); SERIAL_PROTOCOL_F(zprobe_zoffset, 7); - SERIAL_EOL; + SERIAL_EOL(); #endif SERIAL_ECHOLNPAIR("UBL_MESH_MIN_X " STRINGIFY(UBL_MESH_MIN_X) "=", UBL_MESH_MIN_X); @@ -1280,7 +1280,7 @@ SERIAL_PROTOCOLPGM(" "); safe_delay(25); } - SERIAL_EOL; + SERIAL_EOL(); SERIAL_PROTOCOLPGM("Y-Axis Mesh Points at: "); for (uint8_t i = 0; i < GRID_MAX_POINTS_Y; i++) { @@ -1288,19 +1288,19 @@ SERIAL_PROTOCOLPGM(" "); safe_delay(25); } - SERIAL_EOL; + SERIAL_EOL(); #if HAS_KILL SERIAL_PROTOCOLPAIR("Kill pin on :", KILL_PIN); SERIAL_PROTOCOLLNPAIR(" state:", READ(KILL_PIN)); #endif - SERIAL_EOL; + SERIAL_EOL(); safe_delay(50); SERIAL_PROTOCOLLNPAIR("ubl_state_at_invocation :", ubl_state_at_invocation); - SERIAL_EOL; + SERIAL_EOL(); SERIAL_PROTOCOLLNPAIR("ubl_state_recursion_chk :", ubl_state_recursion_chk); - SERIAL_EOL; + SERIAL_EOL(); safe_delay(50); SERIAL_PROTOCOLPAIR("Meshes go from ", hex_address((void*)settings.get_start_of_meshes())); @@ -1308,9 +1308,9 @@ safe_delay(50); SERIAL_PROTOCOLLNPAIR("sizeof(ubl) : ", (int)sizeof(ubl)); - SERIAL_EOL; + SERIAL_EOL(); SERIAL_PROTOCOLLNPAIR("z_value[][] size: ", (int)sizeof(z_values)); - SERIAL_EOL; + SERIAL_EOL(); safe_delay(25); SERIAL_PROTOCOLLNPAIR("EEPROM free for UBL: ", hex_address((void*)(settings.get_end_of_meshes() - settings.get_start_of_meshes()))); @@ -1334,7 +1334,7 @@ unsigned char cccc; uint16_t kkkk; - SERIAL_ECHO_START; + SERIAL_ECHO_START(); SERIAL_ECHOLNPGM("EEPROM Dump:"); for (uint16_t i = 0; i < E2END + 1; i += 16) { if (!(i & 0x3)) idle(); @@ -1346,9 +1346,9 @@ print_hex_byte(cccc); SERIAL_ECHO(' '); } - SERIAL_EOL; + SERIAL_EOL(); } - SERIAL_EOL; + SERIAL_EOL(); } /** @@ -1667,7 +1667,7 @@ if (DEBUGGING(LEVELING)) { SERIAL_ECHOPGM(" final >>>---> "); SERIAL_PROTOCOL_F(measured_z, 7); - SERIAL_EOL; + SERIAL_EOL(); } #endif @@ -1689,7 +1689,7 @@ SERIAL_PROTOCOL_F(lsf_results.B, 7); SERIAL_ECHOPGM(" D="); SERIAL_PROTOCOL_F(lsf_results.D, 7); - SERIAL_EOL; + SERIAL_EOL(); } vector_3 normal = vector_3(lsf_results.A, lsf_results.B, 1.0000).get_normal(); @@ -1753,7 +1753,7 @@ SERIAL_PROTOCOL_F(lsf_results.B, 7); SERIAL_ECHOPGM(" D="); SERIAL_PROTOCOL_F(lsf_results.D, 7); - SERIAL_EOL; + SERIAL_EOL(); safe_delay(55); SERIAL_ECHOPGM("bed plane normal = ["); @@ -1763,7 +1763,7 @@ SERIAL_PROTOCOLCHAR(','); SERIAL_PROTOCOL_F(normal.z, 7); SERIAL_ECHOPGM("]\n"); - SERIAL_EOL; + SERIAL_EOL(); } #endif diff --git a/Marlin/ubl_motion.cpp b/Marlin/ubl_motion.cpp index 396251fb79..d0d27b60ed 100644 --- a/Marlin/ubl_motion.cpp +++ b/Marlin/ubl_motion.cpp @@ -97,7 +97,7 @@ debug_echo_axis(E_AXIS); SERIAL_ECHOPGM(" ) "); SERIAL_ECHO(title); - SERIAL_EOL; + SERIAL_EOL(); } @@ -131,7 +131,7 @@ SERIAL_ECHOPAIR(", ze=", end[Z_AXIS]); SERIAL_ECHOPAIR(", ee=", end[E_AXIS]); SERIAL_CHAR(')'); - SERIAL_EOL; + SERIAL_EOL(); debug_current_and_destination(PSTR("Start of ubl.line_to_destination()")); } diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index 885a6cc439..503ae95b3f 100755 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -4043,12 +4043,12 @@ void lcd_update() { else if (encoderStepRate >= ENCODER_10X_STEPS_PER_SEC) encoderMultiplier = 10; #if ENABLED(ENCODER_RATE_MULTIPLIER_DEBUG) - SERIAL_ECHO_START; + SERIAL_ECHO_START(); SERIAL_ECHOPAIR("Enc Step Rate: ", encoderStepRate); SERIAL_ECHOPAIR(" Multiplier: ", encoderMultiplier); SERIAL_ECHOPAIR(" ENCODER_10X_STEPS_PER_SEC: ", ENCODER_10X_STEPS_PER_SEC); SERIAL_ECHOPAIR(" ENCODER_100X_STEPS_PER_SEC: ", ENCODER_100X_STEPS_PER_SEC); - SERIAL_EOL; + SERIAL_EOL(); #endif // ENCODER_RATE_MULTIPLIER_DEBUG } diff --git a/Marlin/vector_3.cpp b/Marlin/vector_3.cpp index 3471fedcac..7d8efb7e96 100644 --- a/Marlin/vector_3.cpp +++ b/Marlin/vector_3.cpp @@ -89,7 +89,7 @@ void vector_3::debug(const char * const title) { SERIAL_PROTOCOL_F(y, 6); SERIAL_PROTOCOLPGM(" z: "); SERIAL_PROTOCOL_F(z, 6); - SERIAL_EOL; + SERIAL_EOL(); } void apply_rotation_xyz(matrix_3x3 matrix, float &x, float &y, float &z) { @@ -152,7 +152,7 @@ void matrix_3x3::debug(const char * const title) { SERIAL_PROTOCOLCHAR(' '); count++; } - SERIAL_EOL; + SERIAL_EOL(); } } diff --git a/Marlin/watchdog.cpp b/Marlin/watchdog.cpp index fe20b89e90..5e42b5faca 100644 --- a/Marlin/watchdog.cpp +++ b/Marlin/watchdog.cpp @@ -46,7 +46,7 @@ void watchdog_init() { // Watchdog timer interrupt, called if main program blocks >4sec and manual reset is enabled. #if ENABLED(WATCHDOG_RESET_MANUAL) ISR(WDT_vect) { - SERIAL_ERROR_START; + SERIAL_ERROR_START(); SERIAL_ERRORLNPGM("Something is wrong, please turn off the printer."); kill(PSTR("ERR:Please Reset")); //kill blocks //16 characters so it fits on a 16x2 display while (1); //wait for user or serial reset From b378deaf8971952217f32dd74ca201645ba5f156 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 8 Jun 2017 18:05:14 -0500 Subject: [PATCH 044/180] Unify AVR90USB: fastio changes --- Marlin/boards.h | 2 +- Marlin/fastio.h | 31 +- Marlin/fastio_AT90USB-Marlin.h | 681 ------------------ ...stio_AT90USB-Teensy.h => fastio_AT90USB.h} | 20 +- Marlin/pins.h | 29 +- Marlin/ultralcd.cpp | 0 platformio.ini | 2 +- 7 files changed, 48 insertions(+), 717 deletions(-) delete mode 100644 Marlin/fastio_AT90USB-Marlin.h rename Marlin/{fastio_AT90USB-Teensy.h => fastio_AT90USB.h} (97%) mode change 100755 => 100644 Marlin/ultralcd.cpp diff --git a/Marlin/boards.h b/Marlin/boards.h index 24ab48c86d..1ce5a21401 100644 --- a/Marlin/boards.h +++ b/Marlin/boards.h @@ -71,7 +71,7 @@ #define BOARD_PRINTRBOARD_REVF 811 // Printrboard Revision F (AT90USB1286) #define BOARD_BRAINWAVE 82 // Brainwave (AT90USB646) #define BOARD_SAV_MKI 83 // SAV Mk-I (AT90USB1286) -#define BOARD_TEENSY2 84 // Teensy++2.0 (AT90USB1286) - CLI compile: DEFINES=AT90USBxx_TEENSYPP_ASSIGNMENTS HARDWARE_MOTHERBOARD=84 make +#define BOARD_TEENSY2 84 // Teensy++2.0 (AT90USB1286) - CLI compile: HARDWARE_MOTHERBOARD=84 make #define BOARD_BRAINWAVE_PRO 85 // Brainwave Pro (AT90USB1286) #define BOARD_GEN3_PLUS 9 // Gen3+ #define BOARD_GEN3_MONOLITHIC 22 // Gen3 Monolithic Electronics diff --git a/Marlin/fastio.h b/Marlin/fastio.h index 174e5f9cf6..035c9c3a2f 100644 --- a/Marlin/fastio.h +++ b/Marlin/fastio.h @@ -32,27 +32,25 @@ #include #include "macros.h" -/** - * Enable this option to use Teensy++ 2.0 assignments for AT90USB processors. - */ -//#define AT90USBxx_TEENSYPP_ASSIGNMENTS +#define AVR_AT90USB1286_FAMILY (defined(__AVR_AT90USB1287__) || defined(__AVR_AT90USB1286__) || defined(__AVR_AT90USB1286P__) || defined(__AVR_AT90USB646__) || defined(__AVR_AT90USB646P__) || defined(__AVR_AT90USB647__)) +#define AVR_ATmega1284_FAMILY (defined(__AVR_ATmega644__) || defined(__AVR_ATmega644P__) || defined(__AVR_ATmega644PA__) || defined(__AVR_ATmega1284P__)) +#define AVR_ATmega2560_FAMILY (defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)) +#define AVR_ATmega2561_FAMILY (defined(__AVR_ATmega1281__) || defined(__AVR_ATmega2561__)) +#define AVR_ATmega328_FAMILY (defined(__AVR_ATmega168__) || defined(__AVR_ATmega328__) || defined(__AVR_ATmega328p__)) + /** * Include Ports and Functions */ -#if defined(__AVR_ATmega168__) || defined(__AVR_ATmega328__) || defined(__AVR_ATmega328P__) +#if AVR_ATmega328_FAMILY #include "fastio_168.h" -#elif defined(__AVR_ATmega644__) || defined(__AVR_ATmega644P__) || defined(__AVR_ATmega644PA__) || defined(__AVR_ATmega1284P__) +#elif AVR_ATmega1284_FAMILY #include "fastio_644.h" -#elif defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__) +#elif AVR_ATmega2560_FAMILY #include "fastio_1280.h" -#elif defined(__AVR_AT90USB1287__) || defined(__AVR_AT90USB1286__) || defined(__AVR_AT90USB646__) || defined(__AVR_AT90USB647__) - #ifdef AT90USBxx_TEENSYPP_ASSIGNMENTS - #include "fastio_AT90USB-Teensy.h" - #else - #include "fastio_AT90USB-Marlin.h" - #endif -#elif defined(__AVR_ATmega1281__) || defined(__AVR_ATmega2561__) +#elif AVR_AT90USB1286_FAMILY + #include "fastio_AT90USB.h" +#elif AVR_ATmega2561_FAMILY #include "fastio_1281.h" #else #error "Pins for this chip not defined in Arduino.h! If you have a working pins definition, please contribute!" @@ -243,11 +241,6 @@ typedef enum { /** * PWM availability macros */ -#define AVR_AT90USB1286_FAMILY (defined(__AVR_AT90USB1287__) || defined(__AVR_AT90USB1286__) || defined(__AVR_AT90USB1286P__) || defined(__AVR_AT90USB646__) || defined(__AVR_AT90USB646P__) || defined(__AVR_AT90USB647__)) -#define AVR_ATmega1284_FAMILY (defined(__AVR_ATmega644__) || defined(__AVR_ATmega644P__) || defined(__AVR_ATmega644PA__) || defined(__AVR_ATmega1284P__)) -#define AVR_ATmega2560_FAMILY (defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__)) -#define AVR_ATmega2561_FAMILY (defined(__AVR_ATmega1281__) || defined(__AVR_ATmega2561__)) -#define AVR_ATmega328_FAMILY (defined(__AVR_ATmega168__) || defined(__AVR_ATmega328__) || defined(__AVR_ATmega328p__)) //find out which harware PWMs are already in use #if PIN_EXISTS(CONTROLLER_FAN) diff --git a/Marlin/fastio_AT90USB-Marlin.h b/Marlin/fastio_AT90USB-Marlin.h deleted file mode 100644 index 955da40c44..0000000000 --- a/Marlin/fastio_AT90USB-Marlin.h +++ /dev/null @@ -1,681 +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 . - * - */ - -/** - * Pin mapping (Marlin) for AT90USB646, 647, 1286, and 1287 - * - * AT90USB 51 50 49 48 47 46 45 44 10 11 12 13 14 15 16 17 35 36 37 38 39 40 41 42 25 26 27 28 29 30 31 32 33 34 43 09 18 19 01 02 61 60 59 58 57 56 55 54 - * Teensy 28 29 30 31 32 33 34 35 20 21 22 23 24 25 26 27 10 11 12 13 14 15 16 17 00 01 02 03 04 05 06 07 08 09(46*47)36 37 18 19 38 39 40 41 42 43 44 45 - * Port A0 A1 A2 A3 A4 A5 A6 A7 B0 B1 B2 B3 B4 B5 B6 B7 C0 C1 C2 C3 C4 C5 C6 C7 D0 D1 D2 D3 D4 D5 D6 D7 E0 E1 E2 E3 E4 E5 E6 E7 F0 F1 F2 F3 F4 F5 F6 F7 - * > Marlin 00 01 02 03 04 05 06 07 08 09 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 - * The pins 46 and 47 are not supported by Teensyduino, but are supported below. - */ - -#ifndef _FASTIO_AT90USB -#define _FASTIO_AT90USB - -#include "fastio.h" - -// change for your board -#define DEBUG_LED DIO31 /* led D5 red */ - -// SPI -#define SCK DIO9 // 21 -#define MISO DIO11 // 23 -#define MOSI DIO10 // 22 -#define SS DIO8 // 20 - -// Digital I/O - -#define DIO0_PIN PINA0 -#define DIO0_RPORT PINA -#define DIO0_WPORT PORTA -#define DIO0_PWM NULL -#define DIO0_DDR DDRA - -#define DIO1_PIN PINA1 -#define DIO1_RPORT PINA -#define DIO1_WPORT PORTA -#define DIO1_PWM NULL -#define DIO1_DDR DDRA - -#define DIO2_PIN PINA2 -#define DIO2_RPORT PINA -#define DIO2_WPORT PORTA -#define DIO2_PWM NULL -#define DIO2_DDR DDRA - -#define DIO3_PIN PINA3 -#define DIO3_RPORT PINA -#define DIO3_WPORT PORTA -#define DIO3_PWM NULL -#define DIO3_DDR DDRA - -#define DIO4_PIN PINA4 -#define DIO4_RPORT PINA -#define DIO4_WPORT PORTA -#define DIO4_PWM NULL -#define DIO4_DDR DDRA - -#define DIO5_PIN PINA5 -#define DIO5_RPORT PINA -#define DIO5_WPORT PORTA -#define DIO5_PWM NULL -#define DIO5_DDR DDRA - -#define DIO6_PIN PINA6 -#define DIO6_RPORT PINA -#define DIO6_WPORT PORTA -#define DIO6_PWM NULL -#define DIO6_DDR DDRA - -#define DIO7_PIN PINA7 -#define DIO7_RPORT PINA -#define DIO7_WPORT PORTA -#define DIO7_PWM NULL -#define DIO7_DDR DDRA - -#define DIO8_PIN PINB0 -#define DIO8_RPORT PINB -#define DIO8_WPORT PORTB -#define DIO8_PWM NULL -#define DIO8_DDR DDRB - -#define DIO9_PIN PINB1 -#define DIO9_RPORT PINB -#define DIO9_WPORT PORTB -#define DIO9_PWM NULL -#define DIO9_DDR DDRB - -#define DIO10_PIN PINB2 -#define DIO10_RPORT PINB -#define DIO10_WPORT PORTB -#define DIO10_PWM NULL -#define DIO10_DDR DDRB - -#define DIO11_PIN PINB3 -#define DIO11_RPORT PINB -#define DIO11_WPORT PORTB -#define DIO11_PWM NULL -#define DIO11_DDR DDRB - -#define DIO12_PIN PINB4 -#define DIO12_RPORT PINB -#define DIO12_WPORT PORTB -#define DIO12_PWM NULL -#define DIO12_DDR DDRB - -#define DIO13_PIN PINB5 -#define DIO13_RPORT PINB -#define DIO13_WPORT PORTB -#define DIO13_PWM NULL -#define DIO13_DDR DDRB - -#define DIO14_PIN PINB6 -#define DIO14_RPORT PINB -#define DIO14_WPORT PORTB -#define DIO14_PWM NULL -#define DIO14_DDR DDRB - -#define DIO15_PIN PINB7 -#define DIO15_RPORT PINB -#define DIO15_WPORT PORTB -#define DIO15_PWM NULL -#define DIO15_DDR DDRB - -#define DIO16_PIN PINC0 -#define DIO16_RPORT PINC -#define DIO16_WPORT PORTC -#define DIO16_PWM NULL -#define DIO16_DDR DDRC - -#define DIO17_PIN PINC1 -#define DIO17_RPORT PINC -#define DIO17_WPORT PORTC -#define DIO17_PWM NULL -#define DIO17_DDR DDRC - -#define DIO18_PIN PINC2 -#define DIO18_RPORT PINC -#define DIO18_WPORT PORTC -#define DIO18_PWM NULL -#define DIO18_DDR DDRC - -#define DIO19_PIN PINC3 -#define DIO19_RPORT PINC -#define DIO19_WPORT PORTC -#define DIO19_PWM NULL -#define DIO19_DDR DDRC - -#define DIO20_PIN PINC4 -#define DIO20_RPORT PINC -#define DIO20_WPORT PORTC -#define DIO20_PWM NULL -#define DIO20_DDR DDRC - -#define DIO21_PIN PINC5 -#define DIO21_RPORT PINC -#define DIO21_WPORT PORTC -#define DIO21_PWM NULL -#define DIO21_DDR DDRC - -#define DIO22_PIN PINC6 -#define DIO22_RPORT PINC -#define DIO22_WPORT PORTC -#define DIO22_PWM NULL -#define DIO22_DDR DDRC - -#define DIO23_PIN PINC7 -#define DIO23_RPORT PINC -#define DIO23_WPORT PORTC -#define DIO23_PWM NULL -#define DIO23_DDR DDRC - -#define DIO24_PIN PIND0 -#define DIO24_RPORT PIND -#define DIO24_WPORT PORTD -#define DIO24_PWM NULL -#define DIO24_DDR DDRD - -#define DIO25_PIN PIND1 -#define DIO25_RPORT PIND -#define DIO25_WPORT PORTD -#define DIO25_PWM NULL -#define DIO25_DDR DDRD - -#define DIO26_PIN PIND2 -#define DIO26_RPORT PIND -#define DIO26_WPORT PORTD -#define DIO26_PWM NULL -#define DIO26_DDR DDRD - -#define DIO27_PIN PIND3 -#define DIO27_RPORT PIND -#define DIO27_WPORT PORTD -#define DIO27_PWM NULL -#define DIO27_DDR DDRD - -#define DIO28_PIN PIND4 -#define DIO28_RPORT PIND -#define DIO28_WPORT PORTD -#define DIO28_PWM NULL -#define DIO28_DDR DDRD - -#define DIO29_PIN PIND5 -#define DIO29_RPORT PIND -#define DIO29_WPORT PORTD -#define DIO29_PWM NULL -#define DIO29_DDR DDRD - -#define DIO30_PIN PIND6 -#define DIO30_RPORT PIND -#define DIO30_WPORT PORTD -#define DIO30_PWM NULL -#define DIO30_DDR DDRD - -#define DIO31_PIN PIND7 -#define DIO31_RPORT PIND -#define DIO31_WPORT PORTD -#define DIO31_PWM NULL -#define DIO31_DDR DDRD - -#define DIO32_PIN PINE0 -#define DIO32_RPORT PINE -#define DIO32_WPORT PORTE -#define DIO32_PWM NULL -#define DIO32_DDR DDRE - -#define DIO33_PIN PINE1 -#define DIO33_RPORT PINE -#define DIO33_WPORT PORTE -#define DIO33_PWM NULL -#define DIO33_DDR DDRE - -#define DIO34_PIN PINE2 -#define DIO34_RPORT PINE -#define DIO34_WPORT PORTE -#define DIO34_PWM NULL -#define DIO34_DDR DDRE - -#define DIO35_PIN PINE3 -#define DIO35_RPORT PINE -#define DIO35_WPORT PORTE -#define DIO35_PWM NULL -#define DIO35_DDR DDRE - -#define DIO36_PIN PINE4 -#define DIO36_RPORT PINE -#define DIO36_WPORT PORTE -#define DIO36_PWM NULL -#define DIO36_DDR DDRE - -#define DIO37_PIN PINE5 -#define DIO37_RPORT PINE -#define DIO37_WPORT PORTE -#define DIO37_PWM NULL -#define DIO37_DDR DDRE - -#define DIO38_PIN PINE6 -#define DIO38_RPORT PINE -#define DIO38_WPORT PORTE -#define DIO38_PWM NULL -#define DIO38_DDR DDRE - -#define DIO39_PIN PINE7 -#define DIO39_RPORT PINE -#define DIO39_WPORT PORTE -#define DIO39_PWM NULL -#define DIO39_DDR DDRE - -#define AIO0_PIN PINF0 -#define AIO0_RPORT PINF -#define AIO0_WPORT PORTF -#define AIO0_PWM NULL -#define AIO0_DDR DDRF - -#define AIO1_PIN PINF1 -#define AIO1_RPORT PINF -#define AIO1_WPORT PORTF -#define AIO1_PWM NULL -#define AIO1_DDR DDRF - -#define AIO2_PIN PINF2 -#define AIO2_RPORT PINF -#define AIO2_WPORT PORTF -#define AIO2_PWM NULL -#define AIO2_DDR DDRF - -#define AIO3_PIN PINF3 -#define AIO3_RPORT PINF -#define AIO3_WPORT PORTF -#define AIO3_PWM NULL -#define AIO3_DDR DDRF - -#define AIO4_PIN PINF4 -#define AIO4_RPORT PINF -#define AIO4_WPORT PORTF -#define AIO4_PWM NULL -#define AIO4_DDR DDRF - -#define AIO5_PIN PINF5 -#define AIO5_RPORT PINF -#define AIO5_WPORT PORTF -#define AIO5_PWM NULL -#define AIO5_DDR DDRF - -#define AIO6_PIN PINF6 -#define AIO6_RPORT PINF -#define AIO6_WPORT PORTF -#define AIO6_PWM NULL -#define AIO6_DDR DDRF - -#define AIO7_PIN PINF7 -#define AIO7_RPORT PINF -#define AIO7_WPORT PORTF -#define AIO7_PWM NULL -#define AIO7_DDR DDRF - -#define DIO40_PIN PINF0 -#define DIO40_RPORT PINF -#define DIO40_WPORT PORTF -#define DIO40_PWM NULL -#define DIO40_DDR DDRF - -#define DIO41_PIN PINF1 -#define DIO41_RPORT PINF -#define DIO41_WPORT PORTF -#define DIO41_PWM NULL -#define DIO41_DDR DDRF - -#define DIO42_PIN PINF2 -#define DIO42_RPORT PINF -#define DIO42_WPORT PORTF -#define DIO42_PWM NULL -#define DIO42_DDR DDRF - -#define DIO43_PIN PINF3 -#define DIO43_RPORT PINF -#define DIO43_WPORT PORTF -#define DIO43_PWM NULL -#define DIO43_DDR DDRF - -#define DIO44_PIN PINF4 -#define DIO44_RPORT PINF -#define DIO44_WPORT PORTF -#define DIO44_PWM NULL -#define DIO44_DDR DDRF - -#define DIO45_PIN PINF5 -#define DIO45_RPORT PINF -#define DIO45_WPORT PORTF -#define DIO45_PWM NULL -#define DIO45_DDR DDRF - -#define DIO46_PIN PINF6 -#define DIO46_RPORT PINF -#define DIO46_WPORT PORTF -#define DIO46_PWM NULL -#define DIO46_DDR DDRF - -#define DIO47_PIN PINF7 -#define DIO47_RPORT PINF -#define DIO47_WPORT PORTF -#define DIO47_PWM NULL -#define DIO47_DDR DDRF - -// Analog Outputs - -#undef PA0 -#define PA0_PIN PINA0 -#define PA0_RPORT PINA -#define PA0_WPORT PORTA -#define PA0_PWM NULL -#define PA0_DDR DDRA -#undef PA1 -#define PA1_PIN PINA1 -#define PA1_RPORT PINA -#define PA1_WPORT PORTA -#define PA1_PWM NULL -#define PA1_DDR DDRA -#undef PA2 -#define PA2_PIN PINA2 -#define PA2_RPORT PINA -#define PA2_WPORT PORTA -#define PA2_PWM NULL -#define PA2_DDR DDRA -#undef PA3 -#define PA3_PIN PINA3 -#define PA3_RPORT PINA -#define PA3_WPORT PORTA -#define PA3_PWM NULL -#define PA3_DDR DDRA -#undef PA4 -#define PA4_PIN PINA4 -#define PA4_RPORT PINA -#define PA4_WPORT PORTA -#define PA4_PWM NULL -#define PA4_DDR DDRA -#undef PA5 -#define PA5_PIN PINA5 -#define PA5_RPORT PINA -#define PA5_WPORT PORTA -#define PA5_PWM NULL -#define PA5_DDR DDRA -#undef PA6 -#define PA6_PIN PINA6 -#define PA6_RPORT PINA -#define PA6_WPORT PORTA -#define PA6_PWM NULL -#define PA6_DDR DDRA -#undef PA7 -#define PA7_PIN PINA7 -#define PA7_RPORT PINA -#define PA7_WPORT PORTA -#define PA7_PWM NULL -#define PA7_DDR DDRA - -#undef PB0 -#define PB0_PIN PINB0 -#define PB0_RPORT PINB -#define PB0_WPORT PORTB -#define PB0_PWM NULL -#define PB0_DDR DDRB -#undef PB1 -#define PB1_PIN PINB1 -#define PB1_RPORT PINB -#define PB1_WPORT PORTB -#define PB1_PWM NULL -#define PB1_DDR DDRB -#undef PB2 -#define PB2_PIN PINB2 -#define PB2_RPORT PINB -#define PB2_WPORT PORTB -#define PB2_PWM NULL -#define PB2_DDR DDRB -#undef PB3 -#define PB3_PIN PINB3 -#define PB3_RPORT PINB -#define PB3_WPORT PORTB -#define PB3_PWM NULL -#define PB3_DDR DDRB -#undef PB4 -#define PB4_PIN PINB4 -#define PB4_RPORT PINB -#define PB4_WPORT PORTB -#define PB4_PWM NULL -#define PB4_DDR DDRB -#undef PB5 -#define PB5_PIN PINB5 -#define PB5_RPORT PINB -#define PB5_WPORT PORTB -#define PB5_PWM NULL -#define PB5_DDR DDRB -#undef PB6 -#define PB6_PIN PINB6 -#define PB6_RPORT PINB -#define PB6_WPORT PORTB -#define PB6_PWM NULL -#define PB6_DDR DDRB -#undef PB7 -#define PB7_PIN PINB7 -#define PB7_RPORT PINB -#define PB7_WPORT PORTB -#define PB7_PWM NULL -#define PB7_DDR DDRB - -#undef PC0 -#define PC0_PIN PINC0 -#define PC0_RPORT PINC -#define PC0_WPORT PORTC -#define PC0_PWM NULL -#define PC0_DDR DDRC -#undef PC1 -#define PC1_PIN PINC1 -#define PC1_RPORT PINC -#define PC1_WPORT PORTC -#define PC1_PWM NULL -#define PC1_DDR DDRC -#undef PC2 -#define PC2_PIN PINC2 -#define PC2_RPORT PINC -#define PC2_WPORT PORTC -#define PC2_PWM NULL -#define PC2_DDR DDRC -#undef PC3 -#define PC3_PIN PINC3 -#define PC3_RPORT PINC -#define PC3_WPORT PORTC -#define PC3_PWM NULL -#define PC3_DDR DDRC -#undef PC4 -#define PC4_PIN PINC4 -#define PC4_RPORT PINC -#define PC4_WPORT PORTC -#define PC4_PWM NULL -#define PC4_DDR DDRC -#undef PC5 -#define PC5_PIN PINC5 -#define PC5_RPORT PINC -#define PC5_WPORT PORTC -#define PC5_PWM NULL -#define PC5_DDR DDRC -#undef PC6 -#define PC6_PIN PINC6 -#define PC6_RPORT PINC -#define PC6_WPORT PORTC -#define PC6_PWM NULL -#define PC6_DDR DDRC -#undef PC7 -#define PC7_PIN PINC7 -#define PC7_RPORT PINC -#define PC7_WPORT PORTC -#define PC7_PWM NULL -#define PC7_DDR DDRC - -#undef PD0 -#define PD0_PIN PIND0 -#define PD0_RPORT PIND -#define PD0_WPORT PORTD -#define PD0_PWM NULL -#define PD0_DDR DDRD -#undef PD1 -#define PD1_PIN PIND1 -#define PD1_RPORT PIND -#define PD1_WPORT PORTD -#define PD1_PWM NULL -#define PD1_DDR DDRD -#undef PD2 -#define PD2_PIN PIND2 -#define PD2_RPORT PIND -#define PD2_WPORT PORTD -#define PD2_PWM NULL -#define PD2_DDR DDRD -#undef PD3 -#define PD3_PIN PIND3 -#define PD3_RPORT PIND -#define PD3_WPORT PORTD -#define PD3_PWM NULL -#define PD3_DDR DDRD -#undef PD4 -#define PD4_PIN PIND4 -#define PD4_RPORT PIND -#define PD4_WPORT PORTD -#define PD4_PWM NULL -#define PD4_DDR DDRD -#undef PD5 -#define PD5_PIN PIND5 -#define PD5_RPORT PIND -#define PD5_WPORT PORTD -#define PD5_PWM NULL -#define PD5_DDR DDRD -#undef PD6 -#define PD6_PIN PIND6 -#define PD6_RPORT PIND -#define PD6_WPORT PORTD -#define PD6_PWM NULL -#define PD6_DDR DDRD -#undef PD7 -#define PD7_PIN PIND7 -#define PD7_RPORT PIND -#define PD7_WPORT PORTD -#define PD7_PWM NULL -#define PD7_DDR DDRD - -#undef PE0 -#define PE0_PIN PINE0 -#define PE0_RPORT PINE -#define PE0_WPORT PORTE -#define PE0_PWM NULL -#define PE0_DDR DDRE -#undef PE1 -#define PE1_PIN PINE1 -#define PE1_RPORT PINE -#define PE1_WPORT PORTE -#define PE1_PWM NULL -#define PE1_DDR DDRE -#undef PE2 -#define PE2_PIN PINE2 -#define PE2_RPORT PINE -#define PE2_WPORT PORTE -#define PE2_PWM NULL -#define PE2_DDR DDRE -#undef PE3 -#define PE3_PIN PINE3 -#define PE3_RPORT PINE -#define PE3_WPORT PORTE -#define PE3_PWM NULL -#define PE3_DDR DDRE -#undef PE4 -#define PE4_PIN PINE4 -#define PE4_RPORT PINE -#define PE4_WPORT PORTE -#define PE4_PWM NULL -#define PE4_DDR DDRE -#undef PE5 -#define PE5_PIN PINE5 -#define PE5_RPORT PINE -#define PE5_WPORT PORTE -#define PE5_PWM NULL -#define PE5_DDR DDRE -#undef PE6 -#define PE6_PIN PINE6 -#define PE6_RPORT PINE -#define PE6_WPORT PORTE -#define PE6_PWM NULL -#define PE6_DDR DDRE -#undef PE7 -#define PE7_PIN PINE7 -#define PE7_RPORT PINE -#define PE7_WPORT PORTE -#define PE7_PWM NULL -#define PE7_DDR DDRE - -#undef PF0 -#define PF0_PIN PINF0 -#define PF0_RPORT PINF -#define PF0_WPORT PORTF -#define PF0_PWM NULL -#define PF0_DDR DDRF -#undef PF1 -#define PF1_PIN PINF1 -#define PF1_RPORT PINF -#define PF1_WPORT PORTF -#define PF1_PWM NULL -#define PF1_DDR DDRF -#undef PF2 -#define PF2_PIN PINF2 -#define PF2_RPORT PINF -#define PF2_WPORT PORTF -#define PF2_PWM NULL -#define PF2_DDR DDRF -#undef PF3 -#define PF3_PIN PINF3 -#define PF3_RPORT PINF -#define PF3_WPORT PORTF -#define PF3_PWM NULL -#define PF3_DDR DDRF -#undef PF4 -#define PF4_PIN PINF4 -#define PF4_RPORT PINF -#define PF4_WPORT PORTF -#define PF4_PWM NULL -#define PF4_DDR DDRF -#undef PF5 -#define PF5_PIN PINF5 -#define PF5_RPORT PINF -#define PF5_WPORT PORTF -#define PF5_PWM NULL -#define PF5_DDR DDRF -#undef PF6 -#define PF6_PIN PINF6 -#define PF6_RPORT PINF -#define PF6_WPORT PORTF -#define PF6_PWM NULL -#define PF6_DDR DDRF -#undef PF7 -#define PF7_PIN PINF7 -#define PF7_RPORT PINF -#define PF7_WPORT PORTF -#define PF7_PWM NULL -#define PF7_DDR DDRF - -#endif // _FASTIO_AT90USB diff --git a/Marlin/fastio_AT90USB-Teensy.h b/Marlin/fastio_AT90USB.h similarity index 97% rename from Marlin/fastio_AT90USB-Teensy.h rename to Marlin/fastio_AT90USB.h index 0cf94454ad..c643291f77 100644 --- a/Marlin/fastio_AT90USB-Teensy.h +++ b/Marlin/fastio_AT90USB.h @@ -26,8 +26,7 @@ * AT90USB 51 50 49 48 47 46 45 44 10 11 12 13 14 15 16 17 35 36 37 38 39 40 41 42 25 26 27 28 29 30 31 32 33 34 43 09 18 19 01 02 61 60 59 58 57 56 55 54 * > Teensy 28 29 30 31 32 33 34 35 20 21 22 23 24 25 26 27 10 11 12 13 14 15 16 17 00 01 02 03 04 05 06 07 08 09(46*47)36 37 18 19 38 39 40 41 42 43 44 45 * Port A0 A1 A2 A3 A4 A5 A6 A7 B0 B1 B2 B3 B4 B5 B6 B7 C0 C1 C2 C3 C4 C5 C6 C7 D0 D1 D2 D3 D4 D5 D6 D7 E0 E1 E2 E3 E4 E5 E6 E7 F0 F1 F2 F3 F4 F5 F6 F7 - * Marlin 00 01 02 03 04 05 06 07 08 09 10 11 12 13 14 15 16 17 18 19 20 21 22 23 24 25 26 27 28 29 30 31 32 33 34 35 36 37 38 39 40 41 42 43 44 45 46 47 - * The pins 46 and 47 are not supported by Teensyduino, but are supported below. + * The pins 46 and 47 are not supported by Teensyduino, but are supported below as E2 and E3 */ #ifndef _FASTIO_AT90USB @@ -679,4 +678,21 @@ #define PF7_PWM NULL #define PF7_DDR DDRF + +/** + * some of the pin mapping functions of the Teensduino extension to the Arduino IDE + * do not function the same as the other Arduino extensions + */ + +//digitalPinToTimer(pin) function works like Arduino but Timers are not defined +#define TIMER0B 1 +#define TIMER1A 7 +#define TIMER1B 8 +#define TIMER1C 9 +#define TIMER2A 6 +#define TIMER2B 2 +#define TIMER3A 5 +#define TIMER3B 4 +#define TIMER3C 3 + #endif // _FASTIO_AT90USB diff --git a/Marlin/pins.h b/Marlin/pins.h index e4c5e4f5e1..689e305d92 100644 --- a/Marlin/pins.h +++ b/Marlin/pins.h @@ -20,6 +20,18 @@ * */ +/** + * Include pins definitions + * + * Pins numbering schemes: + * + * - Digital I/O pin number if used by READ/WRITE macros. (e.g., X_STEP_DIR) + * The FastIO headers map digital pins to their ports and functions. + * + * - Analog Input number if used by analogRead or DAC. (e.g., TEMP_n_PIN) + * These numbers are the same in any pin mapping. + */ + #ifndef __PINS_H__ #define __PINS_H__ @@ -537,19 +549,10 @@ #define AVR_MOSI_PIN 51 #define AVR_SS_PIN 53 #elif defined(__AVR_AT90USB1287__) || defined(__AVR_AT90USB1286__) || defined(__AVR_AT90USB646__) || defined(__AVR_AT90USB647__) - #if ENABLED(AT90USBxx_TEENSYPP_ASSIGNMENTS) - // Teensy pin assignments - #define AVR_SCK_PIN 21 - #define AVR_MISO_PIN 23 - #define AVR_MOSI_PIN 22 - #define AVR_SS_PIN 20 - #else - // Traditional pin assignments - #define AVR_SCK_PIN 9 - #define AVR_MISO_PIN 11 - #define AVR_MOSI_PIN 10 - #define AVR_SS_PIN 8 - #endif + #define AVR_SCK_PIN 21 + #define AVR_MISO_PIN 23 + #define AVR_MOSI_PIN 22 + #define AVR_SS_PIN 20 #elif defined(__AVR_ATmega1281__) || defined(__AVR_ATmega2561__) #define AVR_SCK_PIN 10 #define AVR_MISO_PIN 12 diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp old mode 100755 new mode 100644 diff --git a/platformio.ini b/platformio.ini index c82fe48696..c5ef19140f 100644 --- a/platformio.ini +++ b/platformio.ini @@ -50,7 +50,7 @@ lib_deps = ${common.lib_deps} platform = teensy framework = arduino board = teensy20pp -build_flags = -I $BUILDSRC_DIR -D MOTHERBOARD=BOARD_BRAINWAVE_PRO -D AT90USBxx_TEENSYPP_ASSIGNMENTS +build_flags = -I $BUILDSRC_DIR -D MOTHERBOARD=BOARD_BRAINWAVE_PRO lib_deps = ${common.lib_deps} [env:rambo] From 87d82232513b999a14f050d7134dc439bb4535c6 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 8 Jun 2017 18:07:37 -0500 Subject: [PATCH 045/180] Unify AVR90USB: Pins remap to Arduino --- Marlin/pins_5DPRINT.h | 107 +++++++++++++++------- Marlin/pins_BRAINWAVE.h | 64 +++++++------ Marlin/pins_BRAINWAVE_PRO.h | 93 ++++++++----------- Marlin/pins_PRINTRBOARD.h | 163 +++++++++++++++++++-------------- Marlin/pins_PRINTRBOARD_REVF.h | 154 +++++++++++++++++-------------- Marlin/pins_SAV_MKI.h | 150 ++++++++++++++++++------------ Marlin/pins_TEENSY2.h | 124 ++++++++++++++++--------- Marlin/pins_TEENSYLU.h | 161 +++++++++++++++----------------- 8 files changed, 569 insertions(+), 447 deletions(-) mode change 100644 => 100755 Marlin/pins_5DPRINT.h mode change 100644 => 100755 Marlin/pins_BRAINWAVE.h mode change 100644 => 100755 Marlin/pins_BRAINWAVE_PRO.h mode change 100644 => 100755 Marlin/pins_PRINTRBOARD.h mode change 100644 => 100755 Marlin/pins_PRINTRBOARD_REVF.h mode change 100644 => 100755 Marlin/pins_SAV_MKI.h mode change 100644 => 100755 Marlin/pins_TEENSY2.h mode change 100644 => 100755 Marlin/pins_TEENSYLU.h diff --git a/Marlin/pins_5DPRINT.h b/Marlin/pins_5DPRINT.h old mode 100644 new mode 100755 index f44a56887d..f56ec0b678 --- a/Marlin/pins_5DPRINT.h +++ b/Marlin/pins_5DPRINT.h @@ -1,6 +1,6 @@ /** * Marlin 3D Printer Firmware - * Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * Copyright (C) 2017 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * * Based on Sprinter and grbl. * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm @@ -20,6 +20,47 @@ * */ +/** + * Rev B 2 JUN 2017 + * + * Converted to Arduino pin numbering + */ + +/** + * There are two Arduino IDE extensions that are compatible with this board + * and with the mainstream Marlin software. + * + * Teensyduino - http://www.pjrc.com/teensy/teensyduino.html + * Select Teensy++ 2.0 in Arduino IDE from the 'Tools -> Boards' menu + * + * Installation instructions are at the above URL. Don't bother loading the + * libraries - they are not used with the Marlin software. + * + * Printrboard - https://github.com/scwimbush/Printrboard-HID-Arduino-IDE-Support + * + * Installation: + * + * 1. Go to the above URL, click on the "Clone or Download" button and then + * click on "Download ZIP" button. + * 2. Unzip the file, find the "printrboard" directory and then copy it to the + * hardware directory in Arduino. The Arduino hardware directory will probably + * be located in a path similar to this: C:\Program Files (x86)\Arduino\hardware. + * 3. Restart Arduino. + * 4. Select "Printrboard" from the 'Tools -> Boards' menu. + * + * Teensyduino is the most popular option. Printrboard is used if your board doesn't have + * the Teensyduino bootloader on it. + */ + +/** + * To burn the bootloader that comes with Printrboard: + * + * 1. Connect your programmer to the board. + * 2. In the Arduino IDE select "Printrboard" and then select the programmer. + * 3. In the Arduino IDE click on "burn bootloader". Don't worry about the "verify failed at 1F000" error message. + * 4. The programmer is no longer needed. Remove it. + */ + /** * 5DPrint D8 Driver board pin assignments * @@ -27,7 +68,7 @@ */ #ifndef __AVR_AT90USB1286__ - #error "Oops! Make sure you have 'Teensy++ 2.0' selected from the 'Tools -> Boards' menu." + #error "Oops! Make sure you have 'Teensy++ 2.0' or 'Printrboard' selected from the 'Tools -> Boards' menu." #endif #define DEFAULT_MACHINE_NAME "Makibox" @@ -39,56 +80,54 @@ // // Limit Switches // -#define X_STOP_PIN 37 -#define Y_STOP_PIN 36 -#define Z_STOP_PIN 39 +#define X_STOP_PIN 37 // E5 +#define Y_STOP_PIN 36 // E4 +#define Z_STOP_PIN 19 // E7 // // Steppers // -#define X_STEP_PIN 0 -#define X_DIR_PIN 1 -#define X_ENABLE_PIN 23 +#define X_STEP_PIN 28 // A0 +#define X_DIR_PIN 29 // A1 +#define X_ENABLE_PIN 17 // C7 -#define Y_STEP_PIN 2 -#define Y_DIR_PIN 3 -#define Y_ENABLE_PIN 19 +#define Y_STEP_PIN 30 // A2 +#define Y_DIR_PIN 31 // A3 +#define Y_ENABLE_PIN 13 // C3 -#define Z_STEP_PIN 4 -#define Z_DIR_PIN 5 -#define Z_ENABLE_PIN 18 +#define Z_STEP_PIN 32 // A4 +#define Z_DIR_PIN 33 // A5 +#define Z_ENABLE_PIN 12 // C2 -#define E0_STEP_PIN 6 -#define E0_DIR_PIN 7 -#define E0_ENABLE_PIN 17 +#define E0_STEP_PIN 34 // A6 +#define E0_DIR_PIN 35 // A7 +#define E0_ENABLE_PIN 11 // C1 -// Microstepping pins - Mapping not from fastio.h (?) -#define X_MS1_PIN 25 -#define X_MS2_PIN 26 -#define Y_MS1_PIN 9 -#define Y_MS2_PIN 8 -#define Z_MS1_PIN 7 -#define Z_MS2_PIN 6 -#define E0_MS1_PIN 5 -#define E0_MS2_PIN 4 + +#define X_MS1_PIN 25 // B5 +#define X_MS2_PIN 26 // B6 +#define Y_MS1_PIN 9 // E1 +#define Y_MS2_PIN 8 // E0 +#define Z_MS1_PIN 7 // D7 +#define Z_MS2_PIN 6 // D6 +#define E0_MS1_PIN 5 // D5 +#define E0_MS2_PIN 4 // D4 // // Temperature Sensors // -#define TEMP_0_PIN 1 // Analog Input -#define TEMP_BED_PIN 0 // Analog Input +#define TEMP_0_PIN 1 // F1 Analog Input +#define TEMP_BED_PIN 0 // F0 Analog Input // // Heaters / Fans // -#define HEATER_0_PIN 21 -#define HEATER_BED_PIN 20 +#define HEATER_0_PIN 15 // C5 +#define HEATER_BED_PIN 14 // C4 -// You may need to change FAN_PIN to 16 because Marlin isn't using fastio.h -// for the fan and Teensyduino uses a different pin mapping. -#define FAN_PIN 16 +#define FAN_PIN 16 // C6 PWM3A // // Misc. Functions // -#define SDSS 20 +#define SDSS 20 // B0 diff --git a/Marlin/pins_BRAINWAVE.h b/Marlin/pins_BRAINWAVE.h old mode 100644 new mode 100755 index 83e7a35a96..2776c50062 --- a/Marlin/pins_BRAINWAVE.h +++ b/Marlin/pins_BRAINWAVE.h @@ -1,6 +1,6 @@ /** * Marlin 3D Printer Firmware - * Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * Copyright (C) 2017 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * * Based on Sprinter and grbl. * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm @@ -34,6 +34,12 @@ * allow this board to use the latest Marlin software */ +/** + * Rev C 2 JUN 2017 + * + * Converted to Arduino pin numbering + */ + /** * Marlin_AT90USB - https://github.com/Bob-the-Kuhn/Marlin_AT90USB * This is the only known IDE extension that is compatible with the pin definitions @@ -49,20 +55,20 @@ * https://rawgit.com/Bob-the-Kuhn/Marlin_AT90USB/master/package_MARLIN_AT90USB_index.json * 2. Under Tools -> Board -> Boards manager, scroll to the bottom, click on MARLIN_AT90USB * and then click on "Install" - * 3. Select "AT90USB646_STANDARD" from the 'Tools -> Boards' menu. + * 3. Select "AT90USB646_TEENSYPP" from the 'Tools -> Boards' menu. */ /** * To burn the bootloader that comes with Marlin_AT90USB: * * 1. Connect your programmer to the board. - * 2. In Arduino IDE select "AT90USB646_STANDARD" and then select the programmer. + * 2. In Arduino IDE select "AT90USB646_TEENSYPP" and then select the programmer. * 3. In Arduino IDE click on "burn bootloader". Don't worry about the "verify failed at 1F000" error message. * 4. The programmer is no longer needed. Remove it. */ #ifndef __AVR_AT90USB646__ - #error "Oops! Make sure you have 'Brainwave' selected from the 'Tools -> Boards' menu." + #error "Oops! Make sure you have 'AT90USB646_TEENSYPP' selected from the 'Tools -> Boards' menu." #endif #define BOARD_NAME "Brainwave" @@ -72,48 +78,48 @@ // // Limit Switches // -#define X_STOP_PIN 7 -#define Y_STOP_PIN 6 -#define Z_STOP_PIN 5 +#define X_STOP_PIN 35 // A7 +#define Y_STOP_PIN 34 // A6 +#define Z_STOP_PIN 33 // A5 // // Steppers // -#define X_STEP_PIN 27 -#define X_DIR_PIN 29 -#define X_ENABLE_PIN 28 -#define X_ATT_PIN 26 +#define X_STEP_PIN 3 // D3 +#define X_DIR_PIN 5 // D5 +#define X_ENABLE_PIN 4 // D4 +#define X_ATT_PIN 2 // D2 -#define Y_STEP_PIN 31 -#define Y_DIR_PIN 33 -#define Y_ENABLE_PIN 32 -#define Y_ATT_PIN 30 +#define Y_STEP_PIN 7 // D7 +#define Y_DIR_PIN 9 // E1 +#define Y_ENABLE_PIN 8 // E0 +#define Y_ATT_PIN 6 // D6 -#define Z_STEP_PIN 17 -#define Z_DIR_PIN 19 -#define Z_ENABLE_PIN 18 -#define Z_ATT_PIN 16 +#define Z_STEP_PIN 11 // C1 +#define Z_DIR_PIN 13 // C3 +#define Z_ENABLE_PIN 12 // C2 +#define Z_ATT_PIN 10 // C0 -#define E0_STEP_PIN 21 -#define E0_DIR_PIN 23 -#define E0_ENABLE_PIN 22 -#define E0_ATT_PIN 20 +#define E0_STEP_PIN 15 // C5 +#define E0_DIR_PIN 17 // C7 +#define E0_ENABLE_PIN 16 // C6 +#define E0_ATT_PIN 14 // C4 // // Temperature Sensors // -#define TEMP_0_PIN 7 // Analog Input -#define TEMP_BED_PIN 6 // Analog Input +#define TEMP_0_PIN 7 // F7 Analog Input +#define TEMP_BED_PIN 6 // F6 Analog Input // // Heaters / Fans // -#define HEATER_0_PIN 4 // Extruder -#define HEATER_BED_PIN 38 // Bed +#define HEATER_0_PIN 32 // A4 Extruder +#define HEATER_BED_PIN 18 // E6 Bed -#define FAN_PIN 3 // Fan +#define FAN_PIN 31 // A3 Fan // // Misc. Functions // -#define LED_PIN 39 +#define LED_PIN 19 // E7 diff --git a/Marlin/pins_BRAINWAVE_PRO.h b/Marlin/pins_BRAINWAVE_PRO.h old mode 100644 new mode 100755 index 02835ca27e..ef780d5797 --- a/Marlin/pins_BRAINWAVE_PRO.h +++ b/Marlin/pins_BRAINWAVE_PRO.h @@ -1,6 +1,6 @@ /** * Marlin 3D Printer Firmware - * Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * Copyright (C) 2017 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * * Based on Sprinter and grbl. * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm @@ -32,11 +32,16 @@ * * Added pointers to currently available Arduino IDE extensions that will * allow this board to use the latest Marlin software + * + * + * Rev C 2 JUN 2017 + * + * Converted to Arduino pin numbering */ /** - * There are three Arduino IDE extensions that are compatible with this board - * and with the mainstream Marlin software. All have been used with Arduino 1.6.12 + * There are two Arduino IDE extensions that are compatible with this board + * and with the mainstream Marlin software. * * Teensyduino - http://www.pjrc.com/teensy/teensyduino.html * Select Teensy++ 2.0 in Arduino IDE from the 'Tools -> Boards' menu @@ -45,8 +50,6 @@ * libraries - they are not used with the Marlin software. * * Printrboard - https://github.com/scwimbush/Printrboard-HID-Arduino-IDE-Support - * This is basically Teensyduino but with a bootloader that can handle image sizes - * larger than 64K. * * Installation: * @@ -54,43 +57,25 @@ * click on "Download ZIP" button. * 2. Unzip the file, find the "printrboard" directory and then copy it to the * hardware directory in Arduino. The Arduino hardware directory will probably - * be located in a path similar to this: C:\Program Files (x86)\Arduino\hardware. + * be located in a path similar to this: C:\Program Files (x86)\Arduino\hardware. * 3. Restart Arduino. * 4. Select "Printrboard" from the 'Tools -> Boards' menu. * - * Marlin_AT90USB - https://github.com/Bob-the-Kuhn/Marlin_AT90USB - * Uses the bootloader from Printerboard above. - * - * "Marlin_AT90USB" makes PWM0A available rather than the usual PWM1C. These PWMs share - * the same physical pin. Marlin uses TIMER1 to generate interrupts and sets it up such - * that PWM1A, PWM1B & PWM1C can't be used. - * - * Installation: - * - * 1. In the Arduino IDE, under Files -> Preferences paste the following URL - * https://rawgit.com/Bob-the-Kuhn/Marlin_AT90USB/master/package_MARLIN_AT90USB_index.json - * 2. Under Tools -> Board -> Boards manager, scroll to the bottom, click on MARLIN_AT90USB - * and then click on "Install" - * 3. Select "AT90USB1286_TEENSYPP" from the 'Tools -> Boards' menu. + * Teensyduino is the most popular option. Printrboard is used if your board doesn't have + * the Teensyduino bootloader on it. */ /** - * To burn the bootloader that comes with Printrboard and Marlin_AT90USB: + * To burn the bootloader that comes with Printrboard: * * 1. Connect your programmer to the board. - * 2. In the Arduino IDE select "Printrboard" or "AT90USB1286_TEENSYPP" and then select the programmer. + * 2. In the Arduino IDE select "Printrboard" and then select the programmer. * 3. In the Arduino IDE click on "burn bootloader". Don't worry about the "verify failed at 1F000" error message. * 4. The programmer is no longer needed. Remove it. */ #ifndef __AVR_AT90USB1286__ - #error "Oops! Make sure you have 'Teensy++ 2.0', 'AT90USB1286_TEENSYPP', or 'Printrboard' selected from the 'Tools -> Boards' menu." -#endif - -#include "fastio.h" - -#if DISABLED(AT90USBxx_TEENSYPP_ASSIGNMENTS) // use Teensyduino Teensy++2.0 pin assignments instead of Marlin alphabetical. - #error "Uncomment '#define AT90USBxx_TEENSYPP_ASSIGNMENTS' in fastio.h for this config" + #error "Oops! Make sure you have 'Teensy++ 2.0' or 'Printrboard' selected from the 'Tools -> Boards' menu." #endif #define BOARD_NAME "Brainwave Pro" @@ -101,53 +86,53 @@ // // Limit Switches // -#define X_STOP_PIN 47 -#define Y_STOP_PIN 18 -#define Z_MAX_PIN 36 +#define X_STOP_PIN 45 // F7 +#define Y_STOP_PIN 12 // C2 +#define Z_STOP_PIN 36 // E4 // // Z Probe (when not Z_MIN_PIN) // #ifndef Z_MIN_PROBE_PIN - #define Z_MIN_PROBE_PIN 17 + #define Z_MIN_PROBE_PIN 11 // C1 #endif // // Steppers // -#define X_STEP_PIN 33 -#define X_DIR_PIN 32 -#define X_ENABLE_PIN 11 +#define X_STEP_PIN 9 // E1 +#define X_DIR_PIN 8 // E0 +#define X_ENABLE_PIN 23 // B3 -#define Y_STEP_PIN 31 -#define Y_DIR_PIN 30 -#define Y_ENABLE_PIN 8 +#define Y_STEP_PIN 7 // D7 +#define Y_DIR_PIN 6 // D6 +#define Y_ENABLE_PIN 20 // B0 -#define Z_STEP_PIN 29 -#define Z_DIR_PIN 28 -#define Z_ENABLE_PIN 37 +#define Z_STEP_PIN 5 // D5 +#define Z_DIR_PIN 4 // D4 +#define Z_ENABLE_PIN 37 // E5 -#define E0_STEP_PIN 35 -#define E0_DIR_PIN 34 -#define E0_ENABLE_PIN 13 +#define E0_STEP_PIN 47 // E3 +#define E0_DIR_PIN 46 // E2 +#define E0_ENABLE_PIN 25 // B5 // // Temperature Sensors // -#define TEMP_0_PIN 2 // Analog Input -#define TEMP_1_PIN 1 // Analog Input -#define TEMP_BED_PIN 0 // Analog Input +#define TEMP_0_PIN 2 // F2 Analog Input +#define TEMP_1_PIN 1 // F1 Analog Input +#define TEMP_BED_PIN 0 // F0 Analog Input // // Heaters / Fans // -#define HEATER_0_PIN 15 -#define HEATER_BED_PIN 14 // Bed -#define FAN_PIN 16 // Fan, PWM +#define HEATER_0_PIN 27 // B7 +#define HEATER_BED_PIN 26 // B6 Bed +#define FAN_PIN 16 // C6 Fan, PWM3A // // Misc. Functions // -#define SDSS 20 -#define SD_DETECT_PIN 12 -#define LED_PIN 19 +#define SDSS 20 // B0 +#define SD_DETECT_PIN 24 // B4 +#define LED_PIN 13 // C3 diff --git a/Marlin/pins_PRINTRBOARD.h b/Marlin/pins_PRINTRBOARD.h old mode 100644 new mode 100755 index a679340e74..7dec695d57 --- a/Marlin/pins_PRINTRBOARD.h +++ b/Marlin/pins_PRINTRBOARD.h @@ -1,6 +1,6 @@ /** * Marlin 3D Printer Firmware - * Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * Copyright (C) 2017 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * * Based on Sprinter and grbl. * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm @@ -21,18 +21,48 @@ */ /** - * Printrboard pin assignments (AT90USB1286) - * Requires the Teensyduino software with Teensy++ 2.0 selected in Arduino IDE! - * http://www.pjrc.com/teensy/teensyduino.html - * See http://reprap.org/wiki/Printrboard for more info + * Rev B 2 JUN 2017 + * + * Converted to Arduino pin numbering + */ + +/** + * There are two Arduino IDE extensions that are compatible with this board + * and with the mainstream Marlin software. + * + * Teensyduino - http://www.pjrc.com/teensy/teensyduino.html + * Select Teensy++ 2.0 in Arduino IDE from the 'Tools -> Boards' menu + * + * Installation instructions are at the above URL. Don't bother loading the + * libraries - they are not used with the Marlin software. + * + * Printrboard - https://github.com/scwimbush/Printrboard-HID-Arduino-IDE-Support + * + * Installation: + * + * 1. Go to the above URL, click on the "Clone or Download" button and then + * click on "Download ZIP" button. + * 2. Unzip the file, find the "printrboard" directory and then copy it to the + * hardware directory in Arduino. The Arduino hardware directory will probably + * be located in a path similar to this: C:\Program Files (x86)\Arduino\hardware. + * 3. Restart Arduino. + * 4. Select "Printrboard" from the 'Tools -> Boards' menu. + * + * Teensyduino is the most popular option. Printrboard is used if your board doesn't have + * the Teensyduino bootloader on it. + */ + +/** + * To burn the bootloader that comes with Printrboard: + * + * 1. Connect your programmer to the board. + * 2. In the Arduino IDE select "Printrboard" and then select the programmer. + * 3. In the Arduino IDE click on "burn bootloader". Don't worry about the "verify failed at 1F000" error message. + * 4. The programmer is no longer needed. Remove it. */ #ifndef __AVR_AT90USB1286__ - #error "Oops! Make sure you have 'Teensy++ 2.0' selected from the 'Tools -> Boards' menu." -#endif - -#if ENABLED(AT90USBxx_TEENSYPP_ASSIGNMENTS) // use Teensyduino Teensy++2.0 pin assignments instead of Marlin traditional. - #error "These Printrboard assignments depend on traditional Marlin assignments, not AT90USBxx_TEENSYPP_ASSIGNMENTS in fastio.h" + #error "Oops! Make sure you have 'Teensy++ 2.0' or 'Printrboard' selected from the 'Tools -> Boards' menu." #endif #define BOARD_NAME "Printrboard" @@ -46,32 +76,32 @@ // // Limit Switches // -#define X_STOP_PIN 35 +#define X_STOP_PIN 47 // E3 #if ENABLED(SDSUPPORT) - #define Y_STOP_PIN 37 // Move Ystop to Estop socket + #define Y_STOP_PIN 37 // E5 - Move Ystop to Estop socket #else - #define Y_STOP_PIN 8 // Ystop in Ystop socket + #define Y_STOP_PIN 20 // B0 SS - Ystop in Ystop socket #endif -#define Z_STOP_PIN 36 +#define Z_STOP_PIN 36 // E4 // // Steppers // -#define X_STEP_PIN 0 -#define X_DIR_PIN 1 -#define X_ENABLE_PIN 39 +#define X_STEP_PIN 28 // A0 +#define X_DIR_PIN 29 // A1 +#define X_ENABLE_PIN 19 // E7 -#define Y_STEP_PIN 2 -#define Y_DIR_PIN 3 -#define Y_ENABLE_PIN 38 +#define Y_STEP_PIN 30 // A2 +#define Y_DIR_PIN 31 // A3 +#define Y_ENABLE_PIN 18 // E6 -#define Z_STEP_PIN 4 -#define Z_DIR_PIN 5 -#define Z_ENABLE_PIN 23 +#define Z_STEP_PIN 32 // A4 +#define Z_DIR_PIN 33 // A5 +#define Z_ENABLE_PIN 17 // C7 -#define E0_STEP_PIN 6 -#define E0_DIR_PIN 7 -#define E0_ENABLE_PIN 19 +#define E0_STEP_PIN 34 // A6 +#define E0_DIR_PIN 35 // A7 +#define E0_ENABLE_PIN 13 // C3 // // Temperature Sensors @@ -82,76 +112,67 @@ // // Heaters / Fans // -#define HEATER_0_PIN 21 // Extruder -#define HEATER_1_PIN 46 -#define HEATER_2_PIN 47 -#define HEATER_BED_PIN 20 +#define HEATER_0_PIN 15 // C5 PWM3B - Extruder +#define HEATER_1_PIN 44 // F6 +#define HEATER_2_PIN 45 // F7 +#define HEATER_BED_PIN 14 // C4 PWM3C -// If soft or fast PWM is off then use Teensyduino pin numbering, Marlin -// fastio pin numbering otherwise -#if ENABLED(FAN_SOFT_PWM) || ENABLED(FAST_PWM_FAN) - #define FAN_PIN 22 -#else - #define FAN_PIN 16 -#endif + +#define FAN_PIN 16 // C6 PWM3A // // Misc. Functions // -#define SDSS 26 - -#ifndef FILWIDTH_PIN - #define FILWIDTH_PIN 2 // Analog Input -#endif +#define SDSS 20 // B0 SS +#define FILWIDTH_PIN 2 // Analog Input // // LCD / Controller // #if ENABLED(ULTRA_LCD) && ENABLED(NEWPANEL) // we have no buzzer installed - #define BEEPER_PIN -1 + #define BEEPER_PIN -1 // LCD Pins #if ENABLED(LCD_I2C_PANELOLU2) - #define BTN_EN1 27 // RX1 - fastio.h pin mapping 27 - #define BTN_EN2 26 // TX1 - fastio.h pin mapping 26 - #define BTN_ENC 43 // A3 - fastio.h pin mapping 43 - #define SDSS 40 // use SD card on Panelolu2 (Teensyduino pin mapping) + #define BTN_EN1 3 // D3 RX1 JP2-7 + #define BTN_EN2 2 // D2 TX1 JP2-5 + #define BTN_ENC 41 // F3 JP2-4 + #define SDSS 38 // F0 B-THERM connector - use SD card on Panelolu2 #else - #define BTN_EN1 16 - #define BTN_EN2 17 - #define BTN_ENC 18 // the click - #endif // LCD_I2C_PANELOLU2 + #define BTN_EN1 10 // C0 JP11-12 + #define BTN_EN2 11 // C1 JP11-13 + #define BTN_ENC 12 // C2 JP11-14 + #endif - // not connected to a pin - #define SD_DETECT_PIN -1 + // not connected + #define SD_DETECT_PIN -1 - #define LCD_PINS_RS 9 - #define LCD_PINS_ENABLE 8 - #define LCD_PINS_D4 7 - #define LCD_PINS_D5 6 - #define LCD_PINS_D6 5 - #define LCD_PINS_D7 4 + #define LCD_PINS_RS 9 // E1 JP11-11 + #define LCD_PINS_ENABLE 8 // E0 JP11-10 + #define LCD_PINS_D4 7 // D7 JP11-8 + #define LCD_PINS_D5 6 // D6 JP11-7 + #define LCD_PINS_D6 5 // D5 JP11-6 + #define LCD_PINS_D7 4 // D4 JP11-5 #endif // ULTRA_LCD && NEWPANEL #if ENABLED(VIKI2) || ENABLED(miniVIKI) - // FastIO - #define BEEPER_PIN 32 + #define BEEPER_PIN 8 // E0 JP11-10 // Pins for DOGM SPI LCD Support - #define DOGLCD_A0 42 // Non-FastIO - #define DOGLCD_CS 43 // Non-FastIO + #define DOGLCD_A0 40 // F2 JP2-2 + #define DOGLCD_CS 41 // F3 JP2-4 #define LCD_SCREEN_ROT_180 - // The encoder and click button (FastIO Pins) - #define BTN_EN1 26 - #define BTN_EN2 27 - #define BTN_ENC 47 + // The encoder and click button + #define BTN_EN1 2 // D2 TX1 JP2-5 + #define BTN_EN2 3 // D3 RX1 JP2-7 + #define BTN_ENC 45 // F7 TDI JP2-12 - #define SDSS 45 - #define SD_DETECT_PIN -1 // FastIO (Manual says 72 I'm not certain cause I can't test) + #define SDSS 43 // F5 TMS JP2-8 + #define SD_DETECT_PIN -1 - #define STAT_LED_RED_PIN 12 // Non-FastIO - #define STAT_LED_BLUE_PIN 10 // Non-FastIO + #define STAT_LED_RED_PIN 12 // C2 JP11-14 + #define STAT_LED_BLUE_PIN 10 // C0 JP11-12 #endif diff --git a/Marlin/pins_PRINTRBOARD_REVF.h b/Marlin/pins_PRINTRBOARD_REVF.h old mode 100644 new mode 100755 index 16753fe327..f83bdf5ab0 --- a/Marlin/pins_PRINTRBOARD_REVF.h +++ b/Marlin/pins_PRINTRBOARD_REVF.h @@ -1,6 +1,6 @@ /** * Marlin 3D Printer Firmware - * Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * Copyright (C) 2017 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * * Based on Sprinter and grbl. * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm @@ -21,18 +21,48 @@ */ /** - * Printrboard pin assignments (AT90USB1286) - * Requires the Teensyduino software with Teensy++ 2.0 selected in Arduino IDE! - * http://www.pjrc.com/teensy/teensyduino.html - * See http://reprap.org/wiki/Printrboard for more info + * Rev B 2 JUN 2017 + * + * Converted to Arduino pin numbering + */ + +/** + * There are two Arduino IDE extensions that are compatible with this board + * and with the mainstream Marlin software. + * + * Teensyduino - http://www.pjrc.com/teensy/teensyduino.html + * Select Teensy++ 2.0 in Arduino IDE from the 'Tools -> Boards' menu + * + * Installation instructions are at the above URL. Don't bother loading the + * libraries - they are not used with the Marlin software. + * + * Printrboard - https://github.com/scwimbush/Printrboard-HID-Arduino-IDE-Support + * + * Installation: + * + * 1. Go to the above URL, click on the "Clone or Download" button and then + * click on "Download ZIP" button. + * 2. Unzip the file, find the "printrboard" directory and then copy it to the + * hardware directory in Arduino. The Arduino hardware directory will probably + * be located in a path similar to this: C:\Program Files (x86)\Arduino\hardware. + * 3. Restart Arduino. + * 4. Select "Printrboard" from the 'Tools -> Boards' menu. + * + * Teensyduino is the most popular option. Printrboard is used if your board doesn't have + * the Teensyduino bootloader on it. + */ + +/** + * To burn the bootloader that comes with Printrboard: + * + * 1. Connect your programmer to the board. + * 2. In the Arduino IDE select "Printrboard" and then select the programmer. + * 3. In the Arduino IDE click on "burn bootloader". Don't worry about the "verify failed at 1F000" error message. + * 4. The programmer is no longer needed. Remove it. */ #ifndef __AVR_AT90USB1286__ - #error "Oops! Make sure you have 'Teensy++ 2.0' selected from the 'Tools -> Boards' menu." -#endif - -#if ENABLED(AT90USBxx_TEENSYPP_ASSIGNMENTS) // use Teensyduino Teensy++2.0 pin assignments instead of Marlin traditional. - #error "These Printrboard assignments depend on traditional Marlin assignments, not AT90USBxx_TEENSYPP_ASSIGNMENTS in fastio.h" + #error "Oops! Make sure you have 'Teensy++ 2.0' or 'Printrboard' selected from the 'Tools -> Boards' menu." #endif #define BOARD_NAME "Printrboard Rev F" @@ -41,28 +71,28 @@ // // Limit Switches // -#define X_STOP_PIN 35 -#define Y_STOP_PIN 12 -#define Z_STOP_PIN 36 +#define X_STOP_PIN 47 // E3 +#define Y_STOP_PIN 24 // B4 PWM2A +#define Z_STOP_PIN 36 // E4 // // Steppers // -#define X_STEP_PIN 0 -#define X_DIR_PIN 1 -#define X_ENABLE_PIN 39 +#define X_STEP_PIN 28 // A0 +#define X_DIR_PIN 29 // A1 +#define X_ENABLE_PIN 19 // E7 -#define Y_STEP_PIN 2 -#define Y_DIR_PIN 3 -#define Y_ENABLE_PIN 38 +#define Y_STEP_PIN 30 // A2 +#define Y_DIR_PIN 31 // A3 +#define Y_ENABLE_PIN 18 // E6 -#define Z_STEP_PIN 4 -#define Z_DIR_PIN 5 -#define Z_ENABLE_PIN 23 +#define Z_STEP_PIN 32 // A4 +#define Z_DIR_PIN 33 // A5 +#define Z_ENABLE_PIN 17 // C7 -#define E0_STEP_PIN 6 -#define E0_DIR_PIN 7 -#define E0_ENABLE_PIN 19 +#define E0_STEP_PIN 34 // A6 +#define E0_DIR_PIN 35 // A7 +#define E0_ENABLE_PIN 13 // C3 // uncomment to enable an I2C based DAC like on the Printrboard REVF #define DAC_STEPPER_CURRENT @@ -72,7 +102,7 @@ #define DAC_STEPPER_SENSE 0.11 #define DAC_STEPPER_ADDRESS 0 #define DAC_STEPPER_MAX 3520 -#define DAC_STEPPER_VREF 1 // internal Vref, gain 1x = 2.048V +#define DAC_STEPPER_VREF 1 // internal Vref, gain 1x = 2.048V #define DAC_STEPPER_GAIN 0 #define DAC_OR_ADDRESS 0x00 @@ -85,68 +115,52 @@ // // Heaters / Fans // -#define HEATER_0_PIN 21 // Extruder -#define HEATER_1_PIN 46 -#define HEATER_2_PIN 47 -#define HEATER_BED_PIN 20 +#define HEATER_0_PIN 15 // C5 PWM3B - Extruder +#define HEATER_1_PIN 44 // F6 +#define HEATER_2_PIN 45 // F7 +#define HEATER_BED_PIN 14 // C4 PWM3C -// If soft or fast PWM is off then use Teensyduino pin numbering, Marlin -// fastio pin numbering otherwise -#if ENABLED(FAN_SOFT_PWM) || ENABLED(FAST_PWM_FAN) - #define FAN_PIN 22 -#else - #define FAN_PIN 16 -#endif +#define FAN_PIN 16 // C6 PWM3A // // Misc. Functions // -#define SDSS 20 // Teensylu pin mapping - -#ifndef FILWIDTH_PIN - #define FILWIDTH_PIN 2 // Analog Input -#endif +#define SDSS 20 // B0 SS +#define FILWIDTH_PIN 2 // Analog Input // // LCD / Controller // #if ENABLED(ULTRA_LCD) - #define BEEPER_PIN -1 + #define BEEPER_PIN -1 - #define LCD_PINS_RS 9 - #define LCD_PINS_ENABLE 8 - #define LCD_PINS_D4 7 - #define LCD_PINS_D5 6 - #define LCD_PINS_D6 5 - #define LCD_PINS_D7 4 + #define LCD_PINS_RS 9 // E1 JP11-11 + #define LCD_PINS_ENABLE 8 // E0 JP11-10 + #define LCD_PINS_D4 7 // D7 JP11-8 + #define LCD_PINS_D5 6 // D6 JP11-7 + #define LCD_PINS_D6 5 // D5 JP11-6 + #define LCD_PINS_D7 4 // D4 JP11-5 - #define BTN_EN1 16 - #define BTN_EN2 17 - #define BTN_ENC 18 // the click + #define BTN_EN1 10 // C0 JP11-12 + #define BTN_EN2 11 // C1 JP11-13 + #define BTN_ENC 12 // C2 JP11-14 - #define SD_DETECT_PIN -1 - - // encoder rotation values - #define encrot0 0 - #define encrot1 2 - #define encrot2 3 - #define encrot3 1 + #define SD_DETECT_PIN -1 #endif #if ENABLED(VIKI2) || ENABLED(miniVIKI) - #define BEEPER_PIN 32 // FastIO - #define DOGLCD_A0 42 // Non-FastIO - #define DOGLCD_CS 43 // Non-FastIO + #define BEEPER_PIN 8 // E0 JP11-10 + #define DOGLCD_A0 40 // F2 JP2-2 + #define DOGLCD_CS 41 // F3 JP2-4 #define LCD_SCREEN_ROT_180 - // (FastIO Pins) - #define BTN_EN1 26 - #define BTN_EN2 27 - #define BTN_ENC 47 + #define BTN_EN1 2 // D2 TX1 JP2-5 + #define BTN_EN2 3 // D3 RX1 JP2-7 + #define BTN_ENC 45 // F7 TDI JP2-12 - #define SDSS 45 - #define SD_DETECT_PIN -1 // FastIO (Manual says 72) + #define SDSS 43 // F5 TMS JP2-8 + #define SD_DETECT_PIN -1 - #define STAT_LED_RED_PIN 12 // Non-FastIO - #define STAT_LED_BLUE_PIN 10 // Non-FastIO + #define STAT_LED_RED_PIN 12 // C2 JP11-14 + #define STAT_LED_BLUE_PIN 10 // C0 JP11-12 #endif diff --git a/Marlin/pins_SAV_MKI.h b/Marlin/pins_SAV_MKI.h old mode 100644 new mode 100755 index 2048af9251..b1ed0bd8c4 --- a/Marlin/pins_SAV_MKI.h +++ b/Marlin/pins_SAV_MKI.h @@ -1,6 +1,6 @@ /** * Marlin 3D Printer Firmware - * Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * Copyright (C) 2017 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * * Based on Sprinter and grbl. * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm @@ -21,14 +21,48 @@ */ /** - * SAV MkI pin assignments (AT90USB1286) - * Requires the Teensyduino software with Teensy++ 2.0 selected in Arduino IDE! - * http://www.pjrc.com/teensy/teensyduino.html - * RepRap Clone Wars project board. + * Rev B 2 JUN 2017 + * + * Converted to Arduino pin numbering + */ + +/** + * There are two Arduino IDE extensions that are compatible with this board + * and with the mainstream Marlin software. + * + * Teensyduino - http://www.pjrc.com/teensy/teensyduino.html + * Select Teensy++ 2.0 in Arduino IDE from the 'Tools -> Boards' menu + * + * Installation instructions are at the above URL. Don't bother loading the + * libraries - they are not used with the Marlin software. + * + * Printrboard - https://github.com/scwimbush/Printrboard-HID-Arduino-IDE-Support + * + * Installation: + * + * 1. Go to the above URL, click on the "Clone or Download" button and then + * click on "Download ZIP" button. + * 2. Unzip the file, find the "printrboard" directory and then copy it to the + * hardware directory in Arduino. The Arduino hardware directory will probably + * be located in a path similar to this: C:\Program Files (x86)\Arduino\hardware. + * 3. Restart Arduino. + * 4. Select "Printrboard" from the 'Tools -> Boards' menu. + * + * Teensyduino is the most popular option. Printrboard is used if your board doesn't have + * the Teensyduino bootloader on it. + */ + +/** + * To burn the bootloader that comes with Printrboard: + * + * 1. Connect your programmer to the board. + * 2. In the Arduino IDE select "Printrboard" and then select the programmer. + * 3. In the Arduino IDE click on "burn bootloader". Don't worry about the "verify failed at 1F000" error message. + * 4. The programmer is no longer needed. Remove it. */ #ifndef __AVR_AT90USB1286__ - #error "Oops! Make sure you have 'Teensy++ 2.0' selected from the 'Tools -> Boards' menu." + #error "Oops! Make sure you have 'Teensy++ 2.0' or 'Printrboard' selected from the 'Tools -> Boards' menu." #endif #define DEFAULT_MACHINE_NAME "SAV MkI" @@ -41,54 +75,54 @@ // // Servos // -#define SERVO0_PIN 41 // In teensy's pin definition for pinMode (in servo.cpp) +#define SERVO0_PIN 39 // F1 In teensy's pin definition for pinMode (in servo.cpp) // // Limit Switches // -#define X_STOP_PIN 13 -#define Y_STOP_PIN 14 -//#define Z_STOP_PIN 15 -#define Z_STOP_PIN 36 // For inductive sensor. +#define X_STOP_PIN 25 // B5 +#define Y_STOP_PIN 26 // B6 +//#define Z_STOP_PIN 27 // B7 +#define Z_STOP_PIN 36 // E4 For inductive sensor. +//#define E_STOP_PIN 36 // E4 // // Steppers // -#define X_STEP_PIN 0 -#define X_DIR_PIN 1 -#define X_ENABLE_PIN 39 +#define X_STEP_PIN 28 // A0 +#define X_DIR_PIN 29 // A1 +#define X_ENABLE_PIN 19 // E7 -#define Y_STEP_PIN 2 -#define Y_DIR_PIN 3 -#define Y_ENABLE_PIN 38 +#define Y_STEP_PIN 30 // A2 +#define Y_DIR_PIN 31 // A3 +#define Y_ENABLE_PIN 18 // E6 -#define Z_STEP_PIN 4 -#define Z_DIR_PIN 5 -#define Z_ENABLE_PIN 23 +#define Z_STEP_PIN 32 // A4 +#define Z_DIR_PIN 33 // A5 +#define Z_ENABLE_PIN 17 // C7 -#define E0_STEP_PIN 6 -#define E0_DIR_PIN 7 -#define E0_ENABLE_PIN 19 +#define E0_STEP_PIN 34 // A6 +#define E0_DIR_PIN 35 // A7 +#define E0_ENABLE_PIN 13 // C3 // // Temperature Sensors // -#define TEMP_0_PIN 7 // Analog Input (Extruder) -#define TEMP_BED_PIN 6 // Analog Input (Bed) +#define TEMP_0_PIN 7 // F7 Analog Input (Extruder) +#define TEMP_BED_PIN 6 // F6 Analog Input (Bed) // // Heaters / Fans // -#define HEATER_0_PIN 21 // Extruder -#define HEATER_BED_PIN 20 // Bed +#define HEATER_0_PIN 15 // C5 PWM3B - Extruder +#define HEATER_BED_PIN 14 // C4 PWM3C - Bed -#define FAN_PIN 16 // Fan -- from Teensyduino environment. - // For the fan and Teensyduino uses a different pin mapping. +#define FAN_PIN 16 // C6 PWM3A // // Misc. Functions // -#define SDSS 20 // PB0 - 8 in marlin env. +#define SDSS 20 // B0 // Extension header pin mapping // ---------------------------- @@ -99,21 +133,21 @@ // PWM-D24 A4 (An), IO // 5V GND // 12V GND -#define EXT_AUX_SCL_D0 0 // 0 (teensy), 24 (marlin) -#define EXT_AUX_SDA_D1 1 // 1 (teensy), 25 (marlin) -#define EXT_AUX_RX1_D2 26 // 2 (teensy), 26 (marlin) -#define EXT_AUX_TX1_D3 27 // 3 (teensy), 27 (marlin) -#define EXT_AUX_PWM_D24 12 // 24 (teensy), 12 (marlin) -#define EXT_AUX_A0 0 // Analog -#define EXT_AUX_A0_IO 40 // Digital IO, 38 (teensy), 40 (marlin) -#define EXT_AUX_A1 1 // Analog -#define EXT_AUX_A1_IO 41 // Digital IO, 39 (teensy), 41 (marlin) -#define EXT_AUX_A2 2 // Analog -#define EXT_AUX_A2_IO 42 // Digital IO, 40 (teensy), 42 (marlin) -#define EXT_AUX_A3 3 // Analog -#define EXT_AUX_A3_IO 43 // Digital IO, 41 (teensy), 43 (marlin) -#define EXT_AUX_A4 4 // Analog -#define EXT_AUX_A4_IO 44 // Digital IO, 42 (teensy), 44 (marlin) +#define EXT_AUX_SCL_D0 0 // D0 PWM0B +#define EXT_AUX_SDA_D1 1 // D1 +#define EXT_AUX_RX1_D2 2 // D2 +#define EXT_AUX_TX1_D3 3 // D3 +#define EXT_AUX_PWM_D24 24 // B4 PWM2A +#define EXT_AUX_A0 0 // F0 Analog Input +#define EXT_AUX_A0_IO 38 // F0 Digital IO +#define EXT_AUX_A1 1 // F1 Analog Input +#define EXT_AUX_A1_IO 39 // F1 Digital IO +#define EXT_AUX_A2 2 // F2 Analog Input +#define EXT_AUX_A2_IO 40 // F2 Digital IO +#define EXT_AUX_A3 3 // F3 Analog Input +#define EXT_AUX_A3_IO 41 // F3 Digital IO +#define EXT_AUX_A4 4 // F4 Analog Input +#define EXT_AUX_A4_IO 42 // F4 Digital IO // // LCD / Controller @@ -128,28 +162,28 @@ #if ENABLED(SAV_3DLCD) // For LCD SHIFT register LCD - #define SR_DATA_PIN EXT_AUX_SDA_D1 - #define SR_CLK_PIN EXT_AUX_SCL_D0 -#endif // SAV_3DLCD + #define SR_DATA_PIN EXT_AUX_SDA_D1 + #define SR_CLK_PIN EXT_AUX_SCL_D0 +#endif #if ENABLED(SAV_3DLCD) || ENABLED(SAV_3DGLCD) - #define BTN_EN1 EXT_AUX_A1_IO - #define BTN_EN2 EXT_AUX_A0_IO - #define BTN_ENC EXT_AUX_PWM_D24 + #define BTN_EN1 EXT_AUX_A1_IO + #define BTN_EN2 EXT_AUX_A0_IO + #define BTN_ENC EXT_AUX_PWM_D24 - #define KILL_PIN EXT_AUX_A2_IO - #define HOME_PIN EXT_AUX_A4_IO + #define KILL_PIN EXT_AUX_A2_IO + #define HOME_PIN EXT_AUX_A4_IO -#else // Try to use the expansion header for spindle control +#else // Use the expansion header for spindle control // // M3/M4/M5 - Spindle/Laser Control // - #define SPINDLE_LASER_PWM_PIN 24 // 12 AT90USB… pin # - #define SPINDLE_LASER_ENABLE_PIN 39 // Pin should have a pullup! 41 AT90USB… pin # - #define SPINDLE_DIR_PIN 40 // 42 AT90USB… pin # + #define SPINDLE_LASER_PWM_PIN 24 // B4 PWM2A + #define SPINDLE_LASER_ENABLE_PIN 39 // F1 Pin should have a pullup! + #define SPINDLE_DIR_PIN 40 // F2 - #define CASE_LIGHT_PIN 0 // 24 AT90USB… pin # + #define CASE_LIGHT_PIN 0 // D0 PWM0B #endif diff --git a/Marlin/pins_TEENSY2.h b/Marlin/pins_TEENSY2.h old mode 100644 new mode 100755 index 971de27e8b..fa4280fc13 --- a/Marlin/pins_TEENSY2.h +++ b/Marlin/pins_TEENSY2.h @@ -1,6 +1,6 @@ /** * Marlin 3D Printer Firmware - * Copyright (C) 2016 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * Copyright (C) 2017 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * * Based on Sprinter and grbl. * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm @@ -20,13 +20,54 @@ * */ +/** + * Rev B 2 JUN 2017 + * + * Converted to Arduino pin numbering + */ + +/** + * There are two Arduino IDE extensions that are compatible with this board + * and with the mainstream Marlin software. + * + * Teensyduino - http://www.pjrc.com/teensy/teensyduino.html + * Select Teensy++ 2.0 in Arduino IDE from the 'Tools -> Boards' menu + * + * Installation instructions are at the above URL. Don't bother loading the + * libraries - they are not used with the Marlin software. + * + * Printrboard - https://github.com/scwimbush/Printrboard-HID-Arduino-IDE-Support + * + * Installation: + * + * 1. Go to the above URL, click on the "Clone or Download" button and then + * click on "Download ZIP" button. + * 2. Unzip the file, find the "printrboard" directory and then copy it to the + * hardware directory in Arduino. The Arduino hardware directory will probably + * be located in a path similar to this: C:\Program Files (x86)\Arduino\hardware. + * 3. Restart Arduino. + * 4. Select "Printrboard" from the 'Tools -> Boards' menu. + * + * Teensyduino is the most popular option. Printrboard is used if your board doesn't have + * the Teensyduino bootloader on it. + */ + +/** + * To burn the bootloader that comes with Printrboard: + * + * 1. Connect your programmer to the board. + * 2. In the Arduino IDE select "Printrboard" and then select the programmer. + * 3. In the Arduino IDE click on "burn bootloader". Don't worry about the "verify failed at 1F000" error message. + * 4. The programmer is no longer needed. Remove it. + */ + /** * Teensy++ 2.0 Breadboard pin assignments (AT90USB1286) * Requires the Teensyduino software with Teensy++ 2.0 selected in Arduino IDE! * http://www.pjrc.com/teensy/teensyduino.html * See http://reprap.org/wiki/Printrboard for more info * - * CLI build: DEFINES=AT90USBxx_TEENSYPP_ASSIGNMENTS HARDWARE_MOTHERBOARD=84 make + * CLI build: HARDWARE_MOTHERBOARD=84 make * * DaveX plan for Teensylu/printrboard-type pinouts for a TeensyBreadboard: * (ref teensylu & sprinter) @@ -66,12 +107,7 @@ */ #ifndef __AVR_AT90USB1286__ - #error "Oops! Make sure you have 'Teensy++ 2.0' selected from the 'Tools -> Boards' menu." -#endif - -#if DISABLED(AT90USBxx_TEENSYPP_ASSIGNMENTS) // use Teensyduino Teensy++2.0 pin assignments instead of Marlin alphabetical. - #error "Uncomment #define AT90USBxx_TEENSYPP_ASSIGNMENTS in fastio.h for this config" - // (or build from command line) + #error "Oops! Make sure you have 'Teensy++ 2.0' or 'Printrboard' selected from the 'Tools -> Boards' menu." #endif #define BOARD_NAME "Teensy++2.0" @@ -82,68 +118,68 @@ // // Limit Switches // -#define X_STOP_PIN 2 -#define Y_STOP_PIN 3 -#define Z_STOP_PIN 4 +#define X_STOP_PIN 2 // D2 +#define Y_STOP_PIN 3 // D3 +#define Z_STOP_PIN 4 // D4 // // Steppers // -#define X_STEP_PIN 28 // 0 Marlin -#define X_DIR_PIN 29 // 1 Marlin -#define X_ENABLE_PIN 26 +#define X_STEP_PIN 28 // A0 Marlin +#define X_DIR_PIN 29 // A1 Marlin +#define X_ENABLE_PIN 26 // B6 -#define Y_STEP_PIN 30 // 2 Marlin -#define Y_DIR_PIN 31 // 3 -#define Y_ENABLE_PIN 26 // Shared w/x +#define Y_STEP_PIN 30 // A2 Marlin +#define Y_DIR_PIN 31 // A3 +#define Y_ENABLE_PIN 26 // B6 Shared w/x -#define Z_STEP_PIN 32 // 4 -#define Z_DIR_PIN 33 // 5 -#define Z_ENABLE_PIN 26 // Shared w/x +#define Z_STEP_PIN 32 // A4 +#define Z_DIR_PIN 33 // A5 +#define Z_ENABLE_PIN 26 // B6 Shared w/x -#define E0_STEP_PIN 34 // 6 -#define E0_DIR_PIN 35 // 7 -#define E0_ENABLE_PIN 26 // Shared w/x +#define E0_STEP_PIN 34 // A6 +#define E0_DIR_PIN 35 // A7 +#define E0_ENABLE_PIN 26 // B6 Shared w/x // // Temperature Sensors // -#define TEMP_0_PIN 7 // Analog Input (Extruder) -#define TEMP_BED_PIN 6 // Analog Input (Bed) +#define TEMP_0_PIN 7 // F7 Analog Input (Extruder) +#define TEMP_BED_PIN 6 // F6 Analog Input (Bed) // // Heaters / Fans // -#define HEATER_0_PIN 15 // 21 // Extruder -#define HEATER_BED_PIN 14 // 20 // Bed -#define FAN_PIN 16 // 22 // Fan +#define HEATER_0_PIN 15 // C5 PWM3B Extruder +#define HEATER_BED_PIN 14 // C4 PWM3C +#define FAN_PIN 16 // C6 PWM3A Fan // // Misc. Functions // -#define SDSS 20 // 8 -#define LED_PIN 6 -#define PS_ON_PIN 27 -#define CASE_LIGHT_PIN 1 // MUST BE HARDWARE PWM +#define SDSS 20 // B0 +#define LED_PIN 6 // D6 +#define PS_ON_PIN 27 // B7 +#define CASE_LIGHT_PIN 1 // D1 PWM2B MUST BE HARDWARE PWM // // LCD / Controller // #if ENABLED(ULTIPANEL) - #define LCD_PINS_RS 8 - #define LCD_PINS_ENABLE 9 - #define LCD_PINS_D4 10 - #define LCD_PINS_D5 11 - #define LCD_PINS_D6 12 - #define LCD_PINS_D7 13 - #define BTN_EN1 38 - #define BTN_EN2 39 - #define BTN_ENC 40 + #define LCD_PINS_RS 8 // E0 + #define LCD_PINS_ENABLE 9 // E1 + #define LCD_PINS_D4 10 // C0 + #define LCD_PINS_D5 11 // C1 + #define LCD_PINS_D6 12 // C2 + #define LCD_PINS_D7 13 // C3 + #define BTN_EN1 38 // F0 + #define BTN_EN2 39 // F1 + #define BTN_ENC 40 // F2 #endif // // M3/M4/M5 - Spindle/Laser Control // -#define SPINDLE_LASER_ENABLE_PIN 5 // Pin should have a pullup! -#define SPINDLE_LASER_PWM_PIN 0 // MUST BE HARDWARE PWM -#define SPINDLE_DIR_PIN 7 +#define SPINDLE_LASER_ENABLE_PIN 5 // D5 Pin should have a pullup! +#define SPINDLE_LASER_PWM_PIN 0 // D0 PWM0B MUST BE HARDWARE PWM +#define SPINDLE_DIR_PIN 7 // D7 diff --git a/Marlin/pins_TEENSYLU.h b/Marlin/pins_TEENSYLU.h old mode 100644 new mode 100755 index 5f12e710cc..3fb7f5c3ec --- a/Marlin/pins_TEENSYLU.h +++ b/Marlin/pins_TEENSYLU.h @@ -21,54 +21,46 @@ */ /** - * rev B 30 DEC 2016 + * Rev C 2 JUN 2017 * - * The original version of this file did NOT result in a useful program because: - * 1. The pin numbers assumed that the "#define AT90USBxx_TEENSYPP_ASSIGNMENTS" line - * in FASTIO.h was commented out. There wasn't an Arduino IDE 1.6.x extension/package - * that supported this pin map so the latest Marlin wouldn't compile. - * 2. The silkscreen for the four end stops don't agree with the schematic. Activating - * the X endstop would tell the software that the Y endstop just went active. - * 3. The thermistor inputs also had heater names assigned to them. The result was - * thermistor inputs that were set to digital outputs. + * Converted to Arduino pin numbering + */ + +/** + * There are two Arduino IDE extensions that are compatible with this board + * and with the mainstream Marlin software. All have been used with Arduino 1.6.12 * - * Rev B corrects the above problems by: - * 1. The "Marlin_AT90USB" extension/package was developed. This extension enables the - * latest Marlin software to compile using Arduino IDE 1.6.x and 1.80. - * 2. The endstop pin numbers in this file were changed to match the silkscreen. This - * makes it a little confusing when trying to correlate the schematic with the pin - * numbers used in this file. - * 3. The offending heater names were deleted. + * Teensyduino - http://www.pjrc.com/teensy/teensyduino.html + * Select Teensy++ 2.0 in Arduino IDE from the 'Tools -> Boards' menu * - * To create a useable image for Teensylu do the following: - * a) Install the Marlin_AT90USB extension with either of the following methods: - * Automatic - paste this URL into preferences and then use Boards manager - * https://rawgit.com/Bob-the-Kuhn/Marlin_AT90USB/master/package_MARLIN_AT90USB_index.json - * Manual: - * 1. Copy the following URL into Go to "https://github.com/Bob-the-Kuhn/Marlin_AT90USB", - * click on the "Clone or Download" button and then click on "Download ZIP" button. - * 2. Unzip the file, find the "Marlin_AT90USB" directory and then copy it to the - * hardware directory in Arduino. The Arduino hardware directory will probably be - * located in a path similar to this: C:\Program Files (x86)\Arduino\hardware - * b) Connect the USBtinyISP to the board. - * c) In the Arduino IDE select the "AT90USB1286_STANDARD" board in the of the "Marlin_AT90USB" - * section and select the "USBtinyISP" programmer. - * d) In the Arduino IDE click on "burn bootloader". Don't worry about the "verify - * failed at 1F000" error message. - * e) The USBtinyISP programmer is no longer needed. Remove it. - * f) In FASTIO.h comment out the "#define AT90USBxx_TEENSYPP_ASSIGNMENTS" line. - * g) To upload a sketch do the following: - * 1. remove the jumper - * 2. press reset - * 3. click on the "upload" button in the Arduino IDE - * 4. wait until the upload finishes (less than a minute) - * 5. put the jumper back on - * 6. press the reset button + * Installation instructions are at the above URL. Don't bother loading the + * libraries - they are not used with the Marlin software. * + * Printrboard - https://github.com/scwimbush/Printrboard-HID-Arduino-IDE-Support + * This is basically Teensyduino but with a bootloader that can handle image sizes + * larger than 64K. * - * NOTE - the "Marlin_AT90USB" pin maps make PWM0A available rather than the usual PWM1C. - * These PWMs share the same physical pin. Marlin uses TIMER1 to generate - * interrupts and sets it up such that PWM1A, PWM1B & PWM1C can't be used. + * Installation: + * + * 1. Go to the above URL, click on the "Clone or Download" button and then + * click on "Download ZIP" button. + * 2. Unzip the file, find the "printrboard" directory and then copy it to the + * hardware directory in Arduino. The Arduino hardware directory will probably + * be located in a path similar to this: C:\Program Files (x86)\Arduino\hardware. + * 3. Restart Arduino. + * 4. Select "Printrboard" from the 'Tools -> Boards' menu. + * + * Teensyduino is the most popular option. Printrboard is used if your board doesn't have + * the Teensyduino bootloader on it. + */ + +/** + * To burn the bootloader that comes with Printrboard: + * + * 1. Connect your programmer to the board. + * 2. In the Arduino IDE select "Printrboard" and then select the programmer. + * 3. In the Arduino IDE click on "burn bootloader". Don't worry about the "verify failed at 1F000" error message. + * 4. The programmer is no longer needed. Remove it. */ /** @@ -81,13 +73,8 @@ * The pin assignments in this file match the silkscreen. */ - #if !defined(__AVR_AT90USB1286__) && !defined(__AVR_AT90USB1286P__) - #error "Oops! Make sure you have 'AT90USB1286_STANDARD' selected from the 'Tools -> Boards' menu." -#endif - -#if ENABLED(AT90USBxx_TEENSYPP_ASSIGNMENTS) - #error "please disable (comment out) the AT90USBxx_TEENSYPP_ASSIGNMENTS flag in FASTIO.h " + #error "Oops! Make sure you have 'Teensy++ 2.0' or 'Printrboard' selected from the 'Tools -> Boards' menu." #endif #define BOARD_NAME "Teensylu" @@ -97,60 +84,60 @@ // -// Limit Switche definitions that match the SCHEMATIC +// Limit Switch definitions that match the SCHEMATIC // -//#define X_STOP_PIN 13 -//#define Y_STOP_PIN 14 -//#define Z_STOP_PIN 15 -//#define E_STOP_PIN 36 +//#define X_STOP_PIN 25 // B5 +//#define Y_STOP_PIN 26 // B6 +//#define Z_STOP_PIN 27 // B7 +//#define E_STOP_PIN 36 // E4 // // Limit Switch definitions that match the SILKSCREEN // -#define X_STOP_PIN 14 -#define Y_STOP_PIN 15 -#define Z_STOP_PIN 36 -//#define E_STOP_PIN 13 +#define X_STOP_PIN 26 // B6 +#define Y_STOP_PIN 27 // B7 +#define Z_STOP_PIN 36 // E4 +//#define E_STOP_PIN 25 // B5 // // Steppers // -#define X_STEP_PIN 0 -#define X_DIR_PIN 1 -#define X_ENABLE_PIN 39 +#define X_STEP_PIN 28 // A0 +#define X_DIR_PIN 29 // A1 +#define X_ENABLE_PIN 19 // E7 -#define Y_STEP_PIN 2 -#define Y_DIR_PIN 3 -#define Y_ENABLE_PIN 38 +#define Y_STEP_PIN 30 // A2 +#define Y_DIR_PIN 31 // A3 +#define Y_ENABLE_PIN 18 // E6 -#define Z_STEP_PIN 4 -#define Z_DIR_PIN 5 -#define Z_ENABLE_PIN 23 - -#define E0_STEP_PIN 6 -#define E0_DIR_PIN 7 -#define E0_ENABLE_PIN 19 +#define Z_STEP_PIN 32 // A4 +#define Z_DIR_PIN 33 // A5 +#define Z_ENABLE_PIN 17 // C7 +#define E0_STEP_PIN 34 // A6 +#define E0_DIR_PIN 35 // A7 +#define E0_ENABLE_PIN 13 // C3 +// // Temperature Sensors - -#define TEMP_0_PIN 7 // Analog Input (Extruder) -#define TEMP_BED_PIN 6 // Analog Input (Bed) +// +#define TEMP_0_PIN 7 // Analog Input (Extruder) +#define TEMP_BED_PIN 6 // Analog Input (Bed) // // Heaters / Fans // -#define HEATER_0_PIN 21 // Extruder -#define HEATER_BED_PIN 20 +#define HEATER_0_PIN 15 // C5 PWM3B - Extruder +#define HEATER_BED_PIN 14 // C4 PWM3C -#define FAN_PIN 22 +#define FAN_PIN 16 // C6 PWM3A // // Misc. Functions // -#define SDSS 8 -#define CASE_LIGHT_PIN 24 +#define SDSS 20 // B0 JP31-6 +#define CASE_LIGHT_PIN 0 // D0 IO-14 PWM0B // // LCD / Controller @@ -160,11 +147,11 @@ #define BEEPER_PIN -1 #if ENABLED(LCD_I2C_PANELOLU2) - #define BTN_EN1 27 - #define BTN_EN2 26 - #define BTN_ENC 43 - #define SDSS 40 // use SD card on Panelolu2 - #endif // LCD_I2C_PANELOLU2 + #define BTN_EN1 3 // D3 IO-8 + #define BTN_EN2 2 // D2 IO-10 + #define BTN_ENC 41 // F3 IO-7 + #define SDSS 38 // F0 IO-13 use SD card on Panelolu2 + #endif #define SD_DETECT_PIN -1 @@ -173,6 +160,6 @@ // // M3/M4/M5 - Spindle/Laser Control // -#define SPINDLE_LASER_PWM_PIN 12 // MUST BE HARDWARE PWM -#define SPINDLE_LASER_ENABLE_PIN 41 // Pin should have a pullup! -#define SPINDLE_DIR_PIN 42 +#define SPINDLE_LASER_PWM_PIN 24 // B4 IO-3 PWM2A - MUST BE HARDWARE PWM +#define SPINDLE_LASER_ENABLE_PIN 39 // F1 IO-11 - Pin should have a pullup! +#define SPINDLE_DIR_PIN 40 // F2 IO-9 From 5426fc1735bad08ff2d85a8940e6e844734340b0 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 8 Jun 2017 18:08:03 -0500 Subject: [PATCH 046/180] Unify AVR90USB: Pins cleanup --- Marlin/pins_AZTEEG_X3_PRO.h | 10 +- Marlin/pins_GEN6.h | 6 +- Marlin/pins_GEN7_CUSTOM.h | 6 +- Marlin/pins_MEGATRONICS_3.h | 8 +- Marlin/pins_MIGHTYBOARD_REVE.h | 151 ++++++++++++++-------------- Marlin/pins_MINITRONICS.h | 6 +- Marlin/pins_RAMBO.h | 20 ++-- Marlin/pins_RAMPS.h | 173 +++++++++++++++++---------------- Marlin/pins_SCOOVO_X9H.h | 26 ++--- Marlin/pins_ULTIMAKER.h | 12 +-- 10 files changed, 211 insertions(+), 207 deletions(-) diff --git a/Marlin/pins_AZTEEG_X3_PRO.h b/Marlin/pins_AZTEEG_X3_PRO.h index 53ecb4c18c..0e76a2a232 100644 --- a/Marlin/pins_AZTEEG_X3_PRO.h +++ b/Marlin/pins_AZTEEG_X3_PRO.h @@ -134,9 +134,9 @@ #if ENABLED(VIKI2) || ENABLED(miniVIKI) #undef SD_DETECT_PIN - #define SD_DETECT_PIN 49 // For easy adapter board + #define SD_DETECT_PIN 49 // For easy adapter board #undef BEEPER_PIN - #define BEEPER_PIN 12 // 33 isn't physically available to the LCD display + #define BEEPER_PIN 12 // 33 isn't physically available to the LCD display #else #define STAT_LED_RED_PIN 32 #define STAT_LED_BLUE_PIN 35 @@ -146,9 +146,9 @@ // Misc. Functions // #if ENABLED(CASE_LIGHT_ENABLE) && PIN_EXISTS(CASE_LIGHT) && defined(DOGLCD_A0) && DOGLCD_A0 == CASE_LIGHT_PIN - #undef DOGLCD_A0 // steal pin 44 for the case light; if you have a Viki2 and have connected it - #define DOGLCD_A0 57 // following the Panucatt wiring diagram, you may need to tweak these pin assignments - // as the wiring diagram uses pin 44 for DOGLCD_A0 + #undef DOGLCD_A0 // Steal pin 44 for the case light; if you have a Viki2 and have connected it + #define DOGLCD_A0 57 // following the Panucatt wiring diagram, you may need to tweak these pin assignments + // as the wiring diagram uses pin 44 for DOGLCD_A0 #endif // diff --git a/Marlin/pins_GEN6.h b/Marlin/pins_GEN6.h index 10a285790d..5611e4d92f 100644 --- a/Marlin/pins_GEN6.h +++ b/Marlin/pins_GEN6.h @@ -107,7 +107,7 @@ // #define SDSS 17 #define DEBUG_PIN 0 -#define CASE_LIGHT_PIN 16 // MUST BE HARDWARE PWM +#define CASE_LIGHT_PIN 16 // MUST BE HARDWARE PWM // RS485 pins #define TX_ENABLE_PIN 12 @@ -116,6 +116,6 @@ // // M3/M4/M5 - Spindle/Laser Control // -#define SPINDLE_LASER_ENABLE_PIN 5 // Pin should have a pullup/pulldown! -#define SPINDLE_LASER_PWM_PIN 16 // MUST BE HARDWARE PWM +#define SPINDLE_LASER_ENABLE_PIN 5 // Pin should have a pullup/pulldown! +#define SPINDLE_LASER_PWM_PIN 16 // MUST BE HARDWARE PWM #define SPINDLE_DIR_PIN 6 diff --git a/Marlin/pins_GEN7_CUSTOM.h b/Marlin/pins_GEN7_CUSTOM.h index 9b83df9aee..d64e94e2d3 100644 --- a/Marlin/pins_GEN7_CUSTOM.h +++ b/Marlin/pins_GEN7_CUSTOM.h @@ -96,14 +96,14 @@ // Heaters // #define HEATER_0_PIN 4 -#define HEATER_BED_PIN 3 // (bed) +#define HEATER_BED_PIN 3 // (bed) // // Misc. Functions // -#define SDSS 31 // SCL pin of I2C header || CS Pin for SD Card support +#define SDSS 31 // SCL pin of I2C header || CS Pin for SD Card support #define PS_ON_PIN 19 -#define CASE_LIGHT_PIN 15 // MUST BE HARDWARE PWM +#define CASE_LIGHT_PIN 15 // MUST BE HARDWARE PWM // A pin for debugging #define DEBUG_PIN -1 diff --git a/Marlin/pins_MEGATRONICS_3.h b/Marlin/pins_MEGATRONICS_3.h index 5e4ca4b586..2ebb209bcb 100644 --- a/Marlin/pins_MEGATRONICS_3.h +++ b/Marlin/pins_MEGATRONICS_3.h @@ -131,7 +131,7 @@ #define SDSS 53 #define LED_PIN 13 #define PS_ON_PIN 12 -#define CASE_LIGHT_PIN 45 // try the keypad connector +#define CASE_LIGHT_PIN 45 // Try the keypad connector // // LCD / Controller @@ -144,9 +144,9 @@ #if ENABLED(REPRAPWORLD_GRAPHICAL_LCD) - #define LCD_PINS_RS 56 // CS chip select / SS chip slave select - #define LCD_PINS_ENABLE 51 // SID (MOSI) - #define LCD_PINS_D4 52 // SCK (CLK) clock + #define LCD_PINS_RS 56 // CS chip select / SS chip slave select + #define LCD_PINS_ENABLE 51 // SID (MOSI) + #define LCD_PINS_D4 52 // SCK (CLK) clock #define SD_DETECT_PIN 35 #else diff --git a/Marlin/pins_MIGHTYBOARD_REVE.h b/Marlin/pins_MIGHTYBOARD_REVE.h index bd13a379d9..5b5d6e7ed1 100644 --- a/Marlin/pins_MIGHTYBOARD_REVE.h +++ b/Marlin/pins_MIGHTYBOARD_REVE.h @@ -64,20 +64,20 @@ // // Servos // -#define SERVO0_PIN 36 // C1 (1280-EX1) -#define SERVO1_PIN 37 // C0 (1280-EX2) -#define SERVO2_PIN 40 // G1 (1280-EX3) -#define SERVO3_PIN 41 // G0 (1280-EX4) +#define SERVO0_PIN 36 // C1 (1280-EX1) +#define SERVO1_PIN 37 // C0 (1280-EX2) +#define SERVO2_PIN 40 // G1 (1280-EX3) +#define SERVO3_PIN 41 // G0 (1280-EX4) // // Limit Switches // -#define X_MIN_PIN 49 // L0 -#define X_MAX_PIN 48 // L1 -#define Y_MIN_PIN 47 // L2 -#define Y_MAX_PIN 46 // L3 -#define Z_MIN_PIN 43 // L6 -#define Z_MAX_PIN 42 // L7 +#define X_MIN_PIN 49 // L0 +#define X_MAX_PIN 48 // L1 +#define Y_MIN_PIN 47 // L2 +#define Y_MAX_PIN 46 // L3 +#define Z_MIN_PIN 43 // L6 +#define Z_MAX_PIN 42 // L7 // // Z Probe (when not Z_MIN_PIN) @@ -89,25 +89,25 @@ // // Steppers // -#define X_STEP_PIN 55 // F1 -#define X_DIR_PIN 54 // F0 -#define X_ENABLE_PIN 56 // F2 +#define X_STEP_PIN 55 // F1 +#define X_DIR_PIN 54 // F0 +#define X_ENABLE_PIN 56 // F2 -#define Y_STEP_PIN 59 // F5 -#define Y_DIR_PIN 58 // F4 -#define Y_ENABLE_PIN 60 // F6 +#define Y_STEP_PIN 59 // F5 +#define Y_DIR_PIN 58 // F4 +#define Y_ENABLE_PIN 60 // F6 -#define Z_STEP_PIN 63 // K1 -#define Z_DIR_PIN 62 // K0 -#define Z_ENABLE_PIN 64 // K2 +#define Z_STEP_PIN 63 // K1 +#define Z_DIR_PIN 62 // K0 +#define Z_ENABLE_PIN 64 // K2 -#define E0_STEP_PIN 25 // A3 -#define E0_DIR_PIN 24 // A2 -#define E0_ENABLE_PIN 26 // A4 +#define E0_STEP_PIN 25 // A3 +#define E0_DIR_PIN 24 // A2 +#define E0_ENABLE_PIN 26 // A4 -#define E1_STEP_PIN 29 // A7 -#define E1_DIR_PIN 28 // A6 -#define E1_ENABLE_PIN 39 // G2 +#define E1_STEP_PIN 29 // A7 +#define E1_DIR_PIN 28 // A6 +#define E1_ENABLE_PIN 39 // G2 // // I2C Digipots - MCP4018 @@ -115,17 +115,17 @@ // Set from 0 - 127 with stop bit. // (Ex. 3F << 1 | 1) // -#define DIGIPOTS_I2C_SCL 76 // J5 -#define DIGIPOTS_I2C_SDA_X 57 // F3 -#define DIGIPOTS_I2C_SDA_Y 61 // F7 -#define DIGIPOTS_I2C_SDA_Z 65 // K3 -#define DIGIPOTS_I2C_SDA_E0 27 // A5 -#define DIGIPOTS_I2C_SDA_E1 77 // J6 +#define DIGIPOTS_I2C_SCL 76 // J5 +#define DIGIPOTS_I2C_SDA_X 57 // F3 +#define DIGIPOTS_I2C_SDA_Y 61 // F7 +#define DIGIPOTS_I2C_SDA_Z 65 // K3 +#define DIGIPOTS_I2C_SDA_E0 27 // A5 +#define DIGIPOTS_I2C_SDA_E1 77 // J6 // // Temperature Sensors // -#define TEMP_BED_PIN 69 // K7 +#define TEMP_BED_PIN 69 // K7 // SPI for Max6675 or Max31855 Thermocouple // Uses a separate SPI bus @@ -135,10 +135,10 @@ // 2 E4 CS2 // 78 E2 SCK // -#define THERMO_SCK_PIN 78 // E2 -#define THERMO_DO_PIN 3 // E5 -#define THERMO_CS1 5 // E3 -#define THERMO_CS2 2 // E4 +#define THERMO_SCK_PIN 78 // E2 +#define THERMO_DO_PIN 3 // E5 +#define THERMO_CS1 5 // E3 +#define THERMO_CS2 2 // E4 #define MAX6675_SS THERMO_CS1 #define MAX6675_SCK_PIN THERMO_SCK_PIN @@ -150,10 +150,10 @@ // 2 extruders or 1 extruder and a heated bed. // With no heated bed, an additional 24V fan is possible. // -#define MOSFET_A_PIN 6 // H3 -#define MOSFET_B_PIN 11 // B5 - Rev A of this file had this pin assigned to 9 -#define MOSFET_C_PIN 45 // L4 -#define MOSFET_D_PIN 44 // L5 +#define MOSFET_A_PIN 6 // H3 +#define MOSFET_B_PIN 11 // B5 - Rev A of this file had this pin assigned to 9 +#define MOSFET_C_PIN 45 // L4 +#define MOSFET_D_PIN 44 // L5 #if HOTENDS > 1 #if TEMP_SENSOR_BED @@ -195,43 +195,43 @@ // // Extruder Auto Fan Pins // -#define ORIG_E0_AUTO_FAN_PIN 7 // H4 -#define ORIG_E1_AUTO_FAN_PIN 12 // B6 +#define ORIG_E0_AUTO_FAN_PIN 7 // H4 +#define ORIG_E1_AUTO_FAN_PIN 12 // B6 // // Misc. Functions // -#define LED_PIN 13 // B7 -#define CUTOFF_RESET_PIN 16 // H1 -#define CUTOFF_TEST_PIN 17 // H0 -#define CASE_LIGHT_PIN 44 // L5 MUST BE HARDWARE PWM +#define LED_PIN 13 // B7 +#define CUTOFF_RESET_PIN 16 // H1 +#define CUTOFF_TEST_PIN 17 // H0 +#define CASE_LIGHT_PIN 44 // L5 MUST BE HARDWARE PWM // // LCD / Controller // #ifdef REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER - #define LCD_PINS_RS 33 // C4, LCD-STROBE - #define LCD_PINS_ENABLE 72 // J2, LEFT - #define LCD_PINS_D4 35 // C2, LCD-CLK - #define LCD_PINS_D5 32 // C5, RLED - #define LCD_PINS_D6 34 // C3, LCD-DATA - #define LCD_PINS_D7 31 // C6, GLED + #define LCD_PINS_RS 33 // C4: LCD-STROBE + #define LCD_PINS_ENABLE 72 // J2: LEFT + #define LCD_PINS_D4 35 // C2: LCD-CLK + #define LCD_PINS_D5 32 // C5: RLED + #define LCD_PINS_D6 34 // C3: LCD-DATA + #define LCD_PINS_D7 31 // C6: GLED - #define BTN_EN2 75 // J4, UP - #define BTN_EN1 73 // J3, DOWN + #define BTN_EN2 75 // J4, UP + #define BTN_EN1 73 // J3, DOWN //STOP button connected as KILL_PIN - #define KILL_PIN 14 // J1, RIGHT + #define KILL_PIN 14 // J1, RIGHT //KILL - not connected - #define BEEPER_PIN 8 // H5, SD_WP + #define BEEPER_PIN 8 // H5, SD_WP - #define BTN_CENTER 15 // J0 - #define BTN_ENC BTN_CENTER + #define BTN_CENTER 15 // J0 + #define BTN_ENC BTN_CENTER //on board leds - #define STAT_LED_RED_LED SERVO0_PIN // C1 (1280-EX1, DEBUG2) - #define STAT_LED_BLUE_PIN SERVO1_PIN // C0 (1280-EX2, DEBUG3) + #define STAT_LED_RED_LED SERVO0_PIN // C1 (1280-EX1, DEBUG2) + #define STAT_LED_BLUE_PIN SERVO1_PIN // C0 (1280-EX2, DEBUG3) #else // Replicator uses a 3-wire SR controller with HD44780 @@ -239,29 +239,29 @@ // #define SAV_3DLCD - #define SR_DATA_PIN 34 // C3 - #define SR_CLK_PIN 35 // C2 - #define SR_STROBE_PIN 33 // C4 + #define SR_DATA_PIN 34 // C3 + #define SR_CLK_PIN 35 // C2 + #define SR_STROBE_PIN 33 // C4 - #define BTN_UP 75 // J4 - #define BTN_DOWN 73 // J3 - #define BTN_LEFT 72 // J2 - #define BTN_RIGHT 14 // J1 - #define BTN_CENTER 15 // J0 - #define BTN_ENC BTN_CENTER + #define BTN_UP 75 // J4 + #define BTN_DOWN 73 // J3 + #define BTN_LEFT 72 // J2 + #define BTN_RIGHT 14 // J1 + #define BTN_CENTER 15 // J0 + #define BTN_ENC BTN_CENTER - #define BEEPER_PIN 4 // G5 + #define BEEPER_PIN 4 // G5 - #define STAT_LED_RED_PIN 32 // C5 - #define STAT_LED_BLUE_PIN 31 // C6 (Actually green) + #define STAT_LED_RED_PIN 32 // C5 + #define STAT_LED_BLUE_PIN 31 // C6 (Actually green) #endif // // SD Card // -#define SDSS 53 // B0 -#define SD_DETECT_PIN 9 // H6 +#define SDSS 53 // B0 +#define SD_DETECT_PIN 9 // H6 #define MAX_PIN THERMO_SCK_PIN @@ -275,9 +275,6 @@ - - - // Check if all pins are defined in mega/pins_arduino.h #include static_assert(NUM_DIGITAL_PINS > MAX_PIN, "add missing pins to [arduino dir]/hardware/arduino/avr/variants/mega/pins_arduino.h based on fastio.h" diff --git a/Marlin/pins_MINITRONICS.h b/Marlin/pins_MINITRONICS.h index 43f63ab231..fbdf7cbb66 100644 --- a/Marlin/pins_MINITRONICS.h +++ b/Marlin/pins_MINITRONICS.h @@ -104,9 +104,9 @@ #if ENABLED(REPRAPWORLD_GRAPHICAL_LCD) - #define LCD_PINS_RS 15 // CS chip select /SS chip slave select - #define LCD_PINS_ENABLE 11 // SID (MOSI) - #define LCD_PINS_D4 10 // SCK (CLK) clock + #define LCD_PINS_RS 15 // CS chip select /SS chip slave select + #define LCD_PINS_ENABLE 11 // SID (MOSI) + #define LCD_PINS_D4 10 // SCK (CLK) clock #define BTN_EN1 18 #define BTN_EN2 17 diff --git a/Marlin/pins_RAMBO.h b/Marlin/pins_RAMBO.h index a317b1b763..268ebfefcb 100644 --- a/Marlin/pins_RAMBO.h +++ b/Marlin/pins_RAMBO.h @@ -151,12 +151,12 @@ #if ENABLED(NEWPANEL) - #define LCD_PINS_RS 70 + #define LCD_PINS_RS 70 #define LCD_PINS_ENABLE 71 - #define LCD_PINS_D4 72 - #define LCD_PINS_D5 73 - #define LCD_PINS_D6 74 - #define LCD_PINS_D7 75 + #define LCD_PINS_D4 72 + #define LCD_PINS_D5 73 + #define LCD_PINS_D6 74 + #define LCD_PINS_D7 75 #if ENABLED(VIKI2) || ENABLED(miniVIKI) #define BEEPER_PIN 44 @@ -202,12 +202,12 @@ //#define SHIFT_OUT 40 //#define SHIFT_EN 17 - #define LCD_PINS_RS 75 + #define LCD_PINS_RS 75 #define LCD_PINS_ENABLE 17 - #define LCD_PINS_D4 23 - #define LCD_PINS_D5 25 - #define LCD_PINS_D6 27 - #define LCD_PINS_D7 29 + #define LCD_PINS_D4 23 + #define LCD_PINS_D5 25 + #define LCD_PINS_D6 27 + #define LCD_PINS_D7 29 #endif // !NEWPANEL diff --git a/Marlin/pins_RAMPS.h b/Marlin/pins_RAMPS.h index 4939a2b245..411e0f47ca 100644 --- a/Marlin/pins_RAMPS.h +++ b/Marlin/pins_RAMPS.h @@ -220,25 +220,25 @@ #if ENABLED(ULTRA_LCD) #if ENABLED(REPRAPWORLD_GRAPHICAL_LCD) - #define LCD_PINS_RS 49 // CS chip select /SS chip slave select - #define LCD_PINS_ENABLE 51 // SID (MOSI) - #define LCD_PINS_D4 52 // SCK (CLK) clock + #define LCD_PINS_RS 49 // CS chip select /SS chip slave select + #define LCD_PINS_ENABLE 51 // SID (MOSI) + #define LCD_PINS_D4 52 // SCK (CLK) clock #elif ENABLED(NEWPANEL) && ENABLED(PANEL_ONE) - #define LCD_PINS_RS 40 - #define LCD_PINS_ENABLE 42 - #define LCD_PINS_D4 65 - #define LCD_PINS_D5 66 - #define LCD_PINS_D6 44 - #define LCD_PINS_D7 64 + #define LCD_PINS_RS 40 + #define LCD_PINS_ENABLE 42 + #define LCD_PINS_D4 65 + #define LCD_PINS_D5 66 + #define LCD_PINS_D6 44 + #define LCD_PINS_D7 64 #else - #define LCD_PINS_RS 16 - #define LCD_PINS_ENABLE 17 - #define LCD_PINS_D4 23 - #define LCD_PINS_D5 25 - #define LCD_PINS_D6 27 - #define LCD_PINS_D7 29 + #define LCD_PINS_RS 16 + #define LCD_PINS_ENABLE 17 + #define LCD_PINS_D4 23 + #define LCD_PINS_D5 25 + #define LCD_PINS_D6 27 + #define LCD_PINS_D7 29 #if DISABLED(NEWPANEL) - #define BEEPER_PIN 33 + #define BEEPER_PIN 33 // Buttons are attached to a shift register // Not wired yet //#define SHIFT_CLK 38 @@ -251,118 +251,125 @@ #if ENABLED(NEWPANEL) #if ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) - #define BEEPER_PIN 37 - #define BTN_EN1 31 - #define BTN_EN2 33 - #define BTN_ENC 35 + #define BEEPER_PIN 37 - #define SD_DETECT_PIN 49 - #define KILL_PIN 41 + #define BTN_EN1 31 + #define BTN_EN2 33 + #define BTN_ENC 35 + + #define SD_DETECT_PIN 49 + #define KILL_PIN 41 #if ENABLED(BQ_LCD_SMART_CONTROLLER) #define LCD_BACKLIGHT_PIN 39 #endif #elif ENABLED(REPRAPWORLD_GRAPHICAL_LCD) - #define BTN_EN1 64 - #define BTN_EN2 59 - #define BTN_ENC 63 - #define SD_DETECT_PIN 42 + + #define BTN_EN1 64 + #define BTN_EN2 59 + #define BTN_ENC 63 + #define SD_DETECT_PIN 42 + #elif ENABLED(LCD_I2C_PANELOLU2) - #define BTN_EN1 47 // reverse if the encoder turns the wrong way. - #define BTN_EN2 43 - #define BTN_ENC 32 - #define LCD_SDSS 53 - #define SD_DETECT_PIN -1 - #define KILL_PIN 41 + + #define BTN_EN1 47 + #define BTN_EN2 43 + #define BTN_ENC 32 + #define LCD_SDSS 53 + #define SD_DETECT_PIN -1 + #define KILL_PIN 41 + #elif ENABLED(LCD_I2C_VIKI) - #define BTN_EN1 22 // reverse if the encoder turns the wrong way. - #define BTN_EN2 7 // http://files.panucatt.com/datasheets/viki_wiring_diagram.pdf - // tells about 40/42. - // 22/7 are unused on RAMPS_14. 22 is unused and 7 the SERVO0_PIN on RAMPS_13. - #define BTN_ENC -1 - #define LCD_SDSS 53 - #define SD_DETECT_PIN 49 + + #define BTN_EN1 22 // http://files.panucatt.com/datasheets/viki_wiring_diagram.pdf explains 40/42. + #define BTN_EN2 7 // 22/7 are unused on RAMPS_14. 22 is unused and 7 the SERVO0_PIN on RAMPS_13. + + #define BTN_ENC -1 + #define LCD_SDSS 53 + #define SD_DETECT_PIN 49 + #elif ENABLED(VIKI2) || ENABLED(miniVIKI) - #define BEEPER_PIN 33 + + #define BEEPER_PIN 33 // Pins for DOGM SPI LCD Support - #define DOGLCD_A0 44 - #define DOGLCD_CS 45 + #define DOGLCD_A0 44 + #define DOGLCD_CS 45 #define LCD_SCREEN_ROT_180 - #define BTN_EN1 22 - #define BTN_EN2 7 - #define BTN_ENC 39 + #define BTN_EN1 22 + #define BTN_EN2 7 + #define BTN_ENC 39 - #define SDSS 53 - #define SD_DETECT_PIN -1 // Pin 49 for display sd interface, 72 for easy adapter board + #define SDSS 53 + #define SD_DETECT_PIN -1 // Pin 49 for display sd interface, 72 for easy adapter board - #define KILL_PIN 31 + #define KILL_PIN 31 - #define STAT_LED_RED_PIN 32 + #define STAT_LED_RED_PIN 32 #define STAT_LED_BLUE_PIN 35 #elif ENABLED(ELB_FULL_GRAPHIC_CONTROLLER) - #define BTN_EN1 35 // reverse if the encoder turns the wrong way. - #define BTN_EN2 37 - #define BTN_ENC 31 - #define SD_DETECT_PIN 49 - #define LCD_SDSS 53 - #define KILL_PIN 41 - #define BEEPER_PIN 23 - #define DOGLCD_CS 29 - #define DOGLCD_A0 27 + #define BTN_EN1 35 + #define BTN_EN2 37 + #define BTN_ENC 31 + #define SD_DETECT_PIN 49 + #define LCD_SDSS 53 + #define KILL_PIN 41 + #define BEEPER_PIN 23 + #define DOGLCD_CS 29 + #define DOGLCD_A0 27 #define LCD_BACKLIGHT_PIN 33 #elif ENABLED(MINIPANEL) - #define BEEPER_PIN 42 + #define BEEPER_PIN 42 // Pins for DOGM SPI LCD Support - #define DOGLCD_A0 44 - #define DOGLCD_CS 66 + #define DOGLCD_A0 44 + #define DOGLCD_CS 66 #define LCD_BACKLIGHT_PIN 65 // backlight LED on A11/D65 - #define SDSS 53 + #define SDSS 53 - #define KILL_PIN 64 + #define KILL_PIN 64 // GLCD features - //#define LCD_CONTRAST 190 + //#define LCD_CONTRAST 190 // Uncomment screen orientation //#define LCD_SCREEN_ROT_90 //#define LCD_SCREEN_ROT_180 //#define LCD_SCREEN_ROT_270 // The encoder and click button - #define BTN_EN1 40 - #define BTN_EN2 63 - #define BTN_ENC 59 + #define BTN_EN1 40 + #define BTN_EN2 63 + #define BTN_ENC 59 // not connected to a pin - #define SD_DETECT_PIN 49 + #define SD_DETECT_PIN 49 #else // Beeper on AUX-4 - #define BEEPER_PIN 33 + #define BEEPER_PIN 33 // buttons are directly attached using AUX-2 #if ENABLED(REPRAPWORLD_KEYPAD) - #define BTN_EN1 64 // encoder - #define BTN_EN2 59 // encoder - #define BTN_ENC 63 // enter button - #define SHIFT_OUT 40 // shift register - #define SHIFT_CLK 44 // shift register - #define SHIFT_LD 42 // shift register + #define BTN_EN1 64 + #define BTN_EN2 59 + #define BTN_ENC 63 + #define SHIFT_OUT 40 + #define SHIFT_CLK 44 + #define SHIFT_LD 42 #elif ENABLED(PANEL_ONE) - #define BTN_EN1 59 // AUX2 PIN 3 - #define BTN_EN2 63 // AUX2 PIN 4 - #define BTN_ENC 49 // AUX3 PIN 7 + #define BTN_EN1 59 // AUX2 PIN 3 + #define BTN_EN2 63 // AUX2 PIN 4 + #define BTN_ENC 49 // AUX3 PIN 7 #else - #define BTN_EN1 37 - #define BTN_EN2 35 - #define BTN_ENC 31 // the click + #define BTN_EN1 37 + #define BTN_EN2 35 + #define BTN_ENC 31 #endif #if ENABLED(G3D_PANEL) - #define SD_DETECT_PIN 49 - #define KILL_PIN 41 + #define SD_DETECT_PIN 49 + #define KILL_PIN 41 #else //#define SD_DETECT_PIN -1 // Ramps doesn't use this #endif diff --git a/Marlin/pins_SCOOVO_X9H.h b/Marlin/pins_SCOOVO_X9H.h index a687c97285..6b7cf4f800 100644 --- a/Marlin/pins_SCOOVO_X9H.h +++ b/Marlin/pins_SCOOVO_X9H.h @@ -126,21 +126,21 @@ // // LCD / Controller // -#define LCD_PINS_RS 70 // Ext2_5 -#define LCD_PINS_ENABLE 71 // Ext2_7 -#define LCD_PINS_D4 72 // Ext2_9 ? -#define LCD_PINS_D5 73 // Ext2_11 ? -#define LCD_PINS_D6 74 // Ext2_13 -#define LCD_PINS_D7 75 // Ext2_15 ? +#define LCD_PINS_RS 70 // Ext2_5 +#define LCD_PINS_ENABLE 71 // Ext2_7 +#define LCD_PINS_D4 72 // Ext2_9 ? +#define LCD_PINS_D5 73 // Ext2_11 ? +#define LCD_PINS_D6 74 // Ext2_13 +#define LCD_PINS_D7 75 // Ext2_15 ? #define BEEPER_PIN -1 -#define BTN_HOME 80 // Ext_16 -#define BTN_CENTER 81 // Ext_14 +#define BTN_HOME 80 // Ext_16 +#define BTN_CENTER 81 // Ext_14 #define BTN_ENC BTN_CENTER -#define BTN_RIGHT 82 // Ext_12 -#define BTN_LEFT 83 // Ext_10 -#define BTN_UP 84 // Ext2_8 -#define BTN_DOWN 85 // Ext2_6 +#define BTN_RIGHT 82 // Ext_12 +#define BTN_LEFT 83 // Ext_10 +#define BTN_UP 84 // Ext2_8 +#define BTN_DOWN 85 // Ext2_6 #define HOME_PIN BTN_HOME @@ -151,7 +151,7 @@ #define DOGLCD_CS 71 #define LCD_SCREEN_ROT_180 - #define SD_DETECT_PIN -1 // Pin 72 if using easy adapter board + #define SD_DETECT_PIN -1 // Pin 72 if using easy adapter board #define STAT_LED_RED_PIN 22 #define STAT_LED_BLUE_PIN 32 diff --git a/Marlin/pins_ULTIMAKER.h b/Marlin/pins_ULTIMAKER.h index cb11768071..d8e7d26bf3 100644 --- a/Marlin/pins_ULTIMAKER.h +++ b/Marlin/pins_ULTIMAKER.h @@ -109,7 +109,7 @@ #define SDSS 53 #define LED_PIN 13 #define PS_ON_PIN 12 -#define SUICIDE_PIN 54 // PIN that has to be turned on right after start, to keep power flowing. +#define SUICIDE_PIN 54 // PIN that has to be turned on right after start, to keep power flowing. #define CASE_LIGHT_PIN 8 // @@ -121,12 +121,12 @@ #if ENABLED(NEWPANEL) - #define LCD_PINS_RS 20 + #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 + #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 40 From 748bf323884fff054a7c998a4c27ea79a568a10b Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 8 Jun 2017 18:08:30 -0500 Subject: [PATCH 047/180] Unify AVR90USB: pinsDebug changes --- Marlin/Marlin_main.cpp | 68 ++++++---- Marlin/pinsDebug.h | 239 +++++++++++++++++++++------------ Marlin/pinsDebug_Teensyduino.h | 26 ++-- Marlin/pinsDebug_list.h | 34 ++++- 4 files changed, 235 insertions(+), 132 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index df12d05513..61c2fbefa9 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -732,9 +732,7 @@ void report_current_position_detail(); SERIAL_ECHOPAIR(", ", y); SERIAL_ECHOPAIR(", ", z); SERIAL_CHAR(')'); - - if (suffix) {serialprintPGM(suffix);} //won't compile for Teensy with the previous construction - else SERIAL_EOL(); + if (suffix) serialprintPGM(suffix); else SERIAL_EOL(); } void print_xyz(const char* prefix, const char* suffix, const float xyz[]) { @@ -6366,23 +6364,44 @@ inline void gcode_M42() { wait = parser.seen('W') ? parser.value_int() : 500; for (uint8_t pin = start; pin <= end; pin++) { + //report_pin_state_extended(pin, I_flag, false); + if (!I_flag && pin_is_protected(pin)) { - SERIAL_ECHOPAIR("Sensitive Pin: ", pin); - SERIAL_ECHOLNPGM(" untouched."); + report_pin_state_extended(pin, I_flag, true, "Untouched "); + SERIAL_EOL(); } else { - SERIAL_ECHOPAIR("Pulsing Pin: ", pin); - pinMode(pin, OUTPUT); - for (int16_t j = 0; j < repeat; j++) { - digitalWrite(pin, 0); - safe_delay(wait); - digitalWrite(pin, 1); - safe_delay(wait); - digitalWrite(pin, 0); - safe_delay(wait); + report_pin_state_extended(pin, I_flag, true, "Pulsing "); + #ifdef AVR_AT90USB1286_FAMILY // Teensy IDEs don't know about these pins so must use FASTIO + if (pin == 46) { + SET_OUTPUT(46); + 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); + } + } + else if (pin == 47) { + SET_OUTPUT(47); + 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); + } + } + else + #endif + { + pinMode(pin, OUTPUT); + for (int16_t j = 0; j < repeat; j++) { + digitalWrite(pin, 0); safe_delay(wait); + digitalWrite(pin, 1); safe_delay(wait); + digitalWrite(pin, 0); safe_delay(wait); + } } + } - SERIAL_CHAR('\n'); + SERIAL_EOL(); } SERIAL_ECHOLNPGM("Done."); @@ -6527,13 +6546,13 @@ inline void gcode_M42() { * M43 E - Enable / disable background endstop monitoring * - Machine continues to operate * - Reports changes to endstops - * - Toggles LED when an endstop changes + * - Toggles LED_PIN when an endstop changes * - Can not reliably catch the 5mS pulse from BLTouch type probes * * M43 T - Toggle pin(s) and report which pin is being toggled * S - Start Pin number. If not given, will default to 0 * L - End Pin number. If not given, will default to last pin defined for this board - * I - Flag to ignore Marlin's pin protection. Use with caution!!!! + * I - Flag to ignore Marlin's pin protection. Use with caution!!!! * R - Repeat pulses on each pin this number of times before continueing to next pin * W - Wait time (in miliseconds) between pulses. If not given will default to 500 * @@ -6542,7 +6561,7 @@ inline void gcode_M42() { */ inline void gcode_M43() { - if (parser.seen('T')) { // must be first ot else it's "S" and "E" parameters will execute endstop or servo test + if (parser.seen('T')) { // must be first or else it's "S" and "E" parameters will execute endstop or servo test toggle_pins(); return; } @@ -6576,6 +6595,7 @@ inline void gcode_M42() { for (int8_t pin = first_pin; pin <= last_pin; pin++) { if (pin_is_protected(pin) && !ignore_protection) continue; pinMode(pin, INPUT_PULLUP); + delay(1); /* if (IS_ANALOG(pin)) pin_state[pin - first_pin] = analogRead(pin - analogInputToDigitalPin(0)); // int16_t pin_state[...] @@ -6591,7 +6611,7 @@ inline void gcode_M42() { for (;;) { for (int8_t pin = first_pin; pin <= last_pin; pin++) { - if (pin_is_protected(pin)) continue; + if (pin_is_protected(pin) && !ignore_protection) continue; const byte val = /* IS_ANALOG(pin) @@ -6600,7 +6620,7 @@ inline void gcode_M42() { //*/ digitalRead(pin); if (val != pin_state[pin - first_pin]) { - report_pin_state(pin); + report_pin_state_extended(pin, ignore_protection, false); pin_state[pin - first_pin] = val; } } @@ -6612,14 +6632,14 @@ inline void gcode_M42() { } #endif - safe_delay(500); + safe_delay(200); } return; } // Report current state of selected pin(s) for (uint8_t pin = first_pin; pin <= last_pin; pin++) - report_pin_state_extended(pin, ignore_protection); + report_pin_state_extended(pin, ignore_protection, true); } #endif // PINS_DEBUGGING @@ -12164,7 +12184,9 @@ void prepare_move_to_destination() { val &= 0x07; switch (digitalPinToTimer(pin)) { #ifdef TCCR0A - case TIMER0A: + #if !AVR_AT90USB1286_FAMILY + case TIMER0A: + #endif case TIMER0B: //_SET_CS(0, val); break; diff --git a/Marlin/pinsDebug.h b/Marlin/pinsDebug.h index dafd51e357..5bd13a491d 100644 --- a/Marlin/pinsDebug.h +++ b/Marlin/pinsDebug.h @@ -20,18 +20,13 @@ * */ - bool endstop_monitor_flag = false; -#define NAME_FORMAT "%-28s" // one place to specify the format of all the sources of names +#define NAME_FORMAT "%-35s" // one place to specify the format of all the sources of names // "-" left justify, "28" minimum width of name, pad with blanks #define IS_ANALOG(P) ((P) >= analogInputToDigitalPin(0) && ((P) <= analogInputToDigitalPin(15) || (P) <= analogInputToDigitalPin(7))) -#define AVR_ATmega2560_FAMILY (defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__) || defined(__AVR_ATmega1281__) || defined(__AVR_ATmega2561__) || defined(__AVR_ATmega1281__) || defined(__AVR_ATmega2561__)) -#define AVR_AT90USB1286_FAMILY (defined(__AVR_AT90USB1287__) || defined(__AVR_AT90USB1286__) || defined(__AVR_AT90USB1286P__) || defined(__AVR_AT90USB646__) || defined(__AVR_AT90USB646P__) || defined(__AVR_AT90USB647__)) -#define AVR_ATmega1284_FAMILY (defined(__AVR_ATmega644__) || defined(__AVR_ATmega644P__) || defined(__AVR_ATmega644PA__) || defined(__AVR_ATmega1284P__)) - /** * This routine minimizes RAM usage by creating a FLASH resident array to * store the pin names, pin numbers and analog/digital flag. @@ -52,7 +47,7 @@ bool endstop_monitor_flag = false; #define REPORT_NAME_ANALOG(NAME, COUNTER) _ADD_PIN(#NAME, COUNTER) #include "pinsDebug_list.h" -#line 56 +#line 51 // manually add pins that have names that are macros which don't play well with these macros #if SERIAL_PORT == 0 && (AVR_ATmega2560_FAMILY || AVR_ATmega1284_FAMILY) @@ -88,27 +83,34 @@ const char* const pin_array[][3] PROGMEM = { // manually add pins ... #if SERIAL_PORT == 0 #if AVR_ATmega2560_FAMILY - { RXD_NAME, "0", "1" }, - { TXD_NAME, "1", "1" }, + { RXD_NAME, 0, 1 }, + { TXD_NAME, 1, 1 }, #elif AVR_ATmega1284_FAMILY - { RXD_NAME, "8", "1" }, - { TXD_NAME, "9", "1" }, + { RXD_NAME, 8, 1 }, + { TXD_NAME, 9, 1 }, #endif #endif #include "pinsDebug_list.h" - #line 101 + #line 96 }; #define n_array (sizeof(pin_array) / sizeof(char*)) / 3 -#ifndef TIMER1B - // working with Teensyduino extension so need to re-define some things +#if AVR_AT90USB1286_FAMILY + // Working with Teensyduino extension so need to re-define some things #include "pinsDebug_Teensyduino.h" + // Can't use the "digitalPinToPort" function from the Teensyduino type IDEs + // portModeRegister takes a different argument + #define digitalPinToPort_DEBUG(p) digitalPinToPort_Teensy(p) + #define get_pinMode(pin) (*portModeRegister(pin) & digitalPinToBitMask(pin)) +#else + #define digitalPinToPort_DEBUG(p) digitalPinToPort(p) + bool get_pinMode(int8_t pin) {return *portModeRegister(digitalPinToPort_DEBUG(pin)) & digitalPinToBitMask(pin); } #endif -#define PWM_PRINT(V) do{ sprintf(buffer, "PWM: %4d", V); SERIAL_ECHO(buffer); }while(0) +#define PWM_PRINT(V) do{ sprintf_P(buffer, PSTR("PWM: %4d"), V); SERIAL_ECHO(buffer); }while(0) #define PWM_CASE(N,Z) \ case TIMER##N##Z: \ if (TCCR##N##A & (_BV(COM##N##Z##1) | _BV(COM##N##Z##0))) { \ @@ -127,7 +129,9 @@ static bool pwm_status(uint8_t pin) { #if defined(TCCR0A) && defined(COM0A1) #ifdef TIMER0A - PWM_CASE(0, A); + #if !AVR_AT90USB1286_FAMILY // not available in Teensyduino type IDEs + PWM_CASE(0, A); + #endif #endif PWM_CASE(0, B); #endif @@ -244,9 +248,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); } void com_print(uint8_t N, uint8_t Z) { - uint8_t *TCCRA = (uint8_t*)TCCR_A(N); + const uint8_t *TCCRA = (uint8_t*)TCCR_A(N); SERIAL_PROTOCOLPGM(" COM"); SERIAL_PROTOCOLCHAR(N + '0'); switch (Z) { @@ -264,8 +269,8 @@ void com_print(uint8_t N, uint8_t Z) { void timer_prefix(uint8_t T, char L, uint8_t N) { // T - timer L - pwm N - WGM bit layout char buffer[20]; // for the sprintf statements - uint8_t *TCCRB = (uint8_t*)TCCR_B(T); - uint8_t *TCCRA = (uint8_t*)TCCR_A(T); + const uint8_t *TCCRB = (uint8_t*)TCCR_B(T), + *TCCRA = (uint8_t*)TCCR_A(T); uint8_t WGM = (((*TCCRB & _BV(WGM_2)) >> 1) | (*TCCRA & (_BV(WGM_0) | _BV(WGM_1)))); if (N == 4) WGM |= ((*TCCRB & _BV(WGM_3)) >> 1); @@ -275,11 +280,11 @@ void timer_prefix(uint8_t T, char L, uint8_t N) { // T - timer L - pwm N - SERIAL_PROTOCOL_SP(3); if (N == 3) { - uint8_t *OCRVAL8 = (uint8_t*)OCR_VAL(T, L - 'A'); + const uint8_t *OCRVAL8 = (uint8_t*)OCR_VAL(T, L - 'A'); PWM_PRINT(*OCRVAL8); } else { - uint16_t *OCRVAL16 = (uint16_t*)OCR_VAL(T, L - 'A'); + const uint16_t *OCRVAL16 = (uint16_t*)OCR_VAL(T, L - 'A'); PWM_PRINT(*OCRVAL16); } SERIAL_PROTOCOLPAIR(" WGM: ", WGM); @@ -294,12 +299,12 @@ void timer_prefix(uint8_t T, char L, uint8_t N) { // T - timer L - pwm N - SERIAL_PROTOCOLCHAR(T + '0'); SERIAL_PROTOCOLPAIR("B: ", *TCCRB); - uint8_t *TMSK = (uint8_t*)TIMSK(T); + const uint8_t *TMSK = (uint8_t*)TIMSK(T); SERIAL_PROTOCOLPGM(" TIMSK"); SERIAL_PROTOCOLCHAR(T + '0'); SERIAL_PROTOCOLPAIR(": ", *TMSK); - uint8_t OCIE = L - 'A' + 1; + const uint8_t OCIE = L - 'A' + 1; if (N == 3) { if (WGM == 0 || WGM == 2 || WGM == 4 || WGM == 6) err_is_counter(); } else { if (WGM == 0 || WGM == 4 || WGM == 12 || WGM == 13) err_is_counter(); } if (TEST(*TMSK, OCIE)) err_is_interrupt(); @@ -311,7 +316,9 @@ static void pwm_details(uint8_t pin) { #if defined(TCCR0A) && defined(COM0A1) #ifdef TIMER0A - case TIMER0A: timer_prefix(0, 'A', 3); break; + #if !AVR_AT90USB1286_FAMILY // not available in Teensyduino type IDEs + case TIMER0A: timer_prefix(0, 'A', 3); break; + #endif #endif case TIMER0B: timer_prefix(0, 'B', 3); break; #endif @@ -357,136 +364,192 @@ static void pwm_details(uint8_t pin) { // on pins that have two PWMs, print info on second PWM #if AVR_ATmega2560_FAMILY || AVR_AT90USB1286_FAMILY // looking for port B7 - PWMs 0A and 1C - if (digitalPinToPort(pin) == 2 && digitalPinToBitMask(pin) == 0x80) { - #ifndef TEENSYDUINO_IDE + if (digitalPinToPort_DEBUG(pin) == 'B' - 64 && 0x80 == digitalPinToBitMask(pin)) { + #if !AVR_AT90USB1286_FAMILY SERIAL_PROTOCOLPGM("\n ."); SERIAL_PROTOCOL_SP(18); - SERIAL_PROTOCOLPGM("TIMER1C is also tied to this pin"); - SERIAL_PROTOCOL_SP(13); + SERIAL_PROTOCOLPGM("TIMER1C"); + print_is_also_tied(); timer_prefix(1, 'C', 4); #else SERIAL_PROTOCOLPGM("\n ."); SERIAL_PROTOCOL_SP(18); - SERIAL_PROTOCOLPGM("TIMER0A is also tied to this pin"); - SERIAL_PROTOCOL_SP(13); + SERIAL_PROTOCOLPGM("TIMER0A"); + print_is_also_tied(); timer_prefix(0, 'A', 3); #endif } #endif } // pwm_details -bool get_pinMode(int8_t pin) { return *portModeRegister(digitalPinToPort(pin)) & digitalPinToBitMask(pin); } - -#ifndef digitalRead_mod // use Teensyduino's version of digitalRead - it doesn't disable the PWMs - int digitalRead_mod(int8_t pin) { // same as digitalRead except the PWM stop section has been removed - uint8_t port = digitalPinToPort(pin); +#ifndef digitalRead_mod // Use Teensyduino's version of digitalRead - it doesn't disable the PWMs + int digitalRead_mod(const int8_t pin) { // same as digitalRead except the PWM stop section has been removed + const uint8_t port = digitalPinToPort_DEBUG(pin); return (port != NOT_A_PIN) && (*portInputRegister(port) & digitalPinToBitMask(pin)) ? HIGH : LOW; } #endif void print_port(int8_t pin) { // print port number - #ifdef digitalPinToPort + #ifdef digitalPinToPort_DEBUG + uint8_t x; SERIAL_PROTOCOLPGM(" Port: "); - uint8_t x = digitalPinToPort(pin) + 64; + #if AVR_AT90USB1286_FAMILY + x = (pin == 46 || pin == 47) ? 'E' : digitalPinToPort_DEBUG(pin) + 64; + #else + x = digitalPinToPort_DEBUG(pin) + 64; + #endif SERIAL_CHAR(x); - uint8_t temp = digitalPinToBitMask(pin); - for (x = '0'; x < '9' && temp != 1; x++) temp >>= 1; + + #if AVR_AT90USB1286_FAMILY + if (pin == 46) + x = '2'; + else if (pin == 47) + x = '3'; + else { + uint8_t temp = digitalPinToBitMask(pin); + for (x = '0'; x < '9' && temp != 1; x++) temp >>= 1; + } + #else + uint8_t temp = digitalPinToBitMask(pin); + for (x = '0'; x < '9' && temp != 1; x++) temp >>= 1; + #endif SERIAL_CHAR(x); #else SERIAL_PROTOCOL_SP(10); #endif } +static void print_input_or_output(const bool isout) { + serialprintPGM(isout ? PSTR("Output = ") : PSTR("Input = ")); +} + // pretty report with PWM info -inline void report_pin_state_extended(int8_t pin, bool ignore, bool extended = true) { +inline void report_pin_state_extended(int8_t pin, bool ignore, bool extended = false,const char *start_string = "") { uint8_t temp_char; - char *name_mem_pointer; - char buffer[30]; // for the sprintf statements - bool found = false, - multi_name_pin = false; + char *name_mem_pointer, buffer[30]; // for the sprintf statements + bool found = false, multi_name_pin = false; for (uint8_t x = 0; x < n_array; x++) { // scan entire array and report all instances of this pin if (pgm_read_byte(&pin_array[x][1]) == pin) { if (found) multi_name_pin = true; found = true; if (!multi_name_pin) { // report digitial and analog pin number only on the first time through - sprintf(buffer, "PIN: %3d ", pin); // digital pin number + sprintf_P(buffer, PSTR("%sPIN: %3d "), start_string, pin); // digital pin number SERIAL_ECHO(buffer); print_port(pin); if (IS_ANALOG(pin)) { - sprintf(buffer, " (A%2d) ", int(pin - analogInputToDigitalPin(0))); // analog pin number + sprintf_P(buffer, PSTR(" (A%2d) "), int(pin - analogInputToDigitalPin(0))); // analog pin number SERIAL_ECHO(buffer); } else SERIAL_ECHO_SP(8); // add padding if not an analog pin } else { SERIAL_CHAR('.'); - SERIAL_ECHO_SP(25); // add padding if not the first instance found + SERIAL_ECHO_SP(26 + strlen(start_string)); // add padding if not the first instance found } name_mem_pointer = (char*)pgm_read_word(&pin_array[x][0]); for (uint8_t y = 0; y < 28; y++) { // always print pin name temp_char = pgm_read_byte(name_mem_pointer + y); - if (temp_char != 0) MYSERIAL.write(temp_char); + if (temp_char != 0) + MYSERIAL.write(temp_char); else { for (uint8_t i = 0; i < 28 - y; i++) MYSERIAL.write(' '); break; } } - if (pin_is_protected(pin) && !ignore) - SERIAL_ECHOPGM("protected "); - else { - if (!(pgm_read_byte(&pin_array[x][2]))) { - sprintf(buffer, "Analog in = %5d", analogRead(pin - analogInputToDigitalPin(0))); - SERIAL_ECHO(buffer); - } + if (extended) { + if (pin_is_protected(pin) && !ignore) + SERIAL_ECHOPGM("protected "); else { - if (!get_pinMode(pin)) { - //pinMode(pin, INPUT_PULLUP); // make sure input isn't floating - stopped doing this - // because this could interfere with inductive/capacitive - // sensors (high impedance voltage divider) and with PT100 amplifier - SERIAL_PROTOCOLPAIR("Input = ", digitalRead_mod(pin)); + #ifdef AVR_AT90USB1286_FAMILY // Teensy IDEs don't know about these pins so must use FASTIO + if (pin == 46) { + print_input_or_output(GET_OUTPUT(46)); + SERIAL_PROTOCOL(READ(46)); + } + else if (pin == 47) + print_input_or_output(GET_OUTPUT(47)); + SERIAL_PROTOCOL(READ(47)); + } + else + #endif + { + if (!(pgm_read_byte(&pin_array[x][2]))) { + sprintf_P(buffer, PSTR("Analog in = %5d"), analogRead(pin - analogInputToDigitalPin(0))); + SERIAL_ECHO(buffer); + } + else { + + if (!get_pinMode(pin)) { + //pinMode(pin, INPUT_PULLUP); // make sure input isn't floating - stopped doing this + // because this could interfere with inductive/capacitive + // sensors (high impedance voltage divider) and with PT100 amplifier + print_input_or_output(false); + SERIAL_PROTOCOL(digitalRead_mod(pin)); + } + else if (pwm_status(pin)) { + // do nothing + } + else { + print_input_or_output(true); + SERIAL_PROTOCOL(digitalRead_mod(pin)); + } + } + if (!multi_name_pin && extended) pwm_details(pin); // report PWM capabilities only on the first pass & only if doing an extended report } - else if (pwm_status(pin)) { - // do nothing - } - else SERIAL_PROTOCOLPAIR("Output = ", digitalRead_mod(pin)); } - if (!multi_name_pin && extended) pwm_details(pin); // report PWM capabilities only on the first pass & only if doing an extended report } SERIAL_EOL(); } // end of IF } // end of for loop if (!found) { - sprintf(buffer, "PIN: %3d ", pin); + sprintf_P(buffer, PSTR("%sPIN: %3d "), start_string, pin); SERIAL_ECHO(buffer); print_port(pin); if (IS_ANALOG(pin)) { - sprintf(buffer, " (A%2d) ", int(pin - analogInputToDigitalPin(0))); // analog pin number + sprintf_P(buffer, PSTR(" (A%2d) "), int(pin - analogInputToDigitalPin(0))); // analog pin number SERIAL_ECHO(buffer); } - else - SERIAL_ECHO_SP(8); // add padding if not an analog pin - SERIAL_ECHOPGM(""); - if (get_pinMode(pin)) { - SERIAL_PROTOCOL_SP(12); - SERIAL_PROTOCOLPAIR("Output = ", digitalRead_mod(pin)); - } else { - if (IS_ANALOG(pin)) { - sprintf(buffer, " Analog in = %5d", analogRead(pin - analogInputToDigitalPin(0))); - SERIAL_ECHO(buffer); - } - else - SERIAL_ECHO_SP(9); // add padding if not an analog pin + SERIAL_ECHO_SP(8); // add padding if not an analog pin + SERIAL_ECHOPGM(""); + if (extended) { + #ifdef AVR_AT90USB1286_FAMILY // Teensy IDEs don't know about these pins so must use FASTIO + if (pin == 46 || pin == 47) { + SERIAL_PROTOCOL_SP(12); + if (pin == 46) { + print_input_or_output(GET_OUTPUT(46)); + SERIAL_PROTOCOL(READ(46)); + } + else { + print_input_or_output(GET_OUTPUT(47)); + SERIAL_PROTOCOL(READ(47)); + } + } + else + #endif + { + if (get_pinMode(pin)) { + SERIAL_PROTOCOL_SP(12); + print_input_or_output(true); + SERIAL_PROTOCOL(digitalRead_mod(pin)); + } + else { + if (IS_ANALOG(pin)) { + sprintf_P(buffer, PSTR(" Analog in = %5d"), analogRead(pin - analogInputToDigitalPin(0))); + SERIAL_ECHO(buffer); + SERIAL_ECHOPGM(" "); + } + else + SERIAL_ECHO_SP(12); // add padding if not an analog pin - SERIAL_PROTOCOLPAIR(" Input = ", digitalRead_mod(pin)); + print_input_or_output(false); + SERIAL_PROTOCOL(digitalRead_mod(pin)); + } + //if (!pwm_status(pin)) SERIAL_CHAR(' '); // add padding if it's not a PWM pin + if (extended) pwm_details(pin); // report PWM capabilities only if doing an extended report + } + } + SERIAL_EOL(); } - //if (!pwm_status(pin)) SERIAL_CHAR(' '); // add padding if it's not a PWM pin - if (extended) pwm_details(pin); // report PWM capabilities only if doing an extended report - SERIAL_EOL(); } } - -inline void report_pin_state(int8_t pin) { - report_pin_state_extended(pin, false, false); -} diff --git a/Marlin/pinsDebug_Teensyduino.h b/Marlin/pinsDebug_Teensyduino.h index 187c190f68..797a2cd71f 100644 --- a/Marlin/pinsDebug_Teensyduino.h +++ b/Marlin/pinsDebug_Teensyduino.h @@ -25,21 +25,16 @@ // do not function the same as the other Arduino extensions // +#ifndef __PINSDEBUG_TEENSYDUINO_H__ +#define __PINSDEBUG_TEENSYDUINO_H__ -#define TEENSYDUINO_IDE +#undef NUM_DIGITAL_PINS +#define NUM_DIGITAL_PINS 48 // Teensy says 46 but FASTIO is 48 -//digitalPinToTimer(pin) function works like Arduino but Timers are not defined -#define TIMER0B 1 -#define TIMER1A 7 -#define TIMER1B 8 -#define TIMER1C 9 -#define TIMER2A 6 -#define TIMER2B 2 -#define TIMER3A 5 -#define TIMER3B 4 -#define TIMER3C 3 +// "digitalPinToPort" function just returns the pin number so need to create our own. +// Can't use the name "digitalPinToPort" for our own because it interferes with the +// FAST_PWM_FAN function if we do -// digitalPinToPort function just returns the pin number so need to create our own #define PA 1 #define PB 2 #define PC 3 @@ -47,9 +42,8 @@ #define PE 5 #define PF 6 -#undef digitalPinToPort -const uint8_t PROGMEM digital_pin_to_port_PGM[] = { +const uint8_t PROGMEM digital_pin_to_port_PGM_Teensy[] = { PD, // 0 - PD0 - INT0 - PWM PD, // 1 - PD1 - INT1 - PWM PD, // 2 - PD2 - INT2 - RX @@ -100,7 +94,7 @@ const uint8_t PROGMEM digital_pin_to_port_PGM[] = { PE, // 47 - PE3 (not defined in teensyduino) }; -#define digitalPinToPort(P) ( pgm_read_byte( digital_pin_to_port_PGM + (P) ) ) +#define digitalPinToPort_Teensy(P) ( pgm_read_byte( digital_pin_to_port_PGM_Teensy + (P) ) ) // digitalPinToBitMask(pin) is OK @@ -108,3 +102,5 @@ const uint8_t PROGMEM digital_pin_to_port_PGM[] = { // disable the PWMs so we can use it as is // portModeRegister(pin) is OK + +#endif // __PINSDEBUG_TEENSYDUINO_H__ diff --git a/Marlin/pinsDebug_list.h b/Marlin/pinsDebug_list.h index dfdd411046..90eaa1c620 100644 --- a/Marlin/pinsDebug_list.h +++ b/Marlin/pinsDebug_list.h @@ -353,22 +353,22 @@ #if defined(LCD_CONTRAST) && LCD_CONTRAST >= 0 REPORT_NAME_DIGITAL(LCD_CONTRAST, __LINE__ ) #endif -#if PIN_EXISTS(LCD) +#if defined(LCD_PINS_D4) && LCD_PINS_D4 >= 0 REPORT_NAME_DIGITAL(LCD_PINS_D4, __LINE__ ) #endif -#if PIN_EXISTS(LCD) +#if defined(LCD_PINS_D5) && LCD_PINS_D5 >= 0 REPORT_NAME_DIGITAL(LCD_PINS_D5, __LINE__ ) #endif -#if PIN_EXISTS(LCD) +#if defined(LCD_PINS_D6) && LCD_PINS_D6 >= 0 REPORT_NAME_DIGITAL(LCD_PINS_D6, __LINE__ ) #endif -#if PIN_EXISTS(LCD) +#if defined(LCD_PINS_D7) && LCD_PINS_D7 >= 0 REPORT_NAME_DIGITAL(LCD_PINS_D7, __LINE__ ) #endif -#if PIN_EXISTS(LCD) +#if defined(LCD_PINS_ENABLE) && LCD_PINS_ENABLE >= 0 REPORT_NAME_DIGITAL(LCD_PINS_ENABLE, __LINE__ ) #endif -#if PIN_EXISTS(LCD) +#if defined(LCD_PINS_RS) && LCD_PINS_RS >= 0 REPORT_NAME_DIGITAL(LCD_PINS_RS, __LINE__ ) #endif #if defined(LCD_SDSS) && LCD_SDSS >= 0 @@ -446,6 +446,18 @@ #if PIN_EXISTS(RAMPS_D9) REPORT_NAME_DIGITAL(RAMPS_D9_PIN, __LINE__ ) #endif +#if PIN_EXISTS(RGB_LED_R) + REPORT_NAME_DIGITAL(RGB_LED_R_PIN, __LINE__ ) +#endif +#if PIN_EXISTS(RGB_LED_G) + REPORT_NAME_DIGITAL(RGB_LED_G_PIN, __LINE__ ) +#endif +#if PIN_EXISTS(RGB_LED_B) + REPORT_NAME_DIGITAL(RGB_LED_B_PIN, __LINE__ ) +#endif +#if PIN_EXISTS(RGB_LED_W) + REPORT_NAME_DIGITAL(RGB_LED_W_PIN, __LINE__ ) +#endif #if PIN_EXISTS(RX_ENABLE) REPORT_NAME_DIGITAL(RX_ENABLE_PIN, __LINE__ ) #endif @@ -500,12 +512,21 @@ #if PIN_EXISTS(SLEEP_WAKE) REPORT_NAME_DIGITAL(SLEEP_WAKE_PIN, __LINE__ ) #endif +#if PIN_EXISTS(SOL0) + REPORT_NAME_DIGITAL(SOL0_PIN, __LINE__ ) +#endif #if PIN_EXISTS(SOL1) REPORT_NAME_DIGITAL(SOL1_PIN, __LINE__ ) #endif #if PIN_EXISTS(SOL2) REPORT_NAME_DIGITAL(SOL2_PIN, __LINE__ ) #endif +#if PIN_EXISTS(SOL3) + REPORT_NAME_DIGITAL(SOL3_PIN, __LINE__ ) +#endif +#if PIN_EXISTS(SOL4) + REPORT_NAME_DIGITAL(SOL4_PIN, __LINE__ ) +#endif #if defined(SPARE_IO) && SPARE_IO >= 0 REPORT_NAME_DIGITAL(SPARE_IO, __LINE__ ) #endif @@ -749,3 +770,4 @@ #if PIN_EXISTS(Z2_STEP) REPORT_NAME_DIGITAL(Z2_STEP_PIN, __LINE__ ) #endif + From 51bc50214afa2ab8faf706c511fcccefa2a1557b Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 8 Jun 2017 18:23:07 -0500 Subject: [PATCH 048/180] Save 8 bytes of SRAM --- Marlin/stepper_dac.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/stepper_dac.cpp b/Marlin/stepper_dac.cpp index 0e7b8c8137..322a9403f6 100644 --- a/Marlin/stepper_dac.cpp +++ b/Marlin/stepper_dac.cpp @@ -49,7 +49,7 @@ bool dac_present = false; const uint8_t dac_order[NUM_AXIS] = DAC_STEPPER_ORDER; - uint16_t dac_channel_pct[XYZE] = DAC_MOTOR_CURRENT_DEFAULT; + uint8_t dac_channel_pct[XYZE] = DAC_MOTOR_CURRENT_DEFAULT; int dac_init() { #if PIN_EXISTS(DAC_DISABLE) @@ -95,7 +95,7 @@ static float dac_amps(int8_t n) { return mcp4728_getDrvPct(dac_order[n]) * (DAC_STEPPER_MAX) * 0.125 * (1.0 / (DAC_STEPPER_SENSE)); } int16_t dac_current_get_percent(AxisEnum axis) { return mcp4728_getDrvPct(dac_order[axis]); } - void dac_current_set_percents(int16_t pct[XYZE]) { + void dac_current_set_percents(const int8_t pct[XYZE]) { LOOP_XYZE(i) dac_channel_pct[i] = pct[dac_order[i]]; mcp4728_setDrvPct(dac_channel_pct); } From 5a72b6818e03ee6722dcf2bae513474c9a2f510f Mon Sep 17 00:00:00 2001 From: Kai Date: Fri, 9 Jun 2017 12:32:09 +0200 Subject: [PATCH 049/180] update language_de.h Following #6990 some more translations and some grammar fixes --- Marlin/language_de.h | 38 +++++++++++++++++++++++++------------- 1 file changed, 25 insertions(+), 13 deletions(-) diff --git a/Marlin/language_de.h b/Marlin/language_de.h index 1a3080def8..5aa647b0d7 100644 --- a/Marlin/language_de.h +++ b/Marlin/language_de.h @@ -44,7 +44,7 @@ #define MSG_AUTOSTART _UxGT("Autostart") #define MSG_DISABLE_STEPPERS _UxGT("Motoren deaktivieren") // M84 #define MSG_DEBUG_MENU _UxGT("Debug Menu") -#define MSG_PROGRESS_BAR_TEST _UxGT("Fortschrittb. Test") +#define MSG_PROGRESS_BAR_TEST _UxGT("Fortschrittsb. Test") #define MSG_AUTO_HOME _UxGT("Home") // G28 #define MSG_AUTO_HOME_X _UxGT("Home X") #define MSG_AUTO_HOME_Y _UxGT("Home Y") @@ -74,8 +74,9 @@ #define MSG_EXTRUDE _UxGT("Extrudieren") #define MSG_RETRACT _UxGT("Retract") #define MSG_MOVE_AXIS _UxGT("Bewegen") -#define MSG_BED_LEVELING _UxGT("Bett nivellieren") +#define MSG_BED_LEVELING _UxGT("Bett Nivellierung") #define MSG_LEVEL_BED _UxGT("Bett nivellieren") +#define MSG_EDITING_STOPPED _UxGT("Netzbearb. angeh.") #define MSG_USER_MENU _UxGT("Benutzer Menü") #define MSG_MOVING _UxGT("In Bewegung...") #define MSG_FREE_XY _UxGT("Abstand XY") @@ -91,7 +92,7 @@ #define MSG_NOZZLE _UxGT("Düse") #define MSG_BED _UxGT("Bett") #define MSG_FAN_SPEED _UxGT("Lüfter") -#define MSG_FLOW _UxGT("Durchfluss") +#define MSG_FLOW _UxGT("Flussrate") #define MSG_CONTROL _UxGT("Einstellungen") #define MSG_MIN LCD_STR_THERMOMETER _UxGT(" min") #define MSG_MAX LCD_STR_THERMOMETER _UxGT(" max") @@ -110,6 +111,7 @@ #define MSG_VY_JERK _UxGT("V Y Jerk") #define MSG_VZ_JERK _UxGT("V Z Jerk") #define MSG_VE_JERK _UxGT("V E Jerk") +#define MSG_VELOCITY _UxGT("Geschwindigkeit") #define MSG_VMAX _UxGT("V max ") // space by purpose #define MSG_VMIN _UxGT("V min") #define MSG_VTRAV_MIN _UxGT("V min Leerfahrt") @@ -136,8 +138,8 @@ #define MSG_CONTRAST _UxGT("LCD Kontrast") #define MSG_STORE_EEPROM _UxGT("Konfig. speichern") #define MSG_LOAD_EEPROM _UxGT("Konfig. laden") -#define MSG_RESTORE_FAILSAFE _UxGT("Standardkonfiguration") -#define MSG_INIT_EEPROM _UxGT("EEPROM initialisieren") +#define MSG_RESTORE_FAILSAFE _UxGT("Standardwerte laden") +#define MSG_INIT_EEPROM _UxGT("Werkseinstellungen") #define MSG_REFRESH _UxGT("Aktualisieren") #define MSG_WATCH _UxGT("Info") #define MSG_PREPARE _UxGT("Vorbereitung") @@ -210,20 +212,25 @@ #define MSG_BILINEAR_LEVELING _UxGT("Bilineare Nivell.") #define MSG_UBL_LEVELING _UxGT("Unified Bed Leveling") #define MSG_MESH_LEVELING _UxGT("Netz Nivellierung") -#define MSG_INFO_STATS_MENU _UxGT("Drucker Stat.") +#define MSG_INFO_STATS_MENU _UxGT("Drucker Statistik") #define MSG_INFO_BOARD_MENU _UxGT("Board Info") #define MSG_INFO_THERMISTOR_MENU _UxGT("Thermistoren") #define MSG_INFO_EXTRUDERS _UxGT("Extruder") #define MSG_INFO_BAUDRATE _UxGT("Baud") #define MSG_INFO_PROTOCOL _UxGT("Protokoll") -#define MSG_CASE_LIGHT _UxGT("Licht") +#define MSG_CASE_LIGHT _UxGT("Beleuchtung") #define MSG_CASE_LIGHT_BRIGHTNESS _UxGT("Helligkeit") #if ENABLED(AUTO_BED_LEVELING_UBL) + #define MSG_UBL_DOING_G29 _UxGT("G29 UBL läuft!") #define MSG_UBL_UNHOMED _UxGT("Erst XYZ homen") #define MSG_UBL_TOOLS _UxGT("UBL Tools") #define MSG_UBL_LEVEL_BED _UxGT("Unified Bed Leveling") #define MSG_UBL_MANUAL_MESH _UxGT("Netz manuell erst.") + #define MSG_UBL_BC_INSERT _UxGT("Unterlegen & messen") + #define MSG_UBL_BC_INSERT2 _UxGT("Messen") + #define MSG_UBL_BC_REMOVE _UxGT("Entfernen & messen") + #define MSG_UBL_MOVING_TO_NEXT _UxGT("Nächster Punkt...") #define MSG_UBL_ACTIVATE_MESH _UxGT("UBL aktivieren") #define MSG_UBL_DEACTIVATE_MESH _UxGT("UBL deaktivieren") #define MSG_UBL_SET_BED_TEMP _UxGT("Bett Temp.") @@ -231,6 +238,8 @@ #define MSG_UBL_SET_HOTEND_TEMP _UxGT("Hotend Temp.") #define MSG_UBL_CUSTOM_HOTEND_TEMP MSG_UBL_SET_HOTEND_TEMP #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") #define MSG_UBL_BUILD_CUSTOM_MESH _UxGT("Eigenes Netz erst.") #define MSG_UBL_BUILD_MESH_MENU _UxGT("Netz erstellen") #define MSG_UBL_BUILD_PLA_MESH _UxGT("Netz erstellen PLA") @@ -241,11 +250,11 @@ #define MSG_UBL_VALIDATE_MESH_MENU _UxGT("Netz validieren") #define MSG_UBL_VALIDATE_PLA_MESH _UxGT("Netz validieren PLA") #define MSG_UBL_VALIDATE_ABS_MESH _UxGT("Netz validieren ABS") - #define MSG_UBL_VALIDATE_CUSTOM_MESH _UxGT("Eigenes Netz validieren") + #define MSG_UBL_VALIDATE_CUSTOM_MESH _UxGT("Eig. Netz validieren") #define MSG_UBL_CONTINUE_MESH _UxGT("Netzerst. forts.") #define MSG_UBL_MESH_LEVELING _UxGT("Netz Nivellierung") #define MSG_UBL_3POINT_MESH_LEVELING _UxGT("3-Punkt Nivellierung") - #define MSG_UBL_GRID_MESH_LEVELING _UxGT("Gitternetz Nivellierung") + #define MSG_UBL_GRID_MESH_LEVELING _UxGT("Gitternetz Nivell.") #define MSG_UBL_MESH_LEVEL _UxGT("Netz nivellieren") #define MSG_UBL_SIDE_POINTS _UxGT("Eckpunkte") #define MSG_UBL_MAP_TYPE _UxGT("Kartentyp") @@ -261,11 +270,14 @@ #define MSG_UBL_INVALIDATE_ALL _UxGT("Alles annullieren") #define MSG_UBL_INVALIDATE_CLOSEST _UxGT("Nächstlieg. ann.") #define MSG_UBL_FINE_TUNE_ALL _UxGT("Feineinstellung Alle") - #define MSG_UBL_FINE_TUNE_CLOSEST _UxGT("Feineinst- Nächstl.") + #define MSG_UBL_FINE_TUNE_CLOSEST _UxGT("Feineinst. Nächstl.") #define MSG_UBL_STORAGE_MESH_MENU _UxGT("Netz Speicherplatz") #define MSG_UBL_STORAGE_SLOT _UxGT("Memory Slot") #define MSG_UBL_LOAD_MESH _UxGT("Bett Netz laden") #define MSG_UBL_SAVE_MESH _UxGT("Bett Netz speichern") + #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") #endif // AUTO_BED_LEVELING_UBL #if LCD_WIDTH >= 20 @@ -304,13 +316,13 @@ #define MSG_FILAMENT_CHANGE_INIT_3 _UxGT("Filamentwechsels") #define MSG_FILAMENT_CHANGE_UNLOAD_1 _UxGT("Warte auf") #define MSG_FILAMENT_CHANGE_UNLOAD_2 _UxGT("Herausnahme") - #define MSG_FILAMENT_CHANGE_UNLOAD_3 _UxGT("des Filaments") + #define MSG_FILAMENT_CHANGE_UNLOAD_3 _UxGT("des Filaments...") #define MSG_FILAMENT_CHANGE_INSERT_1 _UxGT("Filament einlegen") #define MSG_FILAMENT_CHANGE_INSERT_2 _UxGT("und Knopf") #define MSG_FILAMENT_CHANGE_INSERT_3 _UxGT("drücken...") #define MSG_FILAMENT_CHANGE_HEAT_1 _UxGT("Knopf drücken um") #define MSG_FILAMENT_CHANGE_HEAT_2 _UxGT("Düse aufzuheizen.") - #define MSG_FILAMENT_CHANGE_HEATING_1 _UxGT("Düse heizt auf.") + #define MSG_FILAMENT_CHANGE_HEATING_1 _UxGT("Düse heizt auf...") #define MSG_FILAMENT_CHANGE_HEATING_2 _UxGT("Bitte warten...") #define MSG_FILAMENT_CHANGE_LOAD_1 _UxGT("Warte auf") #define MSG_FILAMENT_CHANGE_LOAD_2 _UxGT("Laden des") @@ -320,7 +332,7 @@ #define MSG_FILAMENT_CHANGE_EXTRUDE_3 _UxGT("Filaments") #define MSG_FILAMENT_CHANGE_RESUME_1 _UxGT("Warte auf") #define MSG_FILAMENT_CHANGE_RESUME_2 _UxGT("Fortsetzung des") - #define MSG_FILAMENT_CHANGE_RESUME_3 _UxGT("Druckes") + #define MSG_FILAMENT_CHANGE_RESUME_3 _UxGT("Druckes...") #else // LCD_HEIGHT < 4 // Up to 2 lines allowed #define MSG_FILAMENT_CHANGE_INIT_1 _UxGT("Bitte warten...") From 7864b133a841dd1aa71a18b39e7ceb24f95f4842 Mon Sep 17 00:00:00 2001 From: Dave Johnson Date: Fri, 9 Jun 2017 20:20:02 -0700 Subject: [PATCH 050/180] Fix get/setDrvPct declarations --- Marlin/dac_mcp4728.cpp | 4 ++-- Marlin/dac_mcp4728.h | 4 ++-- 2 files changed, 4 insertions(+), 4 deletions(-) diff --git a/Marlin/dac_mcp4728.cpp b/Marlin/dac_mcp4728.cpp index 2124a803e0..a06346c6eb 100644 --- a/Marlin/dac_mcp4728.cpp +++ b/Marlin/dac_mcp4728.cpp @@ -114,13 +114,13 @@ uint16_t mcp4728_getVout(uint8_t channel) { /** * Returns DAC values as a 0-100 percentage of drive strength */ -uint16_t mcp4728_getDrvPct(uint8_t channel) { return uint16_t(100.0 * mcp4728_values[channel] / (DAC_STEPPER_MAX) + 0.5); } +uint8_t mcp4728_getDrvPct(uint8_t channel) { return uint8_t(100.0 * mcp4728_values[channel] / (DAC_STEPPER_MAX) + 0.5); } /** * Receives all Drive strengths as 0-100 percent values, updates * DAC Values array and calls fastwrite to update the DAC. */ -void mcp4728_setDrvPct(uint16_t pct[XYZE]) { +void mcp4728_setDrvPct(uint8_t pct[XYZE]) { LOOP_XYZE(i) mcp4728_values[i] = 0.01 * pct[i] * (DAC_STEPPER_MAX); mcp4728_fastWrite(); } diff --git a/Marlin/dac_mcp4728.h b/Marlin/dac_mcp4728.h index a1e3e35503..f8337316de 100644 --- a/Marlin/dac_mcp4728.h +++ b/Marlin/dac_mcp4728.h @@ -59,8 +59,8 @@ uint8_t mcp4728_setGain_all(uint8_t value); uint16_t mcp4728_getValue(uint8_t channel); uint8_t mcp4728_fastWrite(); uint8_t mcp4728_simpleCommand(byte simpleCommand); -uint16_t mcp4728_getDrvPct(uint8_t channel); -void mcp4728_setDrvPct(uint16_t pct[XYZE]); +uint8_t mcp4728_getDrvPct(uint8_t channel); +void mcp4728_setDrvPct(uint8_t pct[XYZE]); #endif #endif // DAC_MCP4728_H From 92011e3d8c9a69f7655aa51a422cf1b66eeb3bfd Mon Sep 17 00:00:00 2001 From: Federico Date: Sat, 10 Jun 2017 21:50:14 +0200 Subject: [PATCH 051/180] Create language_it.h --- Marlin/language_it.h | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/Marlin/language_it.h b/Marlin/language_it.h index b0e8cc9fbf..f345e8bd83 100644 --- a/Marlin/language_it.h +++ b/Marlin/language_it.h @@ -56,13 +56,13 @@ #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(" Fine") +#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_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(" Fine") +#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_COOLDOWN _UxGT("Raffredda") @@ -135,7 +135,7 @@ #define MSG_FILAMENT _UxGT("Filamento") #define MSG_VOLUMETRIC_ENABLED _UxGT("E in mm3") #define MSG_FILAMENT_DIAM _UxGT("Diam. filo") -#define MSG_ADVANCE_K _UxGT("K avanzato") +#define MSG_ADVANCE_K _UxGT("K Avanzamento") #define MSG_CONTRAST _UxGT("Contrasto LCD") #define MSG_STORE_EEPROM _UxGT("Salva in memoria") #define MSG_LOAD_EEPROM _UxGT("Carica da memoria") @@ -150,7 +150,7 @@ #define MSG_CARD_MENU _UxGT("Stampa da SD") #define MSG_NO_CARD _UxGT("SD non presente") #define MSG_DWELL _UxGT("Sospensione...") -#define MSG_USERWAIT _UxGT("Attendi Utente..") +#define MSG_USERWAIT _UxGT("Premi tasto..") #define MSG_RESUMING _UxGT("Riprendi Stampa") #define MSG_PRINT_ABORTED _UxGT("Stampa annullata") #define MSG_NO_MOVE _UxGT("Nessun Movimento") From fc89de6d8b92bf13f5390e6918501c832509b6bd Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 10 Jun 2017 16:27:39 -0500 Subject: [PATCH 052/180] Followup to German language update --- Marlin/language_de.h | 114 +++++++++++++++++++++---------------------- 1 file changed, 56 insertions(+), 58 deletions(-) diff --git a/Marlin/language_de.h b/Marlin/language_de.h index 5aa647b0d7..a765b42fd7 100644 --- a/Marlin/language_de.h +++ b/Marlin/language_de.h @@ -221,64 +221,62 @@ #define MSG_CASE_LIGHT _UxGT("Beleuchtung") #define MSG_CASE_LIGHT_BRIGHTNESS _UxGT("Helligkeit") -#if ENABLED(AUTO_BED_LEVELING_UBL) - #define MSG_UBL_DOING_G29 _UxGT("G29 UBL läuft!") - #define MSG_UBL_UNHOMED _UxGT("Erst XYZ homen") - #define MSG_UBL_TOOLS _UxGT("UBL Tools") - #define MSG_UBL_LEVEL_BED _UxGT("Unified Bed Leveling") - #define MSG_UBL_MANUAL_MESH _UxGT("Netz manuell erst.") - #define MSG_UBL_BC_INSERT _UxGT("Unterlegen & messen") - #define MSG_UBL_BC_INSERT2 _UxGT("Messen") - #define MSG_UBL_BC_REMOVE _UxGT("Entfernen & messen") - #define MSG_UBL_MOVING_TO_NEXT _UxGT("Nächster Punkt...") - #define MSG_UBL_ACTIVATE_MESH _UxGT("UBL aktivieren") - #define MSG_UBL_DEACTIVATE_MESH _UxGT("UBL deaktivieren") - #define MSG_UBL_SET_BED_TEMP _UxGT("Bett Temp.") - #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_EDIT_CUSTOM_MESH _UxGT("Eigenes Netz bearb.") - #define MSG_UBL_FINE_TUNE_MESH _UxGT("Feineinstellung...") - #define MSG_UBL_DONE_EDITING_MESH _UxGT("Bearbeitung beendet") - #define MSG_UBL_BUILD_CUSTOM_MESH _UxGT("Eigenes Netz erst.") - #define MSG_UBL_BUILD_MESH_MENU _UxGT("Netz erstellen") - #define MSG_UBL_BUILD_PLA_MESH _UxGT("Netz erstellen PLA") - #define MSG_UBL_BUILD_ABS_MESH _UxGT("Netz erstellen ABS") - #define MSG_UBL_BUILD_COLD_MESH _UxGT("Netz erstellen kalt") - #define MSG_UBL_MESH_HEIGHT_ADJUST _UxGT("Netz Höhe einst.") - #define MSG_UBL_MESH_HEIGHT_AMOUNT _UxGT("Height Amount") - #define MSG_UBL_VALIDATE_MESH_MENU _UxGT("Netz validieren") - #define MSG_UBL_VALIDATE_PLA_MESH _UxGT("Netz validieren PLA") - #define MSG_UBL_VALIDATE_ABS_MESH _UxGT("Netz validieren ABS") - #define MSG_UBL_VALIDATE_CUSTOM_MESH _UxGT("Eig. Netz validieren") - #define MSG_UBL_CONTINUE_MESH _UxGT("Netzerst. forts.") - #define MSG_UBL_MESH_LEVELING _UxGT("Netz Nivellierung") - #define MSG_UBL_3POINT_MESH_LEVELING _UxGT("3-Punkt Nivellierung") - #define MSG_UBL_GRID_MESH_LEVELING _UxGT("Gitternetz Nivell.") - #define MSG_UBL_MESH_LEVEL _UxGT("Netz nivellieren") - #define MSG_UBL_SIDE_POINTS _UxGT("Eckpunkte") - #define MSG_UBL_MAP_TYPE _UxGT("Kartentyp") - #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_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") - #define MSG_UBL_MANUAL_FILLIN _UxGT("Manuelles Fill-in") - #define MSG_UBL_SMART_FILLIN _UxGT("Kluges Fill-in") - #define MSG_UBL_FILLIN_MESH _UxGT("Fill-in Netz") - #define MSG_UBL_INVALIDATE_ALL _UxGT("Alles annullieren") - #define MSG_UBL_INVALIDATE_CLOSEST _UxGT("Nächstlieg. ann.") - #define MSG_UBL_FINE_TUNE_ALL _UxGT("Feineinstellung Alle") - #define MSG_UBL_FINE_TUNE_CLOSEST _UxGT("Feineinst. Nächstl.") - #define MSG_UBL_STORAGE_MESH_MENU _UxGT("Netz Speicherplatz") - #define MSG_UBL_STORAGE_SLOT _UxGT("Memory Slot") - #define MSG_UBL_LOAD_MESH _UxGT("Bett Netz laden") - #define MSG_UBL_SAVE_MESH _UxGT("Bett Netz speichern") - #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") -#endif // AUTO_BED_LEVELING_UBL +#define MSG_UBL_DOING_G29 _UxGT("G29 UBL läuft!") +#define MSG_UBL_UNHOMED _UxGT("Erst XYZ homen") +#define MSG_UBL_TOOLS _UxGT("UBL Tools") +#define MSG_UBL_LEVEL_BED _UxGT("Unified Bed Leveling") +#define MSG_UBL_MANUAL_MESH _UxGT("Netz manuell erst.") +#define MSG_UBL_BC_INSERT _UxGT("Unterlegen & messen") +#define MSG_UBL_BC_INSERT2 _UxGT("Messen") +#define MSG_UBL_BC_REMOVE _UxGT("Entfernen & messen") +#define MSG_UBL_MOVING_TO_NEXT _UxGT("Nächster Punkt...") +#define MSG_UBL_ACTIVATE_MESH _UxGT("UBL aktivieren") +#define MSG_UBL_DEACTIVATE_MESH _UxGT("UBL deaktivieren") +#define MSG_UBL_SET_BED_TEMP _UxGT("Bett Temp.") +#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_EDIT_CUSTOM_MESH _UxGT("Eigenes Netz bearb.") +#define MSG_UBL_FINE_TUNE_MESH _UxGT("Feineinstellung...") +#define MSG_UBL_DONE_EDITING_MESH _UxGT("Bearbeitung beendet") +#define MSG_UBL_BUILD_CUSTOM_MESH _UxGT("Eigenes Netz erst.") +#define MSG_UBL_BUILD_MESH_MENU _UxGT("Netz erstellen") +#define MSG_UBL_BUILD_PLA_MESH _UxGT("Netz erstellen PLA") +#define MSG_UBL_BUILD_ABS_MESH _UxGT("Netz erstellen ABS") +#define MSG_UBL_BUILD_COLD_MESH _UxGT("Netz erstellen kalt") +#define MSG_UBL_MESH_HEIGHT_ADJUST _UxGT("Netz Höhe einst.") +#define MSG_UBL_MESH_HEIGHT_AMOUNT _UxGT("Height Amount") +#define MSG_UBL_VALIDATE_MESH_MENU _UxGT("Netz validieren") +#define MSG_UBL_VALIDATE_PLA_MESH _UxGT("Netz validieren PLA") +#define MSG_UBL_VALIDATE_ABS_MESH _UxGT("Netz validieren ABS") +#define MSG_UBL_VALIDATE_CUSTOM_MESH _UxGT("Eig. Netz validieren") +#define MSG_UBL_CONTINUE_MESH _UxGT("Netzerst. forts.") +#define MSG_UBL_MESH_LEVELING _UxGT("Netz Nivellierung") +#define MSG_UBL_3POINT_MESH_LEVELING _UxGT("3-Punkt Nivellierung") +#define MSG_UBL_GRID_MESH_LEVELING _UxGT("Gitternetz Nivell.") +#define MSG_UBL_MESH_LEVEL _UxGT("Netz nivellieren") +#define MSG_UBL_SIDE_POINTS _UxGT("Eckpunkte") +#define MSG_UBL_MAP_TYPE _UxGT("Kartentyp") +#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_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") +#define MSG_UBL_MANUAL_FILLIN _UxGT("Manuelles Fill-in") +#define MSG_UBL_SMART_FILLIN _UxGT("Kluges Fill-in") +#define MSG_UBL_FILLIN_MESH _UxGT("Fill-in Netz") +#define MSG_UBL_INVALIDATE_ALL _UxGT("Alles annullieren") +#define MSG_UBL_INVALIDATE_CLOSEST _UxGT("Nächstlieg. ann.") +#define MSG_UBL_FINE_TUNE_ALL _UxGT("Feineinstellung Alle") +#define MSG_UBL_FINE_TUNE_CLOSEST _UxGT("Feineinst. Nächstl.") +#define MSG_UBL_STORAGE_MESH_MENU _UxGT("Netz Speicherplatz") +#define MSG_UBL_STORAGE_SLOT _UxGT("Memory Slot") +#define MSG_UBL_LOAD_MESH _UxGT("Bett Netz laden") +#define MSG_UBL_SAVE_MESH _UxGT("Bett Netz speichern") +#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") #if LCD_WIDTH >= 20 #define MSG_INFO_PRINT_COUNT _UxGT("Gesamte Drucke") From 57a51fd5db7a13be1f00b0f08e0214b3dc1f5421 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 10 Jun 2017 16:39:48 -0500 Subject: [PATCH 053/180] Tweak some else clauses --- Marlin/G26_Mesh_Validation_Tool.cpp | 7 +++++-- Marlin/MarlinSerial.cpp | 3 ++- Marlin/nozzle.cpp | 6 ++++-- Marlin/planner.cpp | 11 +++-------- 4 files changed, 14 insertions(+), 13 deletions(-) diff --git a/Marlin/G26_Mesh_Validation_Tool.cpp b/Marlin/G26_Mesh_Validation_Tool.cpp index afbf2b1103..18a28b3c41 100644 --- a/Marlin/G26_Mesh_Validation_Tool.cpp +++ b/Marlin/G26_Mesh_Validation_Tool.cpp @@ -684,7 +684,8 @@ SERIAL_PROTOCOLLNPGM("?Prime length must be specified when not using an LCD."); return UBL_ERR; #endif - } else { + } + else { g26_prime_flag++; g26_prime_length = parser.value_linear_units(); if (!WITHIN(g26_prime_length, 0.0, 25.0)) { @@ -727,7 +728,9 @@ if (!parser.seen('R')) { SERIAL_PROTOCOLLNPGM("?(R)epeat must be specified when not using an LCD."); return UBL_ERR; - } else g26_repeats = parser.has_value() ? parser.value_int() : GRID_MAX_POINTS + 1; + } + else + g26_repeats = parser.has_value() ? parser.value_int() : GRID_MAX_POINTS + 1; #endif if (g26_repeats < 1) { SERIAL_PROTOCOLLNPGM("?(R)epeat value not plausible; must be at least 1."); diff --git a/Marlin/MarlinSerial.cpp b/Marlin/MarlinSerial.cpp index 2ee83def0a..235e018094 100644 --- a/Marlin/MarlinSerial.cpp +++ b/Marlin/MarlinSerial.cpp @@ -320,7 +320,8 @@ // space for us. if (TEST(M_UCSRxA, M_UDREx)) _tx_udr_empty_irq(); - } else { + } + else { // nop, the interrupt handler will free up space for us } } diff --git a/Marlin/nozzle.cpp b/Marlin/nozzle.cpp index 569fba62a6..e5706e862a 100644 --- a/Marlin/nozzle.cpp +++ b/Marlin/nozzle.cpp @@ -136,7 +136,8 @@ void Nozzle::circle( // Order of movement is pretty darn important here do_blocking_move_to_xy(start.x, start.y); do_blocking_move_to_z(start.z); - } else { + } + else { do_blocking_move_to_z(start.z); do_blocking_move_to_xy(start.x, start.y); } @@ -160,7 +161,8 @@ void Nozzle::circle( // As above order is important do_blocking_move_to_z(initial.z); do_blocking_move_to_xy(initial.x, initial.y); - } else { + } + else { do_blocking_move_to_xy(initial.x, initial.y); do_blocking_move_to_z(initial.z); } diff --git a/Marlin/planner.cpp b/Marlin/planner.cpp index dee6eaad02..a755db5767 100644 --- a/Marlin/planner.cpp +++ b/Marlin/planner.cpp @@ -470,14 +470,9 @@ void Planner::check_axes_activity() { if (fan_kick_end[f] == 0) { \ fan_kick_end[f] = ms + FAN_KICKSTART_TIME; \ tail_fan_speed[f] = 255; \ - } else { \ - if (PENDING(ms, fan_kick_end[f])) { \ - tail_fan_speed[f] = 255; \ - } \ - } \ - } else { \ - fan_kick_end[f] = 0; \ - } + } else if (PENDING(ms, fan_kick_end[f])) \ + tail_fan_speed[f] = 255; \ + } else fan_kick_end[f] = 0 #if HAS_FAN0 KICKSTART_FAN(0); From dde8bb7c8b0c90d3c6b4bef6977ce4bf7af97308 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 10 Jun 2017 18:29:17 -0500 Subject: [PATCH 054/180] Fix extrude_min_temp compiler warning --- Marlin/temperature.cpp | 2 +- Marlin/temperature.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/temperature.cpp b/Marlin/temperature.cpp index 911e7b6942..f62e5a94db 100644 --- a/Marlin/temperature.cpp +++ b/Marlin/temperature.cpp @@ -113,7 +113,7 @@ int16_t Temperature::current_temperature_raw[HOTENDS] = { 0 }, #if ENABLED(PREVENT_COLD_EXTRUSION) bool Temperature::allow_cold_extrude = false; - uint16_t Temperature::extrude_min_temp = EXTRUDE_MINTEMP; + int16_t Temperature::extrude_min_temp = EXTRUDE_MINTEMP; #endif // private: diff --git a/Marlin/temperature.h b/Marlin/temperature.h index 0e0556f942..18717dea21 100644 --- a/Marlin/temperature.h +++ b/Marlin/temperature.h @@ -172,7 +172,7 @@ class Temperature { #if ENABLED(PREVENT_COLD_EXTRUSION) static bool allow_cold_extrude; - static uint16_t extrude_min_temp; + static int16_t extrude_min_temp; static bool tooColdToExtrude(uint8_t e) { #if HOTENDS == 1 UNUSED(e); From da8e946efb55fc6924b17df17d986e33edd27f09 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 10 Jun 2017 18:59:23 -0500 Subject: [PATCH 055/180] Reduce size of heater state print code --- Marlin/Marlin_main.cpp | 102 ++++++++++++++++++++++------------------- 1 file changed, 56 insertions(+), 46 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 61c2fbefa9..d66a8d7092 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -5889,7 +5889,7 @@ inline void gcode_M17() { } static bool pause_print(const float &retract, const float &z_lift, const float &x_pos, const float &y_pos, - const float &unload_length = 0 , int8_t max_beep_count = 0, bool show_lcd = false + const float &unload_length = 0 , const int8_t max_beep_count = 0, const bool show_lcd = false ) { if (move_away_flag) return false; // already paused @@ -5989,7 +5989,7 @@ inline void gcode_M17() { return true; } - static void wait_for_filament_reload(int8_t max_beep_count = 0) { + static void wait_for_filament_reload(const int8_t max_beep_count = 0) { bool nozzle_timed_out = false; // Wait for filament insert by user and press button @@ -6014,7 +6014,7 @@ inline void gcode_M17() { KEEPALIVE_STATE(IN_HANDLER); } - static void resume_print(const float &load_length = 0, const float &initial_extrude_length = 0, int8_t max_beep_count = 0) { + static void resume_print(const float &load_length = 0, const float &initial_extrude_length = 0, const int8_t max_beep_count = 0) { bool nozzle_timed_out = false; if (!move_away_flag) return; @@ -6974,39 +6974,57 @@ inline void gcode_M104() { #if HAS_TEMP_HOTEND || HAS_TEMP_BED + void print_heater_state(const float &c, const float &t, + #if ENABLED(SHOW_TEMP_ADC_VALUES) + const float r, + #endif + const int8_t e=-2 + ) { + SERIAL_PROTOCOLCHAR(' '); + SERIAL_PROTOCOLCHAR( + #if HAS_TEMP_BED && HAS_TEMP_HOTEND + e == -1 ? 'B' : 'T' + #elif HAS_TEMP_HOTEND + 'T' + #else + 'B' + #endif + ); + #if HOTENDS > 1 + if (e >= 0) SERIAL_PROTOCOLCHAR('0' + e); + #endif + SERIAL_PROTOCOLCHAR(':'); + SERIAL_PROTOCOL(c); + SERIAL_PROTOCOLPAIR(" /" , t); + #if ENABLED(SHOW_TEMP_ADC_VALUES) + SERIAL_PROTOCOLPAIR(" (", r / OVERSAMPLENR); + SERIAL_PROTOCOLCHAR(')'); + #endif + } + void print_heaterstates() { #if HAS_TEMP_HOTEND - SERIAL_PROTOCOLPGM(" T:"); - SERIAL_PROTOCOL(thermalManager.degHotend(target_extruder)); - SERIAL_PROTOCOLPGM(" /"); - SERIAL_PROTOCOL(thermalManager.degTargetHotend(target_extruder)); - #if ENABLED(SHOW_TEMP_ADC_VALUES) - SERIAL_PROTOCOLPAIR(" (", thermalManager.rawHotendTemp(target_extruder) / OVERSAMPLENR); - SERIAL_PROTOCOLCHAR(')'); - #endif + print_heater_state(thermalManager.degHotend(target_extruder), thermalManager.degTargetHotend(target_extruder) + #if ENABLED(SHOW_TEMP_ADC_VALUES) + , thermalManager.rawHotendTemp(target_extruder) + #endif + ); #endif #if HAS_TEMP_BED - SERIAL_PROTOCOLPGM(" B:"); - SERIAL_PROTOCOL(thermalManager.degBed()); - SERIAL_PROTOCOLPGM(" /"); - SERIAL_PROTOCOL(thermalManager.degTargetBed()); - #if ENABLED(SHOW_TEMP_ADC_VALUES) - SERIAL_PROTOCOLPAIR(" (", thermalManager.rawBedTemp() / OVERSAMPLENR); - SERIAL_PROTOCOLCHAR(')'); - #endif + print_heater_state(thermalManager.degBed(), thermalManager.degTargetBed(), + #if ENABLED(SHOW_TEMP_ADC_VALUES) + thermalManager.rawBedTemp(), + #endif + -1 // BED + ); #endif #if HOTENDS > 1 - HOTEND_LOOP() { - SERIAL_PROTOCOLPAIR(" T", e); - SERIAL_PROTOCOLCHAR(':'); - SERIAL_PROTOCOL(thermalManager.degHotend(e)); - SERIAL_PROTOCOLPGM(" /"); - SERIAL_PROTOCOL(thermalManager.degTargetHotend(e)); + HOTEND_LOOP() print_heater_state(thermalManager.degHotend(e), thermalManager.degTargetHotend(e), #if ENABLED(SHOW_TEMP_ADC_VALUES) - SERIAL_PROTOCOLPAIR(" (", thermalManager.rawHotendTemp(e) / OVERSAMPLENR); - SERIAL_PROTOCOLCHAR(')'); + thermalManager.rawHotendTemp(e), #endif - } + e + ); #endif SERIAL_PROTOCOLPGM(" @:"); SERIAL_PROTOCOL(thermalManager.getHeaterPower(target_extruder)); @@ -7206,16 +7224,12 @@ inline void gcode_M109() { print_heaterstates(); #if TEMP_RESIDENCY_TIME > 0 SERIAL_PROTOCOLPGM(" W:"); - if (residency_start_ms) { - long rem = (((TEMP_RESIDENCY_TIME) * 1000UL) - (now - residency_start_ms)) / 1000UL; - SERIAL_PROTOCOLLN(rem); - } - else { - SERIAL_PROTOCOLLNPGM("?"); - } - #else - SERIAL_EOL(); + if (residency_start_ms) + SERIAL_PROTOCOL(long((((TEMP_RESIDENCY_TIME) * 1000UL) - (now - residency_start_ms)) / 1000UL)); + else + SERIAL_PROTOCOLCHAR('?'); #endif + SERIAL_EOL(); } idle(); @@ -7339,16 +7353,12 @@ inline void gcode_M109() { print_heaterstates(); #if TEMP_BED_RESIDENCY_TIME > 0 SERIAL_PROTOCOLPGM(" W:"); - if (residency_start_ms) { - long rem = (((TEMP_BED_RESIDENCY_TIME) * 1000UL) - (now - residency_start_ms)) / 1000UL; - SERIAL_PROTOCOLLN(rem); - } - else { - SERIAL_PROTOCOLLNPGM("?"); - } - #else - SERIAL_EOL(); + if (residency_start_ms) + SERIAL_PROTOCOL(long((((TEMP_BED_RESIDENCY_TIME) * 1000UL) - (now - residency_start_ms)) / 1000UL)); + else + SERIAL_PROTOCOLCHAR('?'); #endif + SERIAL_EOL(); } idle(); From 21217d53dff1fcf7976539624d0bc27b6fee2720 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 10 Jun 2017 20:05:52 -0500 Subject: [PATCH 056/180] Circular scrolling of the status message --- Marlin/ultralcd_impl_DOGM.h | 30 +++++++++++++++++++++++------- Marlin/ultralcd_impl_HD44780.h | 25 +++++++++++++++++++++---- 2 files changed, 44 insertions(+), 11 deletions(-) diff --git a/Marlin/ultralcd_impl_DOGM.h b/Marlin/ultralcd_impl_DOGM.h index 89fbdf3d98..bfd103a7d3 100644 --- a/Marlin/ultralcd_impl_DOGM.h +++ b/Marlin/ultralcd_impl_DOGM.h @@ -407,15 +407,31 @@ FORCE_INLINE void _draw_axis_label(const AxisEnum axis, const char* const pstr, inline void lcd_implementation_status_message() { #if ENABLED(STATUS_MESSAGE_SCROLLING) static bool last_blink = false; - lcd_print_utf(lcd_status_message + status_scroll_pos); const uint8_t slen = lcd_strlen(lcd_status_message); - if (slen > LCD_WIDTH) { - const bool new_blink = lcd_blink(); - if (last_blink != new_blink) { - last_blink = new_blink; + const char *stat = lcd_status_message + status_scroll_pos; + if (slen <= LCD_WIDTH) + lcd_print_utf(stat); // The string isn't scrolling + else { + if (status_scroll_pos <= slen - LCD_WIDTH) + lcd_print_utf(stat); // The string fills the screen + else { + uint8_t chars = LCD_WIDTH; + if (status_scroll_pos < slen) { // First string still visible + lcd_print_utf(stat); // The string leaves space + chars -= slen - status_scroll_pos; // Amount of space left + } + lcd.print('.'); // Always at 1+ spaces left, draw a dot + if (--chars) { + if (status_scroll_pos < slen + 1) // Draw a second dot if there's space + --chars, lcd.print('.'); + if (chars) lcd_print_utf(lcd_status_message, chars); // Print a second copy of the message + } + } + if (last_blink != blink) { + last_blink = blink; // Skip any non-printing bytes - while (!PRINTABLE(lcd_status_message[status_scroll_pos])) status_scroll_pos++; - if (++status_scroll_pos > slen - LCD_WIDTH) status_scroll_pos = 0; + if (status_scroll_pos < slen) while (!PRINTABLE(lcd_status_message[status_scroll_pos])) status_scroll_pos++; + if (++status_scroll_pos >= slen + 2) status_scroll_pos = 0; } } #else diff --git a/Marlin/ultralcd_impl_HD44780.h b/Marlin/ultralcd_impl_HD44780.h index e281cacaac..ef5301b7f2 100644 --- a/Marlin/ultralcd_impl_HD44780.h +++ b/Marlin/ultralcd_impl_HD44780.h @@ -841,14 +841,31 @@ static void lcd_implementation_status_screen() { #if ENABLED(STATUS_MESSAGE_SCROLLING) static bool last_blink = false; - lcd_print_utf(lcd_status_message + status_scroll_pos); const uint8_t slen = lcd_strlen(lcd_status_message); - if (slen > LCD_WIDTH) { + const char *stat = lcd_status_message + status_scroll_pos; + if (slen <= LCD_WIDTH) + lcd_print_utf(stat); // The string isn't scrolling + else { + if (status_scroll_pos <= slen - LCD_WIDTH) + lcd_print_utf(stat); // The string fills the screen + else { + uint8_t chars = LCD_WIDTH; + if (status_scroll_pos < slen) { // First string still visible + lcd_print_utf(stat); // The string leaves space + chars -= slen - status_scroll_pos; // Amount of space left + } + lcd.print('.'); // Always at 1+ spaces left, draw a dot + if (--chars) { + if (status_scroll_pos < slen + 1) // Draw a second dot if there's space + --chars, lcd.print('.'); + if (chars) lcd_print_utf(lcd_status_message, chars); // Print a second copy of the message + } + } if (last_blink != blink) { last_blink = blink; // Skip any non-printing bytes - while (!PRINTABLE(lcd_status_message[status_scroll_pos])) status_scroll_pos++; - if (++status_scroll_pos > slen - LCD_WIDTH) status_scroll_pos = 0; + if (status_scroll_pos < slen) while (!PRINTABLE(lcd_status_message[status_scroll_pos])) status_scroll_pos++; + if (++status_scroll_pos >= slen + 2) status_scroll_pos = 0; } } #else From 11e28f389e7285d80accca62d29ce580248bb1ce Mon Sep 17 00:00:00 2001 From: Bob-the-Kuhn Date: Sat, 10 Jun 2017 21:49:13 -0500 Subject: [PATCH 057/180] fix pinsDebug.h error, add capability to display more than 70 pins. --- Marlin/pinsDebug.h | 122 +++++++------ Marlin/pinsDebug_list.h | 3 + Marlin/pinsDebug_plus_70.h | 342 +++++++++++++++++++++++++++++++++++++ 3 files changed, 414 insertions(+), 53 deletions(-) create mode 100644 Marlin/pinsDebug_plus_70.h diff --git a/Marlin/pinsDebug.h b/Marlin/pinsDebug.h index 5bd13a491d..8846dabf2b 100644 --- a/Marlin/pinsDebug.h +++ b/Marlin/pinsDebug.h @@ -98,16 +98,31 @@ const char* const pin_array[][3] PROGMEM = { #define n_array (sizeof(pin_array) / sizeof(char*)) / 3 +#define AVR_ATmega2560_FAMILY_PLUS_70 (MOTHERBOARD == BOARD_BQ_ZUM_MEGA_3D \ +|| MOTHERBOARD == BOARD_MIGHTYBOARD_REVE \ +|| MOTHERBOARD == BOARD_MINIRAMBO \ +|| MOTHERBOARD == BOARD_SCOOVO_X9H) + #if AVR_AT90USB1286_FAMILY // Working with Teensyduino extension so need to re-define some things #include "pinsDebug_Teensyduino.h" // Can't use the "digitalPinToPort" function from the Teensyduino type IDEs // portModeRegister takes a different argument - #define digitalPinToPort_DEBUG(p) digitalPinToPort_Teensy(p) - #define get_pinMode(pin) (*portModeRegister(pin) & digitalPinToBitMask(pin)) + #define digitalPinToTimer_DEBUG(p) digitalPinToTimer(p) + #define digitalPinToBitMask_DEBUG(p) digitalPinToBitMask(p) + #define digitalPinToPort_DEBUG(p) digitalPinToPort_Teensy(p) + #define get_pinMode(pin) (*portModeRegister(pin) & digitalPinToBitMask_DEBUG(pin)) +#elif AVR_ATmega2560_FAMILY_PLUS_70 // So we can access/display all the pins on boards using more than 70 + #include "pinsDebug_plus_70.h" + #define digitalPinToTimer_DEBUG(p) digitalPinToTimer_plus_70(p) + #define digitalPinToBitMask_DEBUG(p) digitalPinToBitMask_plus_70(p) + #define digitalPinToPort_DEBUG(p) digitalPinToPort_plus_70(p) + bool get_pinMode(int8_t pin) {return *portModeRegister(digitalPinToPort_DEBUG(pin)) & digitalPinToBitMask_DEBUG(pin); } #else - #define digitalPinToPort_DEBUG(p) digitalPinToPort(p) - bool get_pinMode(int8_t pin) {return *portModeRegister(digitalPinToPort_DEBUG(pin)) & digitalPinToBitMask(pin); } + #define digitalPinToTimer_DEBUG(p) digitalPinToTimer(p) + #define digitalPinToBitMask_DEBUG(p) digitalPinToBitMask(p) + #define digitalPinToPort_DEBUG(p) digitalPinToPort(p) + bool get_pinMode(int8_t pin) {return *portModeRegister(digitalPinToPort_DEBUG(pin)) & digitalPinToBitMask_DEBUG(pin); } #endif #define PWM_PRINT(V) do{ sprintf_P(buffer, PSTR("PWM: %4d"), V); SERIAL_ECHO(buffer); }while(0) @@ -125,7 +140,7 @@ const char* const pin_array[][3] PROGMEM = { static bool pwm_status(uint8_t pin) { char buffer[20]; // for the sprintf statements - switch (digitalPinToTimer(pin)) { + switch (digitalPinToTimer_DEBUG(pin)) { #if defined(TCCR0A) && defined(COM0A1) #ifdef TIMER0A @@ -312,7 +327,7 @@ void timer_prefix(uint8_t T, char L, uint8_t N) { // T - timer L - pwm N - } static void pwm_details(uint8_t pin) { - switch (digitalPinToTimer(pin)) { + switch (digitalPinToTimer_DEBUG(pin)) { #if defined(TCCR0A) && defined(COM0A1) #ifdef TIMER0A @@ -364,7 +379,7 @@ static void pwm_details(uint8_t pin) { // on pins that have two PWMs, print info on second PWM #if AVR_ATmega2560_FAMILY || AVR_AT90USB1286_FAMILY // looking for port B7 - PWMs 0A and 1C - if (digitalPinToPort_DEBUG(pin) == 'B' - 64 && 0x80 == digitalPinToBitMask(pin)) { + if (digitalPinToPort_DEBUG(pin) == 'B' - 64 && 0x80 == digitalPinToBitMask_DEBUG(pin)) { #if !AVR_AT90USB1286_FAMILY SERIAL_PROTOCOLPGM("\n ."); SERIAL_PROTOCOL_SP(18); @@ -385,7 +400,7 @@ static void pwm_details(uint8_t pin) { #ifndef digitalRead_mod // Use Teensyduino's version of digitalRead - it doesn't disable the PWMs int digitalRead_mod(const int8_t pin) { // same as digitalRead except the PWM stop section has been removed const uint8_t port = digitalPinToPort_DEBUG(pin); - return (port != NOT_A_PIN) && (*portInputRegister(port) & digitalPinToBitMask(pin)) ? HIGH : LOW; + return (port != NOT_A_PIN) && (*portInputRegister(port) & digitalPinToBitMask_DEBUG(pin)) ? HIGH : LOW; } #endif @@ -406,11 +421,11 @@ void print_port(int8_t pin) { // print port number else if (pin == 47) x = '3'; else { - uint8_t temp = digitalPinToBitMask(pin); + uint8_t temp = digitalPinToBitMask_DEBUG(pin); for (x = '0'; x < '9' && temp != 1; x++) temp >>= 1; } #else - uint8_t temp = digitalPinToBitMask(pin); + uint8_t temp = digitalPinToBitMask_DEBUG(pin); for (x = '0'; x < '9' && temp != 1; x++) temp >>= 1; #endif SERIAL_CHAR(x); @@ -460,14 +475,16 @@ inline void report_pin_state_extended(int8_t pin, bool ignore, bool extended = f if (pin_is_protected(pin) && !ignore) SERIAL_ECHOPGM("protected "); else { - #ifdef AVR_AT90USB1286_FAMILY // Teensy IDEs don't know about these pins so must use FASTIO - if (pin == 46) { - print_input_or_output(GET_OUTPUT(46)); - SERIAL_PROTOCOL(READ(46)); - } - else if (pin == 47) - print_input_or_output(GET_OUTPUT(47)); - SERIAL_PROTOCOL(READ(47)); + #ifdef AVR_AT90USB1286_FAMILY //Teensy IDEs don't know about these pins so must use FASTIO + if (pin == 46 || pin == 47) { + if (pin == 46) { + print_input_or_output(GET_OUTPUT(46)); + SERIAL_PROTOCOL(READ(46)); + } + else if (pin == 47) { + print_input_or_output(GET_OUTPUT(47)); + SERIAL_PROTOCOL(READ(47)); + } } else #endif @@ -509,47 +526,46 @@ inline void report_pin_state_extended(int8_t pin, bool ignore, bool extended = f sprintf_P(buffer, PSTR(" (A%2d) "), int(pin - analogInputToDigitalPin(0))); // analog pin number SERIAL_ECHO(buffer); } - else { + else SERIAL_ECHO_SP(8); // add padding if not an analog pin - SERIAL_ECHOPGM(""); - if (extended) { - #ifdef AVR_AT90USB1286_FAMILY // Teensy IDEs don't know about these pins so must use FASTIO - if (pin == 46 || pin == 47) { - SERIAL_PROTOCOL_SP(12); - if (pin == 46) { - print_input_or_output(GET_OUTPUT(46)); - SERIAL_PROTOCOL(READ(46)); - } - else { - print_input_or_output(GET_OUTPUT(47)); - SERIAL_PROTOCOL(READ(47)); - } - } - else - #endif - { - if (get_pinMode(pin)) { - SERIAL_PROTOCOL_SP(12); - print_input_or_output(true); - SERIAL_PROTOCOL(digitalRead_mod(pin)); + SERIAL_ECHOPGM(""); + if (extended) { + #ifdef AVR_AT90USB1286_FAMILY //Teensy IDEs don't know about these pins so must use FASTIO + if (pin == 46 || pin == 47) { + SERIAL_PROTOCOL_SP(12); + if (pin == 46) { + print_input_or_output(GET_OUTPUT(46)); + SERIAL_PROTOCOL(READ(46)); } else { - if (IS_ANALOG(pin)) { - sprintf_P(buffer, PSTR(" Analog in = %5d"), analogRead(pin - analogInputToDigitalPin(0))); - SERIAL_ECHO(buffer); - SERIAL_ECHOPGM(" "); - } - else - SERIAL_ECHO_SP(12); // add padding if not an analog pin - - print_input_or_output(false); - SERIAL_PROTOCOL(digitalRead_mod(pin)); + print_input_or_output(GET_OUTPUT(47)); + SERIAL_PROTOCOL(READ(47)); } - //if (!pwm_status(pin)) SERIAL_CHAR(' '); // add padding if it's not a PWM pin - if (extended) pwm_details(pin); // report PWM capabilities only if doing an extended report } + else + #endif + { + if (get_pinMode(pin)) { + SERIAL_PROTOCOL_SP(12); + print_input_or_output(true); + SERIAL_PROTOCOL(digitalRead_mod(pin)); + } + else { + if (IS_ANALOG(pin)) { + sprintf_P(buffer, PSTR(" Analog in = %5d"), analogRead(pin - analogInputToDigitalPin(0))); + SERIAL_ECHO(buffer); + SERIAL_ECHOPGM(" "); + } + else + SERIAL_ECHO_SP(12); // add padding if not an analog pin + + print_input_or_output(false); + SERIAL_PROTOCOL(digitalRead_mod(pin)); + } + //if (!pwm_status(pin)) SERIAL_CHAR(' '); // add padding if it's not a PWM pin + if (extended) pwm_details(pin); // report PWM capabilities only if doing an extended report } - SERIAL_EOL(); } + SERIAL_EOL(); } } diff --git a/Marlin/pinsDebug_list.h b/Marlin/pinsDebug_list.h index 90eaa1c620..9164b6b418 100644 --- a/Marlin/pinsDebug_list.h +++ b/Marlin/pinsDebug_list.h @@ -41,6 +41,9 @@ #if defined(__GS) && __GS >= 0 REPORT_NAME_DIGITAL(__GS, __LINE__ ) #endif +#if PIN_EXISTS(ADC_KEYPAD) + REPORT_NAME_ANALOG(ADC_KEYPAD_PIN, __LINE__ ) +#endif #if PIN_EXISTS(AVR_MISO) REPORT_NAME_DIGITAL(AVR_MISO_PIN, __LINE__ ) #endif diff --git a/Marlin/pinsDebug_plus_70.h b/Marlin/pinsDebug_plus_70.h new file mode 100644 index 0000000000..e02721f813 --- /dev/null +++ b/Marlin/pinsDebug_plus_70.h @@ -0,0 +1,342 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (C) 2017 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * 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 . + * + */ + +/** + * structurs for 2560 family boards that use morre than 70 pins + */ + +#ifndef Plus_70_h + #define Plus_70_h + +#undef NUM_DIGITAL_PINS +#if MOTHERBOARD == BOARD_BQ_ZUM_MEGA_3D + #define NUM_DIGITAL_PINS 85 +#elif MOTHERBOARD == BOARD_MIGHTYBOARD_REVE + #define NUM_DIGITAL_PINS 80 +#elif MOTHERBOARD == BOARD_MINIRAMBO + #define NUM_DIGITAL_PINS 85 +#elif MOTHERBOARD == BOARD_SCOOVO_X9H + #define NUM_DIGITAL_PINS 85 +#endif + +#define PA 1 +#define PB 2 +#define PC 3 +#define PD 4 +#define PE 5 +#define PF 6 +#define PG 7 +#define PH 8 +#define PJ 10 +#define PK 11 +#define PL 12 + +const uint8_t PROGMEM digital_pin_to_port_PGM_plus_70[] = { + // PORTLIST + // ------------------------------------------- + PE , // PE 0 ** 0 ** USART0_RX + PE , // PE 1 ** 1 ** USART0_TX + PE , // PE 4 ** 2 ** PWM2 + PE , // PE 5 ** 3 ** PWM3 + PG , // PG 5 ** 4 ** PWM4 + PE , // PE 3 ** 5 ** PWM5 + PH , // PH 3 ** 6 ** PWM6 + PH , // PH 4 ** 7 ** PWM7 + PH , // PH 5 ** 8 ** PWM8 + PH , // PH 6 ** 9 ** PWM9 + PB , // PB 4 ** 10 ** PWM10 + PB , // PB 5 ** 11 ** PWM11 + PB , // PB 6 ** 12 ** PWM12 + PB , // PB 7 ** 13 ** PWM13 + PJ , // PJ 1 ** 14 ** USART3_TX + PJ , // PJ 0 ** 15 ** USART3_RX + PH , // PH 1 ** 16 ** USART2_TX + PH , // PH 0 ** 17 ** USART2_RX + PD , // PD 3 ** 18 ** USART1_TX + PD , // PD 2 ** 19 ** USART1_RX + PD , // PD 1 ** 20 ** I2C_SDA + PD , // PD 0 ** 21 ** I2C_SCL + PA , // PA 0 ** 22 ** D22 + PA , // PA 1 ** 23 ** D23 + PA , // PA 2 ** 24 ** D24 + PA , // PA 3 ** 25 ** D25 + PA , // PA 4 ** 26 ** D26 + PA , // PA 5 ** 27 ** D27 + PA , // PA 6 ** 28 ** D28 + PA , // PA 7 ** 29 ** D29 + PC , // PC 7 ** 30 ** D30 + PC , // PC 6 ** 31 ** D31 + PC , // PC 5 ** 32 ** D32 + PC , // PC 4 ** 33 ** D33 + PC , // PC 3 ** 34 ** D34 + PC , // PC 2 ** 35 ** D35 + PC , // PC 1 ** 36 ** D36 + PC , // PC 0 ** 37 ** D37 + PD , // PD 7 ** 38 ** D38 + PG , // PG 2 ** 39 ** D39 + PG , // PG 1 ** 40 ** D40 + PG , // PG 0 ** 41 ** D41 + PL , // PL 7 ** 42 ** D42 + PL , // PL 6 ** 43 ** D43 + PL , // PL 5 ** 44 ** D44 + PL , // PL 4 ** 45 ** D45 + PL , // PL 3 ** 46 ** D46 + PL , // PL 2 ** 47 ** D47 + PL , // PL 1 ** 48 ** D48 + PL , // PL 0 ** 49 ** D49 + PB , // PB 3 ** 50 ** SPI_MISO + PB , // PB 2 ** 51 ** SPI_MOSI + PB , // PB 1 ** 52 ** SPI_SCK + PB , // PB 0 ** 53 ** SPI_SS + PF , // PF 0 ** 54 ** A0 + PF , // PF 1 ** 55 ** A1 + PF , // PF 2 ** 56 ** A2 + PF , // PF 3 ** 57 ** A3 + PF , // PF 4 ** 58 ** A4 + PF , // PF 5 ** 59 ** A5 + PF , // PF 6 ** 60 ** A6 + PF , // PF 7 ** 61 ** A7 + PK , // PK 0 ** 62 ** A8 + PK , // PK 1 ** 63 ** A9 + PK , // PK 2 ** 64 ** A10 + PK , // PK 3 ** 65 ** A11 + PK , // PK 4 ** 66 ** A12 + PK , // PK 5 ** 67 ** A13 + PK , // PK 6 ** 68 ** A14 + PK , // PK 7 ** 69 ** A15 + PG , // PG 4 ** 70 ** + PG , // PG 3 ** 71 ** + PJ , // PJ 2 ** 72 ** + PJ , // PJ 3 ** 73 ** + PJ , // PJ 7 ** 74 ** + PJ , // PJ 4 ** 75 ** + PJ , // PJ 5 ** 76 ** + PJ , // PJ 6 ** 77 ** + PE , // PE 2 ** 78 ** + PE , // PE 6 ** 79 ** + PE , // PE 7 ** 80 ** + PD , // PD 4 ** 81 ** + PD , // PD 5 ** 82 ** + PD , // PD 6 ** 83 ** + PH , // PH 2 ** 84 ** + PH , // PH 7 ** 85 ** +}; + +#define digitalPinToPort_plus_70(P) ( pgm_read_byte( digital_pin_to_port_PGM_plus_70 + (P) ) ) + +const uint8_t PROGMEM digital_pin_to_bit_mask_PGM_plus_70[] = { + // PIN IN PORT + // ------------------------------------------- + _BV( 0 ) , // PE 0 ** 0 ** USART0_RX + _BV( 1 ) , // PE 1 ** 1 ** USART0_TX + _BV( 4 ) , // PE 4 ** 2 ** PWM2 + _BV( 5 ) , // PE 5 ** 3 ** PWM3 + _BV( 5 ) , // PG 5 ** 4 ** PWM4 + _BV( 3 ) , // PE 3 ** 5 ** PWM5 + _BV( 3 ) , // PH 3 ** 6 ** PWM6 + _BV( 4 ) , // PH 4 ** 7 ** PWM7 + _BV( 5 ) , // PH 5 ** 8 ** PWM8 + _BV( 6 ) , // PH 6 ** 9 ** PWM9 + _BV( 4 ) , // PB 4 ** 10 ** PWM10 + _BV( 5 ) , // PB 5 ** 11 ** PWM11 + _BV( 6 ) , // PB 6 ** 12 ** PWM12 + _BV( 7 ) , // PB 7 ** 13 ** PWM13 + _BV( 1 ) , // PJ 1 ** 14 ** USART3_TX + _BV( 0 ) , // PJ 0 ** 15 ** USART3_RX + _BV( 1 ) , // PH 1 ** 16 ** USART2_TX + _BV( 0 ) , // PH 0 ** 17 ** USART2_RX + _BV( 3 ) , // PD 3 ** 18 ** USART1_TX + _BV( 2 ) , // PD 2 ** 19 ** USART1_RX + _BV( 1 ) , // PD 1 ** 20 ** I2C_SDA + _BV( 0 ) , // PD 0 ** 21 ** I2C_SCL + _BV( 0 ) , // PA 0 ** 22 ** D22 + _BV( 1 ) , // PA 1 ** 23 ** D23 + _BV( 2 ) , // PA 2 ** 24 ** D24 + _BV( 3 ) , // PA 3 ** 25 ** D25 + _BV( 4 ) , // PA 4 ** 26 ** D26 + _BV( 5 ) , // PA 5 ** 27 ** D27 + _BV( 6 ) , // PA 6 ** 28 ** D28 + _BV( 7 ) , // PA 7 ** 29 ** D29 + _BV( 7 ) , // PC 7 ** 30 ** D30 + _BV( 6 ) , // PC 6 ** 31 ** D31 + _BV( 5 ) , // PC 5 ** 32 ** D32 + _BV( 4 ) , // PC 4 ** 33 ** D33 + _BV( 3 ) , // PC 3 ** 34 ** D34 + _BV( 2 ) , // PC 2 ** 35 ** D35 + _BV( 1 ) , // PC 1 ** 36 ** D36 + _BV( 0 ) , // PC 0 ** 37 ** D37 + _BV( 7 ) , // PD 7 ** 38 ** D38 + _BV( 2 ) , // PG 2 ** 39 ** D39 + _BV( 1 ) , // PG 1 ** 40 ** D40 + _BV( 0 ) , // PG 0 ** 41 ** D41 + _BV( 7 ) , // PL 7 ** 42 ** D42 + _BV( 6 ) , // PL 6 ** 43 ** D43 + _BV( 5 ) , // PL 5 ** 44 ** D44 + _BV( 4 ) , // PL 4 ** 45 ** D45 + _BV( 3 ) , // PL 3 ** 46 ** D46 + _BV( 2 ) , // PL 2 ** 47 ** D47 + _BV( 1 ) , // PL 1 ** 48 ** D48 + _BV( 0 ) , // PL 0 ** 49 ** D49 + _BV( 3 ) , // PB 3 ** 50 ** SPI_MISO + _BV( 2 ) , // PB 2 ** 51 ** SPI_MOSI + _BV( 1 ) , // PB 1 ** 52 ** SPI_SCK + _BV( 0 ) , // PB 0 ** 53 ** SPI_SS + _BV( 0 ) , // PF 0 ** 54 ** A0 + _BV( 1 ) , // PF 1 ** 55 ** A1 + _BV( 2 ) , // PF 2 ** 56 ** A2 + _BV( 3 ) , // PF 3 ** 57 ** A3 + _BV( 4 ) , // PF 4 ** 58 ** A4 + _BV( 5 ) , // PF 5 ** 59 ** A5 + _BV( 6 ) , // PF 6 ** 60 ** A6 + _BV( 7 ) , // PF 7 ** 61 ** A7 + _BV( 0 ) , // PK 0 ** 62 ** A8 + _BV( 1 ) , // PK 1 ** 63 ** A9 + _BV( 2 ) , // PK 2 ** 64 ** A10 + _BV( 3 ) , // PK 3 ** 65 ** A11 + _BV( 4 ) , // PK 4 ** 66 ** A12 + _BV( 5 ) , // PK 5 ** 67 ** A13 + _BV( 6 ) , // PK 6 ** 68 ** A14 + _BV( 7 ) , // PK 7 ** 69 ** A15 + _BV( 4 ) , // PG 4 ** 70 ** + _BV( 3 ) , // PG 3 ** 71 ** + _BV( 2 ) , // PJ 2 ** 72 ** + _BV( 3 ) , // PJ 3 ** 73 ** + _BV( 7 ) , // PJ 7 ** 74 ** + _BV( 4 ) , // PJ 4 ** 75 ** + _BV( 5 ) , // PJ 5 ** 76 ** + _BV( 6 ) , // PJ 6 ** 77 ** + _BV( 2 ) , // PE 2 ** 78 ** + _BV( 6 ) , // PE 6 ** 79 ** + _BV( 7 ) , // PE 7 ** 80 ** + _BV( 4 ) , // PD 4 ** 81 ** + _BV( 5 ) , // PD 5 ** 82 ** + _BV( 6 ) , // PD 6 ** 83 ** + _BV( 2 ) , // PH 2 ** 84 ** + _BV( 7 ) , // PH 7 ** 85 ** +}; + +#define digitalPinToBitMask_plus_70(P) ( pgm_read_byte( digital_pin_to_bit_mask_PGM_plus_70 + (P) ) ) + + +const uint8_t PROGMEM digital_pin_to_timer_PGM_plus_70[] = { + // TIMERS + // ------------------------------------------- + NOT_ON_TIMER , // PE 0 ** 0 ** USART0_RX + NOT_ON_TIMER , // PE 1 ** 1 ** USART0_TX + TIMER3B , // PE 4 ** 2 ** PWM2 + TIMER3C , // PE 5 ** 3 ** PWM3 + TIMER0B , // PG 5 ** 4 ** PWM4 + TIMER3A , // PE 3 ** 5 ** PWM5 + TIMER4A , // PH 3 ** 6 ** PWM6 + TIMER4B , // PH 4 ** 7 ** PWM7 + TIMER4C , // PH 5 ** 8 ** PWM8 + TIMER2B , // PH 6 ** 9 ** PWM9 + TIMER2A , // PB 4 ** 10 ** PWM10 + TIMER1A , // PB 5 ** 11 ** PWM11 + TIMER1B , // PB 6 ** 12 ** PWM12 + TIMER0A , // PB 7 ** 13 ** PWM13 + NOT_ON_TIMER , // PJ 1 ** 14 ** USART3_TX + NOT_ON_TIMER , // PJ 0 ** 15 ** USART3_RX + NOT_ON_TIMER , // PH 1 ** 16 ** USART2_TX + NOT_ON_TIMER , // PH 0 ** 17 ** USART2_RX + NOT_ON_TIMER , // PD 3 ** 18 ** USART1_TX + NOT_ON_TIMER , // PD 2 ** 19 ** USART1_RX + NOT_ON_TIMER , // PD 1 ** 20 ** I2C_SDA + NOT_ON_TIMER , // PD 0 ** 21 ** I2C_SCL + NOT_ON_TIMER , // PA 0 ** 22 ** D22 + NOT_ON_TIMER , // PA 1 ** 23 ** D23 + NOT_ON_TIMER , // PA 2 ** 24 ** D24 + NOT_ON_TIMER , // PA 3 ** 25 ** D25 + NOT_ON_TIMER , // PA 4 ** 26 ** D26 + NOT_ON_TIMER , // PA 5 ** 27 ** D27 + NOT_ON_TIMER , // PA 6 ** 28 ** D28 + NOT_ON_TIMER , // PA 7 ** 29 ** D29 + NOT_ON_TIMER , // PC 7 ** 30 ** D30 + NOT_ON_TIMER , // PC 6 ** 31 ** D31 + NOT_ON_TIMER , // PC 5 ** 32 ** D32 + NOT_ON_TIMER , // PC 4 ** 33 ** D33 + NOT_ON_TIMER , // PC 3 ** 34 ** D34 + NOT_ON_TIMER , // PC 2 ** 35 ** D35 + NOT_ON_TIMER , // PC 1 ** 36 ** D36 + NOT_ON_TIMER , // PC 0 ** 37 ** D37 + NOT_ON_TIMER , // PD 7 ** 38 ** D38 + NOT_ON_TIMER , // PG 2 ** 39 ** D39 + NOT_ON_TIMER , // PG 1 ** 40 ** D40 + NOT_ON_TIMER , // PG 0 ** 41 ** D41 + NOT_ON_TIMER , // PL 7 ** 42 ** D42 + NOT_ON_TIMER , // PL 6 ** 43 ** D43 + TIMER5C , // PL 5 ** 44 ** D44 + TIMER5B , // PL 4 ** 45 ** D45 + TIMER5A , // PL 3 ** 46 ** D46 + NOT_ON_TIMER , // PL 2 ** 47 ** D47 + NOT_ON_TIMER , // PL 1 ** 48 ** D48 + NOT_ON_TIMER , // PL 0 ** 49 ** D49 + NOT_ON_TIMER , // PB 3 ** 50 ** SPI_MISO + NOT_ON_TIMER , // PB 2 ** 51 ** SPI_MOSI + NOT_ON_TIMER , // PB 1 ** 52 ** SPI_SCK + NOT_ON_TIMER , // PB 0 ** 53 ** SPI_SS + NOT_ON_TIMER , // PF 0 ** 54 ** A0 + NOT_ON_TIMER , // PF 1 ** 55 ** A1 + NOT_ON_TIMER , // PF 2 ** 56 ** A2 + NOT_ON_TIMER , // PF 3 ** 57 ** A3 + NOT_ON_TIMER , // PF 4 ** 58 ** A4 + NOT_ON_TIMER , // PF 5 ** 59 ** A5 + NOT_ON_TIMER , // PF 6 ** 60 ** A6 + NOT_ON_TIMER , // PF 7 ** 61 ** A7 + NOT_ON_TIMER , // PK 0 ** 62 ** A8 + NOT_ON_TIMER , // PK 1 ** 63 ** A9 + NOT_ON_TIMER , // PK 2 ** 64 ** A10 + NOT_ON_TIMER , // PK 3 ** 65 ** A11 + NOT_ON_TIMER , // PK 4 ** 66 ** A12 + NOT_ON_TIMER , // PK 5 ** 67 ** A13 + NOT_ON_TIMER , // PK 6 ** 68 ** A14 + NOT_ON_TIMER , // PK 7 ** 69 ** A15 + NOT_ON_TIMER , // PG 4 ** 70 ** + NOT_ON_TIMER , // PG 3 ** 71 ** + NOT_ON_TIMER , // PJ 2 ** 72 ** + NOT_ON_TIMER , // PJ 3 ** 73 ** + NOT_ON_TIMER , // PJ 7 ** 74 ** + NOT_ON_TIMER , // PJ 4 ** 75 ** + NOT_ON_TIMER , // PJ 5 ** 76 ** + NOT_ON_TIMER , // PJ 6 ** 77 ** + NOT_ON_TIMER , // PE 2 ** 78 ** + NOT_ON_TIMER , // PE 6 ** 79 ** +}; + +#define digitalPinToTimer_plus_70(P) ( pgm_read_byte( digital_pin_to_timer_PGM_plus_70 + (P) ) ) + +/** + * Interrupts that are not implemented + * + * INT6 E6 79 + * INT7 E7 80 + * PCINT11 J2 72 + * PCINT12 J3 73 + * PCINT13 J4 75 + * PCINT14 J5 76 + * PCINT15 J6 77 + */ + + +#endif + From 772275ab0c6af8d37919bcecf7cb5da6000107d7 Mon Sep 17 00:00:00 2001 From: Federico Date: Sun, 11 Jun 2017 10:37:34 +0200 Subject: [PATCH 058/180] Create language_it.h --- Marlin/language_it.h | 72 ++++++++++++++++++++++++++++++++++++++++++-- 1 file changed, 69 insertions(+), 3 deletions(-) diff --git a/Marlin/language_it.h b/Marlin/language_it.h index f345e8bd83..23e81f4707 100644 --- a/Marlin/language_it.h +++ b/Marlin/language_it.h @@ -73,6 +73,62 @@ #define MSG_MOVE_AXIS _UxGT("Muovi Asse") #define MSG_BED_LEVELING _UxGT("Livella piano") #define MSG_LEVEL_BED _UxGT("Livella piano") +#define MSG_EDITING_STOPPED _UxGT("Modifica Mesh Fermata") +#define MSG_USER_MENU _UxGT("Comandi Utente") +#define MSG_UBL_DOING_G29 _UxGT("G29 in corso") +#define MSG_UBL_UNHOMED _UxGT("Home XYZ prima") +#define MSG_UBL_TOOLS _UxGT("Strumenti UBL") +#define MSG_UBL_LEVEL_BED _UxGT("Unified Bed Leveling") +#define MSG_UBL_MANUAL_MESH _UxGT("Mesh Manuale") +#define MSG_UBL_BC_INSERT _UxGT("Metti spessore & misura") +#define MSG_UBL_BC_INSERT2 _UxGT("Misura") +#define MSG_UBL_BC_REMOVE _UxGT("Rimuovi & misura piatto") +#define MSG_UBL_MOVING_TO_NEXT _UxGT("Spostamento sucessivo") +#define MSG_UBL_ACTIVATE_MESH _UxGT("Attiva UBL") +#define MSG_UBL_DEACTIVATE_MESH _UxGT("Disattiva UBL") +#define MSG_UBL_SET_BED_TEMP _UxGT("Temp Piatto") +#define MSG_UBL_SET_HOTEND_TEMP _UxGT("Temp Ugello") +#define MSG_UBL_EDIT_CUSTOM_MESH _UxGT("Modif Custom Mesh") +#define MSG_UBL_FINE_TUNE_MESH _UxGT("Ritocca Mesh") +#define MSG_UBL_DONE_EDITING_MESH _UxGT("Done Editing Mesh") +#define MSG_UBL_BUILD_CUSTOM_MESH _UxGT("Crea Custom Mesh") +#define MSG_UBL_BUILD_MESH_MENU _UxGT("Crea Mesh") +#define MSG_UBL_BUILD_PLA_MESH _UxGT("Crea PLA Mesh") +#define MSG_UBL_BUILD_ABS_MESH _UxGT("Crea ABS Mesh") +#define MSG_UBL_BUILD_COLD_MESH _UxGT("Crea Cold Mesh") +#define MSG_UBL_MESH_HEIGHT_ADJUST _UxGT("Aggiusta Altezza Mesh") +#define MSG_UBL_MESH_HEIGHT_AMOUNT _UxGT("Altezza") +#define MSG_UBL_VALIDATE_MESH_MENU _UxGT("Valida Mesh") +#define MSG_UBL_VALIDATE_PLA_MESH _UxGT("Valida PLA Mesh") +#define MSG_UBL_VALIDATE_ABS_MESH _UxGT("Valida ABS Mesh") +#define MSG_UBL_VALIDATE_CUSTOM_MESH _UxGT("Valida Custom Mesh") +#define MSG_UBL_CONTINUE_MESH _UxGT("Continua Mesh") +#define MSG_UBL_MESH_LEVELING _UxGT("Livell. Mesh") +#define MSG_UBL_3POINT_MESH_LEVELING _UxGT("Livell. 3 Punti") +#define MSG_UBL_GRID_MESH_LEVELING _UxGT("Livell. Griglia Mesh") +#define MSG_UBL_MESH_LEVEL _UxGT("Livella Mesh") +#define MSG_UBL_SIDE_POINTS _UxGT("Punti laterali") +#define MSG_UBL_MAP_TYPE _UxGT("Tipo di Mappa") +#define MSG_UBL_OUTPUT_MAP _UxGT("Esporta Mappa") +#define MSG_UBL_OUTPUT_MAP_HOST _UxGT("Esporta per Host") +#define MSG_UBL_OUTPUT_MAP_CSV _UxGT("Esporta in CSV") +#define MSG_UBL_INFO_UBL _UxGT("Esporta Info UBL") +#define MSG_UBL_EDIT_MESH_MENU _UxGT("Modifica Mesh") +#define MSG_UBL_FILLIN_AMOUNT _UxGT("Riempimento") +#define MSG_UBL_MANUAL_FILLIN _UxGT("Riempimento Manuale") +#define MSG_UBL_SMART_FILLIN _UxGT("Riempimento Smart") +#define MSG_UBL_FILLIN_MESH _UxGT("Riempimento Mesh") +#define MSG_UBL_INVALIDATE_ALL _UxGT("Invalida Tutto") +#define MSG_UBL_INVALIDATE_CLOSEST _UxGT("Invalida Punto Vicino") +#define MSG_UBL_FINE_TUNE_ALL _UxGT("Ritocca All") +#define MSG_UBL_FINE_TUNE_CLOSEST _UxGT("Ritocca Punto Vicino") +#define MSG_UBL_STORAGE_MESH_MENU _UxGT("Mesh Salvate") +#define MSG_UBL_STORAGE_SLOT _UxGT("Slot di memoria") +#define MSG_UBL_LOAD_MESH _UxGT("Carica Mesh Piatto") +#define MSG_UBL_SAVE_MESH _UxGT("Salva Mesh Piatto") +#define MSG_UBL_SAVE_ERROR _UxGT("Err: Salvataggio UBL") +#define MSG_UBL_RESTORE_ERROR _UxGT("Err: Ripristino UBL") +#define MSG_UBL_Z_OFFSET_STOPPED _UxGT("Z-Offset Fermato") #define MSG_MOVING _UxGT("In movimento...") #define MSG_FREE_XY _UxGT("XY liberi") #define MSG_MOVE_X _UxGT("Muovi X") @@ -203,6 +259,11 @@ #define MSG_DELTA_HEIGHT_CALIBRATE _UxGT("Imp. altezza Delta") #define MSG_INFO_MENU _UxGT("Riguardo stampante") #define MSG_INFO_PRINTER_MENU _UxGT("Info. stampante") +#define MSG_3POINT_LEVELING _UxGT("Livel. a 3 punti") +#define MSG_LINEAR_LEVELING _UxGT("Livel. Lineare") +#define MSG_BILINEAR_LEVELING _UxGT("Livel. Biliniare") +#define MSG_UBL_LEVELING _UxGT("Livel. UBL") +#define MSG_MESH_LEVELING _UxGT("Livel. Mesh") #define MSG_INFO_STATS_MENU _UxGT("Statistiche") #define MSG_INFO_BOARD_MENU _UxGT("Info. scheda") #define MSG_INFO_THERMISTOR_MENU _UxGT("Termistori") @@ -210,6 +271,11 @@ #define MSG_INFO_BAUDRATE _UxGT("Baud") #define MSG_INFO_PROTOCOL _UxGT("Protocollo") #define MSG_CASE_LIGHT _UxGT("Luci Case") +#if ENABLED(DOGLCD) + #define MSG_CASE_LIGHT_BRIGHTNESS _UxGT("Luminosità Luci") +#else + #define MSG_CASE_LIGHT_BRIGHTNESS _UxGT("Luminosita Luci") +#endif #if LCD_WIDTH >= 20 #define MSG_INFO_PRINT_COUNT _UxGT("Contat. stampa") @@ -240,9 +306,9 @@ #define MSG_DAC_PERCENT _UxGT("Driver %") #define MSG_DAC_EEPROM_WRITE _UxGT("Scrivi DAC EEPROM") -#define MSG_FILAMENT_CHANGE_HEADER _UxGT("PRINT PAUSED") -#define MSG_FILAMENT_CHANGE_OPTION_HEADER _UxGT("RESUME OPTIONS:") -#define MSG_FILAMENT_CHANGE_OPTION_EXTRUDE _UxGT("Estrusione") +#define MSG_FILAMENT_CHANGE_HEADER _UxGT("STAMPA IN PAUSA") +#define MSG_FILAMENT_CHANGE_OPTION_HEADER _UxGT("OPZIONI:") +#define MSG_FILAMENT_CHANGE_OPTION_EXTRUDE _UxGT("Estrudi ancora") #define MSG_FILAMENT_CHANGE_OPTION_RESUME _UxGT("Riprendi stampa") #if ENABLED(DOGLCD) #define MSG_FILAMENT_CHANGE_MINTEMP _UxGT("Temp minima è ") From 07f8da36d22dcb8ec19275cfd1c34e0b0b36d07a Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 11 Jun 2017 19:34:16 -0500 Subject: [PATCH 059/180] CL-260 configs --- .../CL-260/Configuration.h | 1586 +++++++++++++++++ .../example_configurations/CL-260/README.txt | 15 + 2 files changed, 1601 insertions(+) create mode 100644 Marlin/example_configurations/CL-260/Configuration.h create mode 100644 Marlin/example_configurations/CL-260/README.txt diff --git a/Marlin/example_configurations/CL-260/Configuration.h b/Marlin/example_configurations/CL-260/Configuration.h new file mode 100644 index 0000000000..8be2b4427b --- /dev/null +++ b/Marlin/example_configurations/CL-260/Configuration.h @@ -0,0 +1,1586 @@ +/** + * 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 replace the configuration files with the files in the +// example_configurations/delta directory. +// + +//=========================================================================== +//============================= SCARA Printer =============================== +//=========================================================================== +// For a Scara printer replace the configuration files with the files in the +// example_configurations/SCARA directory. +// + +// @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, example CL-260 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_RAMPS_14_EFB +#endif + +// Optional custom name for your RepStrap or other custom machine +// Displayed in the LCD "Ready" message +#define CUSTOM_MACHINE_NAME "CL-260" + +// 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 + +// 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 +#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 800 + +//=========================================================================== +//======================== 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 true // set to true to invert the logic of the endstop. +#define Y_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. +#define Z_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. +#define X_MAX_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. +#define Y_MAX_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. +#define Z_MAX_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. +#define 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, 160.6 } + +/** + * Default Max Feed Rate (mm/s) + * Override with M203 + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] + */ +#define DEFAULT_MAX_FEEDRATE { 300, 300, 5, 25 } + +/** + * Default Max Acceleration (change/s) change = mm/s + * (Maximum start speed for accelerated moves) + * Override with M201 + * X, Y, Z, E0 [, E1[, E2[, E3[, 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 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. + * 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 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 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 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 + +// 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 220 +#define Y_MAX_POS 220 +#define Z_MAX_POS 260 + +// 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) + // 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 + +// +// 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 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, 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':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' } + */ +#define LCD_LANGUAGE en + +/** + * 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 + +// +// 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 + +// +// 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 +// +//#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 + +//define BlinkM/CyzRgb Support +//#define BLINKM + +/** + * 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) + #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 3.00 // (mm) Diameter of the filament generally used (3.0 or 1.75mm), also used in the slicer. Used to validate sensor reading. + +#if ENABLED(FILAMENT_WIDTH_SENSOR) + #define FILAMENT_SENSOR_EXTRUDER_NUM 0 // Index of the extruder that has the filament sensor (0,1,2,3) + #define MEASUREMENT_DELAY_CM 14 // (cm) The distance from the filament sensor to the melting chamber + + #define MEASURED_UPPER_LIMIT 3.30 // (mm) Upper limit used to validate sensor reading + #define MEASURED_LOWER_LIMIT 1.90 // (mm) Lower limit used to validate sensor reading + #define MAX_MEASUREMENT_DELAY 20 // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM. + + #define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially + + // Display filament width on the LCD status line. Status messages will expire after 5 seconds. + //#define FILAMENT_LCD_DISPLAY +#endif + +#endif // CONFIGURATION_H diff --git a/Marlin/example_configurations/CL-260/README.txt b/Marlin/example_configurations/CL-260/README.txt new file mode 100644 index 0000000000..80f82893fe --- /dev/null +++ b/Marlin/example_configurations/CL-260/README.txt @@ -0,0 +1,15 @@ +This is an example configuration for the CL-260. +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 +printer -- it needs tweaking and some parts replaced before being decent.) + +The printer comes with a quite old Marlin, the sources are available here: +http://www.thingiverse.com/thing:1635830/ and I recommend replacing them. + +The setting "works" for my printer and the extruder using my calibration value. +You might want to tweak some settings, e.g enable EEPROM, increase default Z speed, adjust homing speeds,... + +Have fun! +-- +tobi From e47029199e0aaba93451c01307582a29e4ebcad1 Mon Sep 17 00:00:00 2001 From: Thomas Moore Date: Mon, 12 Jun 2017 00:22:31 -0500 Subject: [PATCH 060/180] Remove ADVANCED_PAUSE_FEATURE requirement for PROBING_HEATERS_OFF (#7000) * Remove ADVANCED_PAUSE_FEATURE requirement for PROBING_HEATERS_OFF * Add HEATER_IDLE_HANDLER conditional --- Marlin/Conditionals_post.h | 1 + Marlin/SanityCheck.h | 7 ------- Marlin/temperature.cpp | 18 +++++++++--------- Marlin/temperature.h | 4 ++-- Marlin/ultralcd_impl_DOGM.h | 2 +- Marlin/ultralcd_impl_HD44780.h | 2 +- 6 files changed, 14 insertions(+), 20 deletions(-) diff --git a/Marlin/Conditionals_post.h b/Marlin/Conditionals_post.h index 040885fc2f..4f7272f938 100644 --- a/Marlin/Conditionals_post.h +++ b/Marlin/Conditionals_post.h @@ -653,6 +653,7 @@ #undef PROBING_FANS_OFF #endif #define QUIET_PROBING (HAS_BED_PROBE && (ENABLED(PROBING_HEATERS_OFF) || ENABLED(PROBING_FANS_OFF))) + #define HEATER_IDLE_HANDLER (ENABLED(ADVANCED_PAUSE_FEATURE) || ENABLED(PROBING_HEATERS_OFF)) /** * Servos and probes diff --git a/Marlin/SanityCheck.h b/Marlin/SanityCheck.h index 7260c0e5b2..f975733361 100644 --- a/Marlin/SanityCheck.h +++ b/Marlin/SanityCheck.h @@ -577,13 +577,6 @@ static_assert(1 >= 0 #error "Probes need Z_CLEARANCE_BETWEEN_PROBES >= 0." #endif - /** - * Advanced Pause is required in order to turn the heaters off during probing - */ - #if (ENABLED(PROBING_HEATERS_OFF) && DISABLED(ADVANCED_PAUSE_FEATURE)) - #error "PROBING_HEATERS_OFF requires ADVANCED_PAUSE_FEATURE" - #endif - #else /** diff --git a/Marlin/temperature.cpp b/Marlin/temperature.cpp index f62e5a94db..56be635da2 100644 --- a/Marlin/temperature.cpp +++ b/Marlin/temperature.cpp @@ -203,7 +203,7 @@ uint8_t Temperature::soft_pwm_amount[HOTENDS], bool Temperature::paused; #endif -#if ENABLED(ADVANCED_PAUSE_FEATURE) +#if HEATER_IDLE_HANDLER millis_t Temperature::heater_idle_timeout_ms[HOTENDS] = { 0 }; bool Temperature::heater_idle_timeout_exceeded[HOTENDS] = { false }; #if HAS_TEMP_BED @@ -558,7 +558,7 @@ float Temperature::get_pid_output(int e) { pid_error[HOTEND_INDEX] = target_temperature[HOTEND_INDEX] - current_temperature[HOTEND_INDEX]; dTerm[HOTEND_INDEX] = K2 * PID_PARAM(Kd, HOTEND_INDEX) * (current_temperature[HOTEND_INDEX] - temp_dState[HOTEND_INDEX]) + K1 * dTerm[HOTEND_INDEX]; temp_dState[HOTEND_INDEX] = current_temperature[HOTEND_INDEX]; - #if ENABLED(ADVANCED_PAUSE_FEATURE) + #if HEATER_IDLE_HANDLER if (heater_idle_timeout_exceeded[HOTEND_INDEX]) { pid_output = 0; pid_reset[HOTEND_INDEX] = true; @@ -570,7 +570,7 @@ float Temperature::get_pid_output(int e) { pid_reset[HOTEND_INDEX] = true; } else if (pid_error[HOTEND_INDEX] < -(PID_FUNCTIONAL_RANGE) || target_temperature[HOTEND_INDEX] == 0 - #if ENABLED(ADVANCED_PAUSE_FEATURE) + #if HEATER_IDLE_HANDLER || heater_idle_timeout_exceeded[HOTEND_INDEX] #endif ) { @@ -633,7 +633,7 @@ float Temperature::get_pid_output(int e) { #endif // PID_DEBUG #else /* PID off */ - #if ENABLED(ADVANCED_PAUSE_FEATURE) + #if HEATER_IDLE_HANDLER if (heater_idle_timeout_exceeded[HOTEND_INDEX]) pid_output = 0; else @@ -719,13 +719,13 @@ void Temperature::manage_heater() { if (current_temperature[0] < max(HEATER_0_MINTEMP, MAX6675_TMIN + .01)) min_temp_error(0); #endif - #if WATCH_HOTENDS || WATCH_THE_BED || DISABLED(PIDTEMPBED) || HAS_AUTO_FAN || ENABLED(ADVANCED_PAUSE_FEATURE) + #if WATCH_HOTENDS || WATCH_THE_BED || DISABLED(PIDTEMPBED) || HAS_AUTO_FAN || HEATER_IDLE_HANDLER millis_t ms = millis(); #endif HOTEND_LOOP() { - #if ENABLED(ADVANCED_PAUSE_FEATURE) + #if HEATER_IDLE_HANDLER if (!heater_idle_timeout_exceeded[e] && heater_idle_timeout_ms[e] && ELAPSED(ms, heater_idle_timeout_ms[e])) heater_idle_timeout_exceeded[e] = true; #endif @@ -793,7 +793,7 @@ void Temperature::manage_heater() { #if HAS_TEMP_BED - #if ENABLED(ADVANCED_PAUSE_FEATURE) + #if HEATER_IDLE_HANDLER if (!bed_idle_timeout_exceeded && bed_idle_timeout_ms && ELAPSED(ms, bed_idle_timeout_ms)) bed_idle_timeout_exceeded = true; #endif @@ -802,7 +802,7 @@ void Temperature::manage_heater() { thermal_runaway_protection(&thermal_runaway_bed_state_machine, &thermal_runaway_bed_timer, current_temperature_bed, target_temperature_bed, -1, THERMAL_PROTECTION_BED_PERIOD, THERMAL_PROTECTION_BED_HYSTERESIS); #endif - #if ENABLED(ADVANCED_PAUSE_FEATURE) + #if HEATER_IDLE_HANDLER if (bed_idle_timeout_exceeded) { soft_pwm_amount_bed = 0; @@ -1294,7 +1294,7 @@ void Temperature::init() { int heater_index = heater_id >= 0 ? heater_id : HOTENDS; - #if ENABLED(ADVANCED_PAUSE_FEATURE) + #if HEATER_IDLE_HANDLER // If the heater idle timeout expires, restart if (heater_id >= 0 && heater_idle_timeout_exceeded[heater_id]) { *state = TRInactive; diff --git a/Marlin/temperature.h b/Marlin/temperature.h index 18717dea21..2eff176198 100644 --- a/Marlin/temperature.h +++ b/Marlin/temperature.h @@ -262,7 +262,7 @@ class Temperature { static bool paused; #endif - #if ENABLED(ADVANCED_PAUSE_FEATURE) + #if HEATER_IDLE_HANDLER static millis_t heater_idle_timeout_ms[HOTENDS]; static bool heater_idle_timeout_exceeded[HOTENDS]; #if HAS_TEMP_BED @@ -476,7 +476,7 @@ class Temperature { static bool is_paused() { return paused; } #endif - #if ENABLED(ADVANCED_PAUSE_FEATURE) + #if HEATER_IDLE_HANDLER static void start_heater_idle_timer(uint8_t e, millis_t timeout_ms) { #if HOTENDS == 1 UNUSED(e); diff --git a/Marlin/ultralcd_impl_DOGM.h b/Marlin/ultralcd_impl_DOGM.h index bfd103a7d3..29445262c3 100644 --- a/Marlin/ultralcd_impl_DOGM.h +++ b/Marlin/ultralcd_impl_DOGM.h @@ -357,7 +357,7 @@ FORCE_INLINE void _draw_heater_status(const uint8_t x, const int8_t heater, cons #endif if (PAGE_UNDER(7)) { - #if ENABLED(ADVANCED_PAUSE_FEATURE) + #if HEATER_IDLE_HANDLER const bool is_idle = (!isBed ? thermalManager.is_heater_idle(heater) : #if HAS_TEMP_BED thermalManager.is_bed_idle() diff --git a/Marlin/ultralcd_impl_HD44780.h b/Marlin/ultralcd_impl_HD44780.h index ef5301b7f2..7bc901854e 100644 --- a/Marlin/ultralcd_impl_HD44780.h +++ b/Marlin/ultralcd_impl_HD44780.h @@ -600,7 +600,7 @@ FORCE_INLINE void _draw_heater_status(const int8_t heater, const char prefix, co lcd.print(itostr3(t1 + 0.5)); lcd.print('/'); - #if ENABLED(ADVANCED_PAUSE_FEATURE) + #if HEATER_IDLE_HANDLER const bool is_idle = (!isBed ? thermalManager.is_heater_idle(heater) : #if HAS_TEMP_BED thermalManager.is_bed_idle() From 896dfa05775f9e4464d6aeeb7fb63b36c7521bf6 Mon Sep 17 00:00:00 2001 From: Luc Van Daele Date: Mon, 12 Jun 2017 08:07:19 +0200 Subject: [PATCH 061/180] G33 eccentric probe fixes (#6850) * excentric probe config fix * undo last commit * eccentric probe fix * oops * !stow after each probe * deploy/stow fix * E parameter + bit of cleanup * comment * LCD menu fix --- Marlin/Marlin_main.cpp | 58 ++++++++++++++++++++---------------------- Marlin/ultralcd.cpp | 2 +- 2 files changed, 29 insertions(+), 31 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index d66a8d7092..35a9f3e5dd 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -5080,6 +5080,8 @@ void home_all_axes() { gcode_G28(true); } * V0 Dry-run mode. Report settings and probe results. No calibration. * V1 Report settings * V2 Report settings and probe results + * + * E Engage the probe for each point */ inline void gcode_G33() { @@ -5102,6 +5104,7 @@ void home_all_axes() { gcode_G28(true); } } const bool towers_set = !parser.seen('T'), + stow_after_each = parser.seen('E'), _1p_calibration = probe_points == 1, _4p_calibration = probe_points == 2, _4p_towers_points = _4p_calibration && towers_set, @@ -5120,30 +5123,17 @@ void home_all_axes() { gcode_G28(true); } _7p_double_circle ? 0.5 : 0), radius = (1 + circles * 0.1) * delta_calibration_radius; for (uint8_t axis = 1; axis < 13; ++axis) { - if (!position_is_reachable_by_probe_xy(cos(RADIANS(180 + 30 * axis)) * radius, sin(RADIANS(180 + 30 * axis)) * radius)) { + if (!position_is_reachable_xy(cos(RADIANS(180 + 30 * axis)) * radius, sin(RADIANS(180 + 30 * axis)) * radius)) { SERIAL_PROTOCOLLNPGM("?(M665 B)ed radius is implausible."); return; } } } - SERIAL_PROTOCOLLNPGM("G33 Auto Calibrate"); - - stepper.synchronize(); - #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); - #endif - setup_for_endstop_or_probe_move(); - - endstops.enable(true); - home_delta(); - endstops.not_homing(); - const static char save_message[] PROGMEM = "Save with M500 and/or copy to Configuration.h"; + const float dx = (X_PROBE_OFFSET_FROM_EXTRUDER), + dy = (Y_PROBE_OFFSET_FROM_EXTRUDER); + int8_t iterations = 0; float test_precision, zero_std_dev = (verbose_level ? 999.0 : 0.0), // 0.0 in dry-run mode : forced end zero_std_dev_old = zero_std_dev, @@ -5157,6 +5147,22 @@ void home_all_axes() { gcode_G28(true); } alpha_old = delta_tower_angle_trim[A_AXIS], beta_old = delta_tower_angle_trim[B_AXIS]; + SERIAL_PROTOCOLLNPGM("G33 Auto Calibrate"); + + stepper.synchronize(); + #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); + #endif + setup_for_endstop_or_probe_move(); + DEPLOY_PROBE(); + endstops.enable(true); + home_delta(); + endstops.not_homing(); + // print settings SERIAL_PROTOCOLPGM("Checking... AC"); @@ -5189,13 +5195,7 @@ void home_all_axes() { gcode_G28(true); } SERIAL_EOL(); } - #if ENABLED(Z_PROBE_SLED) - DEPLOY_PROBE(); - #endif - - int8_t iterations = 0; - - home_offset[Z_AXIS] -= probe_pt(0.0, 0.0 , true, 1); // 1st probe to set height + home_offset[Z_AXIS] -= probe_pt(dx, dy, stow_after_each, 1); // 1st probe to set height do_probe_raise(Z_CLEARANCE_BETWEEN_PROBES); do { @@ -5210,12 +5210,12 @@ void home_all_axes() { gcode_G28(true); } // Probe the points if (!_7p_half_circle && !_7p_triple_circle) { // probe the center - z_at_pt[0] += probe_pt(0.0, 0.0 , true, 1); + z_at_pt[0] += probe_pt(dx, dy, stow_after_each, 1); } if (_7p_calibration) { // probe extra center points for (int8_t axis = _7p_multi_circle ? 11 : 9; axis > 0; axis -= _7p_multi_circle ? 2 : 4) { const float a = RADIANS(180 + 30 * axis), r = delta_calibration_radius * 0.1; - z_at_pt[0] += probe_pt(cos(a) * r, sin(a) * r, true, 1); // TODO: Needs error handling + z_at_pt[0] += probe_pt(cos(a) * r + dx, sin(a) * r + dy, stow_after_each, 1); } z_at_pt[0] /= float(_7p_double_circle ? 7 : probe_points); } @@ -5230,7 +5230,7 @@ void home_all_axes() { gcode_G28(true); } for (float circles = -offset_circles ; circles <= offset_circles; circles++) { const float a = RADIANS(180 + 30 * axis), r = delta_calibration_radius * (1 + circles * (zig_zag ? 0.1 : -0.1)); - z_at_pt[axis] += probe_pt(cos(a) * r, sin(a) * r, true, 1); // TODO: Needs error handling + z_at_pt[axis] += probe_pt(cos(a) * r + dx, sin(a) * r + dy, stow_after_each, 1); } zig_zag = !zig_zag; z_at_pt[axis] /= (2 * offset_circles + 1); @@ -5452,13 +5452,11 @@ void home_all_axes() { gcode_G28(true); } #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 - #if ENABLED(Z_PROBE_SLED) - RETRACT_PROBE(); - #endif } #endif // DELTA_AUTO_CALIBRATION diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index 503ae95b3f..fa22df4efa 100644 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -2323,7 +2323,7 @@ void kill_screen(const char* lcd_msg) { MENU_BACK(MSG_MAIN); #if ENABLED(DELTA_AUTO_CALIBRATION) MENU_ITEM(gcode, MSG_DELTA_AUTO_CALIBRATE, PSTR("G33")); - MENU_ITEM(gcode, MSG_DELTA_HEIGHT_CALIBRATE, PSTR("G33 P1 A")); + MENU_ITEM(gcode, MSG_DELTA_HEIGHT_CALIBRATE, PSTR("G33 P1")); #endif MENU_ITEM(submenu, MSG_AUTO_HOME, _lcd_delta_calibrate_home); if (axis_homed[Z_AXIS]) { From 0bc66bf22ceaa2a3a06d657893372f00b2d99f75 Mon Sep 17 00:00:00 2001 From: dot-bob Date: Sat, 10 Jun 2017 00:02:15 -0600 Subject: [PATCH 062/180] PCA9632 PWM color LED support Add support for the PCA9632 PWM color LED driver used on the Ultimaker 2 and Wanhao Duplicator 6. --- .travis.yml | 6 + Marlin/Conditionals_LCD.h | 2 +- Marlin/Configuration.h | 5 +- Marlin/Marlin_main.cpp | 21 +++- Marlin/SanityCheck.h | 8 +- .../CL-260/Configuration.h | 5 +- .../Cartesio/Configuration.h | 5 +- .../Felix/Configuration.h | 5 +- .../Felix/DUAL/Configuration.h | 5 +- .../FolgerTech-i3-2020/Configuration.h | 5 +- .../Hephestos/Configuration.h | 5 +- .../Hephestos_2/Configuration.h | 5 +- .../K8200/Configuration.h | 5 +- .../K8400/Configuration.h | 5 +- .../K8400/Dual-head/Configuration.h | 5 +- .../M150/Configuration.h | 5 +- .../RepRapWorld/Megatronics/Configuration.h | 5 +- .../RigidBot/Configuration.h | 5 +- .../SCARA/Configuration.h | 5 +- .../TAZ4/Configuration.h | 5 +- .../TinyBoy2/Configuration.h | 5 +- .../WITBOX/Configuration.h | 5 +- .../adafruit/ST7565/Configuration.h | 5 +- .../FLSUN/auto_calibrate/Configuration.h | 5 +- .../delta/FLSUN/kossel_mini/Configuration.h | 5 +- .../delta/generic/Configuration.h | 5 +- .../delta/kossel_mini/Configuration.h | 5 +- .../delta/kossel_pro/Configuration.h | 5 +- .../delta/kossel_xl/Configuration.h | 5 +- .../gCreate_gMax1.5+/Configuration.h | 5 +- .../makibox/Configuration.h | 5 +- .../tvrrug/Round2/Configuration.h | 5 +- .../wt150/Configuration.h | 5 +- Marlin/pca9632.cpp | 115 ++++++++++++++++++ Marlin/pca9632.h | 36 ++++++ 35 files changed, 292 insertions(+), 41 deletions(-) create mode 100644 Marlin/pca9632.cpp create mode 100644 Marlin/pca9632.h diff --git a/.travis.yml b/.travis.yml index 03f7585d0c..643517a447 100644 --- a/.travis.yml +++ b/.travis.yml @@ -291,6 +291,12 @@ script: - opt_enable ULTIMAKERCONTROLLER - build_marlin # + # PCA9632 + # + - restore_configs + - opt_enable PCA9632 + - build_marlin + # # MAKRPANEL # Needs to use Melzi and Sanguino hardware # diff --git a/Marlin/Conditionals_LCD.h b/Marlin/Conditionals_LCD.h index b33499e6bf..48cc0141a5 100644 --- a/Marlin/Conditionals_LCD.h +++ b/Marlin/Conditionals_LCD.h @@ -398,6 +398,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)) + #define HAS_COLOR_LEDS (ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632)) #endif // CONDITIONALS_LCD_H diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index cc422b6525..7d6c4a5614 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -1482,6 +1482,9 @@ //define BlinkM/CyzRgb Support //#define BLINKM +//define PCA9632 PWM LED driver Support +//#define PCA9632 + /** * RGB LED / LED Strip Control * @@ -1519,7 +1522,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) #define PRINTER_EVENT_LEDS #endif diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 35a9f3e5dd..da3bf1a12c 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -138,7 +138,7 @@ * M140 - Set bed target temp. S * M145 - Set heatup values for materials on the LCD. H B F for S (0=PLA, 1=ABS) * M149 - Set temperature units. (Requires TEMPERATURE_UNITS_SUPPORT) - * M150 - Set Status LED Color as R U B. Values 0-255. (Requires BLINKM or RGB_LED) + * M150 - Set Status LED Color as R U B. Values 0-255. (Requires BLINKM, RGB_LED, RGBW_LED, or PCA9632) * M155 - Auto-report temperatures with interval of S. (Requires AUTO_REPORT_TEMPERATURES) * M163 - Set a single proportion for a mixing extruder. (Requires MIXING_EXTRUDER) * M164 - Save the mix as a virtual extruder. (Requires MIXING_EXTRUDER and MIXING_VIRTUAL_TOOLS) @@ -280,6 +280,10 @@ #include "Wire.h" #endif +#if ENABLED(PCA9632) + #include "pca9632.h" +#endif + #if HAS_SERVOS #include "servo.h" #endif @@ -986,7 +990,9 @@ void servo_init() { // This variant uses i2c to send the RGB components to the device. SendColors(r, g, b); - #else + #endif + + #if ENABLED(RGB_LED) || ENABLED(RGBW_LED) // This variant uses 3 separate pins for the RGB components. // If the pins can do PWM then their intensity will be set. @@ -1003,6 +1009,11 @@ void servo_init() { #endif #endif + + #if ENABLED(PCA9632) + // Update I2C LED driver + PCA9632_SetColor(r, g, b); + #endif } #endif // HAS_COLOR_LEDS @@ -5893,7 +5904,7 @@ inline void gcode_M17() { if (!DEBUGGING(DRYRUN) && unload_length != 0) { #if ENABLED(PREVENT_COLD_EXTRUSION) - if (!thermalManager.allow_cold_extrude && + if (!thermalManager.allow_cold_extrude && thermalManager.degTargetHotend(active_extruder) < thermalManager.extrude_min_temp) { SERIAL_ERROR_START(); SERIAL_ERRORLNPGM(MSG_TOO_COLD_FOR_M600); @@ -8013,7 +8024,7 @@ inline void gcode_M121() { endstops.enable_globally(false); } ); } -#endif // BLINKM || RGB_LED +#endif // HAS_COLOR_LEDS /** * M200: Set filament diameter and set E axis units to cubic units @@ -10621,7 +10632,7 @@ void process_next_command() { gcode_M150(); break; - #endif // BLINKM + #endif // HAS_COLOR_LEDS #if ENABLED(MIXING_EXTRUDER) case 163: // M163: Set a component weight for mixing extruder diff --git a/Marlin/SanityCheck.h b/Marlin/SanityCheck.h index f975733361..de4f550d2b 100644 --- a/Marlin/SanityCheck.h +++ b/Marlin/SanityCheck.h @@ -1027,17 +1027,13 @@ static_assert(1 >= 0 #error "RGB_LED requires RGB_LED_R_PIN, RGB_LED_G_PIN, and RGB_LED_B_PIN." #elif ENABLED(RGBW_LED) #error "Please enable only one of RGB_LED and RGBW_LED." - #elif ENABLED(BLINKM) - #error "RGB_LED and BLINKM are currently incompatible (both use M150)." #endif #elif ENABLED(RGBW_LED) #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." - #elif ENABLED(BLINKM) - #error "RGBW_LED and BLINKM are currently incompatible (both use M150)." #endif -#elif DISABLED(BLINKM) && ENABLED(PRINTER_EVENT_LEDS) - #error "PRINTER_EVENT_LEDS requires BLINKM, RGB_LED, or RGBW_LED." +#elif ENABLED(PRINTER_EVENT_LEDS) && DISABLED(BLINKM) && DISABLED(PCA9632) + #error "PRINTER_EVENT_LEDS requires BLINKM, PCA9632, RGB_LED, or RGBW_LED." #endif /** diff --git a/Marlin/example_configurations/CL-260/Configuration.h b/Marlin/example_configurations/CL-260/Configuration.h index 8be2b4427b..fe024c71b5 100644 --- a/Marlin/example_configurations/CL-260/Configuration.h +++ b/Marlin/example_configurations/CL-260/Configuration.h @@ -1482,6 +1482,9 @@ //define BlinkM/CyzRgb Support //#define BLINKM +//define PCA9632 PWM LED driver Support +//#define PCA9632 + /** * RGB LED / LED Strip Control * @@ -1519,7 +1522,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) #define PRINTER_EVENT_LEDS #endif diff --git a/Marlin/example_configurations/Cartesio/Configuration.h b/Marlin/example_configurations/Cartesio/Configuration.h index 13929a9543..38fd64f429 100644 --- a/Marlin/example_configurations/Cartesio/Configuration.h +++ b/Marlin/example_configurations/Cartesio/Configuration.h @@ -1479,6 +1479,9 @@ //define BlinkM/CyzRgb Support //#define BLINKM +//define PCA9632 PWM LED driver Support +//#define PCA9632 + /** * RGB LED / LED Strip Control * @@ -1516,7 +1519,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) #define PRINTER_EVENT_LEDS #endif diff --git a/Marlin/example_configurations/Felix/Configuration.h b/Marlin/example_configurations/Felix/Configuration.h index d2fd786a5d..d4c3f07381 100644 --- a/Marlin/example_configurations/Felix/Configuration.h +++ b/Marlin/example_configurations/Felix/Configuration.h @@ -1463,6 +1463,9 @@ //define BlinkM/CyzRgb Support //#define BLINKM +//define PCA9632 PWM LED driver Support +//#define PCA9632 + /** * RGB LED / LED Strip Control * @@ -1500,7 +1503,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) #define PRINTER_EVENT_LEDS #endif diff --git a/Marlin/example_configurations/Felix/DUAL/Configuration.h b/Marlin/example_configurations/Felix/DUAL/Configuration.h index 5189616aad..863b725e9a 100644 --- a/Marlin/example_configurations/Felix/DUAL/Configuration.h +++ b/Marlin/example_configurations/Felix/DUAL/Configuration.h @@ -1463,6 +1463,9 @@ //define BlinkM/CyzRgb Support //#define BLINKM +//define PCA9632 PWM LED driver Support +//#define PCA9632 + /** * RGB LED / LED Strip Control * @@ -1500,7 +1503,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) #define PRINTER_EVENT_LEDS #endif diff --git a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h index 8d72fcc27c..1f464ee041 100644 --- a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h +++ b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h @@ -1485,6 +1485,9 @@ //define BlinkM/CyzRgb Support //#define BLINKM +//define PCA9632 PWM LED driver Support +//#define PCA9632 + /** * RGB LED / LED Strip Control * @@ -1522,7 +1525,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) #define PRINTER_EVENT_LEDS #endif diff --git a/Marlin/example_configurations/Hephestos/Configuration.h b/Marlin/example_configurations/Hephestos/Configuration.h index ae0e3a89a5..44cc30e42e 100644 --- a/Marlin/example_configurations/Hephestos/Configuration.h +++ b/Marlin/example_configurations/Hephestos/Configuration.h @@ -1471,6 +1471,9 @@ //define BlinkM/CyzRgb Support //#define BLINKM +//define PCA9632 PWM LED driver Support +//#define PCA9632 + /** * RGB LED / LED Strip Control * @@ -1508,7 +1511,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) #define PRINTER_EVENT_LEDS #endif diff --git a/Marlin/example_configurations/Hephestos_2/Configuration.h b/Marlin/example_configurations/Hephestos_2/Configuration.h index aab15d09a7..04dd6842cc 100644 --- a/Marlin/example_configurations/Hephestos_2/Configuration.h +++ b/Marlin/example_configurations/Hephestos_2/Configuration.h @@ -1474,6 +1474,9 @@ //define BlinkM/CyzRgb Support //#define BLINKM +//define PCA9632 PWM LED driver Support +//#define PCA9632 + /** * RGB LED / LED Strip Control * @@ -1511,7 +1514,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) #define PRINTER_EVENT_LEDS #endif diff --git a/Marlin/example_configurations/K8200/Configuration.h b/Marlin/example_configurations/K8200/Configuration.h index 2efae18109..86304303e4 100644 --- a/Marlin/example_configurations/K8200/Configuration.h +++ b/Marlin/example_configurations/K8200/Configuration.h @@ -1515,6 +1515,9 @@ //define BlinkM/CyzRgb Support //#define BLINKM +//define PCA9632 PWM LED driver Support +//#define PCA9632 + /** * RGB LED / LED Strip Control * @@ -1552,7 +1555,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) #define PRINTER_EVENT_LEDS #endif diff --git a/Marlin/example_configurations/K8400/Configuration.h b/Marlin/example_configurations/K8400/Configuration.h index 8c2ed2be9f..8152f2d619 100644 --- a/Marlin/example_configurations/K8400/Configuration.h +++ b/Marlin/example_configurations/K8400/Configuration.h @@ -1481,6 +1481,9 @@ //define BlinkM/CyzRgb Support //#define BLINKM +//define PCA9632 PWM LED driver Support +//#define PCA9632 + /** * RGB LED / LED Strip Control * @@ -1518,7 +1521,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) #define PRINTER_EVENT_LEDS #endif diff --git a/Marlin/example_configurations/K8400/Dual-head/Configuration.h b/Marlin/example_configurations/K8400/Dual-head/Configuration.h index 7236ab4968..735ac65718 100644 --- a/Marlin/example_configurations/K8400/Dual-head/Configuration.h +++ b/Marlin/example_configurations/K8400/Dual-head/Configuration.h @@ -1481,6 +1481,9 @@ //define BlinkM/CyzRgb Support //#define BLINKM +//define PCA9632 PWM LED driver Support +//#define PCA9632 + /** * RGB LED / LED Strip Control * @@ -1518,7 +1521,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) #define PRINTER_EVENT_LEDS #endif diff --git a/Marlin/example_configurations/M150/Configuration.h b/Marlin/example_configurations/M150/Configuration.h index 7b5321be9e..75c4f4c129 100644 --- a/Marlin/example_configurations/M150/Configuration.h +++ b/Marlin/example_configurations/M150/Configuration.h @@ -1508,6 +1508,9 @@ //define BlinkM/CyzRgb Support //#define BLINKM +//define PCA9632 PWM LED driver Support +//#define PCA9632 + /** * RGB LED / LED Strip Control * @@ -1545,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) +#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) #define PRINTER_EVENT_LEDS #endif diff --git a/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h b/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h index 409684ed8c..fd0fedc30a 100644 --- a/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h +++ b/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h @@ -1481,6 +1481,9 @@ //define BlinkM/CyzRgb Support //#define BLINKM +//define PCA9632 PWM LED driver Support +//#define PCA9632 + /** * RGB LED / LED Strip Control * @@ -1518,7 +1521,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) #define PRINTER_EVENT_LEDS #endif diff --git a/Marlin/example_configurations/RigidBot/Configuration.h b/Marlin/example_configurations/RigidBot/Configuration.h index ef09f47067..77fa6469bf 100644 --- a/Marlin/example_configurations/RigidBot/Configuration.h +++ b/Marlin/example_configurations/RigidBot/Configuration.h @@ -1481,6 +1481,9 @@ //define BlinkM/CyzRgb Support //#define BLINKM +//define PCA9632 PWM LED driver Support +//#define PCA9632 + /** * RGB LED / LED Strip Control * @@ -1518,7 +1521,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) #define PRINTER_EVENT_LEDS #endif diff --git a/Marlin/example_configurations/SCARA/Configuration.h b/Marlin/example_configurations/SCARA/Configuration.h index 9af3cecde5..6f92b4f892 100644 --- a/Marlin/example_configurations/SCARA/Configuration.h +++ b/Marlin/example_configurations/SCARA/Configuration.h @@ -1496,6 +1496,9 @@ //define BlinkM/CyzRgb Support //#define BLINKM +//define PCA9632 PWM LED driver Support +//#define PCA9632 + /** * RGB LED / LED Strip Control * @@ -1533,7 +1536,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) #define PRINTER_EVENT_LEDS #endif diff --git a/Marlin/example_configurations/TAZ4/Configuration.h b/Marlin/example_configurations/TAZ4/Configuration.h index 4660946752..845c758d2f 100644 --- a/Marlin/example_configurations/TAZ4/Configuration.h +++ b/Marlin/example_configurations/TAZ4/Configuration.h @@ -1500,6 +1500,9 @@ //define BlinkM/CyzRgb Support //#define BLINKM +//define PCA9632 PWM LED driver Support +//#define PCA9632 + /** * RGB LED / LED Strip Control * @@ -1537,7 +1540,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) #define PRINTER_EVENT_LEDS #endif diff --git a/Marlin/example_configurations/TinyBoy2/Configuration.h b/Marlin/example_configurations/TinyBoy2/Configuration.h index 4fefe85d6c..0326daf299 100644 --- a/Marlin/example_configurations/TinyBoy2/Configuration.h +++ b/Marlin/example_configurations/TinyBoy2/Configuration.h @@ -1537,6 +1537,9 @@ //define BlinkM/CyzRgb Support //#define BLINKM +//define PCA9632 PWM LED driver Support +//#define PCA9632 + /** * RGB LED / LED Strip Control * @@ -1574,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) +#if ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) #define PRINTER_EVENT_LEDS #endif diff --git a/Marlin/example_configurations/WITBOX/Configuration.h b/Marlin/example_configurations/WITBOX/Configuration.h index 187fb948a6..d090f55065 100644 --- a/Marlin/example_configurations/WITBOX/Configuration.h +++ b/Marlin/example_configurations/WITBOX/Configuration.h @@ -1471,6 +1471,9 @@ //define BlinkM/CyzRgb Support //#define BLINKM +//define PCA9632 PWM LED driver Support +//#define PCA9632 + /** * RGB LED / LED Strip Control * @@ -1508,7 +1511,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) #define PRINTER_EVENT_LEDS #endif diff --git a/Marlin/example_configurations/adafruit/ST7565/Configuration.h b/Marlin/example_configurations/adafruit/ST7565/Configuration.h index 0f608c7a1d..04c62167b0 100644 --- a/Marlin/example_configurations/adafruit/ST7565/Configuration.h +++ b/Marlin/example_configurations/adafruit/ST7565/Configuration.h @@ -1481,6 +1481,9 @@ //define BlinkM/CyzRgb Support //#define BLINKM +//define PCA9632 PWM LED driver Support +//#define PCA9632 + /** * RGB LED / LED Strip Control * @@ -1518,7 +1521,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) #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 df495943d6..840287c96f 100644 --- a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h +++ b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h @@ -1602,6 +1602,9 @@ //define BlinkM/CyzRgb Support //#define BLINKM +//define PCA9632 PWM LED driver Support +//#define PCA9632 + /** * RGB LED / LED Strip Control * @@ -1639,7 +1642,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) #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 453b0a603f..b7fe4eed91 100644 --- a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h +++ b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h @@ -1603,6 +1603,9 @@ //define BlinkM/CyzRgb Support //#define BLINKM +//define PCA9632 PWM LED driver Support +//#define PCA9632 + /** * RGB LED / LED Strip Control * @@ -1640,7 +1643,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) #define PRINTER_EVENT_LEDS #endif diff --git a/Marlin/example_configurations/delta/generic/Configuration.h b/Marlin/example_configurations/delta/generic/Configuration.h index d005b0876b..39500de3f9 100644 --- a/Marlin/example_configurations/delta/generic/Configuration.h +++ b/Marlin/example_configurations/delta/generic/Configuration.h @@ -1592,6 +1592,9 @@ //define BlinkM/CyzRgb Support //#define BLINKM +//define PCA9632 PWM LED driver Support +//#define PCA9632 + /** * RGB LED / LED Strip Control * @@ -1629,7 +1632,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) #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 edc6ca7905..4e3a7ebb69 100644 --- a/Marlin/example_configurations/delta/kossel_mini/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_mini/Configuration.h @@ -1595,6 +1595,9 @@ //define BlinkM/CyzRgb Support //#define BLINKM +//define PCA9632 PWM LED driver Support +//#define PCA9632 + /** * RGB LED / LED Strip Control * @@ -1632,7 +1635,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) #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 42675f9fff..eabdc13574 100644 --- a/Marlin/example_configurations/delta/kossel_pro/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_pro/Configuration.h @@ -1600,6 +1600,9 @@ //define BlinkM/CyzRgb Support //#define BLINKM +//define PCA9632 PWM LED driver Support +//#define PCA9632 + /** * RGB LED / LED Strip Control * @@ -1637,7 +1640,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) #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 1427f5adbb..acbc9e58d8 100644 --- a/Marlin/example_configurations/delta/kossel_xl/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_xl/Configuration.h @@ -1658,6 +1658,9 @@ //define BlinkM/CyzRgb Support //#define BLINKM +//define PCA9632 PWM LED driver Support +//#define PCA9632 + /** * RGB LED / LED Strip Control * @@ -1695,7 +1698,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) #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 63a698a6c3..67eb606e09 100644 --- a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h +++ b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h @@ -1497,6 +1497,9 @@ //define BlinkM/CyzRgb Support //#define BLINKM +//define PCA9632 PWM LED driver Support +//#define PCA9632 + /** * RGB LED / LED Strip Control * @@ -1534,7 +1537,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) #define PRINTER_EVENT_LEDS #endif diff --git a/Marlin/example_configurations/makibox/Configuration.h b/Marlin/example_configurations/makibox/Configuration.h index a13bb2ed53..ae07c775bd 100644 --- a/Marlin/example_configurations/makibox/Configuration.h +++ b/Marlin/example_configurations/makibox/Configuration.h @@ -1484,6 +1484,9 @@ //define BlinkM/CyzRgb Support //#define BLINKM +//define PCA9632 PWM LED driver Support +//#define PCA9632 + /** * RGB LED / LED Strip Control * @@ -1521,7 +1524,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) #define PRINTER_EVENT_LEDS #endif diff --git a/Marlin/example_configurations/tvrrug/Round2/Configuration.h b/Marlin/example_configurations/tvrrug/Round2/Configuration.h index 046a8a5e2b..57a66e1756 100644 --- a/Marlin/example_configurations/tvrrug/Round2/Configuration.h +++ b/Marlin/example_configurations/tvrrug/Round2/Configuration.h @@ -1476,6 +1476,9 @@ //define BlinkM/CyzRgb Support //#define BLINKM +//define PCA9632 PWM LED driver Support +//#define PCA9632 + /** * RGB LED / LED Strip Control * @@ -1513,7 +1516,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) #define PRINTER_EVENT_LEDS #endif diff --git a/Marlin/example_configurations/wt150/Configuration.h b/Marlin/example_configurations/wt150/Configuration.h index 52fa225197..80addd741b 100644 --- a/Marlin/example_configurations/wt150/Configuration.h +++ b/Marlin/example_configurations/wt150/Configuration.h @@ -1486,6 +1486,9 @@ //define BlinkM/CyzRgb Support //#define BLINKM +//define PCA9632 PWM LED driver Support +//#define PCA9632 + // Support for an RGB LED using 3 separate pins with optional PWM //#define RGB_LED //#define RGBW_LED @@ -1507,7 +1510,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) #define PRINTER_EVENT_LEDS #endif diff --git a/Marlin/pca9632.cpp b/Marlin/pca9632.cpp new file mode 100644 index 0000000000..d8853c4650 --- /dev/null +++ b/Marlin/pca9632.cpp @@ -0,0 +1,115 @@ +/** + * 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 . + * + */ + +/* + * Driver for the Philips PCA9632 LED driver. + * Written by Robert Mendon Feb 2017. + */ + +#include "MarlinConfig.h" + +#if ENABLED(PCA9632) + +#include "pca9632.h" + +#define PCA9632_MODE1_VALUE 0b00000001 //(ALLCALL) +#define PCA9632_MODE2_VALUE 0b00010101 //(DIMMING, INVERT, CHANGE ON STOP,TOTEM) +#define PCA9632_LEDOUT_VALUE 0b00101010 + + +/* Register addresses */ +#define PCA9632_MODE1 0x00 +#define PCA9632_MODE2 0x01 +#define PCA9632_PWM0 0x02 +#define PCA9632_PWM1 0x03 +#define PCA9632_PWM2 0x04 +#define PCA9632_PWM3 0x05 +#define PCA9632_GRPPWM 0x06 +#define PCA9632_GRPFREQ 0x07 +#define PCA9632_LEDOUT 0X08 +#define PCA9632_SUBADR1 0x09 +#define PCA9632_SUBADR2 0x0A +#define PCA9632_SUBADR3 0x0B +#define PCA9632_ALLCALLADDR 0x0C + +#define PCA9632_NO_AUTOINC 0x00 +#define PCA9632_AUTO_ALL 0x80 +#define PCA9632_AUTO_IND 0xA0 +#define PCA9632_AUTOGLO 0xC0 +#define PCA9632_AUTOGI 0xE0 + +// Red LED0 +// Green LED1 +// Blue LED2 +#define PCA9632_RED 0x00 +#define PCA9632_GRN 0x02 +#define PCA9632_BLU 0x04 + +#define LED_OFF 0x00 +#define LED_ON 0x01 +#define LED_PWM 0x02 + +#define PCA9632_ADDRESS 0b01100000 + +byte PCA_init = 0; + +static void PCA9632_WriteRegister(const byte addr, const byte regadd, const byte value) { + Wire.beginTransmission(addr); + Wire.write(regadd); + Wire.write(value); + Wire.endTransmission(); +} + +static void PCA9632_WriteAllRegisters(const byte addr, const byte regadd, const byte value1, const byte value2, const byte value3) { + Wire.beginTransmission(addr); + Wire.write(PCA9632_AUTO_IND | regadd); + Wire.write(value1); + Wire.write(value2); + Wire.write(value3); + 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; +} + +void PCA9632_SetColor(const byte r, const byte g, const byte b) { + if (!PCA_init) { + PCA_init = 1; + Wire.begin(); + PCA9632_WriteRegister(PCA9632_ADDRESS,PCA9632_MODE1, PCA9632_MODE1_VALUE); + PCA9632_WriteRegister(PCA9632_ADDRESS,PCA9632_MODE2, PCA9632_MODE2_VALUE); + } + + const byte LEDOUT = (r ? LED_PWM << PCA9632_RED : 0) + | (g ? LED_PWM << PCA9632_GRN : 0) + | (b ? LED_PWM << PCA9632_BLU : 0); + + PCA9632_WriteAllRegisters(PCA9632_ADDRESS,PCA9632_PWM0, r, g, b); + PCA9632_WriteRegister(PCA9632_ADDRESS,PCA9632_LEDOUT, LEDOUT); +} + +#endif // PCA9632 diff --git a/Marlin/pca9632.h b/Marlin/pca9632.h new file mode 100644 index 0000000000..b8c78f065d --- /dev/null +++ b/Marlin/pca9632.h @@ -0,0 +1,36 @@ +/** + * 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 . + * + */ + +/* + * Driver for the Philips PCA9632 LED driver. + * Written by Robert Mendon Feb 2017. + */ + +#ifndef __PCA9632_H__ +#define __PCA9632_H__ + +#include "Arduino.h" +#include "Wire.h" + +void PCA9632_SetColor(const byte r, const byte g, const byte b); + +#endif // __PCA9632_H__ From 570722a0fed7dc25a39271c062fe7c1cbb50efc1 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 11 Jun 2017 22:49:35 -0500 Subject: [PATCH 063/180] Combine Travis tests to shorten required time --- .travis.yml | 146 ++++++++++++---------------------------------------- 1 file changed, 33 insertions(+), 113 deletions(-) diff --git a/.travis.yml b/.travis.yml index 643517a447..127faef496 100644 --- a/.travis.yml +++ b/.travis.yml @@ -71,48 +71,15 @@ script: # - build_marlin # - # Test heated bed temperature sensor - # - - opt_set TEMP_SENSOR_BED 1 - - build_marlin - # - # Test 2 extruders on basic RAMPS 1.4 + # Test 2 extruders (one MAX6675) and heated bed on basic RAMPS 1.4 + # plus a "Fix Mounted" Probe with Safe Homing # - opt_set MOTHERBOARD BOARD_RAMPS_14_EEB - opt_set EXTRUDERS 2 - - opt_set TEMP_SENSOR_1 1 - - build_marlin - # - # Test 5 extruders on AZTEEG_X3_PRO (can use any board with >=5 extruders defined) - # Include a test for LIN_ADVANCE here also - # - - opt_set MOTHERBOARD BOARD_AZTEEG_X3_PRO - - opt_set EXTRUDERS 5 - - opt_set TEMP_SENSOR_1 1 - - opt_set TEMP_SENSOR_2 5 - - opt_set TEMP_SENSOR_3 20 - - opt_set TEMP_SENSOR_4 999 - - opt_set TEMP_SENSOR_BED 1 - - opt_enable_adv LIN_ADVANCE - - build_marlin - # - # Test PIDTEMPBED - # - - restore_configs - - opt_set TEMP_SENSOR_BED 1 - - opt_enable PIDTEMPBED - - build_marlin - # - # Test MAX6675 - # - - restore_configs - opt_set TEMP_SENSOR_0 -2 - - build_marlin - # - # Test a "Fix Mounted" Probe along with Safe Homing - # - - restore_configs - - opt_enable FIX_MOUNTED_PROBE Z_SAFE_HOMING + - opt_set TEMP_SENSOR_1 1 + - opt_set TEMP_SENSOR_BED 1 + - opt_enable PIDTEMPBED FIX_MOUNTED_PROBE Z_SAFE_HOMING - build_marlin # # ...with AUTO_BED_LEVELING_LINEAR, Z_MIN_PROBE_REPEATABILITY_TEST, and DEBUG_LEVELING_FEATURE @@ -151,17 +118,27 @@ script: - opt_enable MESH_BED_LEVELING MESH_G28_REST_ORIGIN LCD_BED_LEVELING ULTIMAKERCONTROLLER - build_marlin # - # Test PROBE_MANUALLY feature, with LCD support + # Test PROBE_MANUALLY feature, with LCD support, + # EEPROM_SETTINGS, EEPROM_CHITCHAT, M100_FREE_MEMORY_WATCHER, + # INCH_MODE_SUPPORT, TEMPERATURE_UNITS_SUPPORT # - restore_configs + - opt_set MOTHERBOARD BOARD_MINIRAMBO - opt_enable PROBE_MANUALLY AUTO_BED_LEVELING_BILINEAR LCD_BED_LEVELING ULTIMAKERCONTROLLER + - opt_enable EEPROM_SETTINGS EEPROM_CHITCHAT M100_FREE_MEMORY_WATCHER M100_FREE_MEMORY_DUMPER M100_FREE_MEMORY_CORRUPTOR INCH_MODE_SUPPORT TEMPERATURE_UNITS_SUPPORT - build_marlin # - # Test EEPROM_SETTINGS, EEPROM_CHITCHAT, M100_FREE_MEMORY_WATCHER, - # INCH_MODE_SUPPORT, TEMPERATURE_UNITS_SUPPORT + # Test 5 extruders on AZTEEG_X3_PRO (can use any board with >=5 extruders defined) + # Include a test for LIN_ADVANCE here also # - - restore_configs - - opt_enable EEPROM_SETTINGS EEPROM_CHITCHAT M100_FREE_MEMORY_WATCHER M100_FREE_MEMORY_DUMPER M100_FREE_MEMORY_CORRUPTOR INCH_MODE_SUPPORT TEMPERATURE_UNITS_SUPPORT + - opt_set MOTHERBOARD BOARD_AZTEEG_X3_PRO + - opt_set EXTRUDERS 5 + - opt_set TEMP_SENSOR_1 1 + - opt_set TEMP_SENSOR_2 5 + - opt_set TEMP_SENSOR_3 20 + - opt_set TEMP_SENSOR_4 999 + - opt_set TEMP_SENSOR_BED 1 + - opt_enable_adv LIN_ADVANCE - build_marlin # # Mixing Extruder with 5 steppers @@ -202,34 +179,19 @@ script: - build_marlin # # Test MINIRAMBO for PWM_MOTOR_CURRENT + # ULTIMAKERCONTROLLER, FILAMENT_LCD_DISPLAY, FILAMENT_WIDTH_SENSOR, + # PRINTCOUNTER, NOZZLE_PARK_FEATURE, NOZZLE_CLEAN_FEATURE, PCA9632, + # Z_DUAL_STEPPER_DRIVERS, Z_DUAL_ENDSTOPS, BEZIER_CURVE_SUPPORT, EXPERIMENTAL_I2CBUS, + # FILAMENT_CHANGE_FEATURE, PARK_HEAD_ON_PAUSE, LCD_INFO_MENU, # - restore_configs - - opt_set MOTHERBOARD BOARD_MINIRAMBO - - build_marlin - # - # Test FILAMENT_CHANGE_FEATURE, PARK_HEAD_ON_PAUSE, and LCD_INFO_MENU - # - - restore_configs - - opt_enable ULTIMAKERCONTROLLER - - opt_enable_adv FILAMENT_CHANGE_FEATURE PARK_HEAD_ON_PAUSE LCD_INFO_MENU - - build_marlin - # - # Enable filament sensor - # - - restore_configs - - opt_enable FILAMENT_WIDTH_SENSOR - - build_marlin - # - # Enable filament sensor with LCD display - # - - opt_enable ULTIMAKERCONTROLLER FILAMENT_LCD_DISPLAY - - build_marlin - # - # Enable BEZIER_CURVE_SUPPORT, EXPERIMENTAL_I2CBUS, and I2C_SLAVE_ADDRESS - # - - restore_configs - - opt_enable_adv BEZIER_CURVE_SUPPORT EXPERIMENTAL_I2CBUS + - opt_enable ULTIMAKERCONTROLLER FILAMENT_LCD_DISPLAY FILAMENT_WIDTH_SENSOR SDSUPPORT + - opt_enable PRINTCOUNTER NOZZLE_PARK_FEATURE NOZZLE_CLEAN_FEATURE PCA9632 + - opt_enable_adv Z_DUAL_STEPPER_DRIVERS Z_DUAL_ENDSTOPS BEZIER_CURVE_SUPPORT EXPERIMENTAL_I2CBUS - opt_set_adv I2C_SLAVE_ADDRESS 63 + - opt_enable_adv FILAMENT_CHANGE_FEATURE PARK_HEAD_ON_PAUSE LCD_INFO_MENU + - pins_set RAMPS X_MAX_PIN -1 + - opt_set_adv Z2_MAX_PIN 2 - build_marlin # # Enable COREXY @@ -244,34 +206,8 @@ script: - opt_enable COREYX - build_marlin # - # Enable Z_DUAL_STEPPER_DRIVERS, Z_DUAL_ENDSTOPS # - - restore_configs - - opt_enable_adv Z_DUAL_STEPPER_DRIVERS Z_DUAL_ENDSTOPS - - pins_set RAMPS X_MAX_PIN -1 - - opt_set_adv Z2_MAX_PIN 2 - - build_marlin - # - # Test PRINTCOUNTER - # - - restore_configs - - opt_enable PRINTCOUNTER - - build_marlin - # - # Test NOZZLE_PARK_FEATURE - # - - restore_configs - - opt_enable NOZZLE_PARK_FEATURE - - build_marlin - # - # Test NOZZLE_CLEAN_FEATURE - # - - restore_configs - - opt_enable NOZZLE_CLEAN_FEATURE - - build_marlin - # - # - ######## STANDARD LCD/PANELS ############## + ######## Other Standard LCD/Panels ############## # # ULTRA_LCD # @@ -285,18 +221,6 @@ script: - opt_enable DOGLCD - build_marlin # - # ULTIMAKERCONTROLLER - # - - restore_configs - - opt_enable ULTIMAKERCONTROLLER - - build_marlin - # - # PCA9632 - # - - restore_configs - - opt_enable PCA9632 - - build_marlin - # # MAKRPANEL # Needs to use Melzi and Sanguino hardware # @@ -310,15 +234,11 @@ script: - opt_enable REPRAP_DISCOUNT_SMART_CONTROLLER SDSUPPORT BABYSTEPPING - build_marlin # - # G3D_PANEL + # G3D_PANEL with SDCARD_SORT_ALPHA and STATUS_MESSAGE_SCROLLING # - restore_configs - opt_enable G3D_PANEL SDSUPPORT - - build_marlin - # - # Add SDCARD_SORT_ALPHA, test G3D_PANEL again - # - - opt_enable_adv SDCARD_SORT_ALPHA + - opt_enable_adv SDCARD_SORT_ALPHA STATUS_MESSAGE_SCROLLING - opt_set_adv SDSORT_GCODE true - opt_set_adv SDSORT_USES_RAM true - opt_set_adv SDSORT_USES_STACK true From 699aa35df6ada555b5319d38e0eb6035ff436387 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 12 Jun 2017 01:25:40 -0500 Subject: [PATCH 064/180] Code cleanup for G33 --- Marlin/Marlin_main.cpp | 84 ++++++++++++++++-------------------------- 1 file changed, 31 insertions(+), 53 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index da3bf1a12c..0a573af8a3 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -3529,7 +3529,7 @@ inline void gcode_G4() { if (leveling_is_active()) { SERIAL_ECHOLNPGM(" (enabled)"); #if ABL_PLANAR - float diff[XYZ] = { + const float diff[XYZ] = { stepper.get_axis_position_mm(X_AXIS) - current_position[X_AXIS], stepper.get_axis_position_mm(Y_AXIS) - current_position[Y_AXIS], stepper.get_axis_position_mm(Z_AXIS) - current_position[Z_AXIS] @@ -5094,6 +5094,15 @@ void home_all_axes() { gcode_G28(true); } * * E Engage the probe for each point */ + + void print_signed_float(const char * const prefix, const float &f) { + SERIAL_PROTOCOLPGM(" "); + serialprintPGM(prefix); + SERIAL_PROTOCOLCHAR(':'); + if (f >= 0) SERIAL_CHAR('+'); + SERIAL_PROTOCOL_F(f, 2); + } + inline void gcode_G33() { const int8_t probe_points = parser.seen('P') ? parser.value_int() : DELTA_CALIBRATION_DEFAULT_POINTS; @@ -5115,7 +5124,7 @@ void home_all_axes() { gcode_G28(true); } } const bool towers_set = !parser.seen('T'), - stow_after_each = parser.seen('E'), + stow_after_each = parser.seen('E') && parser.value_bool(), _1p_calibration = probe_points == 1, _4p_calibration = probe_points == 2, _4p_towers_points = _4p_calibration && towers_set, @@ -5183,25 +5192,16 @@ void home_all_axes() { gcode_G28(true); } SERIAL_PROTOCOLPAIR(".Height:", DELTA_HEIGHT + home_offset[Z_AXIS]); if (!_1p_calibration) { - SERIAL_PROTOCOLPGM(" Ex:"); - if (endstop_adj[A_AXIS] >= 0) SERIAL_CHAR('+'); - SERIAL_PROTOCOL_F(endstop_adj[A_AXIS], 2); - SERIAL_PROTOCOLPGM(" Ey:"); - if (endstop_adj[B_AXIS] >= 0) SERIAL_CHAR('+'); - SERIAL_PROTOCOL_F(endstop_adj[B_AXIS], 2); - SERIAL_PROTOCOLPGM(" Ez:"); - if (endstop_adj[C_AXIS] >= 0) SERIAL_CHAR('+'); - SERIAL_PROTOCOL_F(endstop_adj[C_AXIS], 2); + 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 : Tx:"); - if (delta_tower_angle_trim[A_AXIS] >= 0) SERIAL_CHAR('+'); - SERIAL_PROTOCOL_F(delta_tower_angle_trim[A_AXIS], 2); - SERIAL_PROTOCOLPGM(" Ty:"); - if (delta_tower_angle_trim[B_AXIS] >= 0) SERIAL_CHAR('+'); - SERIAL_PROTOCOL_F(delta_tower_angle_trim[B_AXIS], 2); + 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(); } @@ -5351,19 +5351,12 @@ void home_all_axes() { gcode_G28(true); } // print report if (verbose_level != 1) { - SERIAL_PROTOCOLPGM(". c:"); - if (z_at_pt[0] > 0) SERIAL_CHAR('+'); - SERIAL_PROTOCOL_F(z_at_pt[0], 2); + SERIAL_PROTOCOLPGM(". "); + print_signed_float(PSTR("c"), z_at_pt[0]); if (_4p_towers_points || _7p_calibration) { - SERIAL_PROTOCOLPGM(" x:"); - if (z_at_pt[1] >= 0) SERIAL_CHAR('+'); - SERIAL_PROTOCOL_F(z_at_pt[1], 2); - SERIAL_PROTOCOLPGM(" y:"); - if (z_at_pt[5] >= 0) SERIAL_CHAR('+'); - SERIAL_PROTOCOL_F(z_at_pt[5], 2); - SERIAL_PROTOCOLPGM(" z:"); - if (z_at_pt[9] >= 0) SERIAL_CHAR('+'); - SERIAL_PROTOCOL_F(z_at_pt[9], 2); + print_signed_float(PSTR(" x"), z_at_pt[1]); + print_signed_float(PSTR(" y"), z_at_pt[5]); + print_signed_float(PSTR(" z"), z_at_pt[9]); } if (!_4p_opposite_points) SERIAL_EOL(); if ((_4p_opposite_points) || _7p_calibration) { @@ -5371,15 +5364,9 @@ void home_all_axes() { gcode_G28(true); } SERIAL_CHAR('.'); SERIAL_PROTOCOL_SP(13); } - SERIAL_PROTOCOLPGM(" yz:"); - if (z_at_pt[7] >= 0) SERIAL_CHAR('+'); - SERIAL_PROTOCOL_F(z_at_pt[7], 2); - SERIAL_PROTOCOLPGM(" zx:"); - if (z_at_pt[11] >= 0) SERIAL_CHAR('+'); - SERIAL_PROTOCOL_F(z_at_pt[11], 2); - SERIAL_PROTOCOLPGM(" xy:"); - if (z_at_pt[3] >= 0) SERIAL_CHAR('+'); - SERIAL_PROTOCOL_F(z_at_pt[3], 2); + print_signed_float(PSTR(" yz"), z_at_pt[7]); + print_signed_float(PSTR("zx"), z_at_pt[11]); + print_signed_float(PSTR("xy"), z_at_pt[3]); SERIAL_EOL(); } } @@ -5409,25 +5396,16 @@ void home_all_axes() { gcode_G28(true); } } SERIAL_PROTOCOLPAIR(".Height:", DELTA_HEIGHT + home_offset[Z_AXIS]); if (!_1p_calibration) { - SERIAL_PROTOCOLPGM(" Ex:"); - if (endstop_adj[A_AXIS] >= 0) SERIAL_CHAR('+'); - SERIAL_PROTOCOL_F(endstop_adj[A_AXIS], 2); - SERIAL_PROTOCOLPGM(" Ey:"); - if (endstop_adj[B_AXIS] >= 0) SERIAL_CHAR('+'); - SERIAL_PROTOCOL_F(endstop_adj[B_AXIS], 2); - SERIAL_PROTOCOLPGM(" Ez:"); - if (endstop_adj[C_AXIS] >= 0) SERIAL_CHAR('+'); - SERIAL_PROTOCOL_F(endstop_adj[C_AXIS], 2); + 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 : Tx:"); - if (delta_tower_angle_trim[A_AXIS] >= 0) SERIAL_CHAR('+'); - SERIAL_PROTOCOL_F(delta_tower_angle_trim[A_AXIS], 2); - SERIAL_PROTOCOLPGM(" Ty:"); - if (delta_tower_angle_trim[B_AXIS] >= 0) SERIAL_CHAR('+'); - SERIAL_PROTOCOL_F(delta_tower_angle_trim[B_AXIS], 2); + 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(); } From 445227c8071242af919b34b18965c484304f95b0 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 12 Jun 2017 01:28:52 -0500 Subject: [PATCH 065/180] Fix missing LCD_STR_REFRESH --- Marlin/Conditionals_LCD.h | 2 +- Marlin/ultralcd_impl_HD44780.h | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/Marlin/Conditionals_LCD.h b/Marlin/Conditionals_LCD.h index 48cc0141a5..d51d6a353d 100644 --- a/Marlin/Conditionals_LCD.h +++ b/Marlin/Conditionals_LCD.h @@ -245,7 +245,7 @@ #define LCD_DEGREE_CHAR 0x01 #define LCD_STR_THERMOMETER "\x02" // Still used with string concatenation #define LCD_UPLEVEL_CHAR 0x03 - #define LCD_REFRESH_CHAR 0x04 + #define LCD_STR_REFRESH "\x04" #define LCD_STR_FOLDER "\x05" #define LCD_FEEDRATE_CHAR 0x06 #define LCD_CLOCK_CHAR 0x07 diff --git a/Marlin/ultralcd_impl_HD44780.h b/Marlin/ultralcd_impl_HD44780.h index 7bc901854e..8adbaf8843 100644 --- a/Marlin/ultralcd_impl_HD44780.h +++ b/Marlin/ultralcd_impl_HD44780.h @@ -341,13 +341,13 @@ static void lcd_set_custom_characters( } else { // Custom characters for submenus createChar_P(LCD_UPLEVEL_CHAR, uplevel); - createChar_P(LCD_REFRESH_CHAR, refresh); + createChar_P(LCD_STR_REFRESH[0], refresh); createChar_P(LCD_STR_FOLDER[0], folder); } } #else createChar_P(LCD_UPLEVEL_CHAR, uplevel); - createChar_P(LCD_REFRESH_CHAR, refresh); + createChar_P(LCD_STR_REFRESH[0], refresh); createChar_P(LCD_STR_FOLDER[0], folder); #endif From 824f71d50372616ca218bcb23e7fe797daa5f797 Mon Sep 17 00:00:00 2001 From: Roxy-3D Date: Mon, 12 Jun 2017 18:26:49 -0500 Subject: [PATCH 066/180] LCD Panel Interactive Mesh Editing (#7045) Original Mesh Bed Leveling replacement put at top of UBL Menu Options to help facilitate the removal of the Original Mesh Bed Leveling. Radar display (and control) of the UBL Interactive Mesh Editing. --- Marlin/Marlin_main.cpp | 14 +- Marlin/language_en.h | 3 + Marlin/ubl.cpp | 27 ++-- Marlin/ubl_G29.cpp | 17 ++- Marlin/ultralcd.cpp | 253 ++++++++++++++++++++++++++++++--- Marlin/ultralcd_impl_DOGM.h | 4 + Marlin/ultralcd_impl_HD44780.h | 8 ++ 7 files changed, 294 insertions(+), 32 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 35a9f3e5dd..33384530f2 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -324,6 +324,8 @@ #if ENABLED(AUTO_BED_LEVELING_UBL) #include "ubl.h" + extern bool defer_return_to_status; + extern bool ubl_lcd_map_control; unified_bed_leveling ubl; #define UBL_MESH_VALID !( ( ubl.z_values[0][0] == ubl.z_values[0][1] && ubl.z_values[0][1] == ubl.z_values[0][2] \ && ubl.z_values[1][0] == ubl.z_values[1][1] && ubl.z_values[1][1] == ubl.z_values[1][2] \ @@ -755,7 +757,7 @@ void report_current_position_detail(); * Set the planner/stepper positions directly from current_position with * no kinematic translation. Used for homing axes and cartesian/core syncing. */ -inline void sync_plan_position() { +void sync_plan_position() { #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) DEBUG_POS("sync_plan_position", current_position); #endif @@ -7656,6 +7658,12 @@ inline void gcode_M18_M84() { if (parser.seen('E')) disable_e_steppers(); #endif } + + #if ENABLED(AUTO_BED_LEVELING_UBL) + ubl_lcd_map_control = false; + defer_return_to_status = false; + #endif + } } @@ -12429,6 +12437,10 @@ void manage_inactivity(bool ignore_stepper_queue/*=false*/) { #if ENABLED(DISABLE_INACTIVE_E) disable_e_steppers(); #endif + #if ENABLED(AUTO_BED_LEVELING_UBL) + ubl_lcd_map_control = false; + defer_return_to_status = false; + #endif } #ifdef CHDK // Check if pin should be set to LOW after M240 set it to HIGH diff --git a/Marlin/language_en.h b/Marlin/language_en.h index 56a0e5642b..dfad170a7a 100644 --- a/Marlin/language_en.h +++ b/Marlin/language_en.h @@ -280,6 +280,9 @@ #ifndef MSG_UBL_OUTPUT_MAP_CSV #define MSG_UBL_OUTPUT_MAP_CSV _UxGT("Output for CSV") #endif + #ifndef MSG_UBL_OUTPUT_MAP_BACKUP + #define MSG_UBL_OUTPUT_MAP_BACKUP _UxGT("Off Printer Backup") + #endif #ifndef MSG_UBL_INFO_UBL #define MSG_UBL_INFO_UBL _UxGT("Output UBL Info") #endif diff --git a/Marlin/ubl.cpp b/Marlin/ubl.cpp index e116296591..14d411e5c6 100644 --- a/Marlin/ubl.cpp +++ b/Marlin/ubl.cpp @@ -107,11 +107,15 @@ } } + // display_map() currently produces three different mesh map types + // 0 : suitable for PronterFace and Repetier's serial console + // 1 : .CSV file suitable for importation into various spread sheets + // 2 : disply of the map data on a RepRap Graphical LCD Panel + void unified_bed_leveling::display_map(const int map_type) { - const bool map0 = map_type == 0; constexpr uint8_t spaces = 8 * (GRID_MAX_POINTS_X - 2); - if (map0) { + if (map_type == 0) { SERIAL_PROTOCOLLNPGM("\nBed Topography Report:\n"); serial_echo_xy(0, GRID_MAX_POINTS_Y - 1); SERIAL_ECHO_SP(spaces + 3); @@ -123,6 +127,9 @@ SERIAL_EOL(); } + if (map_type == 1) { SERIAL_PROTOCOLLNPGM("\nBed Topography Report for CSV:"); SERIAL_EOL(); } + if (map_type == 2) { SERIAL_PROTOCOLLNPGM("\nBed Topography Report for LCD:"); SERIAL_EOL(); } + const float current_xi = get_cell_index_x(current_position[X_AXIS] + (MESH_X_DIST) / 2.0), current_yi = get_cell_index_y(current_position[Y_AXIS] + (MESH_Y_DIST) / 2.0); @@ -131,37 +138,37 @@ const bool is_current = i == current_xi && j == current_yi; // is the nozzle here? then mark the number - if (map0) SERIAL_CHAR(is_current ? '[' : ' '); + if (map_type == 0) SERIAL_CHAR(is_current ? '[' : ' '); const float f = z_values[i][j]; if (isnan(f)) { - serialprintPGM(map0 ? PSTR(" . ") : PSTR("NAN")); + serialprintPGM((map_type == 0) ? PSTR(" . ") : PSTR("NAN")); } else { // if we don't do this, the columns won't line up nicely - if (map0 && f >= 0.0) SERIAL_CHAR(' '); - SERIAL_PROTOCOL_F(f, 3); + if ((map_type == 0) && f >= 0.0) SERIAL_CHAR(' '); + if (map_type <= 1) SERIAL_PROTOCOL_F(f, 3); idle(); } - if (!map0 && i < GRID_MAX_POINTS_X - 1) SERIAL_CHAR(','); + if (map_type == 1 && i < GRID_MAX_POINTS_X - 1) SERIAL_CHAR(','); #if TX_BUFFER_SIZE > 0 MYSERIAL.flushTX(); #endif safe_delay(15); - if (map0) { + if (map_type == 0) { SERIAL_CHAR(is_current ? ']' : ' '); SERIAL_CHAR(' '); } } SERIAL_EOL(); - if (j && map0) { // we want the (0,0) up tight against the block of numbers + if (j && (map_type == 0)) { // we want the (0,0) up tight against the block of numbers SERIAL_CHAR(' '); SERIAL_EOL(); } } - if (map0) { + if (map_type == 0) { serial_echo_xy(UBL_MESH_MIN_X, UBL_MESH_MIN_Y); SERIAL_ECHO_SP(spaces + 4); serial_echo_xy(UBL_MESH_MAX_X, UBL_MESH_MIN_Y); diff --git a/Marlin/ubl_G29.cpp b/Marlin/ubl_G29.cpp index 64a3820f19..7ae5b30990 100644 --- a/Marlin/ubl_G29.cpp +++ b/Marlin/ubl_G29.cpp @@ -45,6 +45,9 @@ void lcd_mesh_edit_setup(float initial); float lcd_mesh_edit(); void lcd_z_offset_edit_setup(float); + #ifdef DOGLCD + extern void _lcd_ubl_output_map_lcd(); + #endif float lcd_z_offset_edit(); #endif @@ -53,6 +56,9 @@ extern float probe_pt(const float &x, const float &y, bool, int); extern bool set_probe_deployed(bool); extern void set_bed_leveling_enabled(bool); + extern bool ubl_lcd_map_control; + typedef void (*screenFunc_t)(); + extern void lcd_goto_screen(screenFunc_t screen, const uint32_t encoder = 0); #define SIZE_OF_LITTLE_RAISE 1 #define BIG_RAISE_NOT_NEEDED 0 @@ -1191,7 +1197,7 @@ #endif g29_map_type = parser.seen('T') && parser.has_value() ? parser.value_int() : 0; - if (!WITHIN(g29_map_type, 0, 1)) { + if (!WITHIN(g29_map_type, 0, 2)) { SERIAL_PROTOCOLLNPGM("Invalid map type.\n"); return UBL_ERR; } @@ -1535,8 +1541,8 @@ while (ubl_lcd_clicked()) { // debounce and watch for abort idle(); if (ELAPSED(millis(), nxt)) { + ubl_lcd_map_control = false; lcd_return_to_status(); - //SERIAL_PROTOCOLLNPGM("\nFine Tuning of Mesh Stopped."); do_blocking_move_to_z(Z_CLEARANCE_BETWEEN_PROBES); LCD_MESSAGEPGM(MSG_EDITING_STOPPED); @@ -1567,6 +1573,13 @@ LCD_MESSAGEPGM(MSG_UBL_DONE_EDITING_MESH); SERIAL_ECHOLNPGM("Done Editing Mesh"); + + if (ubl_lcd_map_control) { + #ifdef DOGLCD + lcd_goto_screen(_lcd_ubl_output_map_lcd); + #endif + } + else lcd_return_to_status(); } #endif diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index fa22df4efa..865a6e3db0 100644 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -26,6 +26,7 @@ #include "language.h" #include "cardreader.h" #include "temperature.h" +#include "planner.h" #include "stepper.h" #include "configuration_store.h" #include "utility.h" @@ -43,6 +44,11 @@ #include "endstops.h" #endif +#if ENABLED(AUTO_BED_LEVELING_UBL) + #include "ubl.h" + bool ubl_lcd_map_control = false; +#endif + int lcd_preheat_hotend_temp[2], lcd_preheat_bed_temp[2], lcd_preheat_fan_speed[2]; #if ENABLED(FILAMENT_LCD_DISPLAY) && ENABLED(SDSUPPORT) @@ -102,9 +108,6 @@ uint16_t max_display_update_time = 0; extern bool powersupply_on; #endif - #if ENABLED(AUTO_BED_LEVELING_UBL) - #include "ubl.h" - #endif //////////////////////////////////////////// ///////////////// Menu Tree //////////////// @@ -1044,6 +1047,7 @@ void kill_screen(const char* lcd_msg) { float lcd_mesh_edit() { lcd_goto_screen(_lcd_mesh_edit_NOP); + lcdDrawUpdate = LCDVIEW_CALL_REDRAW_NEXT; _lcd_mesh_fine_tune(PSTR("Mesh Editor")); return mesh_edit_value; } @@ -1795,8 +1799,10 @@ void kill_screen(const char* lcd_msg) { custom_hotend_temp = 190, side_points = 3, ubl_fillin_amount = 5, - ubl_height_amount, - map_type; + ubl_height_amount = 1, + n_edit_pts = 1, + x_plot = 0, + y_plot = 0; /** * UBL Build Custom Mesh Command @@ -1856,8 +1862,7 @@ void kill_screen(const char* lcd_msg) { void _lcd_ubl_edit_mesh() { START_MENU(); MENU_BACK(MSG_UBL_TOOLS); - MENU_BACK(MSG_UBL_LEVEL_BED); - MENU_ITEM(gcode, MSG_UBL_FINE_TUNE_ALL, PSTR("G29 P4 R T")); + MENU_ITEM(gcode, MSG_UBL_FINE_TUNE_ALL, PSTR("G29 P4 R999 T")); MENU_ITEM(gcode, MSG_UBL_FINE_TUNE_CLOSEST, PSTR("G29 P4 T")); MENU_ITEM(submenu, MSG_UBL_MESH_HEIGHT_ADJUST, _lcd_ubl_height_adjust_menu); MENU_ITEM(function, MSG_WATCH, lcd_return_to_status); @@ -1944,7 +1949,7 @@ void kill_screen(const char* lcd_msg) { */ void _lcd_ubl_smart_fillin_cmd() { char UBL_LCD_GCODE[12]; - sprintf_P(UBL_LCD_GCODE, PSTR("G29 P3 T%i"), map_type); + sprintf_P(UBL_LCD_GCODE, PSTR("G29 P3 T0")); enqueue_and_echo_command(UBL_LCD_GCODE); } @@ -2045,12 +2050,219 @@ void kill_screen(const char* lcd_msg) { } /** - * UBL Output map Command + * UBL LCD "radar" map homing */ - void _lcd_ubl_output_map_cmd() { - char UBL_LCD_GCODE[10]; - sprintf_P(UBL_LCD_GCODE, PSTR("G29 T%i"), map_type); - enqueue_and_echo_command(UBL_LCD_GCODE); + void _lcd_ubl_output_map_lcd(); + + void _lcd_ubl_map_homing() { + if (lcdDrawUpdate) lcd_implementation_drawedit(PSTR(MSG_LEVEL_BED_HOMING), NULL); + lcdDrawUpdate = LCDVIEW_CALL_NO_REDRAW; + if (axis_homed[X_AXIS] && axis_homed[Y_AXIS] && axis_homed[Z_AXIS]) + lcd_goto_screen(_lcd_ubl_output_map_lcd); + } + + /** + * UBL LCD "radar" map point editing + */ + void _lcd_ubl_map_lcd_edit_cmd() { + char ubl_lcd_gcode [50], str[10], str2[10]; + + ubl_lcd_map_control = true; // Used for returning to the map screen + + dtostrf(pgm_read_float(&ubl._mesh_index_to_xpos[x_plot]), 0, 2, str); + dtostrf(pgm_read_float(&ubl._mesh_index_to_ypos[y_plot]), 0, 2, str2); + snprintf_P(ubl_lcd_gcode, sizeof(ubl_lcd_gcode), PSTR("G29 P4 X%s Y%s R%i"), str, str2, n_edit_pts); + enqueue_and_echo_command(ubl_lcd_gcode); + } + + #ifdef DOGLCD + + /** + * UBL LCD "radar" map data + */ + #define MAP_UPPER_LEFT_CORNER_X 35 // These probably should be moved to the .h file But for now, + #define MAP_UPPER_LEFT_CORNER_Y 8 // it is easier to play with things having them here + #define MAP_MAX_PIXELS_X 53 + #define MAP_MAX_PIXELS_Y 49 + + void _lcd_ubl_plot_drawing_prep() { + uint8_t i, j, x_offset, y_offset, x_map_pixels, y_map_pixels; + uint8_t pixels_per_X_mesh_pnt, pixels_per_Y_mesh_pnt, inverted_y; + + /*********************************************************/ + /************ Scale the box pixels appropriately *********/ + /*********************************************************/ + 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; + + 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; + + /*********************************************************/ + /************ Clear the Mesh Map Box**********************/ + /*********************************************************/ + + u8g.setColorIndex(1); // First draw the bigger box in White so we have a border around the mesh map box + u8g.drawBox(x_offset-2, y_offset-2, x_map_pixels+4, y_map_pixels+4); + + u8g.setColorIndex(0); // Now actually clear the mesh map box + u8g.drawBox(x_offset, y_offset, x_map_pixels, y_map_pixels); + + /*********************************************************/ + /************ Display Mesh Point Locations ***************/ + /*********************************************************/ + + u8g.setColorIndex(1); + for (i = 0; i < GRID_MAX_POINTS_X; i++) { + for (j = 0; j < GRID_MAX_POINTS_Y; j++) { + u8g.drawBox(x_offset+i*pixels_per_X_mesh_pnt+pixels_per_X_mesh_pnt/2, + y_offset+j*pixels_per_Y_mesh_pnt+pixels_per_Y_mesh_pnt/2, 1, 1); + } + } + + /*********************************************************/ + /************ Fill in the Specified Mesh Point ***********/ + /*********************************************************/ + + 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. + u8g.drawBox(x_offset+x_plot*pixels_per_X_mesh_pnt, y_offset+inverted_y*pixels_per_Y_mesh_pnt, + pixels_per_X_mesh_pnt, pixels_per_Y_mesh_pnt); + + /*********************************************************/ + /************** Put Relevent Text on Display *************/ + /*********************************************************/ + + // Show X and Y positions at top of screen + u8g.setColorIndex(1); + u8g.setPrintPos(5, 7); + lcd_print("X:"); + lcd_print(ftostr32(LOGICAL_X_POSITION(pgm_read_float(&ubl._mesh_index_to_xpos[x_plot])))); + u8g.setPrintPos(74, 7); + lcd_print("Y:"); + lcd_print(ftostr32(LOGICAL_Y_POSITION(pgm_read_float(&ubl._mesh_index_to_ypos[y_plot])))); + + // Print plot position + u8g.setPrintPos(5, 64); + lcd_print("("); + u8g.print(x_plot); + lcd_print(","); + u8g.print(y_plot); + lcd_print(")"); + + // Show the location value + u8g.setPrintPos(74, 64); + lcd_print("Z:"); + if (!isnan(ubl.z_values[x_plot][y_plot])) { + lcd_print(ftostr43sign(ubl.z_values[x_plot][y_plot])); + } + else { + lcd_print(" -----"); + } + } + + #endif // DOGLCD + + /** + * UBL LCD Map Movement + */ + void ubl_map_move_to_xy() { + current_position[X_AXIS] = LOGICAL_X_POSITION(pgm_read_float(&ubl._mesh_index_to_xpos[x_plot])); + current_position[Y_AXIS] = LOGICAL_Y_POSITION(pgm_read_float(&ubl._mesh_index_to_ypos[y_plot])); + planner.buffer_line_kinematic(current_position, MMM_TO_MMS(XY_PROBE_SPEED), active_extruder); + } + + /** + * UBL LCD "radar" map + */ + void set_current_from_steppers_for_axis(const AxisEnum axis); + void sync_plan_position(); + + void _lcd_ubl_output_map_lcd() { + static int step_scaler=0; + int32_t signed_enc_pos; + + defer_return_to_status = true; + + if (axis_known_position[X_AXIS] && axis_known_position[Y_AXIS] && axis_known_position[Z_AXIS]) { + + if (lcd_clicked) { return _lcd_ubl_map_lcd_edit_cmd(); } + ENCODER_DIRECTION_NORMAL(); + + if (encoderPosition != 0) { + signed_enc_pos = (int32_t)encoderPosition; + step_scaler += signed_enc_pos; + x_plot = (x_plot + step_scaler / ENCODER_STEPS_PER_MENU_ITEM); + + if (abs(step_scaler) >= ENCODER_STEPS_PER_MENU_ITEM) + step_scaler = 0; + refresh_cmd_timeout(); + + lcdDrawUpdate = LCDVIEW_REDRAW_NOW; + } + + encoderPosition = 0; + + // Encoder to the right (++) + if (x_plot >= GRID_MAX_POINTS_X) { x_plot = 0; y_plot++; } + if (y_plot >= GRID_MAX_POINTS_Y) y_plot = 0; + + // Encoder to the left (--) + if (x_plot <= GRID_MAX_POINTS_X - (GRID_MAX_POINTS_X + 1)) { x_plot = GRID_MAX_POINTS_X - 1; y_plot--; } + if (y_plot <= GRID_MAX_POINTS_Y - (GRID_MAX_POINTS_Y + 1)) y_plot = GRID_MAX_POINTS_Y - 1; + + // Prevent underrun/overrun of plot numbers + x_plot = constrain(x_plot, GRID_MAX_POINTS_X - (GRID_MAX_POINTS_X + 1), GRID_MAX_POINTS_X + 1); + y_plot = constrain(y_plot, GRID_MAX_POINTS_Y - (GRID_MAX_POINTS_Y + 1), GRID_MAX_POINTS_Y + 1); + + // Determine number of points to edit + #if IS_KINEMATIC + n_edit_pts = 9; //TODO: Delta accessible edit points + #else + if (x_plot < 1 || x_plot >= GRID_MAX_POINTS_X - 1) + if (y_plot < 1 || y_plot >= GRID_MAX_POINTS_Y - 1) n_edit_pts = 4; // Corners + else n_edit_pts = 6; + else if (y_plot < 1 || y_plot >= GRID_MAX_POINTS_Y - 1) n_edit_pts = 6; // Edges + else n_edit_pts = 9; // Field + #endif + + if (lcdDrawUpdate) { + #if ENABLED(DOGLCD) + _lcd_ubl_plot_drawing_prep(); + #else + _lcd_ubl_output_char_lcd(); + #endif + + 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 + #define ENABLE_STEPPER_DRIVER_INTERRUPT() SBI(TIMSK1, OCIE1A) + #define DISABLE_STEPPER_DRIVER_INTERRUPT() CBI(TIMSK1, OCIE1A) + DISABLE_STEPPER_DRIVER_INTERRUPT(); + while (planner.blocks_queued()) planner.discard_current_block(); + stepper.current_block = NULL; + planner.clear_block_buffer_runtime(); + ENABLE_STEPPER_DRIVER_INTERRUPT(); + set_current_from_steppers_for_axis(ALL_AXES); + sync_plan_position(); + ubl_map_move_to_xy(); // Move to new location + } + } + safe_delay(10); + } + else lcd_goto_screen(_lcd_ubl_map_homing); + } + + /** + * UBL Homing before LCD map + */ + void _lcd_ubl_output_map_lcd_cmd() { + if (!(axis_known_position[X_AXIS] && axis_known_position[Y_AXIS] && axis_known_position[Z_AXIS])) + enqueue_and_echo_commands_P(PSTR("G28")); + lcd_goto_screen(_lcd_ubl_map_homing); } /** @@ -2059,9 +2271,10 @@ void kill_screen(const char* lcd_msg) { void _lcd_ubl_output_map() { START_MENU(); MENU_BACK(MSG_UBL_LEVEL_BED); - MENU_ITEM_EDIT(int3, MSG_UBL_MAP_TYPE, &map_type, 0, 1); - if (map_type == 0) MENU_ITEM(function, MSG_UBL_OUTPUT_MAP_HOST, _lcd_ubl_output_map_cmd); - if (map_type == 1) MENU_ITEM(function, MSG_UBL_OUTPUT_MAP_CSV, _lcd_ubl_output_map_cmd); + MENU_ITEM(gcode, MSG_UBL_OUTPUT_MAP_HOST, PSTR("G29 T0")); + MENU_ITEM(gcode, MSG_UBL_OUTPUT_MAP_CSV, PSTR("G29 T1")); + MENU_ITEM(gcode, MSG_UBL_OUTPUT_MAP_BACKUP, PSTR("G29 S-1")); + MENU_ITEM(function, MSG_UBL_OUTPUT_MAP, _lcd_ubl_output_map_lcd_cmd); END_MENU(); } @@ -2091,8 +2304,10 @@ void kill_screen(const char* lcd_msg) { * Load Bed Mesh * Save Bed Mesh * - Output Map - * Map Type: - * Output Bed Mesh Host / Output Bed Mesh CSV + * Topography to Host + * CSV for Spreadsheet + * Mesh Output Backup + * Output to LCD Grid * - UBL Tools * - Build Mesh * Build PLA Mesh @@ -4035,7 +4250,7 @@ void lcd_update() { int32_t encoderMovementSteps = abs(encoderDiff) / ENCODER_PULSES_PER_STEP; if (lastEncoderMovementMillis != 0) { - // Note that the rate is always calculated between to passes through the + // Note that the rate is always calculated between two passes through the // loop and that the abs of the encoderDiff value is tracked. float encoderStepRate = (float)(encoderMovementSteps) / ((float)(ms - lastEncoderMovementMillis)) * 1000.0; diff --git a/Marlin/ultralcd_impl_DOGM.h b/Marlin/ultralcd_impl_DOGM.h index 29445262c3..676dfcacf9 100644 --- a/Marlin/ultralcd_impl_DOGM.h +++ b/Marlin/ultralcd_impl_DOGM.h @@ -50,6 +50,10 @@ #include +#if ENABLED(AUTO_BED_LEVELING_UBL) + #include "ubl.h" +#endif + #if ENABLED(SHOW_BOOTSCREEN) && ENABLED(SHOW_CUSTOM_BOOTSCREEN) #include "_Bootscreen.h" #endif diff --git a/Marlin/ultralcd_impl_HD44780.h b/Marlin/ultralcd_impl_HD44780.h index 7bc901854e..fe21c0ae8c 100644 --- a/Marlin/ultralcd_impl_HD44780.h +++ b/Marlin/ultralcd_impl_HD44780.h @@ -1076,4 +1076,12 @@ static void lcd_implementation_status_screen() { #endif // LCD_HAS_STATUS_INDICATORS +#ifdef AUTO_BED_LEVELING_UBL + void lcd_return_to_status(); // These are just place holders for the 20x4 LCD work that + void _lcd_ubl_output_char_lcd() { // is coming up very soon. Soon this will morph into the + lcd_return_to_status(); // real code. + } + +#endif // AUTO_BED_LEVELING_UBL + #endif // ULTRALCD_IMPL_HD44780_H From 26d20ebcfc4c525b7fe15939b89eedc09eacdb47 Mon Sep 17 00:00:00 2001 From: Jim Brown Date: Tue, 13 Jun 2017 18:11:37 -0400 Subject: [PATCH 067/180] Don't allow filament change without homing first (#7054) --- Marlin/Marlin_main.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 33384530f2..4d8b0f9fef 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -9276,6 +9276,11 @@ inline void gcode_M503() { */ inline void gcode_M600() { + // Don't allow filament change without homing first + if (axis_unhomed_error()) { + home_all_axes(); + } + // 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 From 40bb0cbf7a991a25f2dacd1f8480dab38887d553 Mon Sep 17 00:00:00 2001 From: Brian Date: Fri, 9 Jun 2017 14:56:32 -0400 Subject: [PATCH 068/180] example configurations, etc. --- Marlin/Configuration_adv.h | 4 +- .../Cartesio/Configuration_adv.h | 83 +++++++++++++++++++ .../Felix/Configuration_adv.h | 83 +++++++++++++++++++ .../FolgerTech-i3-2020/Configuration_adv.h | 83 +++++++++++++++++++ .../Hephestos/Configuration_adv.h | 83 +++++++++++++++++++ .../Hephestos_2/Configuration_adv.h | 83 +++++++++++++++++++ .../K8200/Configuration_adv.h | 83 +++++++++++++++++++ .../K8400/Configuration_adv.h | 83 +++++++++++++++++++ .../M150/Configuration_adv.h | 83 +++++++++++++++++++ .../RigidBot/Configuration_adv.h | 83 +++++++++++++++++++ .../SCARA/Configuration_adv.h | 83 +++++++++++++++++++ .../TAZ4/Configuration_adv.h | 83 +++++++++++++++++++ .../TinyBoy2/Configuration_adv.h | 83 +++++++++++++++++++ .../WITBOX/Configuration_adv.h | 83 +++++++++++++++++++ .../FLSUN/auto_calibrate/Configuration_adv.h | 83 +++++++++++++++++++ .../FLSUN/kossel_mini/Configuration_adv.h | 83 +++++++++++++++++++ .../delta/generic/Configuration_adv.h | 83 +++++++++++++++++++ .../delta/kossel_mini/Configuration_adv.h | 83 +++++++++++++++++++ .../delta/kossel_pro/Configuration_adv.h | 83 +++++++++++++++++++ .../delta/kossel_xl/Configuration_adv.h | 83 +++++++++++++++++++ .../gCreate_gMax1.5+/Configuration_adv.h | 83 +++++++++++++++++++ .../makibox/Configuration_adv.h | 83 +++++++++++++++++++ .../tvrrug/Round2/Configuration_adv.h | 83 +++++++++++++++++++ .../wt150/Configuration_adv.h | 83 +++++++++++++++++++ 24 files changed, 1911 insertions(+), 2 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index c8e30fffec..5eebb573ef 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1262,7 +1262,7 @@ #endif //=========================================================================== -//============================ I2C Encoder Settings ========================= +//====================== I2C Position Encoder Settings ====================== //=========================================================================== /** * I2C position encoders for closed loop control. @@ -1342,6 +1342,6 @@ // Use a rolling average to identify persistant errors that indicate skips, as opposed to vibration and noise. #define I2CPE_ERR_ROLLING_AVERAGE -#endif +#endif // I2C_POSITION_ENCODERS #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/Cartesio/Configuration_adv.h b/Marlin/example_configurations/Cartesio/Configuration_adv.h index 8dfb65a36d..0f420ff4c2 100644 --- a/Marlin/example_configurations/Cartesio/Configuration_adv.h +++ b/Marlin/example_configurations/Cartesio/Configuration_adv.h @@ -1254,4 +1254,87 @@ #define USER_GCODE_5 "G28\nM503" #endif +//=========================================================================== +//====================== 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/Felix/Configuration_adv.h b/Marlin/example_configurations/Felix/Configuration_adv.h index a5940d4566..30b9bfbf9b 100644 --- a/Marlin/example_configurations/Felix/Configuration_adv.h +++ b/Marlin/example_configurations/Felix/Configuration_adv.h @@ -1254,4 +1254,87 @@ //#define USER_GCODE_5 "G28\nM503" #endif +//=========================================================================== +//====================== 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/FolgerTech-i3-2020/Configuration_adv.h b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h index 4174cba825..e10a5c0b95 100644 --- a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h +++ b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h @@ -1267,4 +1267,87 @@ //#define USER_GCODE_5 "G28\nM503" #endif +//=========================================================================== +//====================== 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/Hephestos/Configuration_adv.h b/Marlin/example_configurations/Hephestos/Configuration_adv.h index 3e7f6416d1..f17eb63052 100644 --- a/Marlin/example_configurations/Hephestos/Configuration_adv.h +++ b/Marlin/example_configurations/Hephestos/Configuration_adv.h @@ -1254,4 +1254,87 @@ //#define USER_GCODE_5 "G28\nM503" #endif +//=========================================================================== +//====================== 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/Hephestos_2/Configuration_adv.h b/Marlin/example_configurations/Hephestos_2/Configuration_adv.h index 26af260c3e..7b9c54c62c 100644 --- a/Marlin/example_configurations/Hephestos_2/Configuration_adv.h +++ b/Marlin/example_configurations/Hephestos_2/Configuration_adv.h @@ -1237,4 +1237,87 @@ //#define USER_GCODE_5 "G28\nM503" #endif +//=========================================================================== +//====================== 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/K8200/Configuration_adv.h b/Marlin/example_configurations/K8200/Configuration_adv.h index 4cad884b71..88d9b3feb9 100644 --- a/Marlin/example_configurations/K8200/Configuration_adv.h +++ b/Marlin/example_configurations/K8200/Configuration_adv.h @@ -1267,4 +1267,87 @@ //#define USER_GCODE_5 "G28\nM503" #endif +//=========================================================================== +//====================== 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/K8400/Configuration_adv.h b/Marlin/example_configurations/K8400/Configuration_adv.h index 34ccc3aeb3..a4e0f6bed2 100644 --- a/Marlin/example_configurations/K8400/Configuration_adv.h +++ b/Marlin/example_configurations/K8400/Configuration_adv.h @@ -1254,4 +1254,87 @@ //#define USER_GCODE_5 "G28\nM503" #endif +//=========================================================================== +//====================== 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/M150/Configuration_adv.h b/Marlin/example_configurations/M150/Configuration_adv.h index c2c1c0c3fb..528e1e19a4 100644 --- a/Marlin/example_configurations/M150/Configuration_adv.h +++ b/Marlin/example_configurations/M150/Configuration_adv.h @@ -1261,4 +1261,87 @@ #define USER_GCODE_5 "G28\nM503" #endif +//=========================================================================== +//====================== 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/RigidBot/Configuration_adv.h b/Marlin/example_configurations/RigidBot/Configuration_adv.h index 027e633189..d9ad125856 100644 --- a/Marlin/example_configurations/RigidBot/Configuration_adv.h +++ b/Marlin/example_configurations/RigidBot/Configuration_adv.h @@ -1254,4 +1254,87 @@ //#define USER_GCODE_5 "G28\nM503" #endif +//=========================================================================== +//====================== 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/SCARA/Configuration_adv.h b/Marlin/example_configurations/SCARA/Configuration_adv.h index 9ea1a60bd7..84f9059ddd 100644 --- a/Marlin/example_configurations/SCARA/Configuration_adv.h +++ b/Marlin/example_configurations/SCARA/Configuration_adv.h @@ -1254,4 +1254,87 @@ //#define USER_GCODE_5 "G28\nM503" #endif +//=========================================================================== +//====================== 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/TAZ4/Configuration_adv.h b/Marlin/example_configurations/TAZ4/Configuration_adv.h index 23b616ad53..e06912e287 100644 --- a/Marlin/example_configurations/TAZ4/Configuration_adv.h +++ b/Marlin/example_configurations/TAZ4/Configuration_adv.h @@ -1254,4 +1254,87 @@ //#define USER_GCODE_5 "G28\nM503" #endif +//=========================================================================== +//====================== 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/TinyBoy2/Configuration_adv.h b/Marlin/example_configurations/TinyBoy2/Configuration_adv.h index ba0eae98a7..add1cd2485 100644 --- a/Marlin/example_configurations/TinyBoy2/Configuration_adv.h +++ b/Marlin/example_configurations/TinyBoy2/Configuration_adv.h @@ -1257,4 +1257,87 @@ //#define USER_GCODE_5 "G28\nM503" #endif +//=========================================================================== +//====================== 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/WITBOX/Configuration_adv.h b/Marlin/example_configurations/WITBOX/Configuration_adv.h index 3e7f6416d1..f17eb63052 100644 --- a/Marlin/example_configurations/WITBOX/Configuration_adv.h +++ b/Marlin/example_configurations/WITBOX/Configuration_adv.h @@ -1254,4 +1254,87 @@ //#define USER_GCODE_5 "G28\nM503" #endif +//=========================================================================== +//====================== 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/delta/FLSUN/auto_calibrate/Configuration_adv.h b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h index 1ca156d9b3..941c23d7c5 100644 --- a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h +++ b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h @@ -1259,4 +1259,87 @@ #define USER_GCODE_5 "G28\nM503" #endif +//=========================================================================== +//====================== 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/delta/FLSUN/kossel_mini/Configuration_adv.h b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h index dc5c04e2e0..17301f1505 100644 --- a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h +++ b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h @@ -1258,4 +1258,87 @@ #define USER_GCODE_5 "G28\nM503" #endif +//=========================================================================== +//====================== 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/delta/generic/Configuration_adv.h b/Marlin/example_configurations/delta/generic/Configuration_adv.h index 49a550faee..88ade5ab4d 100644 --- a/Marlin/example_configurations/delta/generic/Configuration_adv.h +++ b/Marlin/example_configurations/delta/generic/Configuration_adv.h @@ -1256,4 +1256,87 @@ #define USER_GCODE_5 "G28\nM503" #endif +//=========================================================================== +//====================== 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/delta/kossel_mini/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h index 49a550faee..88ade5ab4d 100644 --- a/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h @@ -1256,4 +1256,87 @@ #define USER_GCODE_5 "G28\nM503" #endif +//=========================================================================== +//====================== 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/delta/kossel_pro/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h index 3922a31a7a..a0597796dc 100644 --- a/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h @@ -1261,4 +1261,87 @@ #define USER_GCODE_5 "G28\nM503" #endif +//=========================================================================== +//====================== 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/delta/kossel_xl/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h index 9b403edb19..1a9267fd60 100644 --- a/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h @@ -1256,4 +1256,87 @@ //#define USER_GCODE_5 "G28\nM503" #endif +//=========================================================================== +//====================== 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/gCreate_gMax1.5+/Configuration_adv.h b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration_adv.h index ba963dd06d..3eaab4735f 100644 --- a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration_adv.h +++ b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration_adv.h @@ -1263,4 +1263,87 @@ //#define USER_GCODE_5 "G28\nM503" #endif +//=========================================================================== +//====================== 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/makibox/Configuration_adv.h b/Marlin/example_configurations/makibox/Configuration_adv.h index c16680356a..2fb87227f2 100644 --- a/Marlin/example_configurations/makibox/Configuration_adv.h +++ b/Marlin/example_configurations/makibox/Configuration_adv.h @@ -1254,4 +1254,87 @@ //#define USER_GCODE_5 "G28\nM503" #endif +//=========================================================================== +//====================== 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/tvrrug/Round2/Configuration_adv.h b/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h index e218c85ca8..1a19eca8bd 100644 --- a/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h +++ b/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h @@ -1254,4 +1254,87 @@ //#define USER_GCODE_5 "G28\nM503" #endif +//=========================================================================== +//====================== 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/wt150/Configuration_adv.h b/Marlin/example_configurations/wt150/Configuration_adv.h index 09f94b2260..06ab6cb1c5 100644 --- a/Marlin/example_configurations/wt150/Configuration_adv.h +++ b/Marlin/example_configurations/wt150/Configuration_adv.h @@ -1257,4 +1257,87 @@ //#define USER_GCODE_5 "G28\nM503" #endif +//=========================================================================== +//====================== 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 9dda022705e28ce833704e64afd6d0becbcff9bd Mon Sep 17 00:00:00 2001 From: Bob-the-Kuhn Date: Thu, 15 Jun 2017 00:32:05 -0500 Subject: [PATCH 069/180] fix compile errors ================================ Changed to conditional compile for AT90USB issue --- Marlin/G26_Mesh_Validation_Tool.cpp | 6 +++++- Marlin/Marlin_main.cpp | 6 +++--- 2 files changed, 8 insertions(+), 4 deletions(-) diff --git a/Marlin/G26_Mesh_Validation_Tool.cpp b/Marlin/G26_Mesh_Validation_Tool.cpp index 18a28b3c41..aa4b0fb39a 100644 --- a/Marlin/G26_Mesh_Validation_Tool.cpp +++ b/Marlin/G26_Mesh_Validation_Tool.cpp @@ -137,7 +137,11 @@ void set_destination_to_current(); void set_current_to_destination(); void prepare_move_to_destination(); - void sync_plan_position_e(); + #if AVR_AT90USB1286_FAMILY // Teensyduino & Printrboard IDE extensions have compile errors without this + inline void sync_plan_position_e() { planner.set_e_position_mm(current_position[E_AXIS]); } + #else + void sync_plan_position_e(); + #endif #if ENABLED(NEWPANEL) void lcd_setstatusPGM(const char* const message, const int8_t level); void chirp_at_user(); diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 4d8b0f9fef..6762b70abd 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -5895,7 +5895,7 @@ inline void gcode_M17() { if (!DEBUGGING(DRYRUN) && unload_length != 0) { #if ENABLED(PREVENT_COLD_EXTRUSION) - if (!thermalManager.allow_cold_extrude && + if (!thermalManager.allow_cold_extrude && thermalManager.degTargetHotend(active_extruder) < thermalManager.extrude_min_temp) { SERIAL_ERROR_START(); SERIAL_ERRORLNPGM(MSG_TOO_COLD_FOR_M600); @@ -7659,7 +7659,7 @@ inline void gcode_M18_M84() { #endif } - #if ENABLED(AUTO_BED_LEVELING_UBL) + #if ENABLED(AUTO_BED_LEVELING_UBL) && ENABLED(ULTRA_LCD) //only needed if have an LCD ubl_lcd_map_control = false; defer_return_to_status = false; #endif @@ -12442,7 +12442,7 @@ void manage_inactivity(bool ignore_stepper_queue/*=false*/) { #if ENABLED(DISABLE_INACTIVE_E) disable_e_steppers(); #endif - #if ENABLED(AUTO_BED_LEVELING_UBL) + #if ENABLED(AUTO_BED_LEVELING_UBL) && ENABLED(ULTRA_LCD) //only needed if have an LCD ubl_lcd_map_control = false; defer_return_to_status = false; #endif From 09bc34f4dc625bbe2441576aac62137c2b4df4b6 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 29 Sep 2016 00:32:33 -0500 Subject: [PATCH 070/180] Allow arbitrarily long retraction --- 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 5a874bedc3..398855868a 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -11847,7 +11847,7 @@ void prepare_move_to_destination() { SERIAL_ECHOLNPGM(MSG_ERR_COLD_EXTRUDE_STOP); } #if ENABLED(PREVENT_LENGTHY_EXTRUDE) - if (labs(destination[E_AXIS] - current_position[E_AXIS]) > EXTRUDE_MAXLENGTH) { + if (destination[E_AXIS] - current_position[E_AXIS] > EXTRUDE_MAXLENGTH) { current_position[E_AXIS] = destination[E_AXIS]; // Behave as if the move really took place, but ignore E part SERIAL_ECHO_START(); SERIAL_ECHOLNPGM(MSG_ERR_LONG_EXTRUDE_STOP); From 4ebff8eaa54a66cee979a5585c0c537da4bd8400 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 28 May 2017 19:24:39 -0500 Subject: [PATCH 071/180] Drop fastio timer cruft --- Marlin/fastio.h | 4 ---- 1 file changed, 4 deletions(-) diff --git a/Marlin/fastio.h b/Marlin/fastio.h index 035c9c3a2f..d5ae8f2cce 100644 --- a/Marlin/fastio.h +++ b/Marlin/fastio.h @@ -215,10 +215,6 @@ typedef enum { // Set Compare Mode bits #define _SET_COM(T,Q,V) (TCCR##T##Q = (TCCR##T##Q & ~(0x3 << COM##T##Q##0)) | (int(V) << COM##T##Q##0)) -#define _SET_COMA(T,V) _SET_COM(T,A,V) -#define _SET_COMB(T,V) _SET_COM(T,B,V) -#define _SET_COMC(T,V) _SET_COM(T,C,V) -#define _SET_COMS(T,V1,V2,V3) do{ _SET_COMA(T,V1); _SET_COMB(T,V2); _SET_COMC(T,V3); }while(0) #define SET_COM(T,Q,V) _SET_COM(T,Q,COM_##V) #define SET_COMA(T,V) SET_COM(T,A,V) #define SET_COMB(T,V) SET_COM(T,B,V) From c10d763d9819b2226ef5bd5d801d8eb34acd06ee Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 29 May 2017 09:36:41 -0500 Subject: [PATCH 072/180] Simpler prepare move conditions --- Marlin/Marlin_main.cpp | 12 ++++-------- 1 file changed, 4 insertions(+), 8 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 398855868a..0074311107 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -11859,16 +11859,12 @@ void prepare_move_to_destination() { #endif if ( - #if IS_KINEMATIC - #if UBL_DELTA - ubl.prepare_segmented_line_to(destination, feedrate_mm_s) - #else - prepare_kinematic_move_to(destination) - #endif + #if UBL_DELTA // Also works for CARTESIAN (smaller segments follow mesh more closely) + ubl.prepare_segmented_line_to(destination, feedrate_mm_s) + #elif IS_KINEMATIC + prepare_kinematic_move_to(destination) #elif ENABLED(DUAL_X_CARRIAGE) prepare_move_to_destination_dualx() - #elif UBL_DELTA // will work for CARTESIAN too (smaller segments follow mesh more closely) - ubl.prepare_segmented_line_to(destination, feedrate_mm_s) #else prepare_move_to_destination_cartesian() #endif From 7164fd499e5c60bebfec1f30b1078af6e0bfe795 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 15 Jun 2017 14:43:20 -0500 Subject: [PATCH 073/180] Tweak to G33 P error --- 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 0074311107..b3feff7234 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -5109,7 +5109,7 @@ void home_all_axes() { gcode_G28(true); } const int8_t probe_points = parser.seen('P') ? parser.value_int() : 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; } From 499d5c3b2456aeb79161ff34e10d4b7a1f02676a Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 15 Jun 2017 15:07:39 -0500 Subject: [PATCH 074/180] Fix scrolling lcd message for DOGM --- Marlin/ultralcd_impl_DOGM.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/ultralcd_impl_DOGM.h b/Marlin/ultralcd_impl_DOGM.h index 676dfcacf9..295e276760 100644 --- a/Marlin/ultralcd_impl_DOGM.h +++ b/Marlin/ultralcd_impl_DOGM.h @@ -424,10 +424,10 @@ inline void lcd_implementation_status_message() { lcd_print_utf(stat); // The string leaves space chars -= slen - status_scroll_pos; // Amount of space left } - lcd.print('.'); // Always at 1+ spaces left, draw a dot + u8g.print('.'); // Always at 1+ spaces left, draw a dot if (--chars) { if (status_scroll_pos < slen + 1) // Draw a second dot if there's space - --chars, lcd.print('.'); + --chars, u8g.print('.'); if (chars) lcd_print_utf(lcd_status_message, chars); // Print a second copy of the message } } From d9da126776ca9f759cf15d55341385b7260eff25 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 15 Jun 2017 15:10:45 -0500 Subject: [PATCH 075/180] Cleanups for UBL / ultralcd.cpp --- Marlin/ubl_G29.cpp | 4 ++-- Marlin/ultralcd.cpp | 44 +++++++++++++++++----------------- Marlin/ultralcd_impl_HD44780.h | 2 +- 3 files changed, 25 insertions(+), 25 deletions(-) diff --git a/Marlin/ubl_G29.cpp b/Marlin/ubl_G29.cpp index 7ae5b30990..e15c8d7728 100644 --- a/Marlin/ubl_G29.cpp +++ b/Marlin/ubl_G29.cpp @@ -45,7 +45,7 @@ void lcd_mesh_edit_setup(float initial); float lcd_mesh_edit(); void lcd_z_offset_edit_setup(float); - #ifdef DOGLCD + #if ENABLED(DOGLCD) extern void _lcd_ubl_output_map_lcd(); #endif float lcd_z_offset_edit(); @@ -1575,7 +1575,7 @@ SERIAL_ECHOLNPGM("Done Editing Mesh"); if (ubl_lcd_map_control) { - #ifdef DOGLCD + #if ENABLED(DOGLCD) lcd_goto_screen(_lcd_ubl_output_map_lcd); #endif } diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index 865a6e3db0..521b19f22c 100644 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -257,7 +257,7 @@ uint16_t max_display_update_time = 0; _skipStatic = false; \ _MENU_ITEM_PART_1(TYPE, ## __VA_ARGS__); \ _MENU_ITEM_PART_2(TYPE, LABEL, ## __VA_ARGS__); \ - } while(0) + }while(0) #define MENU_BACK(LABEL) MENU_ITEM(back, LABEL, 0) @@ -289,13 +289,13 @@ uint16_t max_display_update_time = 0; encoderRateMultiplierEnabled = true; \ lastEncoderMovementMillis = 0; \ _MENU_ITEM_PART_2(type, label, ## __VA_ARGS__); \ - } while(0) + }while(0) #else // !ENCODER_RATE_MULTIPLIER #define ENCODER_RATE_MULTIPLY(F) NOOP #endif // !ENCODER_RATE_MULTIPLIER - #define MENU_ITEM_DUMMY() do { _thisItemNr++; } while(0) + #define MENU_ITEM_DUMMY() do { _thisItemNr++; }while(0) #define MENU_ITEM_EDIT(type, label, ...) MENU_ITEM(setting_edit_ ## type, label, PSTR(label), ## __VA_ARGS__) #define MENU_ITEM_EDIT_CALLBACK(type, label, ...) MENU_ITEM(setting_edit_callback_ ## type, label, PSTR(label), ## __VA_ARGS__) #if ENABLED(ENCODER_RATE_MULTIPLIER) @@ -2075,19 +2075,19 @@ void kill_screen(const char* lcd_msg) { enqueue_and_echo_command(ubl_lcd_gcode); } - #ifdef DOGLCD + #if ENABLED(DOGLCD) /** * UBL LCD "radar" map data */ - #define MAP_UPPER_LEFT_CORNER_X 35 // These probably should be moved to the .h file But for now, - #define MAP_UPPER_LEFT_CORNER_Y 8 // it is easier to play with things having them here - #define MAP_MAX_PIXELS_X 53 - #define MAP_MAX_PIXELS_Y 49 + #define MAP_UPPER_LEFT_CORNER_X 35 // These probably should be moved to the .h file But for now, + #define MAP_UPPER_LEFT_CORNER_Y 8 // it is easier to play with things having them here + #define MAP_MAX_PIXELS_X 53 + #define MAP_MAX_PIXELS_Y 49 void _lcd_ubl_plot_drawing_prep() { - uint8_t i, j, x_offset, y_offset, x_map_pixels, y_map_pixels; - uint8_t pixels_per_X_mesh_pnt, pixels_per_Y_mesh_pnt, inverted_y; + uint8_t i, j, x_offset, y_offset, x_map_pixels, y_map_pixels, + pixels_per_X_mesh_pnt, pixels_per_Y_mesh_pnt, inverted_y; /*********************************************************/ /************ Scale the box pixels appropriately *********/ @@ -2098,15 +2098,15 @@ void kill_screen(const char* lcd_msg) { 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; + 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; /*********************************************************/ /************ Clear the Mesh Map Box**********************/ /*********************************************************/ u8g.setColorIndex(1); // First draw the bigger box in White so we have a border around the mesh map box - u8g.drawBox(x_offset-2, y_offset-2, x_map_pixels+4, y_map_pixels+4); + u8g.drawBox(x_offset - 2, y_offset - 2, x_map_pixels + 4, y_map_pixels + 4); u8g.setColorIndex(0); // Now actually clear the mesh map box u8g.drawBox(x_offset, y_offset, x_map_pixels, y_map_pixels); @@ -2118,8 +2118,8 @@ void kill_screen(const char* lcd_msg) { u8g.setColorIndex(1); for (i = 0; i < GRID_MAX_POINTS_X; i++) { for (j = 0; j < GRID_MAX_POINTS_Y; j++) { - u8g.drawBox(x_offset+i*pixels_per_X_mesh_pnt+pixels_per_X_mesh_pnt/2, - y_offset+j*pixels_per_Y_mesh_pnt+pixels_per_Y_mesh_pnt/2, 1, 1); + u8g.drawBox(x_offset + i * pixels_per_X_mesh_pnt + pixels_per_X_mesh_pnt / 2, + y_offset + j * pixels_per_Y_mesh_pnt + pixels_per_Y_mesh_pnt / 2, 1, 1); } } @@ -2127,9 +2127,9 @@ void kill_screen(const char* lcd_msg) { /************ Fill in the Specified Mesh Point ***********/ /*********************************************************/ - inverted_y = GRID_MAX_POINTS_Y - y_plot - 1; // The origin is typically in the lower right corner. We need to + 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. - u8g.drawBox(x_offset+x_plot*pixels_per_X_mesh_pnt, y_offset+inverted_y*pixels_per_Y_mesh_pnt, + u8g.drawBox(x_offset + x_plot * pixels_per_X_mesh_pnt, y_offset + inverted_y * pixels_per_Y_mesh_pnt, pixels_per_X_mesh_pnt, pixels_per_Y_mesh_pnt); /*********************************************************/ @@ -2147,11 +2147,11 @@ void kill_screen(const char* lcd_msg) { // Print plot position u8g.setPrintPos(5, 64); - lcd_print("("); + lcd_print('('); u8g.print(x_plot); - lcd_print(","); + lcd_print(','); u8g.print(y_plot); - lcd_print(")"); + lcd_print(')'); // Show the location value u8g.setPrintPos(74, 64); @@ -2262,7 +2262,7 @@ void kill_screen(const char* lcd_msg) { void _lcd_ubl_output_map_lcd_cmd() { if (!(axis_known_position[X_AXIS] && axis_known_position[Y_AXIS] && axis_known_position[Z_AXIS])) enqueue_and_echo_commands_P(PSTR("G28")); - lcd_goto_screen(_lcd_ubl_map_homing); + lcd_goto_screen(_lcd_ubl_map_homing); } /** @@ -3624,7 +3624,7 @@ void kill_screen(const char* lcd_msg) { lcdDrawUpdate = LCDVIEW_CALL_REDRAW_NEXT; \ } \ ++_thisItemNr; \ - } while(0) + }while(0) void lcd_advanced_pause_toocold_menu() { START_MENU(); diff --git a/Marlin/ultralcd_impl_HD44780.h b/Marlin/ultralcd_impl_HD44780.h index 93a623d0ee..0521cb2f25 100644 --- a/Marlin/ultralcd_impl_HD44780.h +++ b/Marlin/ultralcd_impl_HD44780.h @@ -1012,7 +1012,7 @@ static void lcd_implementation_status_screen() { #endif // SDSUPPORT - #define lcd_implementation_drawmenu_back(sel, row, pstr, dummy) lcd_implementation_drawmenu_generic(sel, row, pstr, LCD_UPLEVEL_CHAR,LCD_UPLEVEL_CHAR) + #define lcd_implementation_drawmenu_back(sel, row, pstr, dummy) lcd_implementation_drawmenu_generic(sel, row, pstr, LCD_UPLEVEL_CHAR, LCD_UPLEVEL_CHAR) #define lcd_implementation_drawmenu_submenu(sel, row, pstr, data) lcd_implementation_drawmenu_generic(sel, row, pstr, '>', LCD_STR_ARROW_RIGHT[0]) #define lcd_implementation_drawmenu_gcode(sel, row, pstr, gcode) lcd_implementation_drawmenu_generic(sel, row, pstr, '>', ' ') #define lcd_implementation_drawmenu_function(sel, row, pstr, data) lcd_implementation_drawmenu_generic(sel, row, pstr, '>', ' ') From 7769a220646449e36cd1813301ed99684fc37687 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 15 Jun 2017 15:14:08 -0500 Subject: [PATCH 076/180] Tweaks to temperature code --- Marlin/temperature.cpp | 24 ++++++++++++------------ Marlin/temperature.h | 8 ++++---- Marlin/thermistortable_20.h | 12 ++++++------ 3 files changed, 22 insertions(+), 22 deletions(-) diff --git a/Marlin/temperature.cpp b/Marlin/temperature.cpp index 56be635da2..5eb8f05b4a 100644 --- a/Marlin/temperature.cpp +++ b/Marlin/temperature.cpp @@ -421,13 +421,13 @@ uint8_t Temperature::soft_pwm_amount[HOTENDS], bedKp = workKp; \ bedKi = scalePID_i(workKi); \ bedKd = scalePID_d(workKd); \ - updatePID(); } while(0) + updatePID(); }while(0) #define _SET_EXTRUDER_PID() do { \ PID_PARAM(Kp, hotend) = workKp; \ PID_PARAM(Ki, hotend) = scalePID_i(workKi); \ PID_PARAM(Kd, hotend) = scalePID_d(workKd); \ - updatePID(); } while(0) + updatePID(); }while(0) // Use the result? (As with "M303 U1") if (set_result) { @@ -505,7 +505,7 @@ int Temperature::getHeaterPower(int heater) { // // Temperature Error Handlers // -void Temperature::_temp_error(int e, const char* serial_msg, const char* lcd_msg) { +void Temperature::_temp_error(const int8_t e, const char * const serial_msg, const char * const lcd_msg) { static bool killed = false; if (IsRunning()) { SERIAL_ERROR_START(); @@ -524,7 +524,7 @@ void Temperature::_temp_error(int e, const char* serial_msg, const char* lcd_msg #endif } -void Temperature::max_temp_error(int8_t e) { +void Temperature::max_temp_error(const int8_t e) { #if HAS_TEMP_BED _temp_error(e, PSTR(MSG_T_MAXTEMP), e >= 0 ? PSTR(MSG_ERR_MAXTEMP) : PSTR(MSG_ERR_MAXTEMP_BED)); #else @@ -534,7 +534,7 @@ void Temperature::max_temp_error(int8_t e) { #endif #endif } -void Temperature::min_temp_error(int8_t e) { +void Temperature::min_temp_error(const int8_t e) { #if HAS_TEMP_BED _temp_error(e, PSTR(MSG_T_MINTEMP), e >= 0 ? PSTR(MSG_ERR_MINTEMP) : PSTR(MSG_ERR_MINTEMP_BED)); #else @@ -545,7 +545,7 @@ void Temperature::min_temp_error(int8_t e) { #endif } -float Temperature::get_pid_output(int e) { +float Temperature::get_pid_output(const int8_t e) { #if HOTENDS == 1 UNUSED(e); #define _HOTEND_TEST true @@ -890,7 +890,7 @@ float Temperature::analog2temp(int raw, uint8_t e) { // Derived from RepRap FiveD extruder::getTemperature() // For bed temperature measurement. -float Temperature::analog2tempBed(int raw) { +float Temperature::analog2tempBed(const int raw) { #if ENABLED(BED_USES_THERMISTOR) float celsius = 0; byte i; @@ -1148,7 +1148,7 @@ void Temperature::init() { #define TEMP_MIN_ROUTINE(NR) \ minttemp[NR] = HEATER_ ##NR## _MINTEMP; \ - while(analog2temp(minttemp_raw[NR], NR) < HEATER_ ##NR## _MINTEMP) { \ + while (analog2temp(minttemp_raw[NR], NR) < HEATER_ ##NR## _MINTEMP) { \ if (HEATER_ ##NR## _RAW_LO_TEMP < HEATER_ ##NR## _RAW_HI_TEMP) \ minttemp_raw[NR] += OVERSAMPLENR; \ else \ @@ -1156,7 +1156,7 @@ void Temperature::init() { } #define TEMP_MAX_ROUTINE(NR) \ maxttemp[NR] = HEATER_ ##NR## _MAXTEMP; \ - while(analog2temp(maxttemp_raw[NR], NR) > HEATER_ ##NR## _MAXTEMP) { \ + while (analog2temp(maxttemp_raw[NR], NR) > HEATER_ ##NR## _MAXTEMP) { \ if (HEATER_ ##NR## _RAW_LO_TEMP < HEATER_ ##NR## _RAW_HI_TEMP) \ maxttemp_raw[NR] -= OVERSAMPLENR; \ else \ @@ -1203,7 +1203,7 @@ void Temperature::init() { #endif // HOTENDS > 1 #ifdef BED_MINTEMP - while(analog2tempBed(bed_minttemp_raw) < BED_MINTEMP) { + while (analog2tempBed(bed_minttemp_raw) < BED_MINTEMP) { #if HEATER_BED_RAW_LO_TEMP < HEATER_BED_RAW_HI_TEMP bed_minttemp_raw += OVERSAMPLENR; #else @@ -1292,7 +1292,7 @@ void Temperature::init() { SERIAL_EOL(); */ - int heater_index = heater_id >= 0 ? heater_id : HOTENDS; + const int heater_index = heater_id >= 0 ? heater_id : HOTENDS; #if HEATER_IDLE_HANDLER // If the heater idle timeout expires, restart @@ -1922,7 +1922,7 @@ void Temperature::isr() { case SensorsReady: { // All sensors have been read. Stay in this state for a few // ISRs to save on calls to temp update/checking code below. - constexpr int extra_loops = MIN_ADC_ISR_LOOPS - (int)SensorsReady; + constexpr int8_t extra_loops = MIN_ADC_ISR_LOOPS - (int8_t)SensorsReady; static uint8_t delay_count = 0; if (extra_loops > 0) { if (delay_count == 0) delay_count = extra_loops; // Init this delay diff --git a/Marlin/temperature.h b/Marlin/temperature.h index 2eff176198..9437685789 100644 --- a/Marlin/temperature.h +++ b/Marlin/temperature.h @@ -535,15 +535,15 @@ class Temperature { static void checkExtruderAutoFans(); - static float get_pid_output(int e); + static float get_pid_output(const int8_t e); #if ENABLED(PIDTEMPBED) static float get_pid_output_bed(); #endif - static void _temp_error(int e, const char* serial_msg, const char* lcd_msg); - static void min_temp_error(int8_t e); - static void max_temp_error(int8_t e); + static void _temp_error(const int8_t e, const char * const serial_msg, const char * const lcd_msg); + static void min_temp_error(const int8_t e); + static void max_temp_error(const int8_t e); #if ENABLED(THERMAL_PROTECTION_HOTENDS) || HAS_THERMALLY_PROTECTED_BED diff --git a/Marlin/thermistortable_20.h b/Marlin/thermistortable_20.h index 9ec51d238c..1c27419591 100644 --- a/Marlin/thermistortable_20.h +++ b/Marlin/thermistortable_20.h @@ -23,27 +23,27 @@ // PT100 with INA826 amp on Ultimaker v2.0 electronics // The PT100 in the Ultimaker v2.0 electronics has a high sample value for a high temperature. // This does not match the normal thermistor behaviour so we need to set the following defines -#if (THERMISTORHEATER_0 == 20) +#if THERMISTORHEATER_0 == 20 #define HEATER_0_RAW_HI_TEMP 16383 #define HEATER_0_RAW_LO_TEMP 0 #endif -#if (THERMISTORHEATER_1 == 20) +#if THERMISTORHEATER_1 == 20 #define HEATER_1_RAW_HI_TEMP 16383 #define HEATER_1_RAW_LO_TEMP 0 #endif -#if (THERMISTORHEATER_2 == 20) +#if THERMISTORHEATER_2 == 20 #define HEATER_2_RAW_HI_TEMP 16383 #define HEATER_2_RAW_LO_TEMP 0 #endif -#if (THERMISTORHEATER_3 == 20) +#if THERMISTORHEATER_3 == 20 #define HEATER_3_RAW_HI_TEMP 16383 #define HEATER_3_RAW_LO_TEMP 0 #endif -#if (THERMISTORHEATER_4 == 20) +#if THERMISTORHEATER_4 == 20 #define HEATER_4_RAW_HI_TEMP 16383 #define HEATER_4_RAW_LO_TEMP 0 #endif -#if (THERMISTORBED == 20) +#if THERMISTORBED == 20 #define HEATER_BED_RAW_HI_TEMP 16383 #define HEATER_BED_RAW_LO_TEMP 0 #endif From 8d5a37fb3d044d65b0c81b8dc1533d834a5e5e82 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 15 Jun 2017 15:15:11 -0500 Subject: [PATCH 077/180] Support for a 5th stepper in stepper code --- Marlin/stepper.cpp | 11 ++++++++++- 1 file changed, 10 insertions(+), 1 deletion(-) diff --git a/Marlin/stepper.cpp b/Marlin/stepper.cpp index 4b9167b668..f3c2ff1d62 100644 --- a/Marlin/stepper.cpp +++ b/Marlin/stepper.cpp @@ -370,7 +370,7 @@ void Stepper::isr() { ocr_val = (remainder < OCR_VAL_TOLERANCE) ? ENDSTOP_NOMINAL_OCR_VAL + remainder : ENDSTOP_NOMINAL_OCR_VAL; \ step_remaining = (uint16_t)L - ocr_val; \ } \ - } while(0) + }while(0) if (step_remaining && ENDSTOPS_ENABLED) { // Just check endstops - not yet time for a step endstops.update(); @@ -862,6 +862,9 @@ void Stepper::isr() { SET_E_STEP_DIR(2); #if E_STEPPERS > 3 SET_E_STEP_DIR(3); + #if E_STEPPERS > 4 + SET_E_STEP_DIR(4); + #endif #endif #endif #endif @@ -880,6 +883,9 @@ void Stepper::isr() { START_E_PULSE(2); #if E_STEPPERS > 3 START_E_PULSE(3); + #if E_STEPPERS > 4 + START_E_PULSE(4); + #endif #endif #endif #endif @@ -899,6 +905,9 @@ void Stepper::isr() { STOP_E_PULSE(2); #if E_STEPPERS > 3 STOP_E_PULSE(3); + #if E_STEPPERS > 4 + STOP_E_PULSE(4); + #endif #endif #endif #endif From 428be2789344f5b9cb9ec2e027703645eaa1d46d Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 15 Jun 2017 15:17:41 -0500 Subject: [PATCH 078/180] Formatting adjustments --- Marlin/Marlin_main.cpp | 22 +++++++++++----------- Marlin/pins_SETHI.h | 2 +- Marlin/stepper_indirection.cpp | 2 +- 3 files changed, 13 insertions(+), 13 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index b3feff7234..69296edda2 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -752,7 +752,7 @@ void report_current_position_detail(); #endif #define DEBUG_POS(SUFFIX,VAR) do { \ - print_xyz(PSTR(" " STRINGIFY(VAR) "="), PSTR(" : " SUFFIX "\n"), VAR); } while(0) + print_xyz(PSTR(" " STRINGIFY(VAR) "="), PSTR(" : " SUFFIX "\n"), VAR); }while(0) #endif /** @@ -3492,20 +3492,20 @@ inline void gcode_G4() { SERIAL_ECHOPAIR("Probe Offset X:", X_PROBE_OFFSET_FROM_EXTRUDER); SERIAL_ECHOPAIR(" Y:", Y_PROBE_OFFSET_FROM_EXTRUDER); SERIAL_ECHOPAIR(" Z:", zprobe_zoffset); - #if (X_PROBE_OFFSET_FROM_EXTRUDER > 0) + #if X_PROBE_OFFSET_FROM_EXTRUDER > 0 SERIAL_ECHOPGM(" (Right"); - #elif (X_PROBE_OFFSET_FROM_EXTRUDER < 0) + #elif X_PROBE_OFFSET_FROM_EXTRUDER < 0 SERIAL_ECHOPGM(" (Left"); - #elif (Y_PROBE_OFFSET_FROM_EXTRUDER != 0) + #elif Y_PROBE_OFFSET_FROM_EXTRUDER != 0 SERIAL_ECHOPGM(" (Middle"); #else SERIAL_ECHOPGM(" (Aligned With"); #endif - #if (Y_PROBE_OFFSET_FROM_EXTRUDER > 0) + #if Y_PROBE_OFFSET_FROM_EXTRUDER > 0 SERIAL_ECHOPGM("-Back"); - #elif (Y_PROBE_OFFSET_FROM_EXTRUDER < 0) + #elif Y_PROBE_OFFSET_FROM_EXTRUDER < 0 SERIAL_ECHOPGM("-Front"); - #elif (X_PROBE_OFFSET_FROM_EXTRUDER != 0) + #elif X_PROBE_OFFSET_FROM_EXTRUDER != 0 SERIAL_ECHOPGM("-Center"); #endif if (zprobe_zoffset < 0) @@ -5109,7 +5109,7 @@ void home_all_axes() { gcode_G28(true); } const int8_t probe_points = parser.seen('P') ? parser.value_int() : DELTA_CALIBRATION_DEFAULT_POINTS; if (!WITHIN(probe_points, 1, 7)) { - SERIAL_PROTOCOLLNPGM("?(P)oints is implausible (1-7)."); + SERIAL_PROTOCOLLNPGM("?(P)oints is implausible (1 to 7)."); return; } @@ -11279,7 +11279,7 @@ void ok_to_send() { delta[A_AXIS] = DELTA_Z(A_AXIS); \ delta[B_AXIS] = DELTA_Z(B_AXIS); \ delta[C_AXIS] = DELTA_Z(C_AXIS); \ - } while(0) + }while(0) #define DELTA_LOGICAL_IK() do { \ const float raw[XYZ] = { \ @@ -11288,7 +11288,7 @@ void ok_to_send() { RAW_Z_POSITION(logical[Z_AXIS]) \ }; \ DELTA_RAW_IK(); \ - } while(0) + }while(0) #define DELTA_DEBUG() do { \ SERIAL_ECHOPAIR("cartesian X:", raw[X_AXIS]); \ @@ -11297,7 +11297,7 @@ void ok_to_send() { SERIAL_ECHOPAIR("delta A:", delta[A_AXIS]); \ SERIAL_ECHOPAIR(" B:", delta[B_AXIS]); \ SERIAL_ECHOLNPAIR(" C:", delta[C_AXIS]); \ - } while(0) + }while(0) void inverse_kinematics(const float logical[XYZ]) { DELTA_LOGICAL_IK(); diff --git a/Marlin/pins_SETHI.h b/Marlin/pins_SETHI.h index a05bb9eb27..ac570fd27c 100644 --- a/Marlin/pins_SETHI.h +++ b/Marlin/pins_SETHI.h @@ -99,7 +99,7 @@ #define HEATER_BED_PIN 3 -#if (GEN7_VERSION >= 13) +#if GEN7_VERSION >= 13 // Gen7 v1.3 removed the fan pin #define FAN_PIN -1 #else diff --git a/Marlin/stepper_indirection.cpp b/Marlin/stepper_indirection.cpp index 0fe3a801ce..c2f302704f 100644 --- a/Marlin/stepper_indirection.cpp +++ b/Marlin/stepper_indirection.cpp @@ -296,7 +296,7 @@ stepper##A.setMicroSteps(A##_MICROSTEPS); \ stepper##A.setOverCurrent(A##_OVERCURRENT); \ stepper##A.setStallCurrent(A##_STALLCURRENT); \ - } while(0) + }while(0) void L6470_init() { #if ENABLED(X_IS_L6470) From 92eb55f2468bcda5f4a19e2d1dda18245da35a06 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 15 Jun 2017 15:22:22 -0500 Subject: [PATCH 079/180] Reject generous donation of trailing whitespace --- Marlin/pinsDebug_plus_70.h | 73 +++++++++++++++++++------------------- 1 file changed, 36 insertions(+), 37 deletions(-) diff --git a/Marlin/pinsDebug_plus_70.h b/Marlin/pinsDebug_plus_70.h index e02721f813..1a905bd463 100644 --- a/Marlin/pinsDebug_plus_70.h +++ b/Marlin/pinsDebug_plus_70.h @@ -25,9 +25,9 @@ * structurs for 2560 family boards that use morre than 70 pins */ -#ifndef Plus_70_h - #define Plus_70_h - +#ifndef __PINSDEBUG_PLUS_70_H__ +#define __PINSDEBUG_PLUS_70_H__ + #undef NUM_DIGITAL_PINS #if MOTHERBOARD == BOARD_BQ_ZUM_MEGA_3D #define NUM_DIGITAL_PINS 85 @@ -124,22 +124,22 @@ const uint8_t PROGMEM digital_pin_to_port_PGM_plus_70[] = { PK , // PK 5 ** 67 ** A13 PK , // PK 6 ** 68 ** A14 PK , // PK 7 ** 69 ** A15 - PG , // PG 4 ** 70 ** - PG , // PG 3 ** 71 ** - PJ , // PJ 2 ** 72 ** - PJ , // PJ 3 ** 73 ** - PJ , // PJ 7 ** 74 ** - PJ , // PJ 4 ** 75 ** - PJ , // PJ 5 ** 76 ** - PJ , // PJ 6 ** 77 ** - PE , // PE 2 ** 78 ** - PE , // PE 6 ** 79 ** - PE , // PE 7 ** 80 ** - PD , // PD 4 ** 81 ** - PD , // PD 5 ** 82 ** - PD , // PD 6 ** 83 ** - PH , // PH 2 ** 84 ** - PH , // PH 7 ** 85 ** + PG , // PG 4 ** 70 ** + PG , // PG 3 ** 71 ** + PJ , // PJ 2 ** 72 ** + PJ , // PJ 3 ** 73 ** + PJ , // PJ 7 ** 74 ** + PJ , // PJ 4 ** 75 ** + PJ , // PJ 5 ** 76 ** + PJ , // PJ 6 ** 77 ** + PE , // PE 2 ** 78 ** + PE , // PE 6 ** 79 ** + PE , // PE 7 ** 80 ** + PD , // PD 4 ** 81 ** + PD , // PD 5 ** 82 ** + PD , // PD 6 ** 83 ** + PH , // PH 2 ** 84 ** + PH , // PH 7 ** 85 ** }; #define digitalPinToPort_plus_70(P) ( pgm_read_byte( digital_pin_to_port_PGM_plus_70 + (P) ) ) @@ -217,22 +217,22 @@ const uint8_t PROGMEM digital_pin_to_bit_mask_PGM_plus_70[] = { _BV( 5 ) , // PK 5 ** 67 ** A13 _BV( 6 ) , // PK 6 ** 68 ** A14 _BV( 7 ) , // PK 7 ** 69 ** A15 - _BV( 4 ) , // PG 4 ** 70 ** - _BV( 3 ) , // PG 3 ** 71 ** - _BV( 2 ) , // PJ 2 ** 72 ** - _BV( 3 ) , // PJ 3 ** 73 ** - _BV( 7 ) , // PJ 7 ** 74 ** - _BV( 4 ) , // PJ 4 ** 75 ** - _BV( 5 ) , // PJ 5 ** 76 ** - _BV( 6 ) , // PJ 6 ** 77 ** - _BV( 2 ) , // PE 2 ** 78 ** - _BV( 6 ) , // PE 6 ** 79 ** - _BV( 7 ) , // PE 7 ** 80 ** - _BV( 4 ) , // PD 4 ** 81 ** - _BV( 5 ) , // PD 5 ** 82 ** - _BV( 6 ) , // PD 6 ** 83 ** - _BV( 2 ) , // PH 2 ** 84 ** - _BV( 7 ) , // PH 7 ** 85 ** + _BV( 4 ) , // PG 4 ** 70 ** + _BV( 3 ) , // PG 3 ** 71 ** + _BV( 2 ) , // PJ 2 ** 72 ** + _BV( 3 ) , // PJ 3 ** 73 ** + _BV( 7 ) , // PJ 7 ** 74 ** + _BV( 4 ) , // PJ 4 ** 75 ** + _BV( 5 ) , // PJ 5 ** 76 ** + _BV( 6 ) , // PJ 6 ** 77 ** + _BV( 2 ) , // PE 2 ** 78 ** + _BV( 6 ) , // PE 6 ** 79 ** + _BV( 7 ) , // PE 7 ** 80 ** + _BV( 4 ) , // PD 4 ** 81 ** + _BV( 5 ) , // PD 5 ** 82 ** + _BV( 6 ) , // PD 6 ** 83 ** + _BV( 2 ) , // PH 2 ** 84 ** + _BV( 7 ) , // PH 7 ** 85 ** }; #define digitalPinToBitMask_plus_70(P) ( pgm_read_byte( digital_pin_to_bit_mask_PGM_plus_70 + (P) ) ) @@ -338,5 +338,4 @@ const uint8_t PROGMEM digital_pin_to_timer_PGM_plus_70[] = { */ -#endif - +#endif // __PINSDEBUG_PLUS_70_H__ From 7c95f762f204a9534583e4d76d318370ee7f57c8 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 15 Jun 2017 15:29:56 -0500 Subject: [PATCH 080/180] Show LCD bed options even without thermal protection --- Marlin/ultralcd.cpp | 22 ++++++++++++---------- 1 file changed, 12 insertions(+), 10 deletions(-) diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index 521b19f22c..749274486f 100644 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -1098,9 +1098,11 @@ void kill_screen(const char* lcd_msg) { #endif // HOTENDS > 1 #endif // HAS_TEMP_HOTEND - #if WATCH_THE_BED - void watch_temp_callback_bed() { thermalManager.start_watching_bed(); } - #endif + void watch_temp_callback_bed() { + #if WATCH_THE_BED + thermalManager.start_watching_bed(); + #endif + } #if ENABLED(ADVANCED_PAUSE_FEATURE) @@ -1162,7 +1164,7 @@ void kill_screen(const char* lcd_msg) { // // Bed: // - #if WATCH_THE_BED + #if HAS_TEMP_BED MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(int3, MSG_BED, &thermalManager.target_temperature_bed, 0, BED_MAXTEMP - 15, watch_temp_callback_bed); #endif @@ -1810,7 +1812,7 @@ void kill_screen(const char* lcd_msg) { void _lcd_ubl_build_custom_mesh() { char UBL_LCD_GCODE[20]; enqueue_and_echo_commands_P(PSTR("G28")); - #if WATCH_THE_BED + #if HAS_TEMP_BED sprintf_P(UBL_LCD_GCODE, PSTR("M190 S%i"), custom_bed_temp); enqueue_and_echo_command(UBL_LCD_GCODE); #endif @@ -1826,7 +1828,7 @@ void kill_screen(const char* lcd_msg) { START_MENU(); MENU_BACK(MSG_UBL_BUILD_MESH_MENU); MENU_ITEM_EDIT(int3, MSG_UBL_CUSTOM_HOTEND_TEMP, &custom_hotend_temp, EXTRUDE_MINTEMP, (HEATER_0_MAXTEMP - 10)); - #if WATCH_THE_BED + #if HAS_TEMP_BED MENU_ITEM_EDIT(int3, MSG_UBL_CUSTOM_BED_TEMP, &custom_bed_temp, BED_MINTEMP, (BED_MAXTEMP - 5)); #endif MENU_ITEM(function, MSG_UBL_BUILD_CUSTOM_MESH, _lcd_ubl_build_custom_mesh); @@ -1875,7 +1877,7 @@ void kill_screen(const char* lcd_msg) { void _lcd_ubl_validate_custom_mesh() { char UBL_LCD_GCODE[24]; const int temp = - #if WATCH_THE_BED + #if HAS_TEMP_BED custom_bed_temp #else 0 @@ -1891,7 +1893,7 @@ void kill_screen(const char* lcd_msg) { void _lcd_ubl_validate_mesh() { START_MENU(); MENU_BACK(MSG_UBL_TOOLS); - #if WATCH_THE_BED + #if HAS_TEMP_BED MENU_ITEM(gcode, MSG_UBL_VALIDATE_PLA_MESH, PSTR("G28\nG26 C B" STRINGIFY(PREHEAT_1_TEMP_BED) " H" STRINGIFY(PREHEAT_1_TEMP_HOTEND) " P")); MENU_ITEM(gcode, MSG_UBL_VALIDATE_ABS_MESH, PSTR("G28\nG26 C B" STRINGIFY(PREHEAT_2_TEMP_BED) " H" STRINGIFY(PREHEAT_2_TEMP_HOTEND) " P")); #else @@ -1978,7 +1980,7 @@ void kill_screen(const char* lcd_msg) { void _lcd_ubl_build_mesh() { START_MENU(); MENU_BACK(MSG_UBL_TOOLS); - #if WATCH_THE_BED + #if HAS_TEMP_BED MENU_ITEM(gcode, MSG_UBL_BUILD_PLA_MESH, PSTR( "G28\n" "M190 S" STRINGIFY(PREHEAT_1_TEMP_BED) "\n" @@ -2968,7 +2970,7 @@ void kill_screen(const char* lcd_msg) { // // Bed: // - #if WATCH_THE_BED + #if HAS_TEMP_BED MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(int3, MSG_BED, &thermalManager.target_temperature_bed, 0, BED_MAXTEMP - 15, watch_temp_callback_bed); #endif From 93da4e83f719f5d0c406bda80f263b8c48c6dfbc Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 15 Jun 2017 20:48:07 -0500 Subject: [PATCH 081/180] One more space on a short status message --- Marlin/ultralcd.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index 749274486f..94a7576252 100644 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -4393,11 +4393,11 @@ void pad_message_string() { // pad with spaces to fill up the line while (j++ < LCD_WIDTH) lcd_status_message[i++] = ' '; // chop off at the edge - lcd_status_message[--i] = '\0'; + lcd_status_message[i] = '\0'; } } -void lcd_finishstatus(bool persist=false) { +void lcd_finishstatus(const bool persist=false) { pad_message_string(); From 3d043976f7899cbd979c1e06c2cc078c3e2f25ff Mon Sep 17 00:00:00 2001 From: Jim Brown Date: Wed, 14 Jun 2017 22:06:34 -0400 Subject: [PATCH 082/180] Add option to disallow filament change without homing first --- Marlin/Configuration_adv.h | 1 + Marlin/Marlin_main.cpp | 8 ++++---- Marlin/SanityCheck.h | 2 ++ .../example_configurations/Cartesio/Configuration_adv.h | 1 + Marlin/example_configurations/Felix/Configuration_adv.h | 1 + .../FolgerTech-i3-2020/Configuration_adv.h | 1 + .../example_configurations/Hephestos/Configuration_adv.h | 1 + .../Hephestos_2/Configuration_adv.h | 1 + Marlin/example_configurations/K8200/Configuration_adv.h | 1 + Marlin/example_configurations/K8400/Configuration_adv.h | 1 + Marlin/example_configurations/M150/Configuration_adv.h | 1 + .../example_configurations/RigidBot/Configuration_adv.h | 1 + Marlin/example_configurations/SCARA/Configuration_adv.h | 1 + Marlin/example_configurations/TAZ4/Configuration_adv.h | 1 + .../example_configurations/TinyBoy2/Configuration_adv.h | 1 + Marlin/example_configurations/WITBOX/Configuration_adv.h | 1 + .../delta/FLSUN/auto_calibrate/Configuration_adv.h | 1 + .../delta/FLSUN/kossel_mini/Configuration_adv.h | 1 + .../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 + .../tvrrug/Round2/Configuration_adv.h | 1 + Marlin/example_configurations/wt150/Configuration_adv.h | 1 + 26 files changed, 30 insertions(+), 4 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index c8e30fffec..088554ebb8 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -807,6 +807,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 diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 69296edda2..dd6ec521f7 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -9265,10 +9265,10 @@ inline void gcode_M503() { */ inline void gcode_M600() { - // Don't allow filament change without homing first - if (axis_unhomed_error()) { - home_all_axes(); - } + #if ENABLED(HOME_BEFORE_FILAMENT_CHANGE) + // Don't allow filament change without homing first + if (axis_unhomed_error()) home_all_axes(); + #endif // Initial retract before move to filament change position const float retract = parser.seen('E') ? parser.value_axis_units(E_AXIS) : 0 diff --git a/Marlin/SanityCheck.h b/Marlin/SanityCheck.h index de4f550d2b..ee25709af3 100644 --- a/Marlin/SanityCheck.h +++ b/Marlin/SanityCheck.h @@ -321,6 +321,8 @@ #error "EXTRUDER_RUNOUT_PREVENT is incompatible with ADVANCED_PAUSE_FEATURE." #elif ENABLED(PARK_HEAD_ON_PAUSE) && DISABLED(SDSUPPORT) && DISABLED(NEWPANEL) && DISABLED(EMERGENCY_PARSER) #error "PARK_HEAD_ON_PAUSE requires SDSUPPORT, EMERGENCY_PARSER, or an LCD controller." + #elif ENABLED(HOME_BEFORE_FILAMENT_CHANGE) && DISABLED(PAUSE_PARK_NO_STEPPER_TIMEOUT) + #error "HOME_BEFORE_FILAMENT_CHANGE requires PAUSE_PARK_NO_STEPPER_TIMEOUT" #endif #endif diff --git a/Marlin/example_configurations/Cartesio/Configuration_adv.h b/Marlin/example_configurations/Cartesio/Configuration_adv.h index 8dfb65a36d..81cf8e290a 100644 --- a/Marlin/example_configurations/Cartesio/Configuration_adv.h +++ b/Marlin/example_configurations/Cartesio/Configuration_adv.h @@ -800,6 +800,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 diff --git a/Marlin/example_configurations/Felix/Configuration_adv.h b/Marlin/example_configurations/Felix/Configuration_adv.h index a5940d4566..ac5bdb51ce 100644 --- a/Marlin/example_configurations/Felix/Configuration_adv.h +++ b/Marlin/example_configurations/Felix/Configuration_adv.h @@ -800,6 +800,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 diff --git a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h index 4174cba825..282fdf006f 100644 --- a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h +++ b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h @@ -809,6 +809,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 diff --git a/Marlin/example_configurations/Hephestos/Configuration_adv.h b/Marlin/example_configurations/Hephestos/Configuration_adv.h index 3e7f6416d1..e2ed21f47d 100644 --- a/Marlin/example_configurations/Hephestos/Configuration_adv.h +++ b/Marlin/example_configurations/Hephestos/Configuration_adv.h @@ -800,6 +800,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 diff --git a/Marlin/example_configurations/Hephestos_2/Configuration_adv.h b/Marlin/example_configurations/Hephestos_2/Configuration_adv.h index 26af260c3e..c70eb7c28a 100644 --- a/Marlin/example_configurations/Hephestos_2/Configuration_adv.h +++ b/Marlin/example_configurations/Hephestos_2/Configuration_adv.h @@ -783,6 +783,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 diff --git a/Marlin/example_configurations/K8200/Configuration_adv.h b/Marlin/example_configurations/K8200/Configuration_adv.h index 4cad884b71..82d8adbadf 100644 --- a/Marlin/example_configurations/K8200/Configuration_adv.h +++ b/Marlin/example_configurations/K8200/Configuration_adv.h @@ -813,6 +813,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 diff --git a/Marlin/example_configurations/K8400/Configuration_adv.h b/Marlin/example_configurations/K8400/Configuration_adv.h index 34ccc3aeb3..a49c7d51bd 100644 --- a/Marlin/example_configurations/K8400/Configuration_adv.h +++ b/Marlin/example_configurations/K8400/Configuration_adv.h @@ -800,6 +800,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 diff --git a/Marlin/example_configurations/M150/Configuration_adv.h b/Marlin/example_configurations/M150/Configuration_adv.h index c2c1c0c3fb..a8379526fd 100644 --- a/Marlin/example_configurations/M150/Configuration_adv.h +++ b/Marlin/example_configurations/M150/Configuration_adv.h @@ -807,6 +807,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 diff --git a/Marlin/example_configurations/RigidBot/Configuration_adv.h b/Marlin/example_configurations/RigidBot/Configuration_adv.h index 027e633189..2bfdef25f0 100644 --- a/Marlin/example_configurations/RigidBot/Configuration_adv.h +++ b/Marlin/example_configurations/RigidBot/Configuration_adv.h @@ -800,6 +800,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 diff --git a/Marlin/example_configurations/SCARA/Configuration_adv.h b/Marlin/example_configurations/SCARA/Configuration_adv.h index 9ea1a60bd7..14fb68220f 100644 --- a/Marlin/example_configurations/SCARA/Configuration_adv.h +++ b/Marlin/example_configurations/SCARA/Configuration_adv.h @@ -800,6 +800,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 diff --git a/Marlin/example_configurations/TAZ4/Configuration_adv.h b/Marlin/example_configurations/TAZ4/Configuration_adv.h index 23b616ad53..c11677a8bd 100644 --- a/Marlin/example_configurations/TAZ4/Configuration_adv.h +++ b/Marlin/example_configurations/TAZ4/Configuration_adv.h @@ -800,6 +800,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 diff --git a/Marlin/example_configurations/TinyBoy2/Configuration_adv.h b/Marlin/example_configurations/TinyBoy2/Configuration_adv.h index ba0eae98a7..20c2e79f85 100644 --- a/Marlin/example_configurations/TinyBoy2/Configuration_adv.h +++ b/Marlin/example_configurations/TinyBoy2/Configuration_adv.h @@ -803,6 +803,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 diff --git a/Marlin/example_configurations/WITBOX/Configuration_adv.h b/Marlin/example_configurations/WITBOX/Configuration_adv.h index 3e7f6416d1..e2ed21f47d 100644 --- a/Marlin/example_configurations/WITBOX/Configuration_adv.h +++ b/Marlin/example_configurations/WITBOX/Configuration_adv.h @@ -800,6 +800,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 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 1ca156d9b3..a8a30eabd4 100644 --- a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h +++ b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h @@ -805,6 +805,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 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 dc5c04e2e0..3e27eab9d9 100644 --- a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h +++ b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h @@ -804,6 +804,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 diff --git a/Marlin/example_configurations/delta/generic/Configuration_adv.h b/Marlin/example_configurations/delta/generic/Configuration_adv.h index 49a550faee..f7d78f310e 100644 --- a/Marlin/example_configurations/delta/generic/Configuration_adv.h +++ b/Marlin/example_configurations/delta/generic/Configuration_adv.h @@ -802,6 +802,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 diff --git a/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h index 49a550faee..f7d78f310e 100644 --- a/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h @@ -802,6 +802,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 diff --git a/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h index 3922a31a7a..7f52481171 100644 --- a/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h @@ -807,6 +807,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 diff --git a/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h index 9b403edb19..41ceff3826 100644 --- a/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h @@ -802,6 +802,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 diff --git a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration_adv.h b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration_adv.h index ba963dd06d..4354d717ac 100644 --- a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration_adv.h +++ b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration_adv.h @@ -809,6 +809,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 diff --git a/Marlin/example_configurations/makibox/Configuration_adv.h b/Marlin/example_configurations/makibox/Configuration_adv.h index c16680356a..f6517a6c15 100644 --- a/Marlin/example_configurations/makibox/Configuration_adv.h +++ b/Marlin/example_configurations/makibox/Configuration_adv.h @@ -800,6 +800,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 diff --git a/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h b/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h index e218c85ca8..a6ab735e58 100644 --- a/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h +++ b/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h @@ -800,6 +800,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 diff --git a/Marlin/example_configurations/wt150/Configuration_adv.h b/Marlin/example_configurations/wt150/Configuration_adv.h index 09f94b2260..171f4c3b77 100644 --- a/Marlin/example_configurations/wt150/Configuration_adv.h +++ b/Marlin/example_configurations/wt150/Configuration_adv.h @@ -803,6 +803,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 From 062131554f37ad78850be621890e96f6327d86e1 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 16 Jun 2017 13:01:52 -0500 Subject: [PATCH 083/180] Followup to #7045 --- Marlin/language_en.h | 6 +++--- Marlin/ubl.cpp | 25 +++++++++++++------------ Marlin/ubl_G29.cpp | 2 +- Marlin/ultralcd.cpp | 17 ++++++++--------- 4 files changed, 25 insertions(+), 25 deletions(-) diff --git a/Marlin/language_en.h b/Marlin/language_en.h index dfad170a7a..17d7e77d20 100644 --- a/Marlin/language_en.h +++ b/Marlin/language_en.h @@ -280,9 +280,9 @@ #ifndef MSG_UBL_OUTPUT_MAP_CSV #define MSG_UBL_OUTPUT_MAP_CSV _UxGT("Output for CSV") #endif - #ifndef MSG_UBL_OUTPUT_MAP_BACKUP - #define MSG_UBL_OUTPUT_MAP_BACKUP _UxGT("Off Printer Backup") - #endif +#ifndef MSG_UBL_OUTPUT_MAP_BACKUP + #define MSG_UBL_OUTPUT_MAP_BACKUP _UxGT("Off Printer Backup") +#endif #ifndef MSG_UBL_INFO_UBL #define MSG_UBL_INFO_UBL _UxGT("Output UBL Info") #endif diff --git a/Marlin/ubl.cpp b/Marlin/ubl.cpp index 14d411e5c6..9805aff3fc 100644 --- a/Marlin/ubl.cpp +++ b/Marlin/ubl.cpp @@ -115,8 +115,9 @@ void unified_bed_leveling::display_map(const int map_type) { constexpr uint8_t spaces = 8 * (GRID_MAX_POINTS_X - 2); + SERIAL_PROTOCOLPGM("\nBed Topography Report"); if (map_type == 0) { - SERIAL_PROTOCOLLNPGM("\nBed Topography Report:\n"); + SERIAL_PROTOCOLPGM(":\n\n"); serial_echo_xy(0, GRID_MAX_POINTS_Y - 1); SERIAL_ECHO_SP(spaces + 3); serial_echo_xy(GRID_MAX_POINTS_X - 1, GRID_MAX_POINTS_Y - 1); @@ -126,9 +127,10 @@ serial_echo_xy(UBL_MESH_MAX_X, UBL_MESH_MAX_Y); SERIAL_EOL(); } - - if (map_type == 1) { SERIAL_PROTOCOLLNPGM("\nBed Topography Report for CSV:"); SERIAL_EOL(); } - if (map_type == 2) { SERIAL_PROTOCOLLNPGM("\nBed Topography Report for LCD:"); SERIAL_EOL(); } + else { + SERIAL_PROTOCOLPGM(" for "); + serialprintPGM(map_type == 1 ? PSTR("CSV:\n\n") : PSTR("LCD:\n\n")); + } const float current_xi = get_cell_index_x(current_position[X_AXIS] + (MESH_X_DIST) / 2.0), current_yi = get_cell_index_y(current_position[Y_AXIS] + (MESH_Y_DIST) / 2.0); @@ -142,14 +144,14 @@ const float f = z_values[i][j]; if (isnan(f)) { - serialprintPGM((map_type == 0) ? PSTR(" . ") : PSTR("NAN")); + serialprintPGM(map_type == 0 ? PSTR(" . ") : PSTR("NAN")); } - else { + else if (map_type <= 1) { // if we don't do this, the columns won't line up nicely - if ((map_type == 0) && f >= 0.0) SERIAL_CHAR(' '); - if (map_type <= 1) SERIAL_PROTOCOL_F(f, 3); - idle(); + if (map_type == 0 && f >= 0.0) SERIAL_CHAR(' '); + SERIAL_PROTOCOL_F(f, 3); } + idle(); if (map_type == 1 && i < GRID_MAX_POINTS_X - 1) SERIAL_CHAR(','); #if TX_BUFFER_SIZE > 0 @@ -162,7 +164,7 @@ } } SERIAL_EOL(); - if (j && (map_type == 0)) { // we want the (0,0) up tight against the block of numbers + if (j && map_type == 0) { // we want the (0,0) up tight against the block of numbers SERIAL_CHAR(' '); SERIAL_EOL(); } @@ -183,8 +185,7 @@ bool unified_bed_leveling::sanity_check() { uint8_t error_flag = 0; - const int a = settings.calc_num_meshes(); - if (a < 1) { + if (settings.calc_num_meshes() < 1) { SERIAL_PROTOCOLLNPGM("?Insufficient EEPROM storage for a mesh of this size."); error_flag++; } diff --git a/Marlin/ubl_G29.cpp b/Marlin/ubl_G29.cpp index e15c8d7728..8e047defb5 100644 --- a/Marlin/ubl_G29.cpp +++ b/Marlin/ubl_G29.cpp @@ -1576,7 +1576,7 @@ if (ubl_lcd_map_control) { #if ENABLED(DOGLCD) - lcd_goto_screen(_lcd_ubl_output_map_lcd); + lcd_goto_screen(_lcd_ubl_output_map_lcd); #endif } else lcd_return_to_status(); diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index 94a7576252..71deaa1ee7 100644 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -2094,11 +2094,11 @@ void kill_screen(const char* lcd_msg) { /*********************************************************/ /************ Scale the box pixels appropriately *********/ /*********************************************************/ - 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; + 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; @@ -2184,7 +2184,7 @@ void kill_screen(const char* lcd_msg) { void sync_plan_position(); void _lcd_ubl_output_map_lcd() { - static int step_scaler=0; + static int16_t step_scaler = 0; int32_t signed_enc_pos; defer_return_to_status = true; @@ -2194,11 +2194,10 @@ void kill_screen(const char* lcd_msg) { if (lcd_clicked) { return _lcd_ubl_map_lcd_edit_cmd(); } ENCODER_DIRECTION_NORMAL(); - if (encoderPosition != 0) { + if (encoderPosition) { signed_enc_pos = (int32_t)encoderPosition; step_scaler += signed_enc_pos; - x_plot = (x_plot + step_scaler / ENCODER_STEPS_PER_MENU_ITEM); - + x_plot += step_scaler / (ENCODER_STEPS_PER_MENU_ITEM); if (abs(step_scaler) >= ENCODER_STEPS_PER_MENU_ITEM) step_scaler = 0; refresh_cmd_timeout(); @@ -2240,7 +2239,7 @@ 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 + if (planner.movesplanned() > 1) { // if the nozzle is moving, cancel the move. There is a new location #define ENABLE_STEPPER_DRIVER_INTERRUPT() SBI(TIMSK1, OCIE1A) #define DISABLE_STEPPER_DRIVER_INTERRUPT() CBI(TIMSK1, OCIE1A) DISABLE_STEPPER_DRIVER_INTERRUPT(); From c61c0a9aeb8d02b71fbdc7ece755c43bcd6702a9 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 16 Jun 2017 14:10:31 -0500 Subject: [PATCH 084/180] Fix status message missing "blink" --- Marlin/ultralcd_impl_DOGM.h | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/Marlin/ultralcd_impl_DOGM.h b/Marlin/ultralcd_impl_DOGM.h index 295e276760..af862e02b9 100644 --- a/Marlin/ultralcd_impl_DOGM.h +++ b/Marlin/ultralcd_impl_DOGM.h @@ -408,7 +408,7 @@ FORCE_INLINE void _draw_axis_label(const AxisEnum axis, const char* const pstr, } } -inline void lcd_implementation_status_message() { +inline void lcd_implementation_status_message(const bool blink) { #if ENABLED(STATUS_MESSAGE_SCROLLING) static bool last_blink = false; const uint8_t slen = lcd_strlen(lcd_status_message); @@ -693,7 +693,7 @@ static void lcd_implementation_status_screen() { #if ENABLED(FILAMENT_LCD_DISPLAY) && ENABLED(SDSUPPORT) if (PENDING(millis(), previous_lcd_status_ms + 5000UL)) { //Display both Status message line and Filament display on the last line - lcd_implementation_status_message(); + lcd_implementation_status_message(blink); } else { lcd_printPGM(PSTR(LCD_STR_FILAM_DIA)); @@ -705,7 +705,7 @@ static void lcd_implementation_status_screen() { u8g.print('%'); } #else - lcd_implementation_status_message(); + lcd_implementation_status_message(blink); #endif } } From d4270f15a9067993b8e8d8ed7035855e1eb6d395 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 16 Jun 2017 14:20:58 -0500 Subject: [PATCH 085/180] Spacing tweak in setup() --- Marlin/Marlin_main.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index dd6ec521f7..a15145d31b 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -12702,10 +12702,10 @@ void setup() { // Check startup - does nothing if bootloader sets MCUSR to 0 byte mcu = MCUSR; - if (mcu & 1) SERIAL_ECHOLNPGM(MSG_POWERUP); - if (mcu & 2) SERIAL_ECHOLNPGM(MSG_EXTERNAL_RESET); - if (mcu & 4) SERIAL_ECHOLNPGM(MSG_BROWNOUT_RESET); - if (mcu & 8) SERIAL_ECHOLNPGM(MSG_WATCHDOG_RESET); + if (mcu & 1) SERIAL_ECHOLNPGM(MSG_POWERUP); + if (mcu & 2) SERIAL_ECHOLNPGM(MSG_EXTERNAL_RESET); + if (mcu & 4) SERIAL_ECHOLNPGM(MSG_BROWNOUT_RESET); + if (mcu & 8) SERIAL_ECHOLNPGM(MSG_WATCHDOG_RESET); if (mcu & 32) SERIAL_ECHOLNPGM(MSG_SOFTWARE_RESET); MCUSR = 0; From dd1a84b23f36410d0596f21a73a35aa0cf6f05ff Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 16 Jun 2017 14:48:01 -0500 Subject: [PATCH 086/180] Add Travis test for scrolling on DOGM --- .travis.yml | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/.travis.yml b/.travis.yml index 127faef496..c5cdf4b70c 100644 --- a/.travis.yml +++ b/.travis.yml @@ -245,10 +245,11 @@ script: - opt_set_adv SDSORT_CACHE_NAMES true - build_marlin # - # REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER + # REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER with SDCARD_SORT_ALPHA and STATUS_MESSAGE_SCROLLING # - restore_configs - opt_enable REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER SDSUPPORT + - opt_enable_adv SDCARD_SORT_ALPHA STATUS_MESSAGE_SCROLLING - build_marlin # # REPRAPWORLD_KEYPAD From 6cb9bb27fec0e7f67c372c798b90fd8536f70225 Mon Sep 17 00:00:00 2001 From: Bob-the-Kuhn Date: Thu, 15 Jun 2017 23:54:16 -0500 Subject: [PATCH 087/180] Move lcd_refresh_zprobe_zoffset definition --- Marlin/ultralcd.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index 71deaa1ee7..23cdba92cc 100644 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -1506,7 +1506,11 @@ void kill_screen(const char* lcd_msg) { static void lcd_load_settings() { lcd_completion_feedback(settings.load()); } #endif - #if ENABLED(LCD_BED_LEVELING) + #if HAS_BED_PROBE && DISABLED(BABYSTEP_ZPROBE_OFFSET) + static void lcd_refresh_zprobe_zoffset() { refresh_zprobe_zoffset(); } + #endif + +#if ENABLED(LCD_BED_LEVELING) /** * @@ -3156,10 +3160,6 @@ void kill_screen(const char* lcd_msg) { #endif // E_STEPPERS > 2 #endif - #if HAS_BED_PROBE && DISABLED(BABYSTEP_ZPROBE_OFFSET) - static void lcd_refresh_zprobe_zoffset() { refresh_zprobe_zoffset(); } - #endif - // M203 / M205 Velocity options void lcd_control_motion_velocity_menu() { START_MENU(); From 8fb30aaed640e4eaf3d3ccb936313518f570503a Mon Sep 17 00:00:00 2001 From: Bob-the-Kuhn Date: Sat, 17 Jun 2017 15:02:25 -0500 Subject: [PATCH 088/180] warn user of an invalid combination --- Marlin/SanityCheck.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Marlin/SanityCheck.h b/Marlin/SanityCheck.h index ee25709af3..af054cab10 100644 --- a/Marlin/SanityCheck.h +++ b/Marlin/SanityCheck.h @@ -293,6 +293,8 @@ #error "BABYSTEPPING is not implemented for SCARA yet." #elif ENABLED(DELTA) && ENABLED(BABYSTEP_XY) #error "BABYSTEPPING only implemented for Z axis on deltabots." + #elif ENABLED(BABYSTEP_ZPROBE_OFFSET) && ENABLED(MESH_BED_LEVELING) + #error "MESH_BED_LEVELING and BABYSTEP_ZPROBE_OFFSET is not a valid combination" #elif ENABLED(BABYSTEP_ZPROBE_OFFSET) && !HAS_BED_PROBE #error "BABYSTEP_ZPROBE_OFFSET requires a probe." #endif From 3d24c329af5a4dd71c40bdd918caa792b179373d Mon Sep 17 00:00:00 2001 From: Thomas Moore Date: Mon, 12 Jun 2017 23:09:44 -0500 Subject: [PATCH 089/180] M600 fixes --- Marlin/Marlin_main.cpp | 82 +++++++++++++++++++++++++++++------------- Marlin/ultralcd.cpp | 15 +++++--- 2 files changed, 67 insertions(+), 30 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index a15145d31b..28c6fb058c 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -5866,7 +5866,7 @@ inline void gcode_M17() { idle(); heaters_heating = false; HOTEND_LOOP() { - if (thermalManager.degTargetHotend(e) && abs(thermalManager.degHotend(e) - thermalManager.degTargetHotend(e)) > 3) { + if (thermalManager.degTargetHotend(e) && abs(thermalManager.degHotend(e) - thermalManager.degTargetHotend(e)) > TEMP_HYSTERESIS) { heaters_heating = true; #if ENABLED(ULTIPANEL) lcd_advanced_pause_show_message(ADVANCED_PAUSE_MESSAGE_WAIT_FOR_NOZZLES_TO_HEAT); @@ -5882,7 +5882,7 @@ inline void gcode_M17() { ) { if (move_away_flag) return false; // already paused - if (!DEBUGGING(DRYRUN) && unload_length != 0) { + if (!DEBUGGING(DRYRUN) && (unload_length != 0 || retract != 0)) { #if ENABLED(PREVENT_COLD_EXTRUSION) if (!thermalManager.allow_cold_extrude && thermalManager.degTargetHotend(active_extruder) < thermalManager.extrude_min_temp) { @@ -5919,10 +5919,11 @@ inline void gcode_M17() { COPY(resume_position, current_position); set_destination_to_current(); - // Initial retract before move to filament change position - destination[E_AXIS] += retract; - - RUNPLAN(PAUSE_PARK_RETRACT_FEEDRATE); + if (retract) { + // Initial retract before move to filament change position + destination[E_AXIS] += retract; + RUNPLAN(PAUSE_PARK_RETRACT_FEEDRATE); + } // Lift Z axis if (z_lift > 0) { @@ -5951,23 +5952,25 @@ inline void gcode_M17() { destination[E_AXIS] += unload_length; RUNPLAN(FILAMENT_CHANGE_UNLOAD_FEEDRATE); stepper.synchronize(); - - if (show_lcd) { - #if ENABLED(ULTIPANEL) - lcd_advanced_pause_show_message(ADVANCED_PAUSE_MESSAGE_INSERT); - #endif - } - - #if HAS_BUZZER - filament_change_beep(max_beep_count, true); - #endif - - idle(); } - // Disable extruders steppers for manual filament changing - disable_e_steppers(); - safe_delay(100); + if (show_lcd) { + #if ENABLED(ULTIPANEL) + lcd_advanced_pause_show_message(ADVANCED_PAUSE_MESSAGE_INSERT); + #endif + } + + #if HAS_BUZZER + filament_change_beep(max_beep_count, true); + #endif + + idle(); + + // Disable extruders steppers for manual filament changing (only on boards that have separate ENABLE_PINS) + #if E0_ENABLE_PIN != X_ENABLE_PIN && E1_ENABLE_PIN != Y_ENABLE_PIN + disable_e_steppers(); + safe_delay(100); + #endif // Start the heater idle timers const millis_t nozzle_timeout = (millis_t)(PAUSE_PARK_NOZZLE_TIMEOUT) * 1000UL; @@ -5989,14 +5992,43 @@ inline void gcode_M17() { filament_change_beep(max_beep_count); #endif + // If the nozzle has timed out, wait for the user to press the button to re-heat the nozzle, then + // re-heat the nozzle, re-show the insert screen, restart the idle timers, and start over if (!nozzle_timed_out) HOTEND_LOOP() nozzle_timed_out |= thermalManager.is_heater_idle(e); - #if ENABLED(ULTIPANEL) - if (nozzle_timed_out) + if (nozzle_timed_out) { + #if ENABLED(ULTIPANEL) lcd_advanced_pause_show_message(ADVANCED_PAUSE_MESSAGE_CLICK_TO_HEAT_NOZZLE); - #endif + #endif + + // Wait for LCD click or M108 + while (wait_for_user) idle(true); + + // Re-enable the heaters if they timed out + HOTEND_LOOP() thermalManager.reset_heater_idle_timer(e); + + // Wait for the heaters to reach the target temperatures + ensure_safe_temperature(); + + #if ENABLED(ULTIPANEL) + lcd_advanced_pause_show_message(ADVANCED_PAUSE_MESSAGE_INSERT); + #endif + + // Start the heater idle timers + const millis_t nozzle_timeout = (millis_t)(PAUSE_PARK_NOZZLE_TIMEOUT) * 1000UL; + + HOTEND_LOOP() + thermalManager.start_heater_idle_timer(e, nozzle_timeout); + + wait_for_user = true; /* Wait for user to load filament */ + nozzle_timed_out = false; + + #if HAS_BUZZER + filament_change_beep(max_beep_count, true); + #endif + } idle(true); } @@ -7643,7 +7675,7 @@ inline void gcode_M18_M84() { if (parser.seen('X')) disable_X(); if (parser.seen('Y')) disable_Y(); if (parser.seen('Z')) disable_Z(); - #if ((E0_ENABLE_PIN != X_ENABLE_PIN) && (E1_ENABLE_PIN != Y_ENABLE_PIN)) // Only enable on boards that have seperate ENABLE_PINS + #if E0_ENABLE_PIN != X_ENABLE_PIN && E1_ENABLE_PIN != Y_ENABLE_PIN // Only enable on boards that have seperate ENABLE_PINS if (parser.seen('E')) disable_e_steppers(); #endif } diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index 23cdba92cc..61f8ee7e9b 100644 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -1107,11 +1107,16 @@ void kill_screen(const char* lcd_msg) { #if ENABLED(ADVANCED_PAUSE_FEATURE) void lcd_enqueue_filament_change() { - if (!DEBUGGING(DRYRUN) && thermalManager.tooColdToExtrude(active_extruder)) { - lcd_save_previous_screen(); - lcd_goto_screen(lcd_advanced_pause_toocold_menu); - return; - } + + #if ENABLED(PREVENT_COLD_EXTRUSION) + if (!DEBUGGING(DRYRUN) && !thermalManager.allow_cold_extrude && + thermalManager.degTargetHotend(active_extruder) < thermalManager.extrude_min_temp) { + lcd_save_previous_screen(); + lcd_goto_screen(lcd_advanced_pause_toocold_menu); + return; + } + #endif + lcd_advanced_pause_show_message(ADVANCED_PAUSE_MESSAGE_INIT); enqueue_and_echo_commands_P(PSTR("M600 B0")); } From 4857a3ba48b8168099b78ac65c1f1613c3253bf1 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 18 Jun 2017 22:58:19 -0500 Subject: [PATCH 090/180] Formatting and spelling --- Marlin/Marlin_main.cpp | 4 ++-- Marlin/mesh_bed_leveling.h | 4 ++-- Marlin/planner.cpp | 16 ++++++++-------- Marlin/ultralcd.cpp | 4 ++-- 4 files changed, 14 insertions(+), 14 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 28c6fb058c..81d491d7e3 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -6081,7 +6081,7 @@ inline void gcode_M17() { stepper.synchronize(); } - #if ENABLED(ULTIPANEL) && defined(ADVANCED_PAUSE_EXTRUDE_LENGTH) && ADVANCED_PAUSE_EXTRUDE_LENGTH > 0 + #if ENABLED(ULTIPANEL) && ADVANCED_PAUSE_EXTRUDE_LENGTH > 0 float extrude_length = initial_extrude_length; @@ -7675,7 +7675,7 @@ inline void gcode_M18_M84() { if (parser.seen('X')) disable_X(); if (parser.seen('Y')) disable_Y(); if (parser.seen('Z')) disable_Z(); - #if E0_ENABLE_PIN != X_ENABLE_PIN && E1_ENABLE_PIN != Y_ENABLE_PIN // Only enable on boards that have seperate ENABLE_PINS + #if E0_ENABLE_PIN != X_ENABLE_PIN && E1_ENABLE_PIN != Y_ENABLE_PIN // Only enable on boards that have separate ENABLE_PINS if (parser.seen('E')) disable_e_steppers(); #endif } diff --git a/Marlin/mesh_bed_leveling.h b/Marlin/mesh_bed_leveling.h index 41ba2677c1..f7b701bf28 100644 --- a/Marlin/mesh_bed_leveling.h +++ b/Marlin/mesh_bed_leveling.h @@ -94,8 +94,8 @@ } static float calc_z0(const float &a0, const float &a1, const float &z1, const float &a2, const float &z2) { - const float delta_z = (z2 - z1) / (a2 - a1); - const float delta_a = a0 - a1; + const float delta_z = (z2 - z1) / (a2 - a1), + delta_a = a0 - a1; return z1 + delta_a * delta_z; } diff --git a/Marlin/planner.cpp b/Marlin/planner.cpp index a755db5767..537f334606 100644 --- a/Marlin/planner.cpp +++ b/Marlin/planner.cpp @@ -534,10 +534,10 @@ void Planner::check_axes_activity() { if (!ubl.state.active) return; #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) // if z_fade_height enabled (nonzero) and raw_z above it, no leveling required - if ((planner.z_fade_height) && (planner.z_fade_height <= RAW_Z_POSITION(lz))) return; + if (planner.z_fade_height && planner.z_fade_height <= RAW_Z_POSITION(lz)) return; lz += ubl.state.z_offset + ubl.get_z_correction(lx, ly) * ubl.fade_scaling_factor_for_z(lz); #else // no fade - lz += ubl.state.z_offset + ubl.get_z_correction(lx,ly); + lz += ubl.state.z_offset + ubl.get_z_correction(lx, ly); #endif // FADE #endif // UBL @@ -598,10 +598,10 @@ void Planner::check_axes_activity() { if (ubl.state.active) { - const float z_physical = RAW_Z_POSITION(logical[Z_AXIS]); - const float z_ublmesh = ubl.get_z_correction(logical[X_AXIS], logical[Y_AXIS]); - const float z_virtual = z_physical - ubl.state.z_offset - z_ublmesh; - float z_logical = LOGICAL_Z_POSITION(z_virtual); + const float z_physical = RAW_Z_POSITION(logical[Z_AXIS]), + z_correct = ubl.get_z_correction(logical[X_AXIS], logical[Y_AXIS]), + z_virtual = z_physical - ubl.state.z_offset - z_correct; + float z_logical = LOGICAL_Z_POSITION(z_virtual); #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) @@ -614,10 +614,10 @@ void Planner::check_axes_activity() { // so L=(P-O-M)/(1-M/H) for L= planner.z_fade_height) z_logical = LOGICAL_Z_POSITION(z_physical - ubl.state.z_offset); + else + z_logical /= 1.0 - z_correct * planner.inverse_z_fade_height; } #endif // ENABLE_LEVELING_FADE_HEIGHT diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index 61f8ee7e9b..f7c75cc3dc 100644 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -1018,8 +1018,8 @@ void kill_screen(const char* lcd_msg) { #if ENABLED(AUTO_BED_LEVELING_UBL) - float mesh_edit_value, mesh_edit_accumulator; // We round mesh_edit_value to 2.5 decimal places. So we keep a - // seperate value that doesn't lose precision. + float mesh_edit_value, mesh_edit_accumulator; // We round mesh_edit_value to 2.5 decimal places. So we keep a + // separate value that doesn't lose precision. static int ubl_encoderPosition = 0; static void _lcd_mesh_fine_tune(const char* msg) { From 4c3dc8bf079d27c79b8117153e0096e882603960 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 18 Jun 2017 23:00:25 -0500 Subject: [PATCH 091/180] Remove set_current_to_destination from resume_print Addressing #7057 --- Marlin/Marlin_main.cpp | 2 -- 1 file changed, 2 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 81d491d7e3..61bbaa5141 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -6136,8 +6136,6 @@ inline void gcode_M17() { filament_ran_out = false; #endif - set_current_to_destination(); - #if ENABLED(ULTIPANEL) // Show status screen lcd_advanced_pause_show_message(ADVANCED_PAUSE_MESSAGE_STATUS); From 2e26a7c752aee5d8b9e119623eb449da9338c9dc Mon Sep 17 00:00:00 2001 From: Silvio Didonna Date: Sun, 18 Jun 2017 18:44:53 +0200 Subject: [PATCH 092/180] Added missing Italian translations --- Marlin/language_it.h | 83 ++++++++++++++++++++++++++------------------ 1 file changed, 50 insertions(+), 33 deletions(-) diff --git a/Marlin/language_it.h b/Marlin/language_it.h index 23e81f4707..f6edf68b7e 100644 --- a/Marlin/language_it.h +++ b/Marlin/language_it.h @@ -50,6 +50,7 @@ #define MSG_LEVEL_BED_WAITING _UxGT("Premi per iniziare") #define MSG_LEVEL_BED_NEXT_POINT _UxGT("Punto successivo") #define MSG_LEVEL_BED_DONE _UxGT("Livel. terminato!") +#define MSG_Z_FADE_HEIGHT _UxGT("Fade Height") #define MSG_SET_HOME_OFFSETS _UxGT("Imp. offset home") #define MSG_HOME_OFFSETS_APPLIED _UxGT("Offset applicato") #define MSG_SET_ORIGIN _UxGT("Imposta Origine") @@ -75,6 +76,7 @@ #define MSG_LEVEL_BED _UxGT("Livella piano") #define MSG_EDITING_STOPPED _UxGT("Modifica Mesh Fermata") #define MSG_USER_MENU _UxGT("Comandi Utente") + #define MSG_UBL_DOING_G29 _UxGT("G29 in corso") #define MSG_UBL_UNHOMED _UxGT("Home XYZ prima") #define MSG_UBL_TOOLS _UxGT("Strumenti UBL") @@ -87,7 +89,9 @@ #define MSG_UBL_ACTIVATE_MESH _UxGT("Attiva UBL") #define MSG_UBL_DEACTIVATE_MESH _UxGT("Disattiva UBL") #define MSG_UBL_SET_BED_TEMP _UxGT("Temp Piatto") +#define MSG_UBL_CUSTOM_BED_TEMP MSG_UBL_SET_BED_TEMP #define MSG_UBL_SET_HOTEND_TEMP _UxGT("Temp Ugello") +#define MSG_UBL_CUSTOM_HOTEND_TEMP MSG_UBL_SET_HOTEND_TEMP #define MSG_UBL_EDIT_CUSTOM_MESH _UxGT("Modif Custom Mesh") #define MSG_UBL_FINE_TUNE_MESH _UxGT("Ritocca Mesh") #define MSG_UBL_DONE_EDITING_MESH _UxGT("Done Editing Mesh") @@ -112,6 +116,7 @@ #define MSG_UBL_OUTPUT_MAP _UxGT("Esporta Mappa") #define MSG_UBL_OUTPUT_MAP_HOST _UxGT("Esporta per Host") #define MSG_UBL_OUTPUT_MAP_CSV _UxGT("Esporta in CSV") +#define MSG_UBL_OUTPUT_MAP_BACKUP _UxGT("Backup esterno") #define MSG_UBL_INFO_UBL _UxGT("Esporta Info UBL") #define MSG_UBL_EDIT_MESH_MENU _UxGT("Modifica Mesh") #define MSG_UBL_FILLIN_AMOUNT _UxGT("Riempimento") @@ -129,6 +134,7 @@ #define MSG_UBL_SAVE_ERROR _UxGT("Err: Salvataggio UBL") #define MSG_UBL_RESTORE_ERROR _UxGT("Err: Ripristino UBL") #define MSG_UBL_Z_OFFSET_STOPPED _UxGT("Z-Offset Fermato") + #define MSG_MOVING _UxGT("In movimento...") #define MSG_FREE_XY _UxGT("XY liberi") #define MSG_MOVE_X _UxGT("Muovi X") @@ -170,9 +176,15 @@ #define MSG_VY_JERK _UxGT("Vy-jerk") #define MSG_VZ_JERK _UxGT("Vz-jerk") #define MSG_VE_JERK _UxGT("Ve-jerk") +#if ENABLED(DOGLCD) + #define MSG_VELOCITY _UxGT("Velocità") +#else + #define MSG_VELOCITY _UxGT("Velocita") +#endif #define MSG_VMAX _UxGT("Vmax ") #define MSG_VMIN _UxGT("Vmin") #define MSG_VTRAV_MIN _UxGT("VTrav min") +#define MSG_ACCELERATION _UxGT("Accelerazione") #define MSG_AMAX _UxGT("Amax ") #define MSG_A_RETRACT _UxGT("A-retract") #define MSG_A_TRAVEL _UxGT("A-Spostamento") @@ -196,6 +208,7 @@ #define MSG_STORE_EEPROM _UxGT("Salva in memoria") #define MSG_LOAD_EEPROM _UxGT("Carica da memoria") #define MSG_RESTORE_FAILSAFE _UxGT("Ripristina imp.") +#define MSG_INIT_EEPROM _UxGT("Inizializza EEPROM") #define MSG_REFRESH _UxGT("Aggiorna") #define MSG_WATCH _UxGT("Guarda") #define MSG_PREPARE _UxGT("Prepara") @@ -207,6 +220,7 @@ #define MSG_NO_CARD _UxGT("SD non presente") #define MSG_DWELL _UxGT("Sospensione...") #define MSG_USERWAIT _UxGT("Premi tasto..") +#define MSG_PRINT_PAUSED _UxGT("Stampa sospesa") #define MSG_RESUMING _UxGT("Riprendi Stampa") #define MSG_PRINT_ABORTED _UxGT("Stampa annullata") #define MSG_NO_MOVE _UxGT("Nessun Movimento") @@ -224,8 +238,11 @@ #define MSG_INIT_SDCARD _UxGT("Iniz. SD-Card") #define MSG_CNG_SDCARD _UxGT("Cambia SD-Card") #define MSG_ZPROBE_OUT _UxGT("Z probe out. bed") +#define MSG_BLTOUCH _UxGT("BLTouch") #define MSG_BLTOUCH_SELFTEST _UxGT("Autotest BLTouch") #define MSG_BLTOUCH_RESET _UxGT("Resetta BLTouch") +#define MSG_BLTOUCH_DEPLOY _UxGT("Estendi BLTouch") +#define MSG_BLTOUCH_STOW _UxGT("Ritrai BLTouch") #define MSG_HOME _UxGT("Home") // Used as MSG_HOME " " MSG_X MSG_Y MSG_Z " " MSG_FIRST #define MSG_FIRST _UxGT("prima") #define MSG_ZPROBE_ZOFFSET _UxGT("Z Offset") @@ -272,9 +289,9 @@ #define MSG_INFO_PROTOCOL _UxGT("Protocollo") #define MSG_CASE_LIGHT _UxGT("Luci Case") #if ENABLED(DOGLCD) - #define MSG_CASE_LIGHT_BRIGHTNESS _UxGT("Luminosità Luci") + #define MSG_CASE_LIGHT_BRIGHTNESS _UxGT("Luminosità Luci") #else - #define MSG_CASE_LIGHT_BRIGHTNESS _UxGT("Luminosita Luci") + #define MSG_CASE_LIGHT_BRIGHTNESS _UxGT("Luminosita Luci") #endif #if LCD_WIDTH >= 20 @@ -311,45 +328,45 @@ #define MSG_FILAMENT_CHANGE_OPTION_EXTRUDE _UxGT("Estrudi ancora") #define MSG_FILAMENT_CHANGE_OPTION_RESUME _UxGT("Riprendi stampa") #if ENABLED(DOGLCD) - #define MSG_FILAMENT_CHANGE_MINTEMP _UxGT("Temp minima è ") + #define MSG_FILAMENT_CHANGE_MINTEMP _UxGT("Temp minima è ") #else - #define MSG_FILAMENT_CHANGE_MINTEMP _UxGT("Temp minima e ") + #define MSG_FILAMENT_CHANGE_MINTEMP _UxGT("Temp minima e ") #endif #define MSG_FILAMENT_CHANGE_NOZZLE _UxGT(" Ugello: ") #if LCD_HEIGHT >= 4 // Up to 3 lines allowed - #define MSG_FILAMENT_CHANGE_INIT_1 _UxGT("Attendere avvio") - #define MSG_FILAMENT_CHANGE_INIT_2 _UxGT("del cambio") - #define MSG_FILAMENT_CHANGE_INIT_3 _UxGT("di filamento") - #define MSG_FILAMENT_CHANGE_UNLOAD_1 _UxGT("Attendere") - #define MSG_FILAMENT_CHANGE_UNLOAD_2 _UxGT("l'espulsione") - #define MSG_FILAMENT_CHANGE_UNLOAD_3 _UxGT("del filamento") - #define MSG_FILAMENT_CHANGE_INSERT_1 _UxGT("Inserisci il") - #define MSG_FILAMENT_CHANGE_INSERT_2 _UxGT("filamento e") - #define MSG_FILAMENT_CHANGE_INSERT_3 _UxGT("premi per cont") - #define MSG_FILAMENT_CHANGE_HEAT_1 _UxGT("Premi per") - #define MSG_FILAMENT_CHANGE_HEAT_2 _UxGT("riscald ugello.") - #define MSG_FILAMENT_CHANGE_HEATING_1 _UxGT("Riscald. ugello") - #define MSG_FILAMENT_CHANGE_HEATING_2 _UxGT("Attendere...") - #define MSG_FILAMENT_CHANGE_LOAD_1 _UxGT("Attendere") - #define MSG_FILAMENT_CHANGE_LOAD_2 _UxGT("il caricamento") - #define MSG_FILAMENT_CHANGE_LOAD_3 _UxGT("del filamento") - #define MSG_FILAMENT_CHANGE_EXTRUDE_1 _UxGT("Attendere") - #define MSG_FILAMENT_CHANGE_EXTRUDE_2 _UxGT("l'estrusione") - #define MSG_FILAMENT_CHANGE_EXTRUDE_3 _UxGT("del filamento") - #define MSG_FILAMENT_CHANGE_RESUME_1 _UxGT("Attendere") - #define MSG_FILAMENT_CHANGE_RESUME_2 _UxGT("la ripresa") - #define MSG_FILAMENT_CHANGE_RESUME_3 _UxGT("della stampa") + #define MSG_FILAMENT_CHANGE_INIT_1 _UxGT("Attendere avvio") + #define MSG_FILAMENT_CHANGE_INIT_2 _UxGT("del cambio") + #define MSG_FILAMENT_CHANGE_INIT_3 _UxGT("di filamento") + #define MSG_FILAMENT_CHANGE_UNLOAD_1 _UxGT("Attendere") + #define MSG_FILAMENT_CHANGE_UNLOAD_2 _UxGT("l'espulsione") + #define MSG_FILAMENT_CHANGE_UNLOAD_3 _UxGT("del filamento") + #define MSG_FILAMENT_CHANGE_INSERT_1 _UxGT("Inserisci il") + #define MSG_FILAMENT_CHANGE_INSERT_2 _UxGT("filamento e") + #define MSG_FILAMENT_CHANGE_INSERT_3 _UxGT("premi per cont") + #define MSG_FILAMENT_CHANGE_HEAT_1 _UxGT("Premi per") + #define MSG_FILAMENT_CHANGE_HEAT_2 _UxGT("riscald ugello.") + #define MSG_FILAMENT_CHANGE_HEATING_1 _UxGT("Riscald. ugello") + #define MSG_FILAMENT_CHANGE_HEATING_2 _UxGT("Attendere...") + #define MSG_FILAMENT_CHANGE_LOAD_1 _UxGT("Attendere") + #define MSG_FILAMENT_CHANGE_LOAD_2 _UxGT("il caricamento") + #define MSG_FILAMENT_CHANGE_LOAD_3 _UxGT("del filamento") + #define MSG_FILAMENT_CHANGE_EXTRUDE_1 _UxGT("Attendere") + #define MSG_FILAMENT_CHANGE_EXTRUDE_2 _UxGT("l'estrusione") + #define MSG_FILAMENT_CHANGE_EXTRUDE_3 _UxGT("del filamento") + #define MSG_FILAMENT_CHANGE_RESUME_1 _UxGT("Attendere") + #define MSG_FILAMENT_CHANGE_RESUME_2 _UxGT("la ripresa") + #define MSG_FILAMENT_CHANGE_RESUME_3 _UxGT("della stampa") #else // LCD_HEIGHT < 4 // Up to 2 lines allowed - #define MSG_FILAMENT_CHANGE_INIT_1 _UxGT("Attendere...") - #define MSG_FILAMENT_CHANGE_UNLOAD_1 _UxGT("Espulsione...") - #define MSG_FILAMENT_CHANGE_INSERT_1 _UxGT("Inserisci e premi") - #define MSG_FILAMENT_CHANGE_HEATING_1 _UxGT("Riscaldamento...") - #define MSG_FILAMENT_CHANGE_LOAD_1 _UxGT("Caricamento...") - #define MSG_FILAMENT_CHANGE_EXTRUDE_1 _UxGT("Estrusione...") - #define MSG_FILAMENT_CHANGE_RESUME_1 _UxGT("Ripresa...") + #define MSG_FILAMENT_CHANGE_INIT_1 _UxGT("Attendere...") + #define MSG_FILAMENT_CHANGE_UNLOAD_1 _UxGT("Espulsione...") + #define MSG_FILAMENT_CHANGE_INSERT_1 _UxGT("Inserisci e premi") + #define MSG_FILAMENT_CHANGE_HEATING_1 _UxGT("Riscaldamento...") + #define MSG_FILAMENT_CHANGE_LOAD_1 _UxGT("Caricamento...") + #define MSG_FILAMENT_CHANGE_EXTRUDE_1 _UxGT("Estrusione...") + #define MSG_FILAMENT_CHANGE_RESUME_1 _UxGT("Ripresa...") #endif // LCD_HEIGHT < 4 #endif // LANGUAGE_IT_H From 0b49bddec27fdfaed3ebd4cfee5402d945d989ec Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 19 Jun 2017 01:01:00 -0500 Subject: [PATCH 093/180] Fix Italian language mapper --- Marlin/language_it.h | 43 ++++++++----------------------------------- 1 file changed, 8 insertions(+), 35 deletions(-) diff --git a/Marlin/language_it.h b/Marlin/language_it.h index f6edf68b7e..45d1b58559 100644 --- a/Marlin/language_it.h +++ b/Marlin/language_it.h @@ -30,6 +30,7 @@ #ifndef LANGUAGE_IT_H #define LANGUAGE_IT_H +#define MAPPER_C2C3 #define DISPLAY_CHARSET_ISO10646_1 #define WELCOME_MSG MACHINE_NAME _UxGT(" pronto.") @@ -144,19 +145,11 @@ #define MSG_MOVE_01MM _UxGT("Muovi di 0.1mm") #define MSG_MOVE_1MM _UxGT("Muovi di 1mm") #define MSG_MOVE_10MM _UxGT("Muovi di 10mm") -#if ENABLED(DOGLCD) - #define MSG_SPEED _UxGT("Velocità") -#else - #define MSG_SPEED _UxGT("Velocita") -#endif +#define MSG_SPEED _UxGT("Velocità") #define MSG_BED_Z _UxGT("piatto Z") #define MSG_NOZZLE _UxGT("Ugello") #define MSG_BED _UxGT("Piatto") -#if ENABLED(DOGLCD) - #define MSG_FAN_SPEED _UxGT("Velocità ventola") -#else - #define MSG_FAN_SPEED _UxGT("Velocita ventola") -#endif +#define MSG_FAN_SPEED _UxGT("Velocità ventola") #define MSG_FLOW _UxGT("Flusso") #define MSG_CONTROL _UxGT("Controllo") #define MSG_MIN LCD_STR_THERMOMETER _UxGT(" Min") @@ -176,11 +169,7 @@ #define MSG_VY_JERK _UxGT("Vy-jerk") #define MSG_VZ_JERK _UxGT("Vz-jerk") #define MSG_VE_JERK _UxGT("Ve-jerk") -#if ENABLED(DOGLCD) - #define MSG_VELOCITY _UxGT("Velocità") -#else - #define MSG_VELOCITY _UxGT("Velocita") -#endif +#define MSG_VELOCITY _UxGT("Velocità") #define MSG_VMAX _UxGT("Vmax ") #define MSG_VMIN _UxGT("Vmin") #define MSG_VTRAV_MIN _UxGT("VTrav min") @@ -288,31 +277,19 @@ #define MSG_INFO_BAUDRATE _UxGT("Baud") #define MSG_INFO_PROTOCOL _UxGT("Protocollo") #define MSG_CASE_LIGHT _UxGT("Luci Case") -#if ENABLED(DOGLCD) - #define MSG_CASE_LIGHT_BRIGHTNESS _UxGT("Luminosità Luci") -#else - #define MSG_CASE_LIGHT_BRIGHTNESS _UxGT("Luminosita Luci") -#endif +#define MSG_CASE_LIGHT_BRIGHTNESS _UxGT("Luminosità Luci") #if LCD_WIDTH >= 20 #define MSG_INFO_PRINT_COUNT _UxGT("Contat. stampa") #define MSG_INFO_COMPLETED_PRINTS _UxGT("Completati") #define MSG_INFO_PRINT_TIME _UxGT("Tempo totale") - #if ENABLED(DOGLCD) - #define MSG_INFO_PRINT_LONGEST _UxGT("Lavoro più lungo") - #else - #define MSG_INFO_PRINT_LONGEST _UxGT("Lavoro piu lungo") - #endif + #define MSG_INFO_PRINT_LONGEST _UxGT("Lavoro più lungo") #define MSG_INFO_PRINT_FILAMENT _UxGT("Totale estruso") #else #define MSG_INFO_PRINT_COUNT _UxGT("Stampe") #define MSG_INFO_COMPLETED_PRINTS _UxGT("Completati") #define MSG_INFO_PRINT_TIME _UxGT("Durata") - #if ENABLED(DOGLCD) - #define MSG_INFO_PRINT_LONGEST _UxGT("Più lungo") - #else - #define MSG_INFO_PRINT_LONGEST _UxGT("Piu lungo") - #endif + #define MSG_INFO_PRINT_LONGEST _UxGT("Più lungo") #define MSG_INFO_PRINT_FILAMENT _UxGT("Estruso") #endif #define MSG_INFO_MIN_TEMP _UxGT("Temp min") @@ -327,11 +304,7 @@ #define MSG_FILAMENT_CHANGE_OPTION_HEADER _UxGT("OPZIONI:") #define MSG_FILAMENT_CHANGE_OPTION_EXTRUDE _UxGT("Estrudi ancora") #define MSG_FILAMENT_CHANGE_OPTION_RESUME _UxGT("Riprendi stampa") -#if ENABLED(DOGLCD) - #define MSG_FILAMENT_CHANGE_MINTEMP _UxGT("Temp minima è ") -#else - #define MSG_FILAMENT_CHANGE_MINTEMP _UxGT("Temp minima e ") -#endif +#define MSG_FILAMENT_CHANGE_MINTEMP _UxGT("Temp minima è ") #define MSG_FILAMENT_CHANGE_NOZZLE _UxGT(" Ugello: ") #if LCD_HEIGHT >= 4 From cfcd0695017193d34e307d59917c10de8a4fc3dd Mon Sep 17 00:00:00 2001 From: Ross Allan Date: Mon, 19 Jun 2017 11:14:05 +0100 Subject: [PATCH 094/180] Fix #5699 - LIN_ADVANCE freeze when ADV_RATE returns 0 --- Marlin/stepper.cpp | 23 ++++++++++++++++++----- 1 file changed, 18 insertions(+), 5 deletions(-) diff --git a/Marlin/stepper.cpp b/Marlin/stepper.cpp index f3c2ff1d62..2f8fc6dfcf 100644 --- a/Marlin/stepper.cpp +++ b/Marlin/stepper.cpp @@ -110,9 +110,22 @@ volatile uint32_t Stepper::step_events_completed = 0; // The number of step even Stepper::advance; #endif - #define ADV_RATE(T, L) (e_steps[TOOL_E_INDEX] ? (T) * (L) / abs(e_steps[TOOL_E_INDEX]) : ADV_NEVER) + /** + * See https://github.com/MarlinFirmware/Marlin/issues/5699#issuecomment-309264382 + * + * This fix isn't perfect and may lose steps - but better than locking up completely + * in future the planner should slow down if advance stepping rate would be too high + */ + FORCE_INLINE uint16_t adv_rate(const int steps, const uint16_t timer, const uint8_t loops) { + if (steps) { + const uint16_t rate = (timer * loops) / abs(steps); + //return constrain(rate, 1, ADV_NEVER - 1) + return rate ? rate : 1; + } + return ADV_NEVER; + } -#endif +#endif // ADVANCE || LIN_ADVANCE long Stepper::acceleration_time, Stepper::deceleration_time; @@ -743,7 +756,7 @@ void Stepper::isr() { #endif // ADVANCE or LIN_ADVANCE #if ENABLED(ADVANCE) || ENABLED(LIN_ADVANCE) - eISR_Rate = ADV_RATE(timer, step_loops); + eISR_Rate = adv_rate(e_steps[TOOL_E_INDEX], timer, step_loops); #endif } else if (step_events_completed > (uint32_t)current_block->decelerate_after) { @@ -797,7 +810,7 @@ void Stepper::isr() { #endif // ADVANCE or LIN_ADVANCE #if ENABLED(ADVANCE) || ENABLED(LIN_ADVANCE) - eISR_Rate = ADV_RATE(timer, step_loops); + eISR_Rate = adv_rate(e_steps[TOOL_E_INDEX], timer, step_loops); #endif } else { @@ -807,7 +820,7 @@ void Stepper::isr() { if (current_block->use_advance_lead) current_estep_rate[TOOL_E_INDEX] = final_estep_rate; - eISR_Rate = ADV_RATE(OCR1A_nominal, step_loops_nominal); + eISR_Rate = adv_rate(e_steps[TOOL_E_INDEX], OCR1A_nominal, step_loops_nominal); #endif From 907cafcbfd3977712324c59a4e9af40bde167421 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 19 Jun 2017 16:54:37 -0500 Subject: [PATCH 095/180] Support for two switching extruders --- Marlin/Configuration.h | 5 ++- Marlin/Marlin_main.cpp | 63 ++++++++++++++++++++---------------- Marlin/SanityCheck.h | 28 +++++++--------- Marlin/pins.h | 12 ++++++- Marlin/stepper_indirection.h | 16 +++++++-- 5 files changed, 75 insertions(+), 49 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 7d6c4a5614..6c128f4e14 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -142,7 +142,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 diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 61bbaa5141..b364e6f2fa 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -9843,25 +9843,41 @@ inline void gcode_M999() { } #if ENABLED(SWITCHING_EXTRUDER) - inline void move_extruder_servo(uint8_t e) { - const int angles[2] = SWITCHING_EXTRUDER_SERVO_ANGLES; - MOVE_SERVO(SWITCHING_EXTRUDER_SERVO_NR, angles[e]); - safe_delay(500); + #if EXTRUDERS > 3 + #define REQ_ANGLES 4 + #define _SERVO_NR (e < 2 ? SWITCHING_EXTRUDER_SERVO_NR : SWITCHING_EXTRUDER_E23_SERVO_NR) + #else + #define REQ_ANGLES 2 + #define _SERVO_NR SWITCHING_EXTRUDER_SERVO_NR + #endif + inline void move_extruder_servo(const uint8_t e) { + constexpr int16_t angles[] = SWITCHING_EXTRUDER_SERVO_ANGLES; + static_assert(COUNT(angles) == REQ_ANGLES, "SWITCHING_EXTRUDER_SERVO_ANGLES needs " STRINGIFY(REQ_ANGLES) " angles."); + stepper.synchronize(); + #if EXTRUDERS & 1 + if (e < EXTRUDERS - 1) + #endif + { + MOVE_SERVO(_SERVO_NR, angles[e]); + safe_delay(500); + } } -#endif +#endif // SWITCHING_EXTRUDER #if ENABLED(SWITCHING_NOZZLE) - inline void move_nozzle_servo(uint8_t e) { - const int angles[2] = SWITCHING_NOZZLE_SERVO_ANGLES; + inline void move_nozzle_servo(const uint8_t e) { + const int16_t angles[2] = SWITCHING_NOZZLE_SERVO_ANGLES; + stepper.synchronize(); MOVE_SERVO(SWITCHING_NOZZLE_SERVO_NR, angles[e]); safe_delay(500); } #endif -inline void invalid_extruder_error(const uint8_t &e) { +inline void invalid_extruder_error(const uint8_t e) { SERIAL_ECHO_START(); SERIAL_CHAR('T'); SERIAL_ECHO_F(e, DEC); + SERIAL_CHAR(' '); SERIAL_ECHOLN(MSG_INVALID_EXTRUDER); } @@ -9881,10 +9897,10 @@ void tool_change(const uint8_t tmp_extruder, const float fr_mm_s/*=0.0*/, bool n #else // !MIXING_EXTRUDER || MIXING_VIRTUAL_TOOLS <= 1 - #if HOTENDS > 1 + if (tmp_extruder >= EXTRUDERS) + return invalid_extruder_error(tmp_extruder); - if (tmp_extruder >= EXTRUDERS) - return invalid_extruder_error(tmp_extruder); + #if HOTENDS > 1 const float old_feedrate_mm_s = fr_mm_s > 0.0 ? fr_mm_s : feedrate_mm_s; @@ -10006,6 +10022,7 @@ void tool_change(const uint8_t tmp_extruder, const float fr_mm_s/*=0.0*/, bool n #else // !DUAL_X_CARRIAGE #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. const float z_diff = hotend_offset[Z_AXIS][active_extruder] - hotend_offset[Z_AXIS][tmp_extruder], z_raise = 0.3 + (z_diff > 0.0 ? z_diff : 0.0); @@ -10013,16 +10030,7 @@ void tool_change(const uint8_t tmp_extruder, const float fr_mm_s/*=0.0*/, bool n // Always raise by some amount (destination copied from current_position earlier) current_position[Z_AXIS] += z_raise; planner.buffer_line_kinematic(current_position, planner.max_feedrate_mm_s[Z_AXIS], active_extruder); - stepper.synchronize(); - - move_nozzle_servo(active_extruder); - #endif - - #if ENABLED(SWITCHING_EXTRUDER) - #if !(ENABLED(SWITCHING_NOZZLE) && (SWITCHING_EXTRUDER_SERVO_NR == SWITCHING_NOZZLE_SERVO_NR)) - stepper.synchronize(); - move_extruder_servo(active_extruder); - #endif + move_nozzle_servo(tmp_extruder); #endif /** @@ -10167,19 +10175,18 @@ void tool_change(const uint8_t tmp_extruder, const float fr_mm_s/*=0.0*/, bool n #else // HOTENDS <= 1 - // Set the new active extruder - active_extruder = tmp_extruder; - UNUSED(fr_mm_s); UNUSED(no_move); - #if ENABLED(SWITCHING_EXTRUDER) - stepper.synchronize(); - move_extruder_servo(active_extruder); - #endif + // Set the new active extruder + active_extruder = tmp_extruder; #endif // HOTENDS <= 1 + #if ENABLED(SWITCHING_EXTRUDER) && !DONT_SWITCH + move_extruder_servo(active_extruder); + #endif + SERIAL_ECHO_START(); SERIAL_ECHOLNPAIR(MSG_ACTIVE_EXTRUDER, (int)active_extruder); diff --git a/Marlin/SanityCheck.h b/Marlin/SanityCheck.h index ee25709af3..0b4f612d02 100644 --- a/Marlin/SanityCheck.h +++ b/Marlin/SanityCheck.h @@ -355,12 +355,14 @@ #endif /** - * A dual nozzle x-carriage with switching servo + * A Dual Nozzle carriage with switching servo */ #if ENABLED(SWITCHING_NOZZLE) - #if ENABLED(SINGLENOZZLE) + #if ENABLED(DUAL_X_CARRIAGE) + #error "SWITCHING_NOZZLE and DUAL_X_CARRIAGE are incompatible." + #elif ENABLED(SINGLENOZZLE) #error "SWITCHING_NOZZLE and SINGLENOZZLE are incompatible." - #elif EXTRUDERS < 2 + #elif EXTRUDERS != 2 #error "SWITCHING_NOZZLE requires exactly 2 EXTRUDERS." #elif NUM_SERVOS < 1 #error "SWITCHING_NOZZLE requires NUM_SERVOS >= 1." @@ -370,14 +372,8 @@ /** * Single Stepper Dual Extruder with switching servo */ -#if ENABLED(SWITCHING_EXTRUDER) - #if ENABLED(DUAL_X_CARRIAGE) - #error "SWITCHING_EXTRUDER and DUAL_X_CARRIAGE are incompatible." - #elif EXTRUDERS != 2 - #error "SWITCHING_EXTRUDER requires exactly 2 EXTRUDERS." - #elif NUM_SERVOS < 1 - #error "SWITCHING_EXTRUDER requires NUM_SERVOS >= 1." - #endif +#if ENABLED(SWITCHING_EXTRUDER) && NUM_SERVOS < 1 + #error "SWITCHING_EXTRUDER requires NUM_SERVOS >= 1." #endif /** @@ -938,21 +934,21 @@ static_assert(1 >= 0 #endif /** - * Test Extruder Pins + * Test Extruder Stepper Pins */ -#if EXTRUDERS > 4 +#if E_STEPPERS > 4 #if !PIN_EXISTS(E4_STEP) || !PIN_EXISTS(E4_DIR) || !PIN_EXISTS(E4_ENABLE) #error "E4_STEP_PIN, E4_DIR_PIN, or E4_ENABLE_PIN not defined for this board." #endif -#elif EXTRUDERS > 3 +#elif E_STEPPERS > 3 #if !PIN_EXISTS(E3_STEP) || !PIN_EXISTS(E3_DIR) || !PIN_EXISTS(E3_ENABLE) #error "E3_STEP_PIN, E3_DIR_PIN, or E3_ENABLE_PIN not defined for this board." #endif -#elif EXTRUDERS > 2 +#elif E_STEPPERS > 2 #if !PIN_EXISTS(E2_STEP) || !PIN_EXISTS(E2_DIR) || !PIN_EXISTS(E2_ENABLE) #error "E2_STEP_PIN, E2_DIR_PIN, or E2_ENABLE_PIN not defined for this board." #endif -#elif EXTRUDERS > 1 +#elif E_STEPPERS > 1 #if !PIN_EXISTS(E1_STEP) || !PIN_EXISTS(E1_DIR) || !PIN_EXISTS(E1_ENABLE) #error "E1_STEP_PIN, E1_DIR_PIN, or E1_ENABLE_PIN not defined for this board." #endif diff --git a/Marlin/pins.h b/Marlin/pins.h index 689e305d92..0b43a7a1ca 100644 --- a/Marlin/pins.h +++ b/Marlin/pins.h @@ -330,7 +330,17 @@ #define _E3_PINS #define _E4_PINS -#if EXTRUDERS > 1 +#if ENABLED(SWITCHING_EXTRUDER) + // Tools 0 and 1 use E0 + #if EXTRUDERS > 2 // Tools 2 and 3 use E1 + #undef _E1_PINS + #define _E1_PINS E1_STEP_PIN, E1_DIR_PIN, E1_ENABLE_PIN, E1_MS1_PIN, E1_MS2_PIN, + #if EXTRUDERS > 4 // Tools 4 and 5 use E2 + #undef _E2_PINS + #define _E2_PINS E2_STEP_PIN, E2_DIR_PIN, E2_ENABLE_PIN, + #endif + #endif +#elif EXTRUDERS > 1 #undef _E1_PINS #define _E1_PINS E1_STEP_PIN, E1_DIR_PIN, E1_ENABLE_PIN, E1_MS1_PIN, E1_MS2_PIN, #if EXTRUDERS > 2 diff --git a/Marlin/stepper_indirection.h b/Marlin/stepper_indirection.h index 79a8da4f63..e9af6e43fd 100644 --- a/Marlin/stepper_indirection.h +++ b/Marlin/stepper_indirection.h @@ -416,9 +416,19 @@ * Extruder indirection for the single E axis */ #if ENABLED(SWITCHING_EXTRUDER) - #define E_STEP_WRITE(v) E0_STEP_WRITE(v) - #define NORM_E_DIR() E0_DIR_WRITE(current_block->active_extruder ? INVERT_E0_DIR : !INVERT_E0_DIR) - #define REV_E_DIR() E0_DIR_WRITE(current_block->active_extruder ? !INVERT_E0_DIR : INVERT_E0_DIR) + #if EXTRUDERS == 2 + #define E_STEP_WRITE(v) E0_STEP_WRITE(v) + #define NORM_E_DIR() E0_DIR_WRITE(current_block->active_extruder ? INVERT_E0_DIR : !INVERT_E0_DIR) + #define REV_E_DIR() E0_DIR_WRITE(current_block->active_extruder ? !INVERT_E0_DIR : INVERT_E0_DIR) + #elif EXTRUDERS > 4 + #define E_STEP_WRITE(v) { if (current_block->active_extruder < 2) E0_STEP_WRITE(v); else if (current_block->active_extruder < 4) E1_STEP_WRITE(v); else E2_STEP_WRITE(v); } + #define NORM_E_DIR() { switch (current_block->active_extruder) { case 0: E0_DIR_WRITE(!INVERT_E0_DIR); break; case 1: E0_DIR_WRITE(INVERT_E0_DIR); break; case 2: E1_DIR_WRITE(!INVERT_E1_DIR); break; case 3: E1_DIR_WRITE(INVERT_E1_DIR); break; case 4: E2_DIR_WRITE(!INVERT_E2_DIR); } } + #define REV_E_DIR() { switch (current_block->active_extruder) { case 0: E0_DIR_WRITE(INVERT_E0_DIR); break; case 1: E0_DIR_WRITE(!INVERT_E0_DIR); break; case 2: E1_DIR_WRITE(INVERT_E1_DIR); break; case 3: E1_DIR_WRITE(!INVERT_E1_DIR); break; case 4: E2_DIR_WRITE(INVERT_E2_DIR); } } + #elif EXTRUDERS > 2 + #define E_STEP_WRITE(v) { if (current_block->active_extruder < 2) E0_STEP_WRITE(v); else if (current_block->active_extruder < 4) E1_STEP_WRITE(v); else E1_STEP_WRITE(v); } + #define NORM_E_DIR() { switch (current_block->active_extruder) { case 0: E0_DIR_WRITE(!INVERT_E0_DIR); break; case 1: E0_DIR_WRITE(INVERT_E0_DIR); break; case 2: E1_DIR_WRITE(!INVERT_E1_DIR); break; case 3: E1_DIR_WRITE(INVERT_E1_DIR); } } + #define REV_E_DIR() { switch (current_block->active_extruder) { case 0: E0_DIR_WRITE(INVERT_E0_DIR); break; case 1: E0_DIR_WRITE(!INVERT_E0_DIR); break; case 2: E1_DIR_WRITE(INVERT_E1_DIR); break; case 3: E1_DIR_WRITE(!INVERT_E1_DIR); } } + #endif #elif EXTRUDERS > 4 #define E_STEP_WRITE(v) { switch (current_block->active_extruder) { case 0: E0_STEP_WRITE(v); break; case 1: E1_STEP_WRITE(v); break; case 2: E2_STEP_WRITE(v); break; case 3: E3_STEP_WRITE(v); break; case 4: E4_STEP_WRITE(v); } } #define NORM_E_DIR() { switch (current_block->active_extruder) { case 0: E0_DIR_WRITE(!INVERT_E0_DIR); break; case 1: E1_DIR_WRITE(!INVERT_E1_DIR); break; case 2: E2_DIR_WRITE(!INVERT_E2_DIR); break; case 3: E3_DIR_WRITE(!INVERT_E3_DIR); break; case 4: E4_DIR_WRITE(!INVERT_E4_DIR); } } From a1c65fd3d538e930a1c0bee82e33c35cf6e5a924 Mon Sep 17 00:00:00 2001 From: Bob-the-Kuhn Date: Tue, 13 Jun 2017 21:42:40 -0500 Subject: [PATCH 096/180] convert DAC percent to uint8_t ===================== add test to Travis --- .travis.yml | 5 +++-- Marlin/stepper_dac.cpp | 4 ++-- Marlin/stepper_dac.h | 4 ++-- Marlin/ultralcd.cpp | 12 +++++++----- Marlin/ultralcd_impl_DOGM.h | 1 + Marlin/ultralcd_impl_HD44780.h | 1 + Marlin/utility.cpp | 15 ++++++++------- Marlin/utility.h | 10 +++++----- 8 files changed, 29 insertions(+), 23 deletions(-) diff --git a/.travis.yml b/.travis.yml index 127faef496..57fcefcd18 100644 --- a/.travis.yml +++ b/.travis.yml @@ -228,10 +228,11 @@ script: #- opt_enable MAKRPANEL #- build_marlin # - # REPRAP_DISCOUNT_SMART_CONTROLLER, SDSUPPORT, and BABYSTEPPING + # REPRAP_DISCOUNT_SMART_CONTROLLER, SDSUPPORT, BABYSTEPPING, RIGIDBOARD_V2, and DAC_MOTOR_CURRENT_DEFAULT # - restore_configs - - opt_enable REPRAP_DISCOUNT_SMART_CONTROLLER SDSUPPORT BABYSTEPPING + - opt_set MOTHERBOARD BOARD_RIGIDBOARD_V2 + - opt_enable REPRAP_DISCOUNT_SMART_CONTROLLER SDSUPPORT BABYSTEPPING DAC_MOTOR_CURRENT_DEFAULT - build_marlin # # G3D_PANEL with SDCARD_SORT_ALPHA and STATUS_MESSAGE_SCROLLING diff --git a/Marlin/stepper_dac.cpp b/Marlin/stepper_dac.cpp index 322a9403f6..6ea8b83bce 100644 --- a/Marlin/stepper_dac.cpp +++ b/Marlin/stepper_dac.cpp @@ -94,8 +94,8 @@ static float dac_perc(int8_t n) { return 100.0 * mcp4728_getValue(dac_order[n]) * (1.0 / (DAC_STEPPER_MAX)); } static float dac_amps(int8_t n) { return mcp4728_getDrvPct(dac_order[n]) * (DAC_STEPPER_MAX) * 0.125 * (1.0 / (DAC_STEPPER_SENSE)); } - int16_t dac_current_get_percent(AxisEnum axis) { return mcp4728_getDrvPct(dac_order[axis]); } - void dac_current_set_percents(const int8_t pct[XYZE]) { + uint8_t dac_current_get_percent(AxisEnum axis) { return mcp4728_getDrvPct(dac_order[axis]); } + void dac_current_set_percents(const uint8_t pct[XYZE]) { LOOP_XYZE(i) dac_channel_pct[i] = pct[dac_order[i]]; mcp4728_setDrvPct(dac_channel_pct); } diff --git a/Marlin/stepper_dac.h b/Marlin/stepper_dac.h index ab338a2712..5880350405 100644 --- a/Marlin/stepper_dac.h +++ b/Marlin/stepper_dac.h @@ -51,7 +51,7 @@ void dac_current_percent(uint8_t channel, float val); void dac_current_raw(uint8_t channel, uint16_t val); void dac_print_values(); void dac_commit_eeprom(); -int16_t dac_current_get_percent(AxisEnum axis); -void dac_current_set_percents(int16_t pct[XYZE]); +uint8_t dac_current_get_percent(AxisEnum axis); +void dac_current_set_percents(const uint8_t pct[XYZE]); #endif // STEPPER_DAC_H diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index 749274486f..847ad80a6d 100644 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -92,7 +92,7 @@ uint16_t max_display_update_time = 0; #if ENABLED(DAC_STEPPER_CURRENT) #include "stepper_dac.h" //was dac_mcp4728.h MarlinMain uses stepper dac for the m-codes - int16_t driverPercent[XYZE]; + uint8_t driverPercent[XYZE]; #endif #if ENABLED(ULTIPANEL) @@ -185,6 +185,7 @@ uint16_t max_display_update_time = 0; typedef void _name##_void DECLARE_MENU_EDIT_TYPE(int, int3); + DECLARE_MENU_EDIT_TYPE(uint8_t, int8); DECLARE_MENU_EDIT_TYPE(float, float3); DECLARE_MENU_EDIT_TYPE(float, float32); DECLARE_MENU_EDIT_TYPE(float, float43); @@ -1253,10 +1254,10 @@ void kill_screen(const char* lcd_msg) { dac_driver_getValues(); START_MENU(); MENU_BACK(MSG_CONTROL); - MENU_ITEM_EDIT_CALLBACK(int3, MSG_X " " MSG_DAC_PERCENT, &driverPercent[X_AXIS], 0, 100, dac_driver_commit); - MENU_ITEM_EDIT_CALLBACK(int3, MSG_Y " " MSG_DAC_PERCENT, &driverPercent[Y_AXIS], 0, 100, dac_driver_commit); - MENU_ITEM_EDIT_CALLBACK(int3, MSG_Z " " MSG_DAC_PERCENT, &driverPercent[Z_AXIS], 0, 100, dac_driver_commit); - MENU_ITEM_EDIT_CALLBACK(int3, MSG_E " " MSG_DAC_PERCENT, &driverPercent[E_AXIS], 0, 100, dac_driver_commit); + MENU_ITEM_EDIT_CALLBACK(int8, MSG_X " " MSG_DAC_PERCENT, &driverPercent[X_AXIS], 0, 100, dac_driver_commit); + MENU_ITEM_EDIT_CALLBACK(int8, MSG_Y " " MSG_DAC_PERCENT, &driverPercent[Y_AXIS], 0, 100, dac_driver_commit); + MENU_ITEM_EDIT_CALLBACK(int8, MSG_Z " " MSG_DAC_PERCENT, &driverPercent[Z_AXIS], 0, 100, dac_driver_commit); + MENU_ITEM_EDIT_CALLBACK(int8, MSG_E " " MSG_DAC_PERCENT, &driverPercent[E_AXIS], 0, 100, dac_driver_commit); MENU_ITEM(function, MSG_DAC_EEPROM_WRITE, dac_driver_eeprom_write); END_MENU(); } @@ -3932,6 +3933,7 @@ void kill_screen(const char* lcd_msg) { typedef void _name DEFINE_MENU_EDIT_TYPE(int, int3, itostr3, 1); + DEFINE_MENU_EDIT_TYPE(uint8_t, int8, i8tostr3, 1); DEFINE_MENU_EDIT_TYPE(float, float3, ftostr3, 1.0); DEFINE_MENU_EDIT_TYPE(float, float32, ftostr32, 100.0); DEFINE_MENU_EDIT_TYPE(float, float43, ftostr43sign, 1000.0); diff --git a/Marlin/ultralcd_impl_DOGM.h b/Marlin/ultralcd_impl_DOGM.h index 295e276760..6f4ea34e6c 100644 --- a/Marlin/ultralcd_impl_DOGM.h +++ b/Marlin/ultralcd_impl_DOGM.h @@ -848,6 +848,7 @@ static void lcd_implementation_status_screen() { typedef void _name##_void DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(int, int3, itostr3); + DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(uint8_t, int8, i8tostr3); DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(float, float3, ftostr3); DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(float, float32, ftostr32); DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(float, float43, ftostr43sign); diff --git a/Marlin/ultralcd_impl_HD44780.h b/Marlin/ultralcd_impl_HD44780.h index 0521cb2f25..65ad28165e 100644 --- a/Marlin/ultralcd_impl_HD44780.h +++ b/Marlin/ultralcd_impl_HD44780.h @@ -959,6 +959,7 @@ static void lcd_implementation_status_screen() { typedef void _name##_void DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(int, int3, itostr3); + DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(uint8_t, int8, i8tostr3); DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(float, float3, ftostr3); DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(float, float32, ftostr32); DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(float, float43, ftostr43sign); diff --git a/Marlin/utility.cpp b/Marlin/utility.cpp index ee1bef1c99..0f59193553 100644 --- a/Marlin/utility.cpp +++ b/Marlin/utility.cpp @@ -56,15 +56,16 @@ void safe_delay(millis_t ms) { #define RJDIGIT(n, f) ((n) >= (f) ? DIGIMOD(n, f) : ' ') #define MINUSOR(n, alt) (n >= 0 ? (alt) : (n = -n, '-')) - // Convert unsigned int to string with 12 format - char* itostr2(const uint8_t &xx) { - conv[5] = DIGIMOD(xx, 10); + // Convert unsigned int to string 123 format + char* i8tostr3(const uint8_t xx) { + conv[4] = RJDIGIT(xx, 100); + conv[5] = RJDIGIT(xx, 10); conv[6] = DIGIMOD(xx, 1); - return &conv[5]; + return &conv[4]; } // Convert signed int to rj string with 123 or -12 format - char* itostr3(const int &x) { + char* itostr3(const int x) { int xx = x; conv[4] = MINUSOR(xx, RJDIGIT(xx, 100)); conv[5] = RJDIGIT(xx, 10); @@ -73,7 +74,7 @@ void safe_delay(millis_t ms) { } // Convert unsigned int to lj string with 123 format - char* itostr3left(const int &xx) { + char* itostr3left(const int xx) { char *str = &conv[6]; *str = DIGIMOD(xx, 1); if (xx >= 10) { @@ -85,7 +86,7 @@ void safe_delay(millis_t ms) { } // Convert signed int to rj string with 1234, _123, -123, _-12, or __-1 format - char *itostr4sign(const int &x) { + char *itostr4sign(const int x) { const bool neg = x < 0; const int xx = neg ? -x : x; if (x >= 1000) { diff --git a/Marlin/utility.h b/Marlin/utility.h index 779b788c7f..f88e6943af 100644 --- a/Marlin/utility.h +++ b/Marlin/utility.h @@ -31,17 +31,17 @@ void safe_delay(millis_t ms); #if ENABLED(ULTRA_LCD) - // Convert unsigned int to string with 12 format - char* itostr2(const uint8_t &x); + // Convert uint8_t to string with 123 format + char* i8tostr3(const uint8_t x); // Convert signed int to rj string with 123 or -12 format - char* itostr3(const int &x); + char* itostr3(const int x); // Convert unsigned int to lj string with 123 format - char* itostr3left(const int &xx); + char* itostr3left(const int xx); // Convert signed int to rj string with _123, -123, _-12, or __-1 format - char *itostr4sign(const int &x); + char *itostr4sign(const int x); // Convert unsigned float to string with 1.23 format char* ftostr12ns(const float &x); From 6dcf42f1a7bd0ff451476b10078da8e8c4498e05 Mon Sep 17 00:00:00 2001 From: Florian Heilmann Date: Tue, 20 Jun 2017 00:53:07 +0200 Subject: [PATCH 097/180] Add Z Fade Height to M420 output if it is enabled (#7042) * Add Z Fade Height to M420 Output Echo the z-fade height when M420 is called, if it is enabled. * Fix Whitespace * Fix Compiler complaint * Missing semi-colon --- Marlin/Marlin_main.cpp | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index b364e6f2fa..f895ee46c0 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -9032,6 +9032,15 @@ void quickstop_stepper() { SERIAL_ECHO_START(); SERIAL_ECHOLNPAIR("Bed Leveling ", new_status ? MSG_ON : MSG_OFF); + + #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) + SERIAL_ECHO_START(); + SERIAL_ECHOPGM("Fade Height "); + if (planner.z_fade_height > 0.0) + SERIAL_ECHOLN(planner.z_fade_height); + else + SERIAL_ECHOLNPGM(MSG_OFF); + #endif } #endif From 90f5f82926a38451bc243fa7e72839b9d0575426 Mon Sep 17 00:00:00 2001 From: Tannoo Date: Mon, 5 Jun 2017 22:03:22 -0600 Subject: [PATCH 098/180] Step-by-Step Menu addition --- Marlin/language_en.h | 3 +++ Marlin/ultralcd.cpp | 37 +++++++++++++++++++++++++++++++++++++ 2 files changed, 40 insertions(+) diff --git a/Marlin/language_en.h b/Marlin/language_en.h index 17d7e77d20..e18812f7c4 100644 --- a/Marlin/language_en.h +++ b/Marlin/language_en.h @@ -334,6 +334,9 @@ #ifndef MSG_UBL_Z_OFFSET_STOPPED #define MSG_UBL_Z_OFFSET_STOPPED _UxGT("Z-Offset Stopped") #endif +#ifndef MSG_UBL_STEP_BY_STEP_MENU + #define MSG_UBL_STEP_BY_STEP_MENU _UxGT("Step-By-Step UBL") +#endif #ifndef MSG_MOVING #define MSG_MOVING _UxGT("Moving...") diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index fe90b3734b..b5283f821f 100644 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -2302,6 +2302,22 @@ void kill_screen(const char* lcd_msg) { END_MENU(); } + /** + * UBL Step-By-Step submenu + */ + void _lcd_ubl_step_by_step() { + START_MENU(); + MENU_BACK(MSG_UBL_LEVEL_BED); + MENU_ITEM(gcode, "1 " MSG_UBL_BUILD_COLD_MESH, PSTR("G28\nG29 P1")); + MENU_ITEM(function, "2 " MSG_UBL_SMART_FILLIN, _lcd_ubl_smart_fillin_cmd); + MENU_ITEM(submenu, "3 " MSG_UBL_VALIDATE_MESH_MENU, _lcd_ubl_validate_mesh); + MENU_ITEM(gcode, "4 " MSG_UBL_FINE_TUNE_ALL, PSTR("G29 P4 R999 T")); + MENU_ITEM(submenu, "5 " MSG_UBL_VALIDATE_MESH_MENU, _lcd_ubl_validate_mesh); + MENU_ITEM(gcode, "6 " MSG_UBL_FINE_TUNE_ALL, PSTR("G29 P4 R999 T")); + MENU_ITEM(function, "7 " MSG_UBL_SAVE_MESH, _lcd_ubl_save_mesh_cmd); + END_MENU(); + } + /** * UBL System submenu * @@ -2310,6 +2326,26 @@ void kill_screen(const char* lcd_msg) { * - Manually Build Mesh * - Activate UBL * - Deactivate UBL + * - Step-By-Step UBL + * 1 Build Cold Mesh + * 2 Smart Fill-in + * - 3 Validate Mesh + * PLA Mesh Validation + * ABS Mesh Validation + * - Custom Mesh Validation + * Hotend Temp: + * Bed Temp: + * Validate Mesh + * 4 Fine Tune All + * - 5 Validate Mesh + * PLA Mesh Validation + * ABS Mesh Validation + * - Custom Mesh Validation + * Hotend Temp: + * Bed Temp: + * Validate Mesh + * 6 Fine Tune All + * 7 Save Bed Mesh * - Mesh Storage * Memory Slot: * Load Bed Mesh @@ -2367,6 +2403,7 @@ void kill_screen(const char* lcd_msg) { 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(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); From 499bb85a9560a0009a4f32b603712f61a926b284 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 19 Jun 2017 21:37:21 -0500 Subject: [PATCH 099/180] Clean up, put ubl menu itemization closer at hand --- Marlin/ultralcd.cpp | 177 +++++++++++++++++++++++--------------------- 1 file changed, 94 insertions(+), 83 deletions(-) diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index b5283f821f..4adca82cca 100644 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -1754,15 +1754,16 @@ void kill_screen(const char* lcd_msg) { /** * Step 1: Bed Level entry-point - * - Cancel - * - 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) - * - Load Settings (Req: EEPROM_SETTINGS) - * - Save Settings (Req: EEPROM_SETTINGS) + * + * << 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) + * Load Settings (Req: EEPROM_SETTINGS) + * Save Settings (Req: EEPROM_SETTINGS) */ void lcd_bed_leveling() { START_MENU(); @@ -1833,6 +1834,11 @@ void kill_screen(const char* lcd_msg) { /** * UBL Custom Mesh submenu + * + * << Build Mesh + * Hotend Temp: --- + * Bed Temp: --- + * Build Custom Mesh */ void _lcd_ubl_custom_mesh() { START_MENU(); @@ -1858,6 +1864,11 @@ void kill_screen(const char* lcd_msg) { /** * UBL Adjust Mesh Height submenu + * + * << Edit Mesh + * Height Amount: --- + * Adjust Mesh Height + * << Info Screen */ void _lcd_ubl_height_adjust_menu() { START_MENU(); @@ -1870,6 +1881,12 @@ void kill_screen(const char* lcd_msg) { /** * UBL Edit Mesh submenu + * + * << UBL Tools + * Fine Tune All + * Fine Tune Closest + * - Adjust Mesh Height >> + * << Info Screen */ void _lcd_ubl_edit_mesh() { START_MENU(); @@ -1899,6 +1916,12 @@ void kill_screen(const char* lcd_msg) { /** * UBL Validate Mesh submenu + * + * << UBL Tools + * PLA Mesh Validation + * ABS Mesh Validation + * Validate Custom Mesh + * << Info Screen */ void _lcd_ubl_validate_mesh() { START_MENU(); @@ -1926,6 +1949,10 @@ void kill_screen(const char* lcd_msg) { /** * UBL Grid Leveling submenu + * + * << UBL Tools + * Side points: --- + * Level Mesh */ void _lcd_ubl_grid_level() { START_MENU(); @@ -1937,6 +1964,11 @@ void kill_screen(const char* lcd_msg) { /** * UBL Mesh Leveling submenu + * + * << UBL Tools + * 3-Point Mesh Leveling + * - Grid Mesh Leveling >> + * << Info Screen */ void _lcd_ubl_mesh_leveling() { START_MENU(); @@ -1967,6 +1999,13 @@ void kill_screen(const char* lcd_msg) { /** * UBL Fill-in Mesh submenu + * + * << Build Mesh + * Fill-in Amount: --- + * Fill-in Mesh + * Smart Fill-in + * Manual Fill-in + * << Info Screen */ void _lcd_ubl_fillin_menu() { START_MENU(); @@ -1986,6 +2025,17 @@ void kill_screen(const char* lcd_msg) { /** * UBL Build Mesh submenu + * + * << UBL Tools + * Build PLA Mesh + * Build ABS Mesh + * - Build Custom Mesh >> + * Build Cold Mesh + * - Fill-in Mesh >> + * Continue Bed Mesh + * Invalidate All + * Invalidate Closest + * << Info Screen */ void _lcd_ubl_build_mesh() { START_MENU(); @@ -2051,6 +2101,11 @@ void kill_screen(const char* lcd_msg) { /** * UBL Mesh Storage submenu + * + * << Unified Bed Leveling + * Memory Slot: --- + * Load Bed Mesh + * Save Bed Mesh */ void _lcd_ubl_storage_mesh() { START_MENU(); @@ -2278,6 +2333,12 @@ void kill_screen(const char* lcd_msg) { /** * UBL Output map submenu + * + * << Unified Bed Leveling + * Output for Host + * Output for CSV + * Off Printer Backup + * Output Mesh Map */ void _lcd_ubl_output_map() { START_MENU(); @@ -2291,6 +2352,12 @@ void kill_screen(const char* lcd_msg) { /** * UBL Tools submenu + * + * << Unified Bed Leveling + * - Build Mesh >> + * - Validate Mesh >> + * - Edit Mesh >> + * - Mesh Leveling >> */ void _lcd_ubl_tools_menu() { START_MENU(); @@ -2304,6 +2371,15 @@ void kill_screen(const char* lcd_msg) { /** * UBL Step-By-Step submenu + * + * << Unified Bed Leveling + * 1 Build Cold Mesh + * 2 Smart Fill-in + * - 3 Validate Mesh >> + * 4 Fine Tune All + * - 5 Validate Mesh >> + * 6 Fine Tune All + * 7 Save Bed Mesh */ void _lcd_ubl_step_by_step() { START_MENU(); @@ -2321,80 +2397,15 @@ void kill_screen(const char* lcd_msg) { /** * UBL System submenu * - * Prepare - * - Unified Bed Leveling - * - Manually Build Mesh - * - Activate UBL - * - Deactivate UBL - * - Step-By-Step UBL - * 1 Build Cold Mesh - * 2 Smart Fill-in - * - 3 Validate Mesh - * PLA Mesh Validation - * ABS Mesh Validation - * - Custom Mesh Validation - * Hotend Temp: - * Bed Temp: - * Validate Mesh - * 4 Fine Tune All - * - 5 Validate Mesh - * PLA Mesh Validation - * ABS Mesh Validation - * - Custom Mesh Validation - * Hotend Temp: - * Bed Temp: - * Validate Mesh - * 6 Fine Tune All - * 7 Save Bed Mesh - * - Mesh Storage - * Memory Slot: - * Load Bed Mesh - * Save Bed Mesh - * - Output Map - * Topography to Host - * CSV for Spreadsheet - * Mesh Output Backup - * Output to LCD Grid - * - UBL Tools - * - Build Mesh - * Build PLA Mesh - * Build ABS Mesh - * - Build Custom Mesh - * Hotend Temp: - * Bed Temp: - * Build Custom Mesh - * Info Screen - * - Build Cold Mesh - * - Fill-in Mesh - * Fill-in Mesh - * Smart Fill-in - * Manual Fill-in - * Info Screen - * Continue Bed Mesh - * Invalidate All - * Invalidate Closest - * - Validate Mesh - * PLA Mesh Validation - * ABS Mesh Validation - * - Custom Mesh Validation - * Hotend Temp: - * Bed Temp: - * Validate Mesh - * Info Screen - * - Edit Mesh - * Fine Tune All - * Fine Tune Closest - * - Adjust Mesh Height - * Height Amount: - * Adjust Mesh Height - * Info Screen - * - Mesh Leveling - * 3-Point Mesh Leveling - * - Grid Mesh Leveling - * Side points: - * Level Mesh - * Info Screen - * - Output UBL Info + * << Prepare + * - Manually Build Mesh >> + * - Activate UBL >> + * - Deactivate UBL >> + * - Step-By-Step UBL >> + * - Mesh Storage >> + * - Output Map >> + * - UBL Tools >> + * - Output UBL Info >> */ void _lcd_ubl_level_bed() { From 725d9d9a56d9cfdf720a739eae56fb7c38f7696e Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 19 Jun 2017 21:53:06 -0500 Subject: [PATCH 100/180] Fix and improve LCD value editing display MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit - Fix: When "100.0" changes to "99.0" the LCD shows "199.0" - Use 2 rows if needed on character LCD, (allowing longer labels… Germany, et. al.) - Known issue: A certain length label combined with a certain value drawing function could, for example, display 99.0 on 1 line, but 100.0 on two lines. Workaround would be to pass a nominal value size argument. --- Marlin/ultralcd_impl_DOGM.h | 17 +++++++++++------ Marlin/ultralcd_impl_HD44780.h | 4 +++- 2 files changed, 14 insertions(+), 7 deletions(-) diff --git a/Marlin/ultralcd_impl_DOGM.h b/Marlin/ultralcd_impl_DOGM.h index 5ffe110201..b7a0002299 100644 --- a/Marlin/ultralcd_impl_DOGM.h +++ b/Marlin/ultralcd_impl_DOGM.h @@ -871,7 +871,7 @@ static void lcd_implementation_status_screen() { #if ENABLED(USE_BIG_EDIT_FONT) uint8_t lcd_width, char_width; if (labellen <= LCD_WIDTH_EDIT - 1) { - if (labellen >= LCD_WIDTH_EDIT - vallen) rows = 2; + if (labellen + vallen + 2 >= LCD_WIDTH_EDIT) rows = 2; lcd_width = LCD_WIDTH_EDIT + 1; char_width = DOG_CHAR_WIDTH_EDIT; lcd_setFont(FONT_MENU_EDIT); @@ -890,16 +890,21 @@ static void lcd_implementation_status_screen() { const uint8_t segmentHeight = u8g.getHeight() / (rows + 1); // 1 / (rows+1) = 1/2 or 1/3 uint8_t baseline = segmentHeight + (DOG_CHAR_HEIGHT_EDIT + 1) / 2; - if (PAGE_CONTAINS(baseline + 1 - (DOG_CHAR_HEIGHT_EDIT), baseline)) { + bool onpage = PAGE_CONTAINS(baseline + 1 - (DOG_CHAR_HEIGHT_EDIT), baseline); + if (onpage) { u8g.setPrintPos(0, baseline); lcd_printPGM(pstr); } if (value != NULL) { - baseline += (rows - 1) * segmentHeight; - if (PAGE_CONTAINS(baseline + 1 - (DOG_CHAR_HEIGHT_EDIT), baseline)) { - u8g.print(':'); - u8g.setPrintPos((lcd_width - 1 - vallen) * char_width, baseline); + u8g.print(':'); + if (rows == 2) { + baseline += segmentHeight; + onpage = PAGE_CONTAINS(baseline + 1 - (DOG_CHAR_HEIGHT_EDIT), baseline); + } + if (onpage) { + u8g.setPrintPos(((lcd_width - 1) - (vallen + 1)) * char_width, baseline); // Right-justified, leaving padded by spaces + u8g.print(' '); // overwrite char if value gets shorter lcd_print(value); } } diff --git a/Marlin/ultralcd_impl_HD44780.h b/Marlin/ultralcd_impl_HD44780.h index 65ad28165e..9ec03f0c89 100644 --- a/Marlin/ultralcd_impl_HD44780.h +++ b/Marlin/ultralcd_impl_HD44780.h @@ -978,7 +978,9 @@ static void lcd_implementation_status_screen() { lcd_printPGM(pstr); if (value != NULL) { lcd.print(':'); - lcd.setCursor(LCD_WIDTH - lcd_strlen(value), 1); + const uint8_t valrow = (lcd_strlen_P(pstr) + 1 + lcd_strlen(value) + 1) > (LCD_WIDTH - 2) ? 2 : 1; // Value on the next row if it won't fit + lcd.setCursor((LCD_WIDTH - 1) - (lcd_strlen(value) + 1), valrow); // Right-justified, padded by spaces + lcd.print(' '); // overwrite char if value gets shorter lcd_print(value); } } From 8a51e2960cd86b0087cfedd4e23f76ad03aadb67 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 19 Jun 2017 21:53:26 -0500 Subject: [PATCH 101/180] Improve the experience of editing steps_per_mm --- Marlin/ultralcd.cpp | 20 ++++++++++---------- 1 file changed, 10 insertions(+), 10 deletions(-) diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index 4adca82cca..dc90967029 100644 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -3311,25 +3311,25 @@ void kill_screen(const char* lcd_msg) { START_MENU(); MENU_BACK(MSG_MOTION); - MENU_ITEM_EDIT_CALLBACK(float62, MSG_XSTEPS, &planner.axis_steps_per_mm[X_AXIS], 5, 9999, _planner_refresh_positioning); - MENU_ITEM_EDIT_CALLBACK(float62, MSG_YSTEPS, &planner.axis_steps_per_mm[Y_AXIS], 5, 9999, _planner_refresh_positioning); - MENU_ITEM_EDIT_CALLBACK(float62, MSG_ZSTEPS, &planner.axis_steps_per_mm[Z_AXIS], 5, 9999, _planner_refresh_positioning); + MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float62, MSG_XSTEPS, &planner.axis_steps_per_mm[X_AXIS], 5, 9999, _planner_refresh_positioning); + MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float62, MSG_YSTEPS, &planner.axis_steps_per_mm[Y_AXIS], 5, 9999, _planner_refresh_positioning); + MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float62, MSG_ZSTEPS, &planner.axis_steps_per_mm[Z_AXIS], 5, 9999, _planner_refresh_positioning); #if ENABLED(DISTINCT_E_FACTORS) - MENU_ITEM_EDIT_CALLBACK(float62, MSG_ESTEPS, &planner.axis_steps_per_mm[E_AXIS + active_extruder], 5, 9999, _planner_refresh_positioning); - MENU_ITEM_EDIT_CALLBACK(float62, MSG_E1STEPS, &planner.axis_steps_per_mm[E_AXIS], 5, 9999, _planner_refresh_e0_positioning); - MENU_ITEM_EDIT_CALLBACK(float62, MSG_E2STEPS, &planner.axis_steps_per_mm[E_AXIS + 1], 5, 9999, _planner_refresh_e1_positioning); + MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float62, MSG_ESTEPS, &planner.axis_steps_per_mm[E_AXIS + active_extruder], 5, 9999, _planner_refresh_positioning); + MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float62, MSG_E1STEPS, &planner.axis_steps_per_mm[E_AXIS], 5, 9999, _planner_refresh_e0_positioning); + MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float62, MSG_E2STEPS, &planner.axis_steps_per_mm[E_AXIS + 1], 5, 9999, _planner_refresh_e1_positioning); #if E_STEPPERS > 2 - MENU_ITEM_EDIT_CALLBACK(float62, MSG_E3STEPS, &planner.axis_steps_per_mm[E_AXIS + 2], 5, 9999, _planner_refresh_e2_positioning); + MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float62, MSG_E3STEPS, &planner.axis_steps_per_mm[E_AXIS + 2], 5, 9999, _planner_refresh_e2_positioning); #if E_STEPPERS > 3 - MENU_ITEM_EDIT_CALLBACK(float62, MSG_E4STEPS, &planner.axis_steps_per_mm[E_AXIS + 3], 5, 9999, _planner_refresh_e3_positioning); + MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float62, MSG_E4STEPS, &planner.axis_steps_per_mm[E_AXIS + 3], 5, 9999, _planner_refresh_e3_positioning); #if E_STEPPERS > 4 - MENU_ITEM_EDIT_CALLBACK(float62, MSG_E5STEPS, &planner.axis_steps_per_mm[E_AXIS + 4], 5, 9999, _planner_refresh_e4_positioning); + MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float62, MSG_E5STEPS, &planner.axis_steps_per_mm[E_AXIS + 4], 5, 9999, _planner_refresh_e4_positioning); #endif // E_STEPPERS > 4 #endif // E_STEPPERS > 3 #endif // E_STEPPERS > 2 #else - MENU_ITEM_EDIT_CALLBACK(float62, MSG_ESTEPS, &planner.axis_steps_per_mm[E_AXIS], 5, 9999, _planner_refresh_positioning); + MENU_MULTIPLIER_ITEM_EDIT_CALLBACK(float62, MSG_ESTEPS, &planner.axis_steps_per_mm[E_AXIS], 5, 9999, _planner_refresh_positioning); #endif END_MENU(); From 6c45d0fd818d41c386237e1edd58107a2c7414a8 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 19 Jun 2017 22:39:23 -0500 Subject: [PATCH 102/180] Apply maths macros and type changes ahead of HAL --- Marlin/G26_Mesh_Validation_Tool.cpp | 2 +- Marlin/I2CPositionEncoder.cpp | 41 +++++++++--------- Marlin/I2CPositionEncoder.h | 2 +- Marlin/Marlin.h | 4 +- Marlin/Marlin_main.cpp | 62 ++++++++++++++-------------- Marlin/digipot_mcp4018.cpp | 2 +- Marlin/digipot_mcp4451.cpp | 2 +- Marlin/gcode.h | 2 +- Marlin/least_squares_fit.cpp | 2 +- Marlin/least_squares_fit.h | 8 ++-- Marlin/macros.h | 16 +++++++- Marlin/nozzle.cpp | 8 ++-- Marlin/nozzle.h | 4 +- Marlin/planner.cpp | 64 ++++++++++++++--------------- Marlin/planner.h | 2 +- Marlin/planner_bezier.cpp | 2 +- Marlin/qr_solve.cpp | 8 ++-- Marlin/serial.h | 2 +- Marlin/temperature.cpp | 2 +- Marlin/ubl_G29.cpp | 8 ++-- Marlin/ubl_motion.cpp | 10 ++--- Marlin/ultralcd.cpp | 58 +++++++++++++------------- Marlin/ultralcd.h | 6 +-- Marlin/ultralcd_impl_DOGM.h | 10 ++--- Marlin/ultralcd_impl_HD44780.h | 18 ++++---- Marlin/vector_3.cpp | 2 +- 26 files changed, 181 insertions(+), 166 deletions(-) diff --git a/Marlin/G26_Mesh_Validation_Tool.cpp b/Marlin/G26_Mesh_Validation_Tool.cpp index aa4b0fb39a..4b4f6e5c0f 100644 --- a/Marlin/G26_Mesh_Validation_Tool.cpp +++ b/Marlin/G26_Mesh_Validation_Tool.cpp @@ -600,7 +600,7 @@ // If the end point of the line is closer to the nozzle, flip the direction, // moving from the end to the start. On very small lines the optimization isn't worth it. - if (dist_end < dist_start && (SIZE_OF_INTERSECTION_CIRCLES) < abs(line_length)) { + if (dist_end < dist_start && (SIZE_OF_INTERSECTION_CIRCLES) < FABS(line_length)) { return print_line_from_here_to_there(ex, ey, ez, sx, sy, sz); } diff --git a/Marlin/I2CPositionEncoder.cpp b/Marlin/I2CPositionEncoder.cpp index 212e34f752..8f226d9635 100644 --- a/Marlin/I2CPositionEncoder.cpp +++ b/Marlin/I2CPositionEncoder.cpp @@ -126,16 +126,16 @@ } lastPosition = position; - unsigned long positionTime = millis(); + millis_t positionTime = millis(); //only do error correction if setup and enabled if (ec && ecMethod != I2CPE_ECM_NONE) { #if defined(I2CPE_EC_THRESH_PROPORTIONAL) + millis_t deltaTime = positionTime - lastPositionTime; unsigned long distance = abs(position - lastPosition); - unsigned long deltaTime = positionTime - lastPositionTime; unsigned long speed = distance / deltaTime; - float threshold = constrain((speed / 50), 1, 50) * ecThreshold; + float threshold = constrain(speed / 50, 1, 50) * ecThreshold; #else float threshold = get_error_correct_threshold(); #endif @@ -162,7 +162,7 @@ //SERIAL_ECHOLN(error); #if defined(I2CPE_ERR_THRESH_ABORT) - if (abs(error) > I2CPE_ERR_THRESH_ABORT * planner.axis_steps_per_mm[encoderAxis]) { + if (labs(error) > I2CPE_ERR_THRESH_ABORT * planner.axis_steps_per_mm[encoderAxis]) { //kill("Significant Error"); SERIAL_ECHOPGM("Axis error greater than set threshold, aborting!"); SERIAL_ECHOLN(error); @@ -174,29 +174,32 @@ if (errIdx == 0) { // in order to correct for "error" but avoid correcting for noise and non skips // it must be > threshold and have a difference average of < 10 and be < 2000 steps - if (abs(error) > threshold * planner.axis_steps_per_mm[encoderAxis] && - diffSum < 10*(I2CPE_ERR_ARRAY_SIZE-1) && abs(error) < 2000) { //Check for persistent error (skip) + if (labs(error) > threshold * planner.axis_steps_per_mm[encoderAxis] && + diffSum < 10 * (I2CPE_ERR_ARRAY_SIZE - 1) && labs(error) < 2000) { //Check for persistent error (skip) SERIAL_ECHO(axis_codes[encoderAxis]); - SERIAL_ECHOPAIR(" diffSum: ", diffSum/(I2CPE_ERR_ARRAY_SIZE-1)); + SERIAL_ECHOPAIR(" diffSum: ", diffSum / (I2CPE_ERR_ARRAY_SIZE - 1)); SERIAL_ECHOPAIR(" - err detected: ", error / planner.axis_steps_per_mm[encoderAxis]); SERIAL_ECHOLNPGM("mm; correcting!"); - thermalManager.babystepsTodo[encoderAxis] = -lround(error); + thermalManager.babystepsTodo[encoderAxis] = -LROUND(error); } } #else - if (abs(error) > threshold * planner.axis_steps_per_mm[encoderAxis]) { + if (labs(error) > threshold * planner.axis_steps_per_mm[encoderAxis]) { //SERIAL_ECHOLN(error); //SERIAL_ECHOLN(position); - thermalManager.babystepsTodo[encoderAxis] = -lround(error/2); + thermalManager.babystepsTodo[encoderAxis] = -LROUND(error/2); } #endif - if (abs(error) > (I2CPE_ERR_CNT_THRESH * planner.axis_steps_per_mm[encoderAxis]) && millis() - lastErrorCountTime > I2CPE_ERR_CNT_DEBOUNCE_MS) { - SERIAL_ECHOPAIR("Large error on ", axis_codes[encoderAxis]); - SERIAL_ECHOPAIR(" axis. error: ", (int)error); - SERIAL_ECHOLNPAIR("; diffSum: ", diffSum); - errorCount++; - lastErrorCountTime = millis(); + if (labs(error) > I2CPE_ERR_CNT_THRESH * planner.axis_steps_per_mm[encoderAxis]) { + const millis_t ms = millis(); + if (ELAPSED(ms, nextErrorCountTime)) { + SERIAL_ECHOPAIR("Large error on ", axis_codes[encoderAxis]); + SERIAL_ECHOPAIR(" axis. error: ", (int)error); + SERIAL_ECHOLNPAIR("; diffSum: ", diffSum); + errorCount++; + nextErrorCountTime = ms + I2CPE_ERR_CNT_DEBOUNCE_MS; + } } } @@ -255,7 +258,7 @@ actual = mm_from_count(position); error = actual - target; - if (abs(error) > 10000) error = 0; // ? + if (labs(error) > 10000) error = 0; // ? if (report) { SERIAL_ECHO(axis_codes[encoderAxis]); @@ -284,13 +287,13 @@ stepperTicksPerUnit = (type == I2CPE_ENC_TYPE_ROTARY) ? stepperTicks : planner.axis_steps_per_mm[encoderAxis]; //convert both 'ticks' into same units / base - encoderCountInStepperTicksScaled = lround((stepperTicksPerUnit * encoderTicks) / encoderTicksPerUnit); + encoderCountInStepperTicksScaled = LROUND((stepperTicksPerUnit * encoderTicks) / encoderTicksPerUnit); long target = stepper.position(encoderAxis), error = (encoderCountInStepperTicksScaled - target); //suppress discontinuities (might be caused by bad I2C readings...?) - bool suppressOutput = (abs(error - errorPrev) > 100); + bool suppressOutput = (labs(error - errorPrev) > 100); if (report) { SERIAL_ECHO(axis_codes[encoderAxis]); diff --git a/Marlin/I2CPositionEncoder.h b/Marlin/I2CPositionEncoder.h index a4b7eb3adb..fe0be390a5 100644 --- a/Marlin/I2CPositionEncoder.h +++ b/Marlin/I2CPositionEncoder.h @@ -136,7 +136,7 @@ position; unsigned long lastPositionTime = 0, - lastErrorCountTime = 0, + nextErrorCountTime = 0, lastErrorTime; //double positionMm; //calculate diff --git a/Marlin/Marlin.h b/Marlin/Marlin.h index 5a9b3191d5..6bb45698e6 100644 --- a/Marlin/Marlin.h +++ b/Marlin/Marlin.h @@ -210,7 +210,7 @@ inline void refresh_cmd_timeout() { previous_cmd_ms = millis(); } /** * Feedrate scaling and conversion */ -extern int feedrate_percentage; +extern int16_t feedrate_percentage; #define MMM_TO_MMS(MM_M) ((MM_M)/60.0) #define MMS_TO_MMM(MM_S) ((MM_S)*60.0) @@ -218,7 +218,7 @@ extern int feedrate_percentage; extern bool axis_relative_modes[]; extern bool volumetric_enabled; -extern int flow_percentage[EXTRUDERS]; // Extrusion factor for each extruder +extern int16_t flow_percentage[EXTRUDERS]; // Extrusion factor for each extruder extern float filament_size[EXTRUDERS]; // cross-sectional area of filament (in millimeters), typically around 1.75 or 2.85, 0 disables the volumetric calculations for the extruder. extern float volumetric_multiplier[EXTRUDERS]; // reciprocal of cross-sectional area of filament (in square millimeters), stored this way to reduce computational burden in planner extern bool axis_known_position[XYZ]; diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index f895ee46c0..7399e56dd2 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -421,7 +421,7 @@ FORCE_INLINE float homing_feedrate(const AxisEnum a) { return pgm_read_float(&ho float feedrate_mm_s = MMM_TO_MMS(1500.0); static float saved_feedrate_mm_s; -int feedrate_percentage = 100, saved_feedrate_percentage, +int16_t feedrate_percentage = 100, saved_feedrate_percentage, flow_percentage[EXTRUDERS] = ARRAY_BY_EXTRUDERS1(100); bool axis_relative_modes[] = AXIS_RELATIVE_MODES, @@ -2968,7 +2968,7 @@ static void homeaxis(const AxisEnum axis) { #if ENABLED(Z_DUAL_ENDSTOPS) if (axis == Z_AXIS) { - float adj = fabs(z_endstop_adj); + float adj = FABS(z_endstop_adj); bool lockZ1; if (axis_home_dir > 0) { adj = -adj; @@ -3293,7 +3293,7 @@ inline void gcode_G0_G1( const float e = clockwise ^ (r < 0) ? -1 : 1, // clockwise -1/1, counterclockwise 1/-1 dx = x2 - x1, dy = y2 - y1, // X and Y differences d = HYPOT(dx, dy), // Linear distance between the points - h = sqrt(sq(r) - sq(d * 0.5)), // Distance to the arc pivot-point + h = SQRT(sq(r) - sq(d * 0.5)), // Distance to the arc pivot-point mx = (x1 + x2) * 0.5, my = (y1 + y2) * 0.5, // Point between the two points sx = -dy / d, sy = dx / d, // Slope of the perpendicular bisector cx = mx + e * h * sx, cy = my + e * h * sy; // Pivot-point of the arc @@ -3448,7 +3448,7 @@ inline void gcode_G4() { const float mlx = max_length(X_AXIS), mly = max_length(Y_AXIS), mlratio = mlx > mly ? mly / mlx : mlx / mly, - fr_mm_s = min(homing_feedrate(X_AXIS), homing_feedrate(Y_AXIS)) * sqrt(sq(mlratio) + 1.0); + fr_mm_s = min(homing_feedrate(X_AXIS), homing_feedrate(Y_AXIS)) * SQRT(sq(mlratio) + 1.0); do_blocking_move_to_xy(1.5 * mlx * x_axis_home_dir, 1.5 * mly * home_dir(Y_AXIS), fr_mm_s); endstops.hit_on_purpose(); // clear endstop hit flags @@ -4605,8 +4605,8 @@ void home_all_axes() { gcode_G28(true); } const float xBase = xCount * xGridSpacing + left_probe_bed_position, yBase = yCount * yGridSpacing + front_probe_bed_position; - xProbe = floor(xBase + (xBase < 0 ? 0 : 0.5)); - yProbe = floor(yBase + (yBase < 0 ? 0 : 0.5)); + xProbe = FLOOR(xBase + (xBase < 0 ? 0 : 0.5)); + yProbe = FLOOR(yBase + (yBase < 0 ? 0 : 0.5)); #if ENABLED(AUTO_BED_LEVELING_LINEAR) indexIntoAB[xCount][yCount] = abl_probe_index; @@ -4710,8 +4710,8 @@ void home_all_axes() { gcode_G28(true); } float xBase = left_probe_bed_position + xGridSpacing * xCount, yBase = front_probe_bed_position + yGridSpacing * yCount; - xProbe = floor(xBase + (xBase < 0 ? 0 : 0.5)); - yProbe = floor(yBase + (yBase < 0 ? 0 : 0.5)); + xProbe = FLOOR(xBase + (xBase < 0 ? 0 : 0.5)); + yProbe = FLOOR(yBase + (yBase < 0 ? 0 : 0.5)); #if ENABLED(AUTO_BED_LEVELING_LINEAR) indexIntoAB[xCount][yCount] = ++abl_probe_index; // 0... @@ -5263,7 +5263,7 @@ void home_all_axes() { gcode_G28(true); } N++; } zero_std_dev_old = zero_std_dev; - zero_std_dev = round(sqrt(S2 / N) * 1000.0) / 1000.0 + 0.00001; + zero_std_dev = round(SQRT(S2 / N) * 1000.0) / 1000.0 + 0.00001; if (iterations == 1) home_offset[Z_AXIS] = zh_old; // reset height after 1st probe change @@ -5464,7 +5464,7 @@ void home_all_axes() { gcode_G28(true); } 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); + retract_mm[i] = FABS(dist) < G38_MINIMUM_MOVE ? 0 : home_bump_mm((AxisEnum)i) * (dist > 0 ? -1 : 1); } stepper.synchronize(); // wait until the machine is idle @@ -5528,7 +5528,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 (FABS(destination[i] - current_position[i]) >= G38_MINIMUM_MOVE) { if (!parser.seen('F')) feedrate_mm_s = homing_feedrate(i); // If G38.2 fails throw an error if (!G38_run_probe() && is_38_2) { @@ -6851,7 +6851,7 @@ inline void gcode_M42() { for (uint8_t j = 0; j <= n; j++) sum += sq(sample_set[j] - mean); - sigma = sqrt(sum / (n + 1)); + sigma = SQRT(sum / (n + 1)); if (verbose_level > 0) { if (verbose_level > 1) { SERIAL_PROTOCOL(n + 1); @@ -7266,7 +7266,7 @@ inline void gcode_M109() { #if TEMP_RESIDENCY_TIME > 0 - const float temp_diff = fabs(target_temp - temp); + const float temp_diff = FABS(target_temp - temp); if (!residency_start_ms) { // Start the TEMP_RESIDENCY_TIME timer when we reach target temp for the first time. @@ -7395,7 +7395,7 @@ inline void gcode_M109() { #if TEMP_BED_RESIDENCY_TIME > 0 - const float temp_diff = fabs(target_temp - temp); + const float temp_diff = FABS(target_temp - temp); if (!residency_start_ms) { // Start the TEMP_BED_RESIDENCY_TIME timer when we reach target temp for the first time. @@ -9252,7 +9252,7 @@ inline void gcode_M503() { #if ENABLED(BABYSTEP_ZPROBE_OFFSET) if (!no_babystep && leveling_is_active()) - thermalManager.babystep_axis(Z_AXIS, -lround(diff * planner.axis_steps_per_mm[Z_AXIS])); + thermalManager.babystep_axis(Z_AXIS, -LROUND(diff * planner.axis_steps_per_mm[Z_AXIS])); #else UNUSED(no_babystep); #endif @@ -11171,7 +11171,7 @@ void ok_to_send() { if (last_x != x) { last_x = x; ratio_x = x * ABL_BG_FACTOR(X_AXIS); - const float gx = constrain(floor(ratio_x), 0, ABL_BG_POINTS_X - FAR_EDGE_OR_BOX); + const float gx = constrain(FLOOR(ratio_x), 0, ABL_BG_POINTS_X - FAR_EDGE_OR_BOX); ratio_x -= gx; // Subtract whole to get the ratio within the grid box #if DISABLED(EXTRAPOLATE_BEYOND_GRID) @@ -11188,7 +11188,7 @@ void ok_to_send() { if (last_y != y) { last_y = y; ratio_y = y * ABL_BG_FACTOR(Y_AXIS); - const float gy = constrain(floor(ratio_y), 0, ABL_BG_POINTS_Y - FAR_EDGE_OR_BOX); + const float gy = constrain(FLOOR(ratio_y), 0, ABL_BG_POINTS_Y - FAR_EDGE_OR_BOX); ratio_y -= gy; #if DISABLED(EXTRAPOLATE_BEYOND_GRID) @@ -11221,7 +11221,7 @@ void ok_to_send() { /* static float last_offset = 0; - if (fabs(last_offset - offset) > 0.2) { + if (FABS(last_offset - offset) > 0.2) { SERIAL_ECHOPGM("Sudden Shift at "); SERIAL_ECHOPAIR("x=", x); SERIAL_ECHOPAIR(" / ", bilinear_grid_spacing[X_AXIS]); @@ -11290,7 +11290,7 @@ void ok_to_send() { #else - #define _SQRT(n) sqrt(n) + #define _SQRT(n) SQRT(n) #endif @@ -11364,7 +11364,7 @@ void ok_to_send() { float distance = delta[A_AXIS]; cartesian[Y_AXIS] = LOGICAL_Y_POSITION(DELTA_PRINTABLE_RADIUS); inverse_kinematics(cartesian); - return abs(distance - delta[A_AXIS]); + return FABS(distance - delta[A_AXIS]); } /** @@ -11397,7 +11397,7 @@ void ok_to_send() { float p12[3] = { delta_tower[B_AXIS][X_AXIS] - delta_tower[A_AXIS][X_AXIS], delta_tower[B_AXIS][Y_AXIS] - delta_tower[A_AXIS][Y_AXIS], z2 - z1 }; // Get the Magnitude of vector. - float d = sqrt( sq(p12[0]) + sq(p12[1]) + sq(p12[2]) ); + float d = SQRT( sq(p12[0]) + sq(p12[1]) + sq(p12[2]) ); // Create unit vector by dividing by magnitude. float ex[3] = { p12[0] / d, p12[1] / d, p12[2] / d }; @@ -11416,7 +11416,7 @@ void ok_to_send() { float ey[3] = { p13[0] - iex[0], p13[1] - iex[1], p13[2] - iex[2] }; // The magnitude of Y component - float j = sqrt( sq(ey[0]) + sq(ey[1]) + sq(ey[2]) ); + float j = SQRT( sq(ey[0]) + sq(ey[1]) + sq(ey[2]) ); // Convert to a unit vector ey[0] /= j; ey[1] /= j; ey[2] /= j; @@ -11433,7 +11433,7 @@ void ok_to_send() { // Plug them into the equations defined in Wikipedia for Xnew, Ynew and Znew float Xnew = (delta_diagonal_rod_2_tower[A_AXIS] - delta_diagonal_rod_2_tower[B_AXIS] + sq(d)) / (d * 2), Ynew = ((delta_diagonal_rod_2_tower[A_AXIS] - delta_diagonal_rod_2_tower[C_AXIS] + HYPOT2(i, j)) / 2 - i * Xnew) / j, - Znew = sqrt(delta_diagonal_rod_2_tower[A_AXIS] - HYPOT2(Xnew, Ynew)); + Znew = SQRT(delta_diagonal_rod_2_tower[A_AXIS] - HYPOT2(Xnew, Ynew)); // Start from the origin of the old coordinates and add vectors in the // old coords that represent the Xnew, Ynew and Znew to find the point @@ -11656,10 +11656,10 @@ void set_current_from_steppers_for_axis(const AxisEnum axis) { }; // Get the linear distance in XYZ - float cartesian_mm = sqrt(sq(difference[X_AXIS]) + sq(difference[Y_AXIS]) + sq(difference[Z_AXIS])); + float cartesian_mm = SQRT(sq(difference[X_AXIS]) + sq(difference[Y_AXIS]) + sq(difference[Z_AXIS])); // If the move is very short, check the E move distance - if (UNEAR_ZERO(cartesian_mm)) cartesian_mm = abs(difference[E_AXIS]); + if (UNEAR_ZERO(cartesian_mm)) cartesian_mm = FABS(difference[E_AXIS]); // No E move either? Game over. if (UNEAR_ZERO(cartesian_mm)) return true; @@ -11947,7 +11947,7 @@ void prepare_move_to_destination() { extruder_travel = logical[E_AXIS] - current_position[E_AXIS]; // CCW angle of rotation between position and target from the circle center. Only one atan2() trig computation required. - float angular_travel = atan2(r_X * rt_Y - r_Y * rt_X, r_X * rt_X + r_Y * rt_Y); + float angular_travel = ATAN2(r_X * rt_Y - r_Y * rt_X, r_X * rt_X + r_Y * rt_Y); if (angular_travel < 0) angular_travel += RADIANS(360); if (clockwise) angular_travel -= RADIANS(360); @@ -11955,10 +11955,10 @@ void prepare_move_to_destination() { if (angular_travel == 0 && current_position[X_AXIS] == logical[X_AXIS] && current_position[Y_AXIS] == logical[Y_AXIS]) angular_travel += RADIANS(360); - const float mm_of_travel = HYPOT(angular_travel * radius, fabs(linear_travel)); + const float mm_of_travel = HYPOT(angular_travel * radius, FABS(linear_travel)); if (mm_of_travel < 0.001) return; - uint16_t segments = floor(mm_of_travel / (MM_PER_ARC_SEGMENT)); + uint16_t segments = FLOOR(mm_of_travel / (MM_PER_ARC_SEGMENT)); if (segments == 0) segments = 1; /** @@ -12155,7 +12155,7 @@ void prepare_move_to_destination() { else C2 = (HYPOT2(sx, sy) - (L1_2 + L2_2)) / (2.0 * L1 * L2); - S2 = sqrt(1 - sq(C2)); + S2 = SQRT(1 - sq(C2)); // Unrotated Arm1 plus rotated Arm2 gives the distance from Center to End SK1 = L1 + L2 * C2; @@ -12164,10 +12164,10 @@ void prepare_move_to_destination() { SK2 = L2 * S2; // Angle of Arm1 is the difference between Center-to-End angle and the Center-to-Elbow - THETA = atan2(SK1, SK2) - atan2(sx, sy); + THETA = ATAN2(SK1, SK2) - ATAN2(sx, sy); // Angle of Arm2 - PSI = atan2(S2, C2); + PSI = ATAN2(S2, C2); delta[A_AXIS] = DEGREES(THETA); // theta is support arm angle delta[B_AXIS] = DEGREES(THETA + PSI); // equal to sub arm angle (inverted motor) diff --git a/Marlin/digipot_mcp4018.cpp b/Marlin/digipot_mcp4018.cpp index a13302b034..db8070a73e 100644 --- a/Marlin/digipot_mcp4018.cpp +++ b/Marlin/digipot_mcp4018.cpp @@ -44,7 +44,7 @@ #define DIGIPOT_A4988_MAX_CURRENT (DIGIPOT_A4988_Itripmax(DIGIPOT_A4988_Vrefmax) - 0.5) static byte current_to_wiper(const float current) { - return byte(ceil(float(DIGIPOT_A4988_FACTOR) * current)); + return byte(CEIL(float(DIGIPOT_A4988_FACTOR) * current)); } const uint8_t sda_pins[DIGIPOT_I2C_NUM_CHANNELS] = { diff --git a/Marlin/digipot_mcp4451.cpp b/Marlin/digipot_mcp4451.cpp index 6e94778cf2..d79915cc94 100644 --- a/Marlin/digipot_mcp4451.cpp +++ b/Marlin/digipot_mcp4451.cpp @@ -38,7 +38,7 @@ #endif static byte current_to_wiper(const float current) { - return byte(ceil(float((DIGIPOT_I2C_FACTOR * current)))); + return byte(CEIL(float((DIGIPOT_I2C_FACTOR * current)))); } static void i2c_send(const byte addr, const byte a, const byte b) { diff --git a/Marlin/gcode.h b/Marlin/gcode.h index 3001b8b2e0..1cd1cfabcf 100644 --- a/Marlin/gcode.h +++ b/Marlin/gcode.h @@ -213,7 +213,7 @@ public: linear_unit_factor = 1.0; break; } - volumetric_unit_factor = pow(linear_unit_factor, 3.0); + volumetric_unit_factor = POW(linear_unit_factor, 3.0); } inline static float axis_unit_factor(const AxisEnum axis) { diff --git a/Marlin/least_squares_fit.cpp b/Marlin/least_squares_fit.cpp index 9d1d84a2a8..42adc8fe68 100644 --- a/Marlin/least_squares_fit.cpp +++ b/Marlin/least_squares_fit.cpp @@ -59,7 +59,7 @@ int finish_incremental_LSF(struct linear_fit_data *lsf) { lsf->xzbar = lsf->xzbar / N - lsf->xbar * lsf->zbar; const float DD = lsf->x2bar * lsf->y2bar - sq(lsf->xybar); - if (fabs(DD) <= 1e-10 * (lsf->max_absx + lsf->max_absy)) + if (FABS(DD) <= 1e-10 * (lsf->max_absx + lsf->max_absy)) return 1; lsf->A = (lsf->yzbar * lsf->xybar - lsf->xzbar * lsf->y2bar) / DD; diff --git a/Marlin/least_squares_fit.h b/Marlin/least_squares_fit.h index a5da16a8a7..bdb4271597 100644 --- a/Marlin/least_squares_fit.h +++ b/Marlin/least_squares_fit.h @@ -65,8 +65,8 @@ void inline incremental_WLSF(struct linear_fit_data *lsf, const float &x, const lsf->xzbar += w * x * z; lsf->yzbar += w * y * z; lsf->N += w; - lsf->max_absx = max(fabs(w * x), lsf->max_absx); - lsf->max_absy = max(fabs(w * y), lsf->max_absy); + lsf->max_absx = max(FABS(w * x), lsf->max_absx); + lsf->max_absy = max(FABS(w * y), lsf->max_absy); } void inline incremental_LSF(struct linear_fit_data *lsf, const float &x, const float &y, const float &z) { @@ -79,8 +79,8 @@ void inline incremental_LSF(struct linear_fit_data *lsf, const float &x, const f lsf->xybar += x * y; lsf->xzbar += x * z; lsf->yzbar += y * z; - lsf->max_absx = max(fabs(x), lsf->max_absx); - lsf->max_absy = max(fabs(y), lsf->max_absy); + lsf->max_absx = max(FABS(x), lsf->max_absx); + lsf->max_absy = max(FABS(y), lsf->max_absy); lsf->N += 1.0; } diff --git a/Marlin/macros.h b/Marlin/macros.h index f1575cad12..3b79ba9b83 100644 --- a/Marlin/macros.h +++ b/Marlin/macros.h @@ -106,7 +106,6 @@ #define RADIANS(d) ((d)*M_PI/180.0) #define DEGREES(r) ((r)*180.0/M_PI) #define HYPOT2(x,y) (sq(x)+sq(y)) -#define HYPOT(x,y) sqrt(HYPOT2(x,y)) #define SIGN(a) ((a>0)-(a<0)) @@ -193,4 +192,17 @@ #define RECIPROCAL(x) (NEAR_ZERO(x) ? 0.0 : 1.0 / (x)) #define FIXFLOAT(f) (f + 0.00001) -#endif // __MACROS_H +// +// Maths macros that can be overridden by HAL +// +#define ATAN2(y, x) atan2(y, x) +#define FABS(x) fabs(x) +#define POW(x, y) pow(x, y) +#define SQRT(x) sqrt(x) +#define CEIL(x) ceil(x) +#define FLOOR(x) floor(x) +#define LROUND(x) lround(x) +#define FMOD(x, y) fmod(x, y) +#define HYPOT(x,y) SQRT(HYPOT2(x,y)) + +#endif //__MACROS_H diff --git a/Marlin/nozzle.cpp b/Marlin/nozzle.cpp index e5706e862a..eec8bfa39a 100644 --- a/Marlin/nozzle.cpp +++ b/Marlin/nozzle.cpp @@ -80,16 +80,16 @@ void Nozzle::zigzag( for (uint8_t j = 0; j < strokes; j++) { for (uint8_t i = 0; i < (objects << 1); i++) { - float const x = start.x + ( nozzle_clean_horizontal ? i * P : (A/P) * (P - fabs(fmod((i*P), (2*P)) - P)) ); - float const y = start.y + (!nozzle_clean_horizontal ? i * P : (A/P) * (P - fabs(fmod((i*P), (2*P)) - P)) ); + float const x = start.x + ( nozzle_clean_horizontal ? i * P : (A/P) * (P - FABS(FMOD((i*P), (2*P)) - P)) ); + float const y = start.y + (!nozzle_clean_horizontal ? i * P : (A/P) * (P - FABS(FMOD((i*P), (2*P)) - P)) ); do_blocking_move_to_xy(x, y); if (i == 0) do_blocking_move_to_z(start.z); } for (int i = (objects << 1); i > -1; i--) { - float const x = start.x + ( nozzle_clean_horizontal ? i * P : (A/P) * (P - fabs(fmod((i*P), (2*P)) - P)) ); - float const y = start.y + (!nozzle_clean_horizontal ? i * P : (A/P) * (P - fabs(fmod((i*P), (2*P)) - P)) ); + float const x = start.x + ( nozzle_clean_horizontal ? i * P : (A/P) * (P - FABS(FMOD((i*P), (2*P)) - P)) ); + float const y = start.y + (!nozzle_clean_horizontal ? i * P : (A/P) * (P - FABS(FMOD((i*P), (2*P)) - P)) ); do_blocking_move_to_xy(x, y); } diff --git a/Marlin/nozzle.h b/Marlin/nozzle.h index 39c007f632..2fbe98fb06 100644 --- a/Marlin/nozzle.h +++ b/Marlin/nozzle.h @@ -29,8 +29,8 @@ #if ENABLED(NOZZLE_CLEAN_FEATURE) constexpr float nozzle_clean_start_point[4] = NOZZLE_CLEAN_START_POINT, nozzle_clean_end_point[4] = NOZZLE_CLEAN_END_POINT, - nozzle_clean_length = fabs(nozzle_clean_start_point[X_AXIS] - nozzle_clean_end_point[X_AXIS]), //abs x size of wipe pad - nozzle_clean_height = fabs(nozzle_clean_start_point[Y_AXIS] - nozzle_clean_end_point[Y_AXIS]); //abs y size of wipe pad + nozzle_clean_length = FABS(nozzle_clean_start_point[X_AXIS] - nozzle_clean_end_point[X_AXIS]), //abs x size of wipe pad + nozzle_clean_height = FABS(nozzle_clean_start_point[Y_AXIS] - nozzle_clean_end_point[Y_AXIS]); //abs y size of wipe pad constexpr bool nozzle_clean_horizontal = nozzle_clean_length >= nozzle_clean_height; //whether to zig-zag horizontally or vertically #endif // NOZZLE_CLEAN_FEATURE diff --git a/Marlin/planner.cpp b/Marlin/planner.cpp index 537f334606..5897e4fe6a 100644 --- a/Marlin/planner.cpp +++ b/Marlin/planner.cpp @@ -178,23 +178,23 @@ void Planner::init() { * by the provided factors. */ void Planner::calculate_trapezoid_for_block(block_t* const block, const float &entry_factor, const float &exit_factor) { - uint32_t initial_rate = ceil(block->nominal_rate * entry_factor), - final_rate = ceil(block->nominal_rate * exit_factor); // (steps per second) + uint32_t initial_rate = CEIL(block->nominal_rate * entry_factor), + final_rate = CEIL(block->nominal_rate * exit_factor); // (steps per second) // Limit minimal step rate (Otherwise the timer will overflow.) NOLESS(initial_rate, MINIMAL_STEP_RATE); NOLESS(final_rate, MINIMAL_STEP_RATE); int32_t accel = block->acceleration_steps_per_s2, - accelerate_steps = ceil(estimate_acceleration_distance(initial_rate, block->nominal_rate, accel)), - decelerate_steps = floor(estimate_acceleration_distance(block->nominal_rate, final_rate, -accel)), + accelerate_steps = CEIL(estimate_acceleration_distance(initial_rate, block->nominal_rate, accel)), + decelerate_steps = FLOOR(estimate_acceleration_distance(block->nominal_rate, final_rate, -accel)), plateau_steps = block->step_event_count - accelerate_steps - decelerate_steps; // Is the Plateau of Nominal Rate smaller than nothing? That means no cruising, and we will // have to use intersection_distance() to calculate when to abort accel and start braking // in order to reach the final_rate exactly at the end of this block. if (plateau_steps < 0) { - accelerate_steps = ceil(intersection_distance(initial_rate, final_rate, accel, block->step_event_count)); + accelerate_steps = CEIL(intersection_distance(initial_rate, final_rate, accel, block->step_event_count)); NOLESS(accelerate_steps, 0); // Check limits due to numerical round-off accelerate_steps = min((uint32_t)accelerate_steps, block->step_event_count);//(We can cast here to unsigned, because the above line ensures that we are above zero) plateau_steps = 0; @@ -221,8 +221,8 @@ void Planner::calculate_trapezoid_for_block(block_t* const block, const float &e // This method will calculate the junction jerk as the euclidean distance between the nominal // velocities of the respective blocks. //inline float junction_jerk(block_t *before, block_t *after) { -// return sqrt( -// pow((before->speed_x-after->speed_x), 2)+pow((before->speed_y-after->speed_y), 2)); +// return SQRT( +// POW((before->speed_x-after->speed_x), 2)+POW((before->speed_y-after->speed_y), 2)); //} @@ -693,22 +693,22 @@ void Planner::_buffer_line(const float &a, const float &b, const float &c, const // Calculate target position in absolute steps //this should be done after the wait, because otherwise a M92 code within the gcode disrupts this calculation somehow const long target[XYZE] = { - lround(a * axis_steps_per_mm[X_AXIS]), - lround(b * axis_steps_per_mm[Y_AXIS]), - lround(c * axis_steps_per_mm[Z_AXIS]), - lround(e * axis_steps_per_mm[E_AXIS_N]) + LROUND(a * axis_steps_per_mm[X_AXIS]), + LROUND(b * axis_steps_per_mm[Y_AXIS]), + LROUND(c * axis_steps_per_mm[Z_AXIS]), + LROUND(e * axis_steps_per_mm[E_AXIS_N]) }; // When changing extruders recalculate steps corresponding to the E position #if ENABLED(DISTINCT_E_FACTORS) if (last_extruder != extruder && axis_steps_per_mm[E_AXIS_N] != axis_steps_per_mm[E_AXIS + last_extruder]) { - position[E_AXIS] = lround(position[E_AXIS] * axis_steps_per_mm[E_AXIS_N] * steps_to_mm[E_AXIS + last_extruder]); + position[E_AXIS] = LROUND(position[E_AXIS] * axis_steps_per_mm[E_AXIS_N] * steps_to_mm[E_AXIS + last_extruder]); last_extruder = extruder; } #endif #if ENABLED(LIN_ADVANCE) - const float mm_D_float = sqrt(sq(a - position_float[X_AXIS]) + sq(b - position_float[Y_AXIS])); + const float mm_D_float = SQRT(sq(a - position_float[X_AXIS]) + sq(b - position_float[Y_AXIS])); #endif const long da = target[X_AXIS] - position[X_AXIS], @@ -1036,10 +1036,10 @@ void Planner::_buffer_line(const float &a, const float &b, const float &c, const delta_mm[E_AXIS] = esteps_float * steps_to_mm[E_AXIS_N]; if (block->steps[X_AXIS] < MIN_STEPS_PER_SEGMENT && block->steps[Y_AXIS] < MIN_STEPS_PER_SEGMENT && block->steps[Z_AXIS] < MIN_STEPS_PER_SEGMENT) { - block->millimeters = fabs(delta_mm[E_AXIS]); + block->millimeters = FABS(delta_mm[E_AXIS]); } else { - block->millimeters = sqrt( + block->millimeters = SQRT( #if CORE_IS_XY sq(delta_mm[X_HEAD]) + sq(delta_mm[Y_HEAD]) + sq(delta_mm[Z_AXIS]) #elif CORE_IS_XZ @@ -1061,15 +1061,15 @@ void Planner::_buffer_line(const float &a, const float &b, const float &c, const // Slow down when the buffer starts to empty, rather than wait at the corner for a buffer refill #if ENABLED(SLOWDOWN) || ENABLED(ULTRA_LCD) || defined(XY_FREQUENCY_LIMIT) // Segment time im micro seconds - unsigned long segment_time = lround(1000000.0 / inverse_mm_s); + unsigned long segment_time = LROUND(1000000.0 / inverse_mm_s); #endif #if ENABLED(SLOWDOWN) if (WITHIN(moves_queued, 2, (BLOCK_BUFFER_SIZE) / 2 - 1)) { if (segment_time < min_segment_time) { // buffer is draining, add extra time. The amount of time added increases if the buffer is still emptied more. - inverse_mm_s = 1000000.0 / (segment_time + lround(2 * (min_segment_time - segment_time) / moves_queued)); + inverse_mm_s = 1000000.0 / (segment_time + LROUND(2 * (min_segment_time - segment_time) / moves_queued)); #if defined(XY_FREQUENCY_LIMIT) || ENABLED(ULTRA_LCD) - segment_time = lround(1000000.0 / inverse_mm_s); + segment_time = LROUND(1000000.0 / inverse_mm_s); #endif } } @@ -1082,7 +1082,7 @@ void Planner::_buffer_line(const float &a, const float &b, const float &c, const #endif block->nominal_speed = block->millimeters * inverse_mm_s; // (mm/sec) Always > 0 - block->nominal_rate = ceil(block->step_event_count * inverse_mm_s); // (step/sec) Always > 0 + block->nominal_rate = CEIL(block->step_event_count * inverse_mm_s); // (step/sec) Always > 0 #if ENABLED(FILAMENT_WIDTH_SENSOR) static float filwidth_e_count = 0, filwidth_delay_dist = 0; @@ -1121,7 +1121,7 @@ void Planner::_buffer_line(const float &a, const float &b, const float &c, const // Calculate and limit speed in mm/sec for each axis float current_speed[NUM_AXIS], speed_factor = 1.0; // factor <1 decreases speed LOOP_XYZE(i) { - const float cs = fabs(current_speed[i] = delta_mm[i] * inverse_mm_s); + const float cs = FABS(current_speed[i] = delta_mm[i] * inverse_mm_s); #if ENABLED(DISTINCT_E_FACTORS) if (i == E_AXIS) i += extruder; #endif @@ -1134,7 +1134,7 @@ void Planner::_buffer_line(const float &a, const float &b, const float &c, const // Check and limit the xy direction change frequency const unsigned char direction_change = block->direction_bits ^ old_direction_bits; old_direction_bits = block->direction_bits; - segment_time = lround((float)segment_time / speed_factor); + segment_time = LROUND((float)segment_time / speed_factor); long xs0 = axis_segment_time[X_AXIS][0], xs1 = axis_segment_time[X_AXIS][1], @@ -1178,7 +1178,7 @@ void Planner::_buffer_line(const float &a, const float &b, const float &c, const uint32_t accel; if (!block->steps[X_AXIS] && !block->steps[Y_AXIS] && !block->steps[Z_AXIS]) { // convert to: acceleration steps/sec^2 - accel = ceil(retract_acceleration * steps_per_mm); + accel = CEIL(retract_acceleration * steps_per_mm); } else { #define LIMIT_ACCEL_LONG(AXIS,INDX) do{ \ @@ -1196,7 +1196,7 @@ void Planner::_buffer_line(const float &a, const float &b, const float &c, const }while(0) // Start with print or travel acceleration - accel = ceil((esteps ? acceleration : travel_acceleration) * steps_per_mm); + accel = CEIL((esteps ? acceleration : travel_acceleration) * steps_per_mm); #if ENABLED(DISTINCT_E_FACTORS) #define ACCEL_IDX extruder @@ -1267,8 +1267,8 @@ void Planner::_buffer_line(const float &a, const float &b, const float &c, const // Skip and avoid divide by zero for straight junctions at 180 degrees. Limit to min() of nominal speeds. if (cos_theta > -0.95) { // Compute maximum junction velocity based on maximum acceleration and junction deviation - float sin_theta_d2 = sqrt(0.5 * (1.0 - cos_theta)); // Trig half angle identity. Always positive. - NOMORE(vmax_junction, sqrt(block->acceleration * junction_deviation * sin_theta_d2 / (1.0 - sin_theta_d2))); + float sin_theta_d2 = SQRT(0.5 * (1.0 - cos_theta)); // Trig half angle identity. Always positive. + NOMORE(vmax_junction, SQRT(block->acceleration * junction_deviation * sin_theta_d2 / (1.0 - sin_theta_d2))); } } } @@ -1286,7 +1286,7 @@ void Planner::_buffer_line(const float &a, const float &b, const float &c, const float safe_speed = block->nominal_speed; uint8_t limited = 0; LOOP_XYZE(i) { - const float jerk = fabs(current_speed[i]), maxj = max_jerk[i]; + const float jerk = FABS(current_speed[i]), maxj = max_jerk[i]; if (jerk > maxj) { if (limited) { const float mjerk = maxj * block->nominal_speed; @@ -1395,7 +1395,7 @@ void Planner::_buffer_line(const float &a, const float &b, const float &c, const && (uint32_t)esteps != block->step_event_count && de_float > 0.0; if (block->use_advance_lead) - block->abs_adv_steps_multiplier8 = lround( + block->abs_adv_steps_multiplier8 = LROUND( extruder_advance_k * (UNEAR_ZERO(advance_ed_ratio) ? de_float / mm_D_float : advance_ed_ratio) // Use the fixed ratio, if set * (block->nominal_speed / (float)block->nominal_rate) @@ -1458,10 +1458,10 @@ void Planner::_set_position_mm(const float &a, const float &b, const float &c, c #else #define _EINDEX E_AXIS #endif - long na = position[X_AXIS] = lround(a * axis_steps_per_mm[X_AXIS]), - nb = position[Y_AXIS] = lround(b * axis_steps_per_mm[Y_AXIS]), - nc = position[Z_AXIS] = lround(c * axis_steps_per_mm[Z_AXIS]), - ne = position[E_AXIS] = lround(e * axis_steps_per_mm[_EINDEX]); + long na = position[X_AXIS] = LROUND(a * axis_steps_per_mm[X_AXIS]), + nb = position[Y_AXIS] = LROUND(b * axis_steps_per_mm[Y_AXIS]), + nc = position[Z_AXIS] = LROUND(c * axis_steps_per_mm[Z_AXIS]), + ne = position[E_AXIS] = LROUND(e * axis_steps_per_mm[_EINDEX]); #if ENABLED(LIN_ADVANCE) position_float[X_AXIS] = a; position_float[Y_AXIS] = b; @@ -1514,7 +1514,7 @@ void Planner::set_position_mm(const AxisEnum axis, const float &v) { #else const uint8_t axis_index = axis; #endif - position[axis] = lround(v * axis_steps_per_mm[axis_index]); + position[axis] = LROUND(v * axis_steps_per_mm[axis_index]); #if ENABLED(LIN_ADVANCE) position_float[axis] = v; #endif diff --git a/Marlin/planner.h b/Marlin/planner.h index d389adc46d..90593816ee 100644 --- a/Marlin/planner.h +++ b/Marlin/planner.h @@ -454,7 +454,7 @@ class Planner { * 'distance'. */ static float max_allowable_speed(const float &accel, const float &target_velocity, const float &distance) { - return sqrt(sq(target_velocity) - 2 * accel * distance); + return SQRT(sq(target_velocity) - 2 * accel * distance); } static void calculate_trapezoid_for_block(block_t* const block, const float &entry_factor, const float &exit_factor); diff --git a/Marlin/planner_bezier.cpp b/Marlin/planner_bezier.cpp index d7dd960900..71697e04ae 100644 --- a/Marlin/planner_bezier.cpp +++ b/Marlin/planner_bezier.cpp @@ -64,7 +64,7 @@ inline static float eval_bezier(float a, float b, float c, float d, float t) { * We approximate Euclidean distance with the sum of the coordinates * offset (so-called "norm 1"), which is quicker to compute. */ -inline static float dist1(float x1, float y1, float x2, float y2) { return fabs(x1 - x2) + fabs(y1 - y2); } +inline static float dist1(float x1, float y1, float x2, float y2) { return FABS(x1 - x2) + FABS(y1 - y2); } /** * The algorithm for computing the step is loosely based on the one in Kig diff --git a/Marlin/qr_solve.cpp b/Marlin/qr_solve.cpp index 20bbb62994..7706c6f8cf 100644 --- a/Marlin/qr_solve.cpp +++ b/Marlin/qr_solve.cpp @@ -521,7 +521,7 @@ float dnrm2(int n, float x[], int incx) } ix += incx; } - norm = scale * sqrt(ssq); + norm = scale * SQRT(ssq); } return norm; } @@ -791,12 +791,12 @@ void dqrdc(float a[], int lda, int n, int p, float qraux[], int jpvt[], 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 = 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); + 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); + 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]; diff --git a/Marlin/serial.h b/Marlin/serial.h index 08a4c08c6d..8be90c06a5 100644 --- a/Marlin/serial.h +++ b/Marlin/serial.h @@ -40,7 +40,7 @@ extern const char echomagic[] PROGMEM; extern const char errormagic[] PROGMEM; -#define SERIAL_CHAR(x) (MYSERIAL.write(x)) +#define SERIAL_CHAR(x) ((void)MYSERIAL.write(x)) #define SERIAL_EOL() SERIAL_CHAR('\n') #define SERIAL_PROTOCOLCHAR(x) SERIAL_CHAR(x) diff --git a/Marlin/temperature.cpp b/Marlin/temperature.cpp index 5eb8f05b4a..99aec7f4da 100644 --- a/Marlin/temperature.cpp +++ b/Marlin/temperature.cpp @@ -749,7 +749,7 @@ void Temperature::manage_heater() { #if ENABLED(TEMP_SENSOR_1_AS_REDUNDANT) // Make sure measured temperatures are close together - if (fabs(current_temperature[0] - redundant_temperature) > MAX_REDUNDANT_TEMP_SENSOR_DIFF) + if (FABS(current_temperature[0] - redundant_temperature) > MAX_REDUNDANT_TEMP_SENSOR_DIFF) _temp_error(0, PSTR(MSG_REDUNDANCY), PSTR(MSG_ERR_REDUNDANT_TEMP)); #endif diff --git a/Marlin/ubl_G29.cpp b/Marlin/ubl_G29.cpp index 8e047defb5..3fe2240d76 100644 --- a/Marlin/ubl_G29.cpp +++ b/Marlin/ubl_G29.cpp @@ -498,7 +498,7 @@ if (parser.seen('B')) { g29_card_thickness = parser.has_value() ? parser.value_float() : measure_business_card_thickness(height); - if (fabs(g29_card_thickness) > 1.5) { + if (FABS(g29_card_thickness) > 1.5) { SERIAL_PROTOCOLLNPGM("?Error in Business Card measurement."); return; } @@ -562,7 +562,7 @@ // P3.13 1000X distance weighting, approaches simple average of nearest points const float weight_power = (cvf - 3.10) * 100.0, // 3.12345 -> 2.345 - weight_factor = weight_power ? pow(10.0, weight_power) : 0; + weight_factor = weight_power ? POW(10.0, weight_power) : 0; smart_fill_wlsf(weight_factor); } break; @@ -774,7 +774,7 @@ SERIAL_ECHO_F(mean, 6); SERIAL_EOL(); - const float sigma = sqrt(sum_of_diff_squared / (n + 1)); + const float sigma = SQRT(sum_of_diff_squared / (n + 1)); SERIAL_ECHOPGM("Standard Deviation: "); SERIAL_ECHO_F(sigma, 6); SERIAL_EOL(); @@ -1508,7 +1508,7 @@ do_blocking_move_to_z(Z_CLEARANCE_BETWEEN_PROBES); // Move the nozzle to where we are going to edit do_blocking_move_to_xy(LOGICAL_X_POSITION(rawx), LOGICAL_Y_POSITION(rawy)); - new_z = floor(new_z * 1000.0) * 0.001; // Chop off digits after the 1000ths place + new_z = FLOOR(new_z * 1000.0) * 0.001; // Chop off digits after the 1000ths place KEEPALIVE_STATE(PAUSED_FOR_USER); has_control_of_lcd_panel = true; diff --git a/Marlin/ubl_motion.cpp b/Marlin/ubl_motion.cpp index d0d27b60ed..6d39f9570b 100644 --- a/Marlin/ubl_motion.cpp +++ b/Marlin/ubl_motion.cpp @@ -492,15 +492,15 @@ #if ENABLED(DELTA) // apply delta inverse_kinematics - const float delta_A = rz + sqrt( delta_diagonal_rod_2_tower[A_AXIS] + const float delta_A = rz + SQRT( delta_diagonal_rod_2_tower[A_AXIS] - HYPOT2( delta_tower[A_AXIS][X_AXIS] - rx, delta_tower[A_AXIS][Y_AXIS] - ry )); - const float delta_B = rz + sqrt( delta_diagonal_rod_2_tower[B_AXIS] + const float delta_B = rz + SQRT( delta_diagonal_rod_2_tower[B_AXIS] - HYPOT2( delta_tower[B_AXIS][X_AXIS] - rx, delta_tower[B_AXIS][Y_AXIS] - ry )); - const float delta_C = rz + sqrt( delta_diagonal_rod_2_tower[C_AXIS] + const float delta_C = rz + SQRT( delta_diagonal_rod_2_tower[C_AXIS] - HYPOT2( delta_tower[C_AXIS][X_AXIS] - rx, delta_tower[C_AXIS][Y_AXIS] - ry )); @@ -516,8 +516,8 @@ inverse_kinematics(lseg); // this writes delta[ABC] from lseg[XYZ] // should move the feedrate scaling to scara inverse_kinematics - float adiff = abs(delta[A_AXIS] - scara_oldA), - bdiff = abs(delta[B_AXIS] - scara_oldB); + const float adiff = FABS(delta[A_AXIS] - scara_oldA), + bdiff = FABS(delta[B_AXIS] - scara_oldB); scara_oldA = delta[A_AXIS]; scara_oldB = delta[B_AXIS]; float s_feedrate = max(adiff, bdiff) * scara_feed_factor; diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index fe90b3734b..2749aafc11 100644 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -49,7 +49,7 @@ bool ubl_lcd_map_control = false; #endif -int lcd_preheat_hotend_temp[2], lcd_preheat_bed_temp[2], lcd_preheat_fan_speed[2]; +int16_t lcd_preheat_hotend_temp[2], lcd_preheat_bed_temp[2], lcd_preheat_fan_speed[2]; #if ENABLED(FILAMENT_LCD_DISPLAY) && ENABLED(SDSUPPORT) millis_t previous_lcd_status_ms = 0; @@ -184,7 +184,7 @@ uint16_t max_display_update_time = 0; void menu_action_setting_edit_callback_ ## _name(const char * const pstr, _type * const ptr, const _type minValue, const _type maxValue, const screenFunc_t callback, const bool live=false); \ typedef void _name##_void - DECLARE_MENU_EDIT_TYPE(int, int3); + DECLARE_MENU_EDIT_TYPE(int16_t, int3); DECLARE_MENU_EDIT_TYPE(uint8_t, int8); DECLARE_MENU_EDIT_TYPE(float, float3); DECLARE_MENU_EDIT_TYPE(float, float32); @@ -193,7 +193,7 @@ uint16_t max_display_update_time = 0; DECLARE_MENU_EDIT_TYPE(float, float51); DECLARE_MENU_EDIT_TYPE(float, float52); DECLARE_MENU_EDIT_TYPE(float, float62); - DECLARE_MENU_EDIT_TYPE(unsigned long, long5); + DECLARE_MENU_EDIT_TYPE(uint32_t, long5); void menu_action_setting_edit_bool(const char* pstr, bool* ptr); void menu_action_setting_edit_callback_bool(const char* pstr, bool* ptr, screenFunc_t callbackFunc); @@ -602,7 +602,7 @@ void lcd_status_screen() { } #if ENABLED(ULTIPANEL_FEEDMULTIPLY) - const int new_frm = feedrate_percentage + (int32_t)encoderPosition; + const int16_t new_frm = feedrate_percentage + (int32_t)encoderPosition; // Dead zone at 100% feedrate if ((feedrate_percentage < 100 && new_frm > 100) || (feedrate_percentage > 100 && new_frm < 100)) { feedrate_percentage = 100; @@ -966,7 +966,7 @@ void kill_screen(const char* lcd_msg) { if (lcd_clicked) { defer_return_to_status = false; return lcd_goto_previous_menu(); } ENCODER_DIRECTION_NORMAL(); if (encoderPosition) { - const int babystep_increment = (int32_t)encoderPosition * (BABYSTEP_MULTIPLICATOR); + const int16_t babystep_increment = (int32_t)encoderPosition * (BABYSTEP_MULTIPLICATOR); encoderPosition = 0; lcdDrawUpdate = LCDVIEW_REDRAW_NOW; thermalManager.babystep_axis(axis, babystep_increment); @@ -990,7 +990,7 @@ void kill_screen(const char* lcd_msg) { defer_return_to_status = true; ENCODER_DIRECTION_NORMAL(); if (encoderPosition) { - const int babystep_increment = (int32_t)encoderPosition * (BABYSTEP_MULTIPLICATOR); + const int16_t babystep_increment = (int32_t)encoderPosition * (BABYSTEP_MULTIPLICATOR); encoderPosition = 0; const float new_zoffset = zprobe_zoffset + planner.steps_to_mm[Z_AXIS] * babystep_increment; @@ -1021,7 +1021,7 @@ void kill_screen(const char* lcd_msg) { float mesh_edit_value, mesh_edit_accumulator; // We round mesh_edit_value to 2.5 decimal places. So we keep a // separate value that doesn't lose precision. - static int ubl_encoderPosition = 0; + static int16_t ubl_encoderPosition = 0; static void _lcd_mesh_fine_tune(const char* msg) { defer_return_to_status = true; @@ -1275,7 +1275,7 @@ void kill_screen(const char* lcd_msg) { * "Prepare" submenu items * */ - void _lcd_preheat(const int endnum, const int16_t temph, const int16_t tempb, const int16_t fan) { + void _lcd_preheat(const int16_t endnum, const int16_t temph, const int16_t tempb, const int16_t fan) { if (temph > 0) thermalManager.setTargetHotend(min(heater_maxtemp[endnum], temph), endnum); #if TEMP_SENSOR_BED != 0 if (tempb >= 0) thermalManager.setTargetBed(tempb); @@ -1806,7 +1806,7 @@ void kill_screen(const char* lcd_msg) { void _lcd_ubl_level_bed(); - static int ubl_storage_slot = 0, + static int16_t ubl_storage_slot = 0, custom_bed_temp = 50, custom_hotend_temp = 190, side_points = 3, @@ -2624,7 +2624,7 @@ void kill_screen(const char* lcd_msg) { // This assumes the center is 0,0 #if ENABLED(DELTA) if (axis != Z_AXIS) { - max = sqrt(sq((float)(DELTA_PRINTABLE_RADIUS)) - sq(current_position[Y_AXIS - axis])); + max = SQRT(sq((float)(DELTA_PRINTABLE_RADIUS)) - sq(current_position[Y_AXIS - axis])); min = -max; } #endif @@ -2872,14 +2872,14 @@ void kill_screen(const char* lcd_msg) { #if ENABLED(PID_AUTOTUNE_MENU) #if ENABLED(PIDTEMP) - int autotune_temp[HOTENDS] = ARRAY_BY_HOTENDS1(150); + int16_t autotune_temp[HOTENDS] = ARRAY_BY_HOTENDS1(150); #endif #if ENABLED(PIDTEMPBED) - int autotune_temp_bed = 70; + int16_t autotune_temp_bed = 70; #endif - void _lcd_autotune(int e) { + void _lcd_autotune(int16_t e) { char cmd[30]; sprintf_P(cmd, PSTR("M303 U1 E%i S%i"), e, #if HAS_PID_FOR_BOTH @@ -2899,14 +2899,14 @@ void kill_screen(const char* lcd_msg) { // Helpers for editing PID Ki & Kd values // grab the PID value out of the temp variable; scale it; then update the PID driver - void copy_and_scalePID_i(int e) { + void copy_and_scalePID_i(int16_t e) { #if DISABLED(PID_PARAMS_PER_HOTEND) || HOTENDS == 1 UNUSED(e); #endif PID_PARAM(Ki, e) = scalePID_i(raw_Ki); thermalManager.updatePID(); } - void copy_and_scalePID_d(int e) { + void copy_and_scalePID_d(int16_t e) { #if DISABLED(PID_PARAMS_PER_HOTEND) || HOTENDS == 1 UNUSED(e); #endif @@ -3475,7 +3475,7 @@ void kill_screen(const char* lcd_msg) { STATIC_ITEM(MSG_INFO_PRINT_LONGEST ": ", false, false); // Longest job time: STATIC_ITEM("", false, false, buffer); // 99y 364d 23h 59m 59s - sprintf_P(buffer, PSTR("%ld.%im"), long(stats.filamentUsed / 1000), int(stats.filamentUsed / 100) % 10); + sprintf_P(buffer, PSTR("%ld.%im"), long(stats.filamentUsed / 1000), int16_t(stats.filamentUsed / 100) % 10); STATIC_ITEM(MSG_INFO_PRINT_FILAMENT ": ", false, false); // Extruded total: STATIC_ITEM("", false, false, buffer); // 125m END_SCREEN(); @@ -3878,14 +3878,14 @@ void kill_screen(const char* lcd_msg) { * * The "DEFINE_MENU_EDIT_TYPE" macro generates the functions needed to edit a numerical value. * - * For example, DEFINE_MENU_EDIT_TYPE(int, int3, itostr3, 1) expands into these functions: + * For example, DEFINE_MENU_EDIT_TYPE(int16_t, int3, itostr3, 1) expands into these functions: * * bool _menu_edit_int3(); - * void menu_edit_int3(); // edit int (interactively) - * void menu_edit_callback_int3(); // edit int (interactively) with callback on completion - * void _menu_action_setting_edit_int3(const char * const pstr, int * const ptr, const int minValue, const int maxValue); - * void menu_action_setting_edit_int3(const char * const pstr, int * const ptr, const int minValue, const int maxValue); - * void menu_action_setting_edit_callback_int3(const char * const pstr, int * const ptr, const int minValue, const int maxValue, const screenFunc_t callback, const bool live); // edit int with callback + * void menu_edit_int3(); // edit int16_t (interactively) + * void menu_edit_callback_int3(); // edit int16_t (interactively) with callback on completion + * void _menu_action_setting_edit_int3(const char * const pstr, int16_t * const ptr, const int16_t minValue, const int16_t maxValue); + * void menu_action_setting_edit_int3(const char * const pstr, int16_t * const ptr, const int16_t minValue, const int16_t maxValue); + * void menu_action_setting_edit_callback_int3(const char * const pstr, int16_t * const ptr, const int16_t minValue, const int16_t maxValue, const screenFunc_t callback, const bool live); // edit int16_t with callback * * You can then use one of the menu macros to present the edit interface: * MENU_ITEM_EDIT(int3, MSG_SPEED, &feedrate_percentage, 10, 999) @@ -3936,7 +3936,7 @@ void kill_screen(const char* lcd_msg) { } \ typedef void _name - DEFINE_MENU_EDIT_TYPE(int, int3, itostr3, 1); + DEFINE_MENU_EDIT_TYPE(int16_t, int3, itostr3, 1); DEFINE_MENU_EDIT_TYPE(uint8_t, int8, i8tostr3, 1); DEFINE_MENU_EDIT_TYPE(float, float3, ftostr3, 1.0); DEFINE_MENU_EDIT_TYPE(float, float32, ftostr32, 100.0); @@ -3945,7 +3945,7 @@ void kill_screen(const char* lcd_msg) { DEFINE_MENU_EDIT_TYPE(float, float51, ftostr51sign, 10.0); DEFINE_MENU_EDIT_TYPE(float, float52, ftostr52sign, 100.0); DEFINE_MENU_EDIT_TYPE(float, float62, ftostr62rj, 100.0); - DEFINE_MENU_EDIT_TYPE(unsigned long, long5, ftostr5rj, 0.01); + DEFINE_MENU_EDIT_TYPE(uint32_t, long5, ftostr5rj, 0.01); /** * @@ -3953,7 +3953,7 @@ void kill_screen(const char* lcd_msg) { * */ #if ENABLED(REPRAPWORLD_KEYPAD) - void _reprapworld_keypad_move(AxisEnum axis, int dir) { + void _reprapworld_keypad_move(AxisEnum axis, int16_t dir) { move_menu_scale = REPRAPWORLD_KEYPAD_MOVE_STEP; encoderPosition = dir; switch (axis) { @@ -4112,8 +4112,8 @@ void lcd_init() { #endif } -int lcd_strlen(const char* s) { - int i = 0, j = 0; +int16_t lcd_strlen(const char* s) { + int16_t i = 0, j = 0; while (s[i]) { if (PRINTABLE(s[i])) j++; i++; @@ -4121,8 +4121,8 @@ int lcd_strlen(const char* s) { return j; } -int lcd_strlen_P(const char* s) { - int j = 0; +int16_t lcd_strlen_P(const char* s) { + int16_t j = 0; while (pgm_read_byte(s)) { if (PRINTABLE(pgm_read_byte(s))) j++; s++; diff --git a/Marlin/ultralcd.h b/Marlin/ultralcd.h index bda80cd48b..eb6d2e5bf5 100644 --- a/Marlin/ultralcd.h +++ b/Marlin/ultralcd.h @@ -30,10 +30,10 @@ #define BUTTON_EXISTS(BN) (defined(BTN_## BN) && BTN_## BN >= 0) #define BUTTON_PRESSED(BN) !READ(BTN_## BN) - extern int lcd_preheat_hotend_temp[2], lcd_preheat_bed_temp[2], lcd_preheat_fan_speed[2]; + extern int16_t lcd_preheat_hotend_temp[2], lcd_preheat_bed_temp[2], lcd_preheat_fan_speed[2]; - int lcd_strlen(const char* s); - int lcd_strlen_P(const char* s); + int16_t lcd_strlen(const char* s); + int16_t lcd_strlen_P(const char* s); void lcd_update(); void lcd_init(); bool lcd_hasstatus(); diff --git a/Marlin/ultralcd_impl_DOGM.h b/Marlin/ultralcd_impl_DOGM.h index 5ffe110201..a6c684a859 100644 --- a/Marlin/ultralcd_impl_DOGM.h +++ b/Marlin/ultralcd_impl_DOGM.h @@ -346,7 +346,7 @@ void lcd_implementation_clear() { } // Automatically cleared by Picture Loop // Status Screen // -FORCE_INLINE void _draw_centered_temp(const int temp, const uint8_t x, const uint8_t y) { +FORCE_INLINE void _draw_centered_temp(const int16_t temp, const uint8_t x, const uint8_t y) { const uint8_t degsize = 6 * (temp >= 100 ? 3 : temp >= 10 ? 2 : 1); // number's pixel width u8g.setPrintPos(x - (18 - degsize) / 2, y); // move left if shorter lcd_print(itostr3(temp)); @@ -484,7 +484,7 @@ static void lcd_implementation_status_screen() { #if HAS_FAN0 if (PAGE_CONTAINS(20, 27)) { // Fan - const int per = ((fanSpeeds[0] + 1) * 100) / 256; + const int16_t per = ((fanSpeeds[0] + 1) * 100) / 256; if (per) { u8g.setPrintPos(104, 27); lcd_print(itostr3(per)); @@ -533,7 +533,7 @@ static void lcd_implementation_status_screen() { if (PAGE_CONTAINS(50, 51 - (TALL_FONT_CORRECTION))) // 50-51 (or just 50) u8g.drawBox( PROGRESS_BAR_X + 1, 50, - (unsigned int)((PROGRESS_BAR_WIDTH - 2) * card.percentDone() * 0.01), 2 - (TALL_FONT_CORRECTION) + (uint16_t)((PROGRESS_BAR_WIDTH - 2) * card.percentDone() * 0.01), 2 - (TALL_FONT_CORRECTION) ); // @@ -847,7 +847,7 @@ static void lcd_implementation_status_screen() { } \ typedef void _name##_void - DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(int, int3, itostr3); + DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(int16_t, int3, itostr3); DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(uint8_t, int8, i8tostr3); DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(float, float3, ftostr3); DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(float, float32, ftostr32); @@ -856,7 +856,7 @@ static void lcd_implementation_status_screen() { DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(float, float51, ftostr51sign); DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(float, float52, ftostr52sign); DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(float, float62, ftostr62rj); - DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(unsigned long, long5, ftostr5rj); + DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(uint32_t, long5, ftostr5rj); #define lcd_implementation_drawmenu_setting_edit_bool(sel, row, pstr, pstr2, data) lcd_implementation_drawmenu_setting_edit_generic_P(sel, row, pstr, (*(data))?PSTR(MSG_ON):PSTR(MSG_OFF)) #define lcd_implementation_drawmenu_setting_edit_callback_bool(sel, row, pstr, pstr2, data, callback) lcd_implementation_drawmenu_setting_edit_generic_P(sel, row, pstr, (*(data))?PSTR(MSG_ON):PSTR(MSG_OFF)) diff --git a/Marlin/ultralcd_impl_HD44780.h b/Marlin/ultralcd_impl_HD44780.h index 65ad28165e..14fc95bca0 100644 --- a/Marlin/ultralcd_impl_HD44780.h +++ b/Marlin/ultralcd_impl_HD44780.h @@ -337,7 +337,7 @@ static void lcd_set_custom_characters( if (info_screen_charset != char_mode) { char_mode = info_screen_charset; if (info_screen_charset) { // Progress bar characters for info screen - for (int i = 3; i--;) createChar_P(LCD_STR_PROGRESS[i], progress[i]); + for (int16_t i = 3; i--;) createChar_P(LCD_STR_PROGRESS[i], progress[i]); } else { // Custom characters for submenus createChar_P(LCD_UPLEVEL_CHAR, uplevel); @@ -414,17 +414,17 @@ void lcd_printPGM_utf(const char *str, uint8_t n=LCD_WIDTH) { #if ENABLED(SHOW_BOOTSCREEN) - void lcd_erase_line(const int line) { + void lcd_erase_line(const int16_t line) { lcd.setCursor(0, line); for (uint8_t i = LCD_WIDTH + 1; --i;) lcd.print(' '); } // Scroll the PSTR 'text' in a 'len' wide field for 'time' milliseconds at position col,line - void lcd_scroll(const int col, const int line, const char* const text, const int len, const int time) { + void lcd_scroll(const int16_t col, const int16_t line, const char* const text, const int16_t len, const int16_t time) { char tmp[LCD_WIDTH + 1] = {0}; - int n = max(lcd_strlen_P(text) - len, 0); - for (int i = 0; i <= n; i++) { + int16_t n = max(lcd_strlen_P(text) - len, 0); + for (int16_t i = 0; i <= n; i++) { strncpy_P(tmp, text + i, min(len, LCD_WIDTH)); lcd.setCursor(col, line); lcd_print(tmp); @@ -433,7 +433,7 @@ void lcd_printPGM_utf(const char *str, uint8_t n=LCD_WIDTH) { } static void logo_lines(const char* const extra) { - int indent = (LCD_WIDTH - 8 - lcd_strlen_P(extra)) / 2; + int16_t indent = (LCD_WIDTH - 8 - lcd_strlen_P(extra)) / 2; lcd.setCursor(indent, 0); lcd.print('\x00'); lcd_printPGM(PSTR( "------" )); lcd.print('\x01'); lcd.setCursor(indent, 1); lcd_printPGM(PSTR("|Marlin|")); lcd_printPGM(extra); lcd.setCursor(indent, 2); lcd.print('\x02'); lcd_printPGM(PSTR( "------" )); lcd.print('\x03'); @@ -628,7 +628,7 @@ FORCE_INLINE void _draw_heater_status(const int8_t heater, const char prefix, co #if ENABLED(LCD_PROGRESS_BAR) inline void lcd_draw_progress_bar(const uint8_t percent) { - const int tix = (int)(percent * (LCD_WIDTH) * 3) / 100, + const int16_t tix = (int16_t)(percent * (LCD_WIDTH) * 3) / 100, cel = tix / 3, rem = tix % 3; uint8_t i = LCD_WIDTH; @@ -958,7 +958,7 @@ static void lcd_implementation_status_screen() { } \ typedef void _name##_void - DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(int, int3, itostr3); + DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(int16_t, int3, itostr3); DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(uint8_t, int8, i8tostr3); DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(float, float3, ftostr3); DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(float, float32, ftostr32); @@ -967,7 +967,7 @@ static void lcd_implementation_status_screen() { DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(float, float51, ftostr51sign); DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(float, float52, ftostr52sign); DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(float, float62, ftostr62rj); - DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(unsigned long, long5, ftostr5rj); + DEFINE_LCD_IMPLEMENTATION_DRAWMENU_SETTING_EDIT_TYPE(uint32_t, long5, ftostr5rj); #define lcd_implementation_drawmenu_setting_edit_bool(sel, row, pstr, pstr2, data) lcd_implementation_drawmenu_setting_edit_generic_P(sel, row, pstr, '>', (*(data))?PSTR(MSG_ON):PSTR(MSG_OFF)) #define lcd_implementation_drawmenu_setting_edit_callback_bool(sel, row, pstr, pstr2, data, callback) lcd_implementation_drawmenu_setting_edit_generic_P(sel, row, pstr, '>', (*(data))?PSTR(MSG_ON):PSTR(MSG_OFF)) diff --git a/Marlin/vector_3.cpp b/Marlin/vector_3.cpp index 7d8efb7e96..f9615bcf08 100644 --- a/Marlin/vector_3.cpp +++ b/Marlin/vector_3.cpp @@ -63,7 +63,7 @@ vector_3 vector_3::get_normal() { return normalized; } -float vector_3::get_length() { return sqrt(sq(x) + sq(y) + sq(z)); } +float vector_3::get_length() { return SQRT(sq(x) + sq(y) + sq(z)); } void vector_3::normalize() { const float inv_length = 1.0 / get_length(); From e907654d6aa3ae8c8b049d90b0bbd81d75575676 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 19 Jun 2017 23:08:38 -0500 Subject: [PATCH 103/180] Do two or three fewer test builds --- .travis.yml | 15 ++++----------- 1 file changed, 4 insertions(+), 11 deletions(-) diff --git a/.travis.yml b/.travis.yml index bc7c8c7705..76edc5f87c 100644 --- a/.travis.yml +++ b/.travis.yml @@ -300,12 +300,11 @@ script: ######## Example Configurations ############## # # BQ Hephestos 2 - - restore_configs - - use_example_configs Hephestos_2 - - build_marlin + #- restore_configs + #- use_example_configs Hephestos_2 + #- build_marlin # # Delta Config (generic) + ABL bilinear + PROBE_MANUALLY - - restore_configs - use_example_configs delta/generic - opt_enable REPRAP_DISCOUNT_SMART_CONTROLLER DELTA_CALIBRATION_MENU AUTO_BED_LEVELING_BILINEAR PROBE_MANUALLY - build_marlin @@ -327,17 +326,11 @@ script: #- use_example_configs makibox #- build_marlin # - # SCARA Config + # SCARA with TMC2130 # - use_example_configs SCARA - opt_enable AUTO_BED_LEVELING_BILINEAR FIX_MOUNTED_PROBE USE_ZMIN_PLUG EEPROM_SETTINGS EEPROM_CHITCHAT ULTIMAKERCONTROLLER - - build_marlin - # - # TMC2130 Config - # - - restore_configs - opt_enable_adv HAVE_TMC2130 X_IS_TMC2130 Y_IS_TMC2130 Z_IS_TMC2130 - - build_marlin - opt_enable_adv AUTOMATIC_CURRENT_CONTROL STEALTHCHOP HYBRID_THRESHOLD SENSORLESS_HOMING - build_marlin # From 37bc0fce6244fcfaa1aa81bc5c644e109fe68f0f Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 20 Jun 2017 00:09:59 -0500 Subject: [PATCH 104/180] Make G29 compatible with M206 Z and G92 Z Use the raw position for mesh measurement. Otherwise the `M206` and `M92` Z offsets will get canceled out by bed leveling. The downside is `G29` will not compensate for a poorly set small `M206` fudge value. To elaborate on this issue, imagine you are probing with a Z home offset of -0.1, meaning when Z homes, -0.1 is the current position, implying the ideal bed zero for the nozzle is 0.1mm higher than the Z endstop. Ordinarily when printing, Z would raise 0.1mm higher. What happens when we probe is that all points are measured with that -0.1 included. So when bed leveling is enabled the `M206 Z` offset gets exactly canceled out by the bed readings. --- 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 7399e56dd2..74426c00ac 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -2278,7 +2278,7 @@ static void clean_up_after_endstop_or_probe_move() { SERIAL_ECHOLNPAIR(" Discrepancy:", first_probe_z - current_position[Z_AXIS]); } #endif - return current_position[Z_AXIS] + zprobe_zoffset; + return RAW_CURRENT_POSITION(Z) + zprobe_zoffset; } /** From 5c59ee4e938665ac2cb26888b9515a52d15039b2 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 20 Jun 2017 00:10:52 -0500 Subject: [PATCH 105/180] Use current (raw) Z if omitted from G29 WXY or G29 WIJ. --- Marlin/Marlin_main.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 74426c00ac..f30291f2e2 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -4183,7 +4183,7 @@ void home_all_axes() { gcode_G28(true); } * W Write a mesh point. (Ignored during leveling.) * X Required X for mesh point * Y Required Y for mesh point - * Z Required Z for mesh point + * Z Z for mesh point. Otherwise, current Z minus Z probe offset. * * Without PROBE_MANUALLY: * @@ -4316,8 +4316,8 @@ void home_all_axes() { gcode_G28(true); } return; } - const float z = parser.seen('Z') && parser.has_value() ? parser.value_float() : NAN; - if (!isnan(z) || !WITHIN(z, -10, 10)) { + const float z = parser.seen('Z') && parser.has_value() ? parser.value_float() : RAW_CURRENT_POSITION(Z); + if (!WITHIN(z, -10, 10)) { SERIAL_ERROR_START(); SERIAL_ERRORLNPGM("Bad Z value"); return; From 417152072932fd17102afa5055a0aef0a3e44373 Mon Sep 17 00:00:00 2001 From: Silvio Didonna Date: Wed, 21 Jun 2017 11:08:39 +0200 Subject: [PATCH 106/180] added missing italian translation --- Marlin/language_it.h | 1 + 1 file changed, 1 insertion(+) diff --git a/Marlin/language_it.h b/Marlin/language_it.h index 45d1b58559..532650014e 100644 --- a/Marlin/language_it.h +++ b/Marlin/language_it.h @@ -135,6 +135,7 @@ #define MSG_UBL_SAVE_ERROR _UxGT("Err: Salvataggio UBL") #define MSG_UBL_RESTORE_ERROR _UxGT("Err: Ripristino UBL") #define MSG_UBL_Z_OFFSET_STOPPED _UxGT("Z-Offset Fermato") +#define MSG_UBL_STEP_BY_STEP_MENU _UxGT("UBL passo passo") #define MSG_MOVING _UxGT("In movimento...") #define MSG_FREE_XY _UxGT("XY liberi") From c7f04fbcc7c3789568544398b5d1b723586734b5 Mon Sep 17 00:00:00 2001 From: Gege2B Date: Mon, 19 Jun 2017 23:13:58 +0200 Subject: [PATCH 107/180] French translation --- Marlin/language_fr.h | 126 ++++++++++++++++++++++++++++++++++--------- 1 file changed, 100 insertions(+), 26 deletions(-) diff --git a/Marlin/language_fr.h b/Marlin/language_fr.h index a919eb9b00..17b29b543b 100644 --- a/Marlin/language_fr.h +++ b/Marlin/language_fr.h @@ -42,7 +42,7 @@ #define MSG_AUTOSTART _UxGT("Demarrage auto") #define MSG_DISABLE_STEPPERS _UxGT("Arrêter moteurs") #define MSG_DEBUG_MENU _UxGT("Menu debug") -#define MSG_PROGRESS_BAR_TEST _UxGT("Test barre progression") +#define MSG_PROGRESS_BAR_TEST _UxGT("Test barre progress.") #define MSG_AUTO_HOME _UxGT("Origine auto.") #define MSG_AUTO_HOME_X _UxGT("Origine X Auto.") #define MSG_AUTO_HOME_Y _UxGT("Origine Y Auto.") @@ -51,6 +51,7 @@ #define MSG_LEVEL_BED_WAITING _UxGT("Clic pour commencer") #define MSG_LEVEL_BED_NEXT_POINT _UxGT("Point suivant") #define MSG_LEVEL_BED_DONE _UxGT("Mise à niveau OK!") +#define MSG_Z_FADE_HEIGHT _UxGT("Adoucir hauteur") #define MSG_SET_HOME_OFFSETS _UxGT("Regl. décal. origine") #define MSG_HOME_OFFSETS_APPLIED _UxGT("Décalages appliqués") #define MSG_SET_ORIGIN _UxGT("Régler origine") @@ -74,6 +75,68 @@ #define MSG_MOVE_AXIS _UxGT("Déplacer un axe") #define MSG_BED_LEVELING _UxGT("Règl. Niv. lit") #define MSG_LEVEL_BED _UxGT("Règl. Niv. lit") +#define MSG_EDITING_STOPPED _UxGT("Arrêt edit. maillage") +#define MSG_USER_MENU _UxGT("Commandes perso") + +#define MSG_UBL_DOING_G29 _UxGT("G29 en cours") +#define MSG_UBL_UNHOMED _UxGT("Origine XYZ d'abord") +#define MSG_UBL_TOOLS _UxGT("Outils UBL") +#define MSG_UBL_LEVEL_BED _UxGT("Niveau lit unifié") +#define MSG_UBL_MANUAL_MESH _UxGT("Maillage manuel") +#define MSG_UBL_BC_INSERT _UxGT("Poser câle & mesurer") +#define MSG_UBL_BC_INSERT2 _UxGT("Mesure") +#define MSG_UBL_BC_REMOVE _UxGT("ôter et mesurer lit") +#define MSG_UBL_MOVING_TO_NEXT _UxGT("Aller au suivant") +#define MSG_UBL_ACTIVATE_MESH _UxGT("Activer l'UBL") +#define MSG_UBL_DEACTIVATE_MESH _UxGT("Désactiver l'UBL") +#define MSG_UBL_SET_BED_TEMP _UxGT("Température lit") +#define MSG_UBL_CUSTOM_BED_TEMP MSG_UBL_SET_BED_TEMP +#define MSG_UBL_SET_HOTEND_TEMP _UxGT("Température buse") +#define MSG_UBL_CUSTOM_HOTEND_TEMP MSG_UBL_SET_HOTEND_TEMP +#define MSG_UBL_EDIT_CUSTOM_MESH _UxGT("Editer maille perso") +#define MSG_UBL_FINE_TUNE_MESH _UxGT("Réglage fin maille") +#define MSG_UBL_DONE_EDITING_MESH _UxGT("Termier maille") +#define MSG_UBL_BUILD_CUSTOM_MESH _UxGT("Créer maille perso") +#define MSG_UBL_BUILD_MESH_MENU _UxGT("Créer maille") +#define MSG_UBL_BUILD_PLA_MESH _UxGT("Créer maille PLA") +#define MSG_UBL_BUILD_ABS_MESH _UxGT("Créer maille ABS") +#define MSG_UBL_BUILD_COLD_MESH _UxGT("Créer maille froide") +#define MSG_UBL_MESH_HEIGHT_ADJUST _UxGT("Ajuster haut. maille") +#define MSG_UBL_MESH_HEIGHT_AMOUNT _UxGT("Hauteur") +#define MSG_UBL_VALIDATE_MESH_MENU _UxGT("Valider maille") +#define MSG_UBL_VALIDATE_PLA_MESH _UxGT("Valider maille PLA") +#define MSG_UBL_VALIDATE_ABS_MESH _UxGT("Valider maille ABS") +#define MSG_UBL_VALIDATE_CUSTOM_MESH _UxGT("Valider maille perso") +#define MSG_UBL_CONTINUE_MESH _UxGT("Continuer maille") +#define MSG_UBL_MESH_LEVELING _UxGT("Niveau par maille") +#define MSG_UBL_3POINT_MESH_LEVELING _UxGT("Niveau à 3 points") +#define MSG_UBL_GRID_MESH_LEVELING _UxGT("Niveau grille") +#define MSG_UBL_MESH_LEVEL _UxGT("Maille de niveau") +#define MSG_UBL_SIDE_POINTS _UxGT("Point latéral") +#define MSG_UBL_MAP_TYPE _UxGT("Type de carte") +#define MSG_UBL_OUTPUT_MAP _UxGT("Voir maille") +#define MSG_UBL_OUTPUT_MAP_HOST _UxGT("Voir pour hôte") +#define MSG_UBL_OUTPUT_MAP_CSV _UxGT("Voir pour CSV") +#define MSG_UBL_OUTPUT_MAP_BACKUP _UxGT("Off Printer Backup") +#define MSG_UBL_INFO_UBL _UxGT("Voir info UBL") +#define MSG_UBL_EDIT_MESH_MENU _UxGT("Modifier maille") +#define MSG_UBL_FILLIN_AMOUNT _UxGT("Taux de remplissage") +#define MSG_UBL_MANUAL_FILLIN _UxGT("Remplissage manuel") +#define MSG_UBL_SMART_FILLIN _UxGT("Remplissage auto") +#define MSG_UBL_FILLIN_MESH _UxGT("Maille remplissage") +#define MSG_UBL_INVALIDATE_ALL _UxGT("Annuler tout") +#define MSG_UBL_INVALIDATE_CLOSEST _UxGT("Annuler le plus près") +#define MSG_UBL_FINE_TUNE_ALL _UxGT("Réglage fin (tous)") +#define MSG_UBL_FINE_TUNE_CLOSEST _UxGT("Réglage fin (proche)") +#define MSG_UBL_STORAGE_MESH_MENU _UxGT("Stockage maille") +#define MSG_UBL_STORAGE_SLOT _UxGT("Slot mémoire") +#define MSG_UBL_LOAD_MESH _UxGT("Charger maille") +#define MSG_UBL_SAVE_MESH _UxGT("Sauver maille") +#define MSG_UBL_SAVE_ERROR _UxGT("Err: Enreg. UBL") +#define MSG_UBL_RESTORE_ERROR _UxGT("Err: Ouvrir UBL") +#define MSG_UBL_Z_OFFSET_STOPPED _UxGT("Offset Z arrêté") + + #define MSG_MOVING _UxGT("Déplacement...") #define MSG_FREE_XY _UxGT("Débloquer XY") #define MSG_MOVE_X _UxGT("Dépl. X") @@ -107,9 +170,11 @@ #define MSG_VY_JERK _UxGT("Vy-jerk") #define MSG_VZ_JERK _UxGT("Vz-jerk") #define MSG_VE_JERK _UxGT("Ve-jerk") +#define MSG_VELOCITY _UxGT("Vélocité") #define MSG_VMAX _UxGT("Vmax") #define MSG_VMIN _UxGT("Vmin") #define MSG_VTRAV_MIN _UxGT("Vdepl min") +#define MSG_ACCELERATION _UxGT("Accélération") #define MSG_AMAX _UxGT("Amax ") #define MSG_A_RETRACT _UxGT("A-retract") #define MSG_A_TRAVEL _UxGT("A-Dépl.") @@ -133,6 +198,7 @@ #define MSG_STORE_EEPROM _UxGT("Sauver config") #define MSG_LOAD_EEPROM _UxGT("Lire config") #define MSG_RESTORE_FAILSAFE _UxGT("Restaurer défauts") +#define MSG_INIT_EEPROM _UxGT("Initialiser EEPROM") #define MSG_REFRESH _UxGT("Actualiser") #define MSG_WATCH _UxGT("Surveiller") #define MSG_PREPARE _UxGT("Préparer") @@ -144,6 +210,7 @@ #define MSG_NO_CARD _UxGT("Pas de carte") #define MSG_DWELL _UxGT("Repos...") #define MSG_USERWAIT _UxGT("Atten. de l'util.") +#define MSG_PRINT_PAUSED _UxGT("Impr. en pause") #define MSG_RESUMING _UxGT("Repri. de l'impr.") #define MSG_PRINT_ABORTED _UxGT("Impr. Annulée") #define MSG_NO_MOVE _UxGT("Moteurs bloqués.") @@ -161,6 +228,7 @@ #define MSG_INIT_SDCARD _UxGT("Init. la carte SD") #define MSG_CNG_SDCARD _UxGT("Changer de carte") #define MSG_ZPROBE_OUT _UxGT("Z sonde extè. lit") +#define MSG_BLTOUCH _UxGT("BLTouch") #define MSG_BLTOUCH_SELFTEST _UxGT("Autotest BLTouch") #define MSG_BLTOUCH_RESET _UxGT("RaZ BLTouch") #define MSG_BLTOUCH_DEPLOY _UxGT("Déployer BLTouch") @@ -201,13 +269,19 @@ #define MSG_INFO_MENU _UxGT("Infos imprimante") #define MSG_INFO_PRINTER_MENU _UxGT("Infos imprimante") +#define MSG_3POINT_LEVELING _UxGT("Niveau à 3 points") +#define MSG_LINEAR_LEVELING _UxGT("Niveau linéaire") +#define MSG_BILINEAR_LEVELING _UxGT("Niveau bilinéaire") +#define MSG_UBL_LEVELING _UxGT("Niveau lit unifié") +#define MSG_MESH_LEVELING _UxGT("Niveau maillage") #define MSG_INFO_STATS_MENU _UxGT("Stats. imprimante") #define MSG_INFO_BOARD_MENU _UxGT("Infos carte") #define MSG_INFO_THERMISTOR_MENU _UxGT("Thermistors") #define MSG_INFO_EXTRUDERS _UxGT("Extrudeurs") #define MSG_INFO_BAUDRATE _UxGT("Baud") #define MSG_INFO_PROTOCOL _UxGT("Protocole") -#define MSG_CASE_LIGHT _UxGT("Lumière") +#define MSG_CASE_LIGHT _UxGT("Lumière caisson") +#define MSG_CASE_LIGHT_BRIGHTNESS _UxGT("Luminosité") #if LCD_WIDTH >= 20 #define MSG_INFO_PRINT_COUNT _UxGT("Nbre impressions") @@ -239,32 +313,32 @@ #if LCD_HEIGHT >= 4 // Up to 3 lines allowed - #define MSG_FILAMENT_CHANGE_INIT_1 _UxGT("Attente Démarrage") - #define MSG_FILAMENT_CHANGE_INIT_2 _UxGT("du filament") - #define MSG_FILAMENT_CHANGE_INIT_3 _UxGT("changer") - #define MSG_FILAMENT_CHANGE_UNLOAD_1 _UxGT("attente de") - #define MSG_FILAMENT_CHANGE_UNLOAD_2 _UxGT("décharger filament") - #define MSG_FILAMENT_CHANGE_INSERT_1 _UxGT("insérer filament") - #define MSG_FILAMENT_CHANGE_INSERT_2 _UxGT("et app. bouton") - #define MSG_FILAMENT_CHANGE_INSERT_3 _UxGT("pour continuer...") - #define MSG_FILAMENT_CHANGE_HEAT_1 _UxGT("Appuyer sur le bouton...") - #define MSG_FILAMENT_CHANGE_HEAT_2 _UxGT("Pour chauffer la buse.") - #define MSG_FILAMENT_CHANGE_HEATING_1 _UxGT("Buse en chauffe") - #define MSG_FILAMENT_CHANGE_HEATING_2 _UxGT("Patientez SVP...") - #define MSG_FILAMENT_CHANGE_LOAD_1 _UxGT("attente de") - #define MSG_FILAMENT_CHANGE_LOAD_2 _UxGT("chargement filament") - #define MSG_FILAMENT_CHANGE_EXTRUDE_1 _UxGT("attente de") - #define MSG_FILAMENT_CHANGE_EXTRUDE_2 _UxGT("extrusion filament") - #define MSG_FILAMENT_CHANGE_RESUME_1 _UxGT("attente impression") - #define MSG_FILAMENT_CHANGE_RESUME_2 _UxGT("pour reprendre") + #define MSG_FILAMENT_CHANGE_INIT_1 _UxGT("Attente Démarrage") + #define MSG_FILAMENT_CHANGE_INIT_2 _UxGT("du filament") + #define MSG_FILAMENT_CHANGE_INIT_3 _UxGT("changer") + #define MSG_FILAMENT_CHANGE_UNLOAD_1 _UxGT("attente de") + #define MSG_FILAMENT_CHANGE_UNLOAD_2 _UxGT("décharger filament") + #define MSG_FILAMENT_CHANGE_INSERT_1 _UxGT("insérer filament") + #define MSG_FILAMENT_CHANGE_INSERT_2 _UxGT("et app. bouton") + #define MSG_FILAMENT_CHANGE_INSERT_3 _UxGT("pour continuer...") + #define MSG_FILAMENT_CHANGE_HEAT_1 _UxGT("Presser le bouton...") + #define MSG_FILAMENT_CHANGE_HEAT_2 _UxGT("Pr chauffer la buse") + #define MSG_FILAMENT_CHANGE_HEATING_1 _UxGT("Buse en chauffe") + #define MSG_FILAMENT_CHANGE_HEATING_2 _UxGT("Patientez SVP...") + #define MSG_FILAMENT_CHANGE_LOAD_1 _UxGT("attente de") + #define MSG_FILAMENT_CHANGE_LOAD_2 _UxGT("chargement filament") + #define MSG_FILAMENT_CHANGE_EXTRUDE_1 _UxGT("attente de") + #define MSG_FILAMENT_CHANGE_EXTRUDE_2 _UxGT("extrusion filament") + #define MSG_FILAMENT_CHANGE_RESUME_1 _UxGT("attente impression") + #define MSG_FILAMENT_CHANGE_RESUME_2 _UxGT("pour reprendre") #else // LCD_HEIGHT < 4 // Up to 2 lines allowed - #define MSG_FILAMENT_CHANGE_INIT_1 _UxGT("Patientez...") - #define MSG_FILAMENT_CHANGE_UNLOAD_1 _UxGT("Ejection...") - #define MSG_FILAMENT_CHANGE_INSERT_1 _UxGT("Insérer et clic") - #define MSG_FILAMENT_CHANGE_LOAD_1 _UxGT("Chargement...") - #define MSG_FILAMENT_CHANGE_EXTRUDE_1 _UxGT("Extrusion...") - #define MSG_FILAMENT_CHANGE_RESUME_1 _UxGT("Reprise...") + #define MSG_FILAMENT_CHANGE_INIT_1 _UxGT("Patientez...") + #define MSG_FILAMENT_CHANGE_UNLOAD_1 _UxGT("Ejection...") + #define MSG_FILAMENT_CHANGE_INSERT_1 _UxGT("Insérer et clic") + #define MSG_FILAMENT_CHANGE_LOAD_1 _UxGT("Chargement...") + #define MSG_FILAMENT_CHANGE_EXTRUDE_1 _UxGT("Extrusion...") + #define MSG_FILAMENT_CHANGE_RESUME_1 _UxGT("Reprise...") #endif // LCD_HEIGHT < 4 #endif // LANGUAGE_FR_H From d26c8cc5c80d355e08a4f05e6c9566d274dea2c0 Mon Sep 17 00:00:00 2001 From: MagoKimbra Date: Thu, 22 Jun 2017 19:59:22 +0200 Subject: [PATCH 108/180] fix_planner_refresh_e_positioning (#7103) * fix_planner_refresh_e_positioning * Fix --- Marlin/ultralcd.cpp | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index c9bc6d9111..074923e1d3 100644 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -3199,16 +3199,16 @@ void kill_screen(const char* lcd_msg) { if (e == active_extruder) _planner_refresh_positioning(); else - planner.steps_to_mm[e] = 1.0 / planner.axis_steps_per_mm[e]; + planner.steps_to_mm[E_AXIS + e] = 1.0 / planner.axis_steps_per_mm[E_AXIS + e]; } - void _planner_refresh_e0_positioning() { _reset_e_acceleration_rate(0); } - void _planner_refresh_e1_positioning() { _reset_e_acceleration_rate(1); } + void _planner_refresh_e0_positioning() { _planner_refresh_e_positioning(0); } + void _planner_refresh_e1_positioning() { _planner_refresh_e_positioning(1); } #if E_STEPPERS > 2 - void _planner_refresh_e2_positioning() { _reset_e_acceleration_rate(2); } + void _planner_refresh_e2_positioning() { _planner_refresh_e_positioning(2); } #if E_STEPPERS > 3 - void _planner_refresh_e3_positioning() { _reset_e_acceleration_rate(3); } + void _planner_refresh_e3_positioning() { _planner_refresh_e_positioning(3); } #if E_STEPPERS > 4 - void _planner_refresh_e4_positioning() { _reset_e_acceleration_rate(4); } + void _planner_refresh_e4_positioning() { _planner_refresh_e_positioning(4); } #endif // E_STEPPERS > 4 #endif // E_STEPPERS > 3 #endif // E_STEPPERS > 2 From 325f09ea6c2073e5d0fadbf92470f372e64512ab Mon Sep 17 00:00:00 2001 From: Bob-the-Kuhn Date: Wed, 21 Jun 2017 21:30:43 -0500 Subject: [PATCH 109/180] Add link to custom LiquidCrystal library by F. Malpartida --- Marlin/Conditionals_LCD.h | 4 ++-- Marlin/Configuration.h | 3 +++ Marlin/example_configurations/CL-260/Configuration.h | 3 +++ Marlin/example_configurations/Cartesio/Configuration.h | 3 +++ Marlin/example_configurations/Felix/Configuration.h | 3 +++ Marlin/example_configurations/Felix/DUAL/Configuration.h | 3 +++ .../example_configurations/FolgerTech-i3-2020/Configuration.h | 3 +++ Marlin/example_configurations/Hephestos/Configuration.h | 3 +++ Marlin/example_configurations/Hephestos_2/Configuration.h | 3 +++ Marlin/example_configurations/K8200/Configuration.h | 3 +++ Marlin/example_configurations/K8400/Configuration.h | 3 +++ Marlin/example_configurations/K8400/Dual-head/Configuration.h | 3 +++ Marlin/example_configurations/M150/Configuration.h | 3 +++ .../RepRapWorld/Megatronics/Configuration.h | 3 +++ Marlin/example_configurations/RigidBot/Configuration.h | 3 +++ Marlin/example_configurations/SCARA/Configuration.h | 3 +++ Marlin/example_configurations/TAZ4/Configuration.h | 3 +++ Marlin/example_configurations/TinyBoy2/Configuration.h | 3 +++ Marlin/example_configurations/WITBOX/Configuration.h | 3 +++ Marlin/example_configurations/adafruit/ST7565/Configuration.h | 3 +++ .../delta/FLSUN/auto_calibrate/Configuration.h | 3 +++ .../delta/FLSUN/kossel_mini/Configuration.h | 3 +++ Marlin/example_configurations/delta/generic/Configuration.h | 3 +++ .../example_configurations/delta/kossel_mini/Configuration.h | 3 +++ .../example_configurations/delta/kossel_pro/Configuration.h | 3 +++ Marlin/example_configurations/delta/kossel_xl/Configuration.h | 3 +++ .../example_configurations/gCreate_gMax1.5+/Configuration.h | 3 +++ Marlin/example_configurations/makibox/Configuration.h | 3 +++ Marlin/example_configurations/tvrrug/Round2/Configuration.h | 3 +++ Marlin/example_configurations/wt150/Configuration.h | 3 +++ 30 files changed, 89 insertions(+), 2 deletions(-) diff --git a/Marlin/Conditionals_LCD.h b/Marlin/Conditionals_LCD.h index d51d6a353d..bd6fc29de9 100644 --- a/Marlin/Conditionals_LCD.h +++ b/Marlin/Conditionals_LCD.h @@ -129,8 +129,8 @@ */ #if ENABLED(LCD_I2C_SAINSMART_YWROBOT) - // This uses the LiquidCrystal_I2C library ( https://bitbucket.org/fmalpartida/new-liquidcrystal/wiki/Home ) - // Make sure it is placed in the Arduino libraries directory. + // Note: This controller requires F.Malpartida's LiquidCrystal_I2C library + // https://bitbucket.org/fmalpartida/new-liquidcrystal/wiki/Home #define LCD_I2C_TYPE_PCF8575 #define LCD_I2C_ADDRESS 0x27 // I2C Address of the port expander #define ULTIPANEL diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 6c128f4e14..78aaa2fabe 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -1389,6 +1389,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 // diff --git a/Marlin/example_configurations/CL-260/Configuration.h b/Marlin/example_configurations/CL-260/Configuration.h index fe024c71b5..9692777ef8 100644 --- a/Marlin/example_configurations/CL-260/Configuration.h +++ b/Marlin/example_configurations/CL-260/Configuration.h @@ -1386,6 +1386,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 // diff --git a/Marlin/example_configurations/Cartesio/Configuration.h b/Marlin/example_configurations/Cartesio/Configuration.h index 38fd64f429..b3f7c2a11b 100644 --- a/Marlin/example_configurations/Cartesio/Configuration.h +++ b/Marlin/example_configurations/Cartesio/Configuration.h @@ -1383,6 +1383,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 // diff --git a/Marlin/example_configurations/Felix/Configuration.h b/Marlin/example_configurations/Felix/Configuration.h index d4c3f07381..12790b1d0b 100644 --- a/Marlin/example_configurations/Felix/Configuration.h +++ b/Marlin/example_configurations/Felix/Configuration.h @@ -1367,6 +1367,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 // diff --git a/Marlin/example_configurations/Felix/DUAL/Configuration.h b/Marlin/example_configurations/Felix/DUAL/Configuration.h index 863b725e9a..63fe048e05 100644 --- a/Marlin/example_configurations/Felix/DUAL/Configuration.h +++ b/Marlin/example_configurations/Felix/DUAL/Configuration.h @@ -1367,6 +1367,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 // diff --git a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h index 1f464ee041..b55f79b259 100644 --- a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h +++ b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h @@ -1389,6 +1389,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 // diff --git a/Marlin/example_configurations/Hephestos/Configuration.h b/Marlin/example_configurations/Hephestos/Configuration.h index 44cc30e42e..094cfb204f 100644 --- a/Marlin/example_configurations/Hephestos/Configuration.h +++ b/Marlin/example_configurations/Hephestos/Configuration.h @@ -1375,6 +1375,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 // diff --git a/Marlin/example_configurations/Hephestos_2/Configuration.h b/Marlin/example_configurations/Hephestos_2/Configuration.h index 04dd6842cc..74a715f094 100644 --- a/Marlin/example_configurations/Hephestos_2/Configuration.h +++ b/Marlin/example_configurations/Hephestos_2/Configuration.h @@ -1378,6 +1378,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 // diff --git a/Marlin/example_configurations/K8200/Configuration.h b/Marlin/example_configurations/K8200/Configuration.h index 86304303e4..64f945a0e8 100644 --- a/Marlin/example_configurations/K8200/Configuration.h +++ b/Marlin/example_configurations/K8200/Configuration.h @@ -1417,6 +1417,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 // diff --git a/Marlin/example_configurations/K8400/Configuration.h b/Marlin/example_configurations/K8400/Configuration.h index 8152f2d619..4e06cc1c07 100644 --- a/Marlin/example_configurations/K8400/Configuration.h +++ b/Marlin/example_configurations/K8400/Configuration.h @@ -1385,6 +1385,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 // diff --git a/Marlin/example_configurations/K8400/Dual-head/Configuration.h b/Marlin/example_configurations/K8400/Dual-head/Configuration.h index 735ac65718..301779ad6c 100644 --- a/Marlin/example_configurations/K8400/Dual-head/Configuration.h +++ b/Marlin/example_configurations/K8400/Dual-head/Configuration.h @@ -1385,6 +1385,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 // diff --git a/Marlin/example_configurations/M150/Configuration.h b/Marlin/example_configurations/M150/Configuration.h index 75c4f4c129..abc640cc92 100644 --- a/Marlin/example_configurations/M150/Configuration.h +++ b/Marlin/example_configurations/M150/Configuration.h @@ -1412,6 +1412,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 // diff --git a/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h b/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h index fd0fedc30a..3d8b999dd1 100644 --- a/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h +++ b/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h @@ -1385,6 +1385,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 // diff --git a/Marlin/example_configurations/RigidBot/Configuration.h b/Marlin/example_configurations/RigidBot/Configuration.h index 77fa6469bf..2bda3307eb 100644 --- a/Marlin/example_configurations/RigidBot/Configuration.h +++ b/Marlin/example_configurations/RigidBot/Configuration.h @@ -1385,6 +1385,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 // diff --git a/Marlin/example_configurations/SCARA/Configuration.h b/Marlin/example_configurations/SCARA/Configuration.h index 6f92b4f892..78a96445af 100644 --- a/Marlin/example_configurations/SCARA/Configuration.h +++ b/Marlin/example_configurations/SCARA/Configuration.h @@ -1400,6 +1400,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 // diff --git a/Marlin/example_configurations/TAZ4/Configuration.h b/Marlin/example_configurations/TAZ4/Configuration.h index 845c758d2f..a34a74cd68 100644 --- a/Marlin/example_configurations/TAZ4/Configuration.h +++ b/Marlin/example_configurations/TAZ4/Configuration.h @@ -1404,6 +1404,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 // diff --git a/Marlin/example_configurations/TinyBoy2/Configuration.h b/Marlin/example_configurations/TinyBoy2/Configuration.h index 0326daf299..c1e9a615f3 100644 --- a/Marlin/example_configurations/TinyBoy2/Configuration.h +++ b/Marlin/example_configurations/TinyBoy2/Configuration.h @@ -1441,6 +1441,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 // diff --git a/Marlin/example_configurations/WITBOX/Configuration.h b/Marlin/example_configurations/WITBOX/Configuration.h index d090f55065..b1c97d3527 100644 --- a/Marlin/example_configurations/WITBOX/Configuration.h +++ b/Marlin/example_configurations/WITBOX/Configuration.h @@ -1375,6 +1375,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 // diff --git a/Marlin/example_configurations/adafruit/ST7565/Configuration.h b/Marlin/example_configurations/adafruit/ST7565/Configuration.h index 04c62167b0..49c98edf5f 100644 --- a/Marlin/example_configurations/adafruit/ST7565/Configuration.h +++ b/Marlin/example_configurations/adafruit/ST7565/Configuration.h @@ -1385,6 +1385,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 // diff --git a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h index 840287c96f..facbfb596c 100644 --- a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h +++ b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h @@ -1506,6 +1506,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 // diff --git a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h index b7fe4eed91..ad51210310 100644 --- a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h +++ b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h @@ -1507,6 +1507,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 // diff --git a/Marlin/example_configurations/delta/generic/Configuration.h b/Marlin/example_configurations/delta/generic/Configuration.h index 39500de3f9..2c3ce91c51 100644 --- a/Marlin/example_configurations/delta/generic/Configuration.h +++ b/Marlin/example_configurations/delta/generic/Configuration.h @@ -1496,6 +1496,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 // diff --git a/Marlin/example_configurations/delta/kossel_mini/Configuration.h b/Marlin/example_configurations/delta/kossel_mini/Configuration.h index 4e3a7ebb69..ea21701b7b 100644 --- a/Marlin/example_configurations/delta/kossel_mini/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_mini/Configuration.h @@ -1499,6 +1499,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 // diff --git a/Marlin/example_configurations/delta/kossel_pro/Configuration.h b/Marlin/example_configurations/delta/kossel_pro/Configuration.h index eabdc13574..97650792fb 100644 --- a/Marlin/example_configurations/delta/kossel_pro/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_pro/Configuration.h @@ -1504,6 +1504,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 // diff --git a/Marlin/example_configurations/delta/kossel_xl/Configuration.h b/Marlin/example_configurations/delta/kossel_xl/Configuration.h index acbc9e58d8..5d76043335 100644 --- a/Marlin/example_configurations/delta/kossel_xl/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_xl/Configuration.h @@ -1562,6 +1562,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 // diff --git a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h index 67eb606e09..400eb6b24e 100644 --- a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h +++ b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h @@ -1401,6 +1401,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 // diff --git a/Marlin/example_configurations/makibox/Configuration.h b/Marlin/example_configurations/makibox/Configuration.h index ae07c775bd..c23d4b747a 100644 --- a/Marlin/example_configurations/makibox/Configuration.h +++ b/Marlin/example_configurations/makibox/Configuration.h @@ -1388,6 +1388,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 // diff --git a/Marlin/example_configurations/tvrrug/Round2/Configuration.h b/Marlin/example_configurations/tvrrug/Round2/Configuration.h index 57a66e1756..2ff81f3a1c 100644 --- a/Marlin/example_configurations/tvrrug/Round2/Configuration.h +++ b/Marlin/example_configurations/tvrrug/Round2/Configuration.h @@ -1380,6 +1380,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 // diff --git a/Marlin/example_configurations/wt150/Configuration.h b/Marlin/example_configurations/wt150/Configuration.h index 80addd741b..2ec162abfc 100644 --- a/Marlin/example_configurations/wt150/Configuration.h +++ b/Marlin/example_configurations/wt150/Configuration.h @@ -1390,6 +1390,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 // From a18324bc8d40de50a4f407085ede7a1a8e7a0028 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 22 Jun 2017 18:00:01 -0500 Subject: [PATCH 110/180] Give a more detailed issue template --- .github/issue_template.md | 37 +++++++++++++++++++++++++++++++++---- 1 file changed, 33 insertions(+), 4 deletions(-) diff --git a/.github/issue_template.md b/.github/issue_template.md index 8be2b3e995..17f680d57f 100644 --- a/.github/issue_template.md +++ b/.github/issue_template.md @@ -1,7 +1,36 @@ -### Expected behaviour +Thank you for submitting your feedback to the Marlin project. +Please use one of the templates below to fill out this box. -### Actual behaviour +------------------------------------------------------------ +### Feature Request +Please put [FR] in the issue title: `[FR] Add-on that goes 'ping'` -### Steps to reproduce the behaviour +------------------------------------------------------------ +### Compile Error +When I compile with `FEATURE_X` I get an error: +``` +Paste_the_error_text_here +``` -#### please add your Configuration.h and Configuration_adv.h to a zip file and attach it to this issue +------------------------------------------------------------ +### Bug Report +- Description: --- +- Expected behaviour: --- +- Actual behaviour: --- +- Steps to reproduce: + - Do this + - Do that + +Attach a ZIP of `Configuration.h` and `Configuration_adv.h` by dropping here. + +------------------------------------------------------------ +### Bug Report Tips +- When troubleshooting, use `M502` followed by `M500` to reset EEPROM to defaults. +- Use `DEBUG_LEVELING_FEATURE` with `M111 S247` for detailed logging of homing/leveling. +- Format text with: **bold**, _italic_, `code`. +- Format C++ with three backticks, plus "cpp": +```cpp +void my_function(bool do_it) { + // Hold this spot +} +``` From a9f8e518bf67190207fb318a353b2cab958a8e92 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 23 Jun 2017 14:48:02 -0500 Subject: [PATCH 111/180] Fix FILAMENT_WIDTH_SENSOR infinite loop issue Addressing #6992 and #5851 --- Marlin/Marlin.h | 6 +++--- Marlin/Marlin_main.cpp | 10 +++++----- Marlin/planner.cpp | 4 ++-- Marlin/temperature.cpp | 6 +++--- Marlin/temperature.h | 4 ++-- 5 files changed, 15 insertions(+), 15 deletions(-) diff --git a/Marlin/Marlin.h b/Marlin/Marlin.h index 6bb45698e6..307dd370d5 100644 --- a/Marlin/Marlin.h +++ b/Marlin/Marlin.h @@ -370,9 +370,9 @@ extern float soft_endstop_min[XYZ], soft_endstop_max[XYZ]; extern bool filament_sensor; // Flag that filament sensor readings should control extrusion extern float filament_width_nominal, // Theoretical filament diameter i.e., 3.00 or 1.75 filament_width_meas; // Measured filament diameter - extern int8_t measurement_delay[]; // Ring buffer to delay measurement - extern int filwidth_delay_index[2]; // Ring buffer indexes. Used by planner, temperature, and main code - extern int meas_delay_cm; // Delay distance + extern uint8_t meas_delay_cm, // Delay distance + measurement_delay[]; // Ring buffer to delay measurement + extern int8_t filwidth_delay_index[2]; // Ring buffer indexes. Used by planner, temperature, and main code #endif #if ENABLED(ADVANCED_PAUSE_FEATURE) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index f30291f2e2..d5c0cbf81b 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -630,9 +630,9 @@ float cartes[XYZ] = { 0 }; bool filament_sensor = false; // M405 turns on filament sensor control. M406 turns it off. float filament_width_nominal = DEFAULT_NOMINAL_FILAMENT_DIA, // Nominal filament width. Change with M404. filament_width_meas = DEFAULT_MEASURED_FILAMENT_DIA; // Measured filament diameter - int8_t measurement_delay[MAX_MEASUREMENT_DELAY + 1]; // Ring buffer to delayed measurement. Store extruder factor after subtracting 100 - int filwidth_delay_index[2] = { 0, -1 }; // Indexes into ring buffer - int meas_delay_cm = MEASUREMENT_DELAY_CM; // Distance delay setting + uint8_t meas_delay_cm = MEASUREMENT_DELAY_CM, // Distance delay setting + measurement_delay[MAX_MEASUREMENT_DELAY + 1]; // Ring buffer to delayed measurement. Store extruder factor after subtracting 100 + int8_t filwidth_delay_index[2] = { 0, -1 }; // Indexes into ring buffer #endif #if ENABLED(FILAMENT_RUNOUT_SENSOR) @@ -8898,11 +8898,11 @@ inline void gcode_M400() { stepper.synchronize(); } inline void gcode_M405() { // This is technically a linear measurement, but since it's quantized to centimeters and is a different unit than // everything else, it uses parser.value_int() instead of parser.value_linear_units(). - if (parser.seen('D')) meas_delay_cm = parser.value_int(); + if (parser.seen('D')) meas_delay_cm = parser.value_byte(); NOMORE(meas_delay_cm, MAX_MEASUREMENT_DELAY); if (filwidth_delay_index[1] == -1) { // Initialize the ring buffer if not done since startup - const int temp_ratio = thermalManager.widthFil_to_size_ratio() - 100; // -100 to scale within a signed byte + const uint8_t temp_ratio = thermalManager.widthFil_to_size_ratio() - 100; // -100 to scale within a signed byte for (uint8_t i = 0; i < COUNT(measurement_delay); ++i) measurement_delay[i] = temp_ratio; diff --git a/Marlin/planner.cpp b/Marlin/planner.cpp index 5897e4fe6a..8cac74f146 100644 --- a/Marlin/planner.cpp +++ b/Marlin/planner.cpp @@ -1103,12 +1103,12 @@ void Planner::_buffer_line(const float &a, const float &b, const float &c, const while (filwidth_delay_dist >= MMD_MM) filwidth_delay_dist -= MMD_MM; // Convert into an index into the measurement array - filwidth_delay_index[0] = (int)(filwidth_delay_dist * 0.1 + 0.0001); + filwidth_delay_index[0] = int8_t(filwidth_delay_dist * 0.1); // If the index has changed (must have gone forward)... if (filwidth_delay_index[0] != filwidth_delay_index[1]) { filwidth_e_count = 0; // Reset the E movement counter - const int8_t meas_sample = thermalManager.widthFil_to_size_ratio() - 100; // Subtract 100 to reduce magnitude - to store in a signed char + const uint8_t meas_sample = thermalManager.widthFil_to_size_ratio() - 100; // Subtract 100 to reduce magnitude - to store in a signed char do { filwidth_delay_index[1] = (filwidth_delay_index[1] + 1) % MMD_CM; // The next unused slot measurement_delay[filwidth_delay_index[1]] = meas_sample; // Store the measurement diff --git a/Marlin/temperature.cpp b/Marlin/temperature.cpp index 99aec7f4da..6111bab442 100644 --- a/Marlin/temperature.cpp +++ b/Marlin/temperature.cpp @@ -180,7 +180,7 @@ int16_t Temperature::minttemp_raw[HOTENDS] = ARRAY_BY_HOTENDS(HEATER_0_RAW_LO_TE #endif #if ENABLED(FILAMENT_WIDTH_SENSOR) - int16_t Temperature::meas_shift_index; // Index of a delayed sample in buffer + int8_t Temperature::meas_shift_index; // Index of a delayed sample in buffer #endif #if HAS_AUTO_FAN @@ -196,7 +196,7 @@ uint8_t Temperature::soft_pwm_amount[HOTENDS], #endif #if ENABLED(FILAMENT_WIDTH_SENSOR) - int Temperature::current_raw_filwidth = 0; //Holds measured filament diameter - one extruder only + uint16_t Temperature::current_raw_filwidth = 0; // Measured filament diameter - one extruder only #endif #if ENABLED(PROBING_HEATERS_OFF) @@ -957,7 +957,7 @@ void Temperature::updateTemperaturesFromRawValues() { // Convert raw Filament Width to millimeters float Temperature::analog2widthFil() { - return current_raw_filwidth / 16383.0 * 5.0; + return current_raw_filwidth * 5.0 * (1.0 / 16383.0); //return current_raw_filwidth; } diff --git a/Marlin/temperature.h b/Marlin/temperature.h index 9437685789..60a85684a2 100644 --- a/Marlin/temperature.h +++ b/Marlin/temperature.h @@ -247,7 +247,7 @@ class Temperature { #endif #if ENABLED(FILAMENT_WIDTH_SENSOR) - static int16_t meas_shift_index; // Index of a delayed sample in buffer + static int8_t meas_shift_index; // Index of a delayed sample in buffer #endif #if HAS_AUTO_FAN @@ -255,7 +255,7 @@ class Temperature { #endif #if ENABLED(FILAMENT_WIDTH_SENSOR) - static int current_raw_filwidth; //Holds measured filament diameter - one extruder only + static uint16_t current_raw_filwidth; // Measured filament diameter - one extruder only #endif #if ENABLED(PROBING_HEATERS_OFF) From ee7163fd3ad355b5d4960ebf9ee3655e48a7ecc4 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 15 Jun 2017 11:52:23 -0500 Subject: [PATCH 112/180] Fix pinsDebug compile errors --- Marlin/pinsDebug.h | 38 +++++++++++++++++++++----------------- 1 file changed, 21 insertions(+), 17 deletions(-) diff --git a/Marlin/pinsDebug.h b/Marlin/pinsDebug.h index 8846dabf2b..495513a893 100644 --- a/Marlin/pinsDebug.h +++ b/Marlin/pinsDebug.h @@ -41,7 +41,7 @@ bool endstop_monitor_flag = false; // first pass - put the name strings into FLASH -#define _ADD_PIN_2(PIN_NAME, ENTRY_NAME) static const unsigned char ENTRY_NAME[] PROGMEM = { PIN_NAME }; +#define _ADD_PIN_2(PIN_NAME, ENTRY_NAME) static const char ENTRY_NAME[] PROGMEM = { PIN_NAME }; #define _ADD_PIN(PIN_NAME, COUNTER) _ADD_PIN_2(PIN_NAME, entry_NAME_##COUNTER) #define REPORT_NAME_DIGITAL(NAME, COUNTER) _ADD_PIN(#NAME, COUNTER) #define REPORT_NAME_ANALOG(NAME, COUNTER) _ADD_PIN(#NAME, COUNTER) @@ -64,12 +64,18 @@ bool endstop_monitor_flag = false; #undef REPORT_NAME_DIGITAL #undef REPORT_NAME_ANALOG -#define _ADD_PIN_2(ENTRY_NAME, NAME, IS_DIGITAL) { (const char*)ENTRY_NAME, (const char*)NAME, (const char*)IS_DIGITAL }, +#define _ADD_PIN_2(ENTRY_NAME, NAME, IS_DIGITAL) { ENTRY_NAME, NAME, IS_DIGITAL }, #define _ADD_PIN(NAME, COUNTER, IS_DIGITAL) _ADD_PIN_2(entry_NAME_##COUNTER, NAME, IS_DIGITAL) -#define REPORT_NAME_DIGITAL(NAME, COUNTER) _ADD_PIN(NAME, COUNTER, (uint8_t)1) -#define REPORT_NAME_ANALOG(NAME, COUNTER) _ADD_PIN(analogInputToDigitalPin(NAME), COUNTER, 0) +#define REPORT_NAME_DIGITAL(NAME, COUNTER) _ADD_PIN(NAME, COUNTER, true) +#define REPORT_NAME_ANALOG(NAME, COUNTER) _ADD_PIN(analogInputToDigitalPin(NAME), COUNTER, false) -const char* const pin_array[][3] PROGMEM = { +typedef struct { + const char * const name; + uint8_t pin; + bool is_digital; +} PinInfo; + +const PinInfo pin_array[] PROGMEM = { /** * [pin name] [pin number] [is digital or analog] 1 = digital, 0 = analog @@ -83,21 +89,19 @@ const char* const pin_array[][3] PROGMEM = { // manually add pins ... #if SERIAL_PORT == 0 #if AVR_ATmega2560_FAMILY - { RXD_NAME, 0, 1 }, - { TXD_NAME, 1, 1 }, + { RXD_NAME, 0, true }, + { TXD_NAME, 1, true }, #elif AVR_ATmega1284_FAMILY - { RXD_NAME, 8, 1 }, - { TXD_NAME, 9, 1 }, + { RXD_NAME, 8, true }, + { TXD_NAME, 9, true }, #endif #endif #include "pinsDebug_list.h" - #line 96 + #line 102 }; -#define n_array (sizeof(pin_array) / sizeof(char*)) / 3 - #define AVR_ATmega2560_FAMILY_PLUS_70 (MOTHERBOARD == BOARD_BQ_ZUM_MEGA_3D \ || MOTHERBOARD == BOARD_MIGHTYBOARD_REVE \ || MOTHERBOARD == BOARD_MINIRAMBO \ @@ -439,12 +443,12 @@ static void print_input_or_output(const bool isout) { } // pretty report with PWM info -inline void report_pin_state_extended(int8_t pin, bool ignore, bool extended = false,const char *start_string = "") { +inline void report_pin_state_extended(int8_t pin, bool ignore, bool extended = false, const char *start_string = "") { uint8_t temp_char; char *name_mem_pointer, buffer[30]; // for the sprintf statements bool found = false, multi_name_pin = false; - for (uint8_t x = 0; x < n_array; x++) { // scan entire array and report all instances of this pin - if (pgm_read_byte(&pin_array[x][1]) == pin) { + for (uint8_t x = 0; x < COUNT(pin_array); x++) { // scan entire array and report all instances of this pin + if (pgm_read_byte(&pin_array[x].pin) == pin) { if (found) multi_name_pin = true; found = true; if (!multi_name_pin) { // report digitial and analog pin number only on the first time through @@ -461,7 +465,7 @@ inline void report_pin_state_extended(int8_t pin, bool ignore, bool extended = f SERIAL_CHAR('.'); SERIAL_ECHO_SP(26 + strlen(start_string)); // add padding if not the first instance found } - name_mem_pointer = (char*)pgm_read_word(&pin_array[x][0]); + name_mem_pointer = (char*)pgm_read_word(&pin_array[x].name); for (uint8_t y = 0; y < 28; y++) { // always print pin name temp_char = pgm_read_byte(name_mem_pointer + y); if (temp_char != 0) @@ -489,7 +493,7 @@ inline void report_pin_state_extended(int8_t pin, bool ignore, bool extended = f else #endif { - if (!(pgm_read_byte(&pin_array[x][2]))) { + if (!(pgm_read_byte(&pin_array[x].is_digital))) { sprintf_P(buffer, PSTR("Analog in = %5d"), analogRead(pin - analogInputToDigitalPin(0))); SERIAL_ECHO(buffer); } From 786cdea124ab8dd5d2fa5b36bd7ed4696aafc81b Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 22 Jun 2017 09:42:48 -0500 Subject: [PATCH 113/180] Ensure REPRAPWORLD_KEYPAD_MOVE_STEP is defined --- Marlin/Conditionals_LCD.h | 3 +++ 1 file changed, 3 insertions(+) diff --git a/Marlin/Conditionals_LCD.h b/Marlin/Conditionals_LCD.h index bd6fc29de9..ea998f2f1e 100644 --- a/Marlin/Conditionals_LCD.h +++ b/Marlin/Conditionals_LCD.h @@ -108,6 +108,9 @@ #if ENABLED(REPRAPWORLD_KEYPAD) #define NEWPANEL + #if ENABLED(ULTIPANEL) && !defined(REPRAPWORLD_KEYPAD_MOVE_STEP) + #define REPRAPWORLD_KEYPAD_MOVE_STEP 1.0 + #endif #endif #if ENABLED(RA_CONTROL_PANEL) From ed04d0b6be8666b661712746ee604defd714bae6 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 22 Jun 2017 08:57:53 -0500 Subject: [PATCH 114/180] Label DualXMode enums --- Marlin/enum.h | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/Marlin/enum.h b/Marlin/enum.h index 764e154cd0..34c5bb68af 100644 --- a/Marlin/enum.h +++ b/Marlin/enum.h @@ -167,10 +167,13 @@ enum LCDViewAction { LCDVIEW_CALL_NO_REDRAW }; +/** + * Dual X Carriage modes. A Dual Nozzle can also do duplication. + */ #if ENABLED(DUAL_X_CARRIAGE) || ENABLED(DUAL_NOZZLE_DUPLICATION_MODE) enum DualXMode { - DXC_FULL_CONTROL_MODE, - DXC_AUTO_PARK_MODE, + DXC_FULL_CONTROL_MODE, // DUAL_X_CARRIAGE only + DXC_AUTO_PARK_MODE, // DUAL_X_CARRIAGE only DXC_DUPLICATION_MODE }; #endif From 5fb0d401eb34984695bfb021fafd31ca6eef8727 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 22 Jun 2017 09:44:39 -0500 Subject: [PATCH 115/180] Formatting tweaks --- Marlin/Marlin_main.cpp | 8 +++++--- Marlin/ultralcd.cpp | 2 +- 2 files changed, 6 insertions(+), 4 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index d5c0cbf81b..a2c0abdb71 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -73,7 +73,7 @@ * "M" Codes * * M0 - Unconditional stop - Wait for user to press a button on the LCD (Only if ULTRA_LCD is enabled) - * M1 - Same as M0 + * M1 -> M0 * M3 - Turn laser/spindle on, set spindle/laser speed/power, set rotation to clockwise * M4 - Turn laser/spindle on, set spindle/laser speed/power, set rotation to counter-clockwise * M5 - Turn laser/spindle off @@ -3270,6 +3270,7 @@ inline void gcode_G0_G1( * G3 X20 Y12 R14 ; CCW circle with r=14 ending at X20 Y12 */ #if ENABLED(ARC_SUPPORT) + inline void gcode_G2_G3(bool clockwise) { if (IsRunning()) { @@ -3318,7 +3319,8 @@ inline void gcode_G0_G1( } } } -#endif + +#endif // ARC_SUPPORT /** * G4: Dwell S or P @@ -12201,7 +12203,7 @@ void prepare_move_to_destination() { #endif HOTEND_LOOP() max_temp = MAX3(max_temp, thermalManager.degHotend(e), thermalManager.degTargetHotend(e)); - bool new_led = (max_temp > 55.0) ? true : (max_temp < 54.0) ? false : red_led; + const bool new_led = (max_temp > 55.0) ? true : (max_temp < 54.0) ? false : red_led; if (new_led != red_led) { red_led = new_led; #if PIN_EXISTS(STAT_LED_RED) diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index 074923e1d3..ed26888db8 100644 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -4001,7 +4001,7 @@ void kill_screen(const char* lcd_msg) { * */ #if ENABLED(REPRAPWORLD_KEYPAD) - void _reprapworld_keypad_move(AxisEnum axis, int16_t dir) { + void _reprapworld_keypad_move(const AxisEnum axis, const int16_t dir) { move_menu_scale = REPRAPWORLD_KEYPAD_MOVE_STEP; encoderPosition = dir; switch (axis) { From 80a232419d866c62c6cac4baf5204afdb352ba18 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 23 Jun 2017 14:28:28 -0500 Subject: [PATCH 116/180] CNC workspace planes and 'P' argument for G2/G3 --- .travis.yml | 4 +- Marlin/Configuration_adv.h | 14 +- Marlin/Marlin_main.cpp | 159 +++++++++++++----- Marlin/enum.h | 8 + .../Cartesio/Configuration_adv.h | 14 +- .../Felix/Configuration_adv.h | 14 +- .../FolgerTech-i3-2020/Configuration_adv.h | 14 +- .../Hephestos/Configuration_adv.h | 14 +- .../Hephestos_2/Configuration_adv.h | 14 +- .../K8200/Configuration_adv.h | 14 +- .../K8400/Configuration_adv.h | 14 +- .../M150/Configuration_adv.h | 14 +- .../RigidBot/Configuration_adv.h | 14 +- .../SCARA/Configuration_adv.h | 14 +- .../TAZ4/Configuration_adv.h | 14 +- .../TinyBoy2/Configuration_adv.h | 14 +- .../WITBOX/Configuration_adv.h | 14 +- .../FLSUN/auto_calibrate/Configuration_adv.h | 14 +- .../FLSUN/kossel_mini/Configuration_adv.h | 14 +- .../delta/generic/Configuration_adv.h | 14 +- .../delta/kossel_mini/Configuration_adv.h | 14 +- .../delta/kossel_pro/Configuration_adv.h | 14 +- .../delta/kossel_xl/Configuration_adv.h | 14 +- .../gCreate_gMax1.5+/Configuration_adv.h | 14 +- .../makibox/Configuration_adv.h | 14 +- .../tvrrug/Round2/Configuration_adv.h | 14 +- .../wt150/Configuration_adv.h | 14 +- 27 files changed, 370 insertions(+), 137 deletions(-) diff --git a/.travis.yml b/.travis.yml index 76edc5f87c..d3ef785f7e 100644 --- a/.travis.yml +++ b/.travis.yml @@ -72,14 +72,14 @@ script: - build_marlin # # Test 2 extruders (one MAX6675) and heated bed on basic RAMPS 1.4 - # plus a "Fix Mounted" Probe with Safe Homing + # plus a "Fix Mounted" Probe with Safe Homing and some arc options # - opt_set MOTHERBOARD BOARD_RAMPS_14_EEB - opt_set EXTRUDERS 2 - opt_set TEMP_SENSOR_0 -2 - opt_set TEMP_SENSOR_1 1 - opt_set TEMP_SENSOR_BED 1 - - opt_enable PIDTEMPBED FIX_MOUNTED_PROBE Z_SAFE_HOMING + - opt_enable PIDTEMPBED FIX_MOUNTED_PROBE Z_SAFE_HOMING ARC_P_CIRCLES CNC_WORKSPACE_PLANES - build_marlin # # ...with AUTO_BED_LEVELING_LINEAR, Z_MIN_PROBE_REPEATABILITY_TEST, and DEBUG_LEVELING_FEATURE diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 0ae9282f05..76ad8bec41 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -678,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 diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index a2c0abdb71..de275d192c 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -54,6 +54,9 @@ * G10 - Retract filament according to settings of M207 * G11 - Retract recover filament according to settings of M208 * G12 - Clean tool + * 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 * G26 - Mesh Validation Pattern (Requires UBL_G26_MESH_VALIDATION) @@ -688,6 +691,10 @@ static bool send_ok[BUFSIZE]; millis_t lastUpdateMillis; #endif +#if ENABLED(CNC_WORKSPACE_PLANES) + static WorkspacePlane workspace_plane = PLANE_XY; +#endif + FORCE_INLINE float pgm_read_any(const float *p) { return pgm_read_float_near(p); } FORCE_INLINE signed char pgm_read_any(const signed char *p) { return pgm_read_byte_near(p); } @@ -3264,6 +3271,9 @@ inline void gcode_G0_G1( * X or Y must differ from the current XY. * Mixing R with I or J will throw an error. * + * - P specifies the number of full circles to do + * before the specified arc move. + * * Examples: * * G2 I10 ; CW circle centered at X+10 @@ -3288,27 +3298,39 @@ inline void gcode_G0_G1( float arc_offset[2] = { 0.0, 0.0 }; if (parser.seen('R')) { const float r = parser.value_linear_units(), - x1 = current_position[X_AXIS], y1 = current_position[Y_AXIS], - x2 = destination[X_AXIS], y2 = destination[Y_AXIS]; - if (r && (x2 != x1 || y2 != y1)) { + p1 = current_position[X_AXIS], q1 = current_position[Y_AXIS], + p2 = destination[X_AXIS], q2 = destination[Y_AXIS]; + if (r && (p2 != p1 || q2 != q1)) { const float e = clockwise ^ (r < 0) ? -1 : 1, // clockwise -1/1, counterclockwise 1/-1 - dx = x2 - x1, dy = y2 - y1, // X and Y differences + dx = p2 - p1, dy = q2 - q1, // X and Y differences d = HYPOT(dx, dy), // Linear distance between the points h = SQRT(sq(r) - sq(d * 0.5)), // Distance to the arc pivot-point - mx = (x1 + x2) * 0.5, my = (y1 + y2) * 0.5, // Point between the two points + mx = (p1 + p2) * 0.5, my = (q1 + q2) * 0.5, // Point between the two points sx = -dy / d, sy = dx / d, // Slope of the perpendicular bisector cx = mx + e * h * sx, cy = my + e * h * sy; // Pivot-point of the arc - arc_offset[X_AXIS] = cx - x1; - arc_offset[Y_AXIS] = cy - y1; + arc_offset[0] = cx - p1; + arc_offset[1] = cy - q1; } } else { - if (parser.seen('I')) arc_offset[X_AXIS] = parser.value_linear_units(); - if (parser.seen('J')) arc_offset[Y_AXIS] = parser.value_linear_units(); + if (parser.seen('I')) arc_offset[0] = parser.value_linear_units(); + if (parser.seen('J')) arc_offset[1] = parser.value_linear_units(); } if (arc_offset[0] || arc_offset[1]) { - // Send an arc to the planner + + #if ENABLED(ARC_P_CIRCLES) + // P indicates number of circles to do + int8_t circles_to_do = parser.seen('P') ? parser.value_byte() : 0; + if (!WITHIN(circles_to_do, 0, 100)) { + SERIAL_ERROR_START(); + SERIAL_ERRORLNPGM(MSG_ERR_ARC_ARGS); + } + while (circles_to_do--) + plan_arc(current_position, arc_offset, clockwise); + #endif + + // Send the arc to the planner plan_arc(destination, arc_offset, clockwise); refresh_cmd_timeout(); } @@ -3408,6 +3430,25 @@ inline void gcode_G4() { } #endif +#if ENABLED(CNC_WORKSPACE_PLANES) + + void report_workspace_plane() { + SERIAL_ECHO_START(); + SERIAL_ECHOPGM("Workspace Plane "); + serialprintPGM(workspace_plane == PLANE_YZ ? PSTR("YZ\n") : workspace_plane == PLANE_ZX ? PSTR("ZX\n") : PSTR("XY\n")); + } + + /** + * G17: Select Plane XY + * G18: Select Plane ZX + * G19: Select Plane YZ + */ + inline void gcode_G17() { workspace_plane = PLANE_XY; } + inline void gcode_G18() { workspace_plane = PLANE_ZX; } + inline void gcode_G19() { workspace_plane = PLANE_YZ; } + +#endif // CNC_WORKSPACE_PLANES + #if ENABLED(INCH_MODE_SUPPORT) /** * G20: Set input mode to inches @@ -3722,6 +3763,10 @@ inline void gcode_G28(const bool always_home_all) { set_bed_leveling_enabled(false); #endif + #if ENABLED(CNC_WORKSPACE_PLANES) + workspace_plane = PLANE_XY; + #endif + // Always home with tool 0 active #if HOTENDS > 1 const uint8_t old_tool_index = active_extruder; @@ -10311,6 +10356,18 @@ void process_next_command() { break; #endif // NOZZLE_CLEAN_FEATURE + #if ENABLED(CNC_WORKSPACE_PLANES) + case 17: // G17: Select Plane XY + gcode_G17(); + break; + case 18: // G18: Select Plane ZX + gcode_G18(); + break; + case 19: // G19: Select Plane YZ + gcode_G19(); + break; + #endif // CNC_WORKSPACE_PLANES + #if ENABLED(INCH_MODE_SUPPORT) case 20: //G20: Inch Mode gcode_G20(); @@ -11922,6 +11979,12 @@ void prepare_move_to_destination() { } #if ENABLED(ARC_SUPPORT) + + #if N_ARC_CORRECTION < 1 + #undef N_ARC_CORRECTION + #define N_ARC_CORRECTION 1 + #endif + /** * Plan an arc in 2 dimensions * @@ -11936,26 +11999,36 @@ void prepare_move_to_destination() { float *offset, // Center of rotation relative to current_position uint8_t clockwise // Clockwise? ) { + #if ENABLED(CNC_WORKSPACE_PLANES) + AxisEnum p_axis, q_axis, l_axis; + switch (workspace_plane) { + case PLANE_XY: p_axis = X_AXIS; q_axis = Y_AXIS; l_axis = Z_AXIS; break; + case PLANE_ZX: p_axis = Z_AXIS; q_axis = X_AXIS; l_axis = Y_AXIS; break; + case PLANE_YZ: p_axis = Y_AXIS; q_axis = Z_AXIS; l_axis = X_AXIS; break; + } + #else + constexpr AxisEnum p_axis = X_AXIS, q_axis = Y_AXIS, l_axis = Z_AXIS; + #endif - float r_X = -offset[X_AXIS], // Radius vector from center to current location - r_Y = -offset[Y_AXIS]; + // Radius vector from center to current location + float r_P = -offset[0], r_Q = -offset[1]; - const float radius = HYPOT(r_X, r_Y), - center_X = current_position[X_AXIS] - r_X, - center_Y = current_position[Y_AXIS] - r_Y, - rt_X = logical[X_AXIS] - center_X, - rt_Y = logical[Y_AXIS] - center_Y, - linear_travel = logical[Z_AXIS] - current_position[Z_AXIS], + const float radius = HYPOT(r_P, r_Q), + center_P = current_position[p_axis] - r_P, + center_Q = current_position[q_axis] - r_Q, + rt_X = logical[p_axis] - center_P, + rt_Y = logical[q_axis] - center_Q, + linear_travel = logical[l_axis] - current_position[l_axis], extruder_travel = logical[E_AXIS] - current_position[E_AXIS]; // CCW angle of rotation between position and target from the circle center. Only one atan2() trig computation required. - float angular_travel = ATAN2(r_X * rt_Y - r_Y * rt_X, r_X * rt_X + r_Y * rt_Y); + float angular_travel = ATAN2(r_P * rt_Y - r_Q * rt_X, r_P * rt_X + r_Q * rt_Y); if (angular_travel < 0) angular_travel += RADIANS(360); if (clockwise) angular_travel -= RADIANS(360); - // Make a circle if the angular rotation is 0 - if (angular_travel == 0 && current_position[X_AXIS] == logical[X_AXIS] && current_position[Y_AXIS] == logical[Y_AXIS]) - angular_travel += RADIANS(360); + // Make a circle if the angular rotation is 0 and the target is current position + if (angular_travel == 0 && current_position[p_axis] == logical[p_axis] && current_position[q_axis] == logical[q_axis]) + angular_travel = RADIANS(360); const float mm_of_travel = HYPOT(angular_travel * radius, FABS(linear_travel)); if (mm_of_travel < 0.001) return; @@ -11998,7 +12071,7 @@ void prepare_move_to_destination() { cos_T = 1 - 0.5 * sq(theta_per_segment); // Small angle approximation // Initialize the linear axis - arc_target[Z_AXIS] = current_position[Z_AXIS]; + arc_target[l_axis] = current_position[l_axis]; // Initialize the extruder axis arc_target[E_AXIS] = current_position[E_AXIS]; @@ -12007,7 +12080,10 @@ void prepare_move_to_destination() { millis_t next_idle_ms = millis() + 200UL; - int8_t count = 0; + #if N_ARC_CORRECTION > 1 + int8_t count = N_ARC_CORRECTION; + #endif + for (uint16_t i = 1; i < segments; i++) { // Iterate (segments-1) times thermalManager.manage_heater(); @@ -12016,28 +12092,33 @@ void prepare_move_to_destination() { idle(); } - if (++count < N_ARC_CORRECTION) { - // Apply vector rotation matrix to previous r_X / 1 - const float r_new_Y = r_X * sin_T + r_Y * cos_T; - r_X = r_X * cos_T - r_Y * sin_T; - r_Y = r_new_Y; - } - else { + #if N_ARC_CORRECTION > 1 + if (--count) { + // Apply vector rotation matrix to previous r_P / 1 + const float r_new_Y = r_P * sin_T + r_Q * cos_T; + r_P = r_P * cos_T - r_Q * sin_T; + r_Q = r_new_Y; + } + else + #endif + { + #if N_ARC_CORRECTION > 1 + count = N_ARC_CORRECTION; + #endif + // Arc correction to radius vector. Computed only every N_ARC_CORRECTION increments. // Compute exact location by applying transformation matrix from initial radius vector(=-offset). // To reduce stuttering, the sin and cos could be computed at different times. // For now, compute both at the same time. - const float cos_Ti = cos(i * theta_per_segment), - sin_Ti = sin(i * theta_per_segment); - r_X = -offset[X_AXIS] * cos_Ti + offset[Y_AXIS] * sin_Ti; - r_Y = -offset[X_AXIS] * sin_Ti - offset[Y_AXIS] * cos_Ti; - count = 0; + const float cos_Ti = cos(i * theta_per_segment), sin_Ti = sin(i * theta_per_segment); + r_P = -offset[0] * cos_Ti + offset[1] * sin_Ti; + r_Q = -offset[0] * sin_Ti - offset[1] * cos_Ti; } // Update arc_target location - arc_target[X_AXIS] = center_X + r_X; - arc_target[Y_AXIS] = center_Y + r_Y; - arc_target[Z_AXIS] += linear_per_segment; + arc_target[p_axis] = center_P + r_P; + arc_target[q_axis] = center_Q + r_Q; + arc_target[l_axis] += linear_per_segment; arc_target[E_AXIS] += extruder_per_segment; clamp_to_software_endstops(arc_target); diff --git a/Marlin/enum.h b/Marlin/enum.h index 34c5bb68af..c3e9ad0121 100644 --- a/Marlin/enum.h +++ b/Marlin/enum.h @@ -178,4 +178,12 @@ enum LCDViewAction { }; #endif +/** + * Workspace planes only apply to G2/G3 moves + * (and "canned cycles" - not a current feature) + */ +#if ENABLED(CNC_WORKSPACE_PLANES) + enum WorkspacePlane { PLANE_XY, PLANE_ZX, PLANE_YZ }; +#endif + #endif // __ENUM_H__ diff --git a/Marlin/example_configurations/Cartesio/Configuration_adv.h b/Marlin/example_configurations/Cartesio/Configuration_adv.h index 7aee917f1f..11bda31e50 100644 --- a/Marlin/example_configurations/Cartesio/Configuration_adv.h +++ b/Marlin/example_configurations/Cartesio/Configuration_adv.h @@ -671,10 +671,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 diff --git a/Marlin/example_configurations/Felix/Configuration_adv.h b/Marlin/example_configurations/Felix/Configuration_adv.h index 0482c91522..d8fb3be6be 100644 --- a/Marlin/example_configurations/Felix/Configuration_adv.h +++ b/Marlin/example_configurations/Felix/Configuration_adv.h @@ -671,10 +671,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 diff --git a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h index d69e55e122..16912fc31f 100644 --- a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h +++ b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h @@ -678,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 diff --git a/Marlin/example_configurations/Hephestos/Configuration_adv.h b/Marlin/example_configurations/Hephestos/Configuration_adv.h index ba118973c0..c5c232d750 100644 --- a/Marlin/example_configurations/Hephestos/Configuration_adv.h +++ b/Marlin/example_configurations/Hephestos/Configuration_adv.h @@ -671,10 +671,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 diff --git a/Marlin/example_configurations/Hephestos_2/Configuration_adv.h b/Marlin/example_configurations/Hephestos_2/Configuration_adv.h index c786d941de..ee5ebd90a4 100644 --- a/Marlin/example_configurations/Hephestos_2/Configuration_adv.h +++ b/Marlin/example_configurations/Hephestos_2/Configuration_adv.h @@ -654,10 +654,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 diff --git a/Marlin/example_configurations/K8200/Configuration_adv.h b/Marlin/example_configurations/K8200/Configuration_adv.h index 1b99078725..974b848022 100644 --- a/Marlin/example_configurations/K8200/Configuration_adv.h +++ b/Marlin/example_configurations/K8200/Configuration_adv.h @@ -684,10 +684,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 diff --git a/Marlin/example_configurations/K8400/Configuration_adv.h b/Marlin/example_configurations/K8400/Configuration_adv.h index 81b5f8bfa0..d0bed6cc49 100644 --- a/Marlin/example_configurations/K8400/Configuration_adv.h +++ b/Marlin/example_configurations/K8400/Configuration_adv.h @@ -671,10 +671,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 diff --git a/Marlin/example_configurations/M150/Configuration_adv.h b/Marlin/example_configurations/M150/Configuration_adv.h index f80078a3c4..8be8497c13 100644 --- a/Marlin/example_configurations/M150/Configuration_adv.h +++ b/Marlin/example_configurations/M150/Configuration_adv.h @@ -678,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 diff --git a/Marlin/example_configurations/RigidBot/Configuration_adv.h b/Marlin/example_configurations/RigidBot/Configuration_adv.h index 8003884c46..8cfe7891cb 100644 --- a/Marlin/example_configurations/RigidBot/Configuration_adv.h +++ b/Marlin/example_configurations/RigidBot/Configuration_adv.h @@ -671,10 +671,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 diff --git a/Marlin/example_configurations/SCARA/Configuration_adv.h b/Marlin/example_configurations/SCARA/Configuration_adv.h index 252d47e1eb..327fa817c9 100644 --- a/Marlin/example_configurations/SCARA/Configuration_adv.h +++ b/Marlin/example_configurations/SCARA/Configuration_adv.h @@ -671,10 +671,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 diff --git a/Marlin/example_configurations/TAZ4/Configuration_adv.h b/Marlin/example_configurations/TAZ4/Configuration_adv.h index ce7846a7eb..17e2f20f0d 100644 --- a/Marlin/example_configurations/TAZ4/Configuration_adv.h +++ b/Marlin/example_configurations/TAZ4/Configuration_adv.h @@ -671,10 +671,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 diff --git a/Marlin/example_configurations/TinyBoy2/Configuration_adv.h b/Marlin/example_configurations/TinyBoy2/Configuration_adv.h index e1d2342c1c..fa05c07d79 100644 --- a/Marlin/example_configurations/TinyBoy2/Configuration_adv.h +++ b/Marlin/example_configurations/TinyBoy2/Configuration_adv.h @@ -674,10 +674,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 diff --git a/Marlin/example_configurations/WITBOX/Configuration_adv.h b/Marlin/example_configurations/WITBOX/Configuration_adv.h index ba118973c0..c5c232d750 100644 --- a/Marlin/example_configurations/WITBOX/Configuration_adv.h +++ b/Marlin/example_configurations/WITBOX/Configuration_adv.h @@ -671,10 +671,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 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 219e1dc305..77a0756cff 100644 --- a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h +++ b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h @@ -676,10 +676,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 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 b7af3e93ad..e37422f910 100644 --- a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h +++ b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h @@ -676,10 +676,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 diff --git a/Marlin/example_configurations/delta/generic/Configuration_adv.h b/Marlin/example_configurations/delta/generic/Configuration_adv.h index 67e62445b1..c6ec4183d5 100644 --- a/Marlin/example_configurations/delta/generic/Configuration_adv.h +++ b/Marlin/example_configurations/delta/generic/Configuration_adv.h @@ -673,10 +673,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 diff --git a/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h index 67e62445b1..c6ec4183d5 100644 --- a/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h @@ -673,10 +673,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 diff --git a/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h index 0cc65d57eb..ed52679ee4 100644 --- a/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h @@ -678,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 diff --git a/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h index f7ea0949e4..0f8eba5360 100644 --- a/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h @@ -673,10 +673,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 diff --git a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration_adv.h b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration_adv.h index 4481edd1fc..8d46562d67 100644 --- a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration_adv.h +++ b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration_adv.h @@ -678,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 diff --git a/Marlin/example_configurations/makibox/Configuration_adv.h b/Marlin/example_configurations/makibox/Configuration_adv.h index d69b043d76..cef8ddd734 100644 --- a/Marlin/example_configurations/makibox/Configuration_adv.h +++ b/Marlin/example_configurations/makibox/Configuration_adv.h @@ -671,10 +671,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 diff --git a/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h b/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h index 9f95e0d763..635c36394e 100644 --- a/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h +++ b/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h @@ -671,10 +671,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 diff --git a/Marlin/example_configurations/wt150/Configuration_adv.h b/Marlin/example_configurations/wt150/Configuration_adv.h index 72f73f7bb4..83c683f053 100644 --- a/Marlin/example_configurations/wt150/Configuration_adv.h +++ b/Marlin/example_configurations/wt150/Configuration_adv.h @@ -674,10 +674,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 From 1e47c17b462bce00fe45c379ff4460d49fcd1c22 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Pawe=C5=82=20Stawicki?= Date: Thu, 15 Jun 2017 16:45:44 +0200 Subject: [PATCH 117/180] Fix: set digipot mcp4018 Vrefmax to 1.666V --- Marlin/digipot_mcp4018.cpp | 8 +- .../wt150/Configuration.h | 29 ++++-- .../wt150/Configuration_adv.h | 95 ++++++++++++++++++- 3 files changed, 118 insertions(+), 14 deletions(-) diff --git a/Marlin/digipot_mcp4018.cpp b/Marlin/digipot_mcp4018.cpp index db8070a73e..06622d057f 100644 --- a/Marlin/digipot_mcp4018.cpp +++ b/Marlin/digipot_mcp4018.cpp @@ -34,17 +34,17 @@ #define DIGIPOT_I2C_ADDRESS 0x2F #define DIGIPOT_A4988_Rsx 0.250 -#define DIGIPOT_A4988_Vrefmax 5.0 +#define DIGIPOT_A4988_Vrefmax 1.666 #define DIGIPOT_A4988_MAX_VALUE 127 #define DIGIPOT_A4988_Itripmax(Vref) ((Vref)/(8.0*DIGIPOT_A4988_Rsx)) #define DIGIPOT_A4988_FACTOR ((DIGIPOT_A4988_MAX_VALUE)/DIGIPOT_A4988_Itripmax(DIGIPOT_A4988_Vrefmax)) -//TODO: MAX_CURRENT -0.5A ?? (currently set to 2A, max possible current 2.5A) -#define DIGIPOT_A4988_MAX_CURRENT (DIGIPOT_A4988_Itripmax(DIGIPOT_A4988_Vrefmax) - 0.5) +#define DIGIPOT_A4988_MAX_CURRENT 2.0 static byte current_to_wiper(const float current) { - return byte(CEIL(float(DIGIPOT_A4988_FACTOR) * current)); + const int16_t value = ceil(float(DIGIPOT_A4988_FACTOR) * current); + return byte(constrain(value, 0, DIGIPOT_A4988_MAX_VALUE)); } const uint8_t sda_pins[DIGIPOT_I2C_NUM_CHANNELS] = { diff --git a/Marlin/example_configurations/wt150/Configuration.h b/Marlin/example_configurations/wt150/Configuration.h index 2ec162abfc..3f62e5aeb1 100644 --- a/Marlin/example_configurations/wt150/Configuration.h +++ b/Marlin/example_configurations/wt150/Configuration.h @@ -58,8 +58,8 @@ //=========================================================================== //============================= DELTA Printer =============================== //=========================================================================== -// For Delta printers start with one of the configuration files in the -// example_configurations/delta directory and customize for your machine. +// For a Delta printer replace the configuration files with the files in the +// example_configurations/delta directory. // //=========================================================================== @@ -311,13 +311,13 @@ // 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 + //WT150, based on: M303 E0 S220 C8 #define DEFAULT_Kp 22.10 #define DEFAULT_Ki 1.10 #define DEFAULT_Kd 110.78 - // 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 @@ -534,6 +534,7 @@ #define DEFAULT_ZJERK 0.4 #define DEFAULT_EJERK 5.0 + //=========================================================================== //============================= Z Probe Options ============================= //=========================================================================== @@ -575,7 +576,7 @@ * Probe Type * * Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, etc. - * Activate one of these to use Auto Bed Leveling below. + * You must activate one of these to use Auto Bed Leveling below. */ /** @@ -1492,7 +1493,23 @@ //define PCA9632 PWM LED driver Support //#define PCA9632 -// Support for an RGB LED using 3 separate pins with optional PWM +/** + * 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) diff --git a/Marlin/example_configurations/wt150/Configuration_adv.h b/Marlin/example_configurations/wt150/Configuration_adv.h index 83c683f053..f52325e9b1 100644 --- a/Marlin/example_configurations/wt150/Configuration_adv.h +++ b/Marlin/example_configurations/wt150/Configuration_adv.h @@ -428,7 +428,7 @@ #define DIGIPOT_MCP4018 // Requires library from https://github.com/stawel/SlowSoftI2CMaster #define DIGIPOT_I2C_NUM_CHANNELS 5 // 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 {0.68, 0.68, 1.18, 1.27, 1.27} +#define DIGIPOT_I2C_MOTOR_CURRENTS {0.22, 0.22, 0.39, 0.42, 0.42} //=========================================================================== //=============================Additional Features=========================== @@ -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 @@ -795,7 +799,7 @@ // 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 10 // Load filament feedrate in mm/s - filament loading into the bowden tube can be fast + #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 @@ -1260,8 +1264,91 @@ #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" + #define USER_DESC_5 "Home & Info" + #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 //=========================================================================== From afbc6e3e2f1741f46c13304d3c660f69999de26c Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 24 Jun 2017 12:37:10 -0500 Subject: [PATCH 118/180] Update DELTA/SCARA config comments --- Marlin/Configuration.h | 8 ++++---- .../CL-260/Configuration.h | 8 ++++---- .../Cartesio/Configuration.h | 6 +++--- .../Felix/Configuration.h | 6 +++--- .../Felix/DUAL/Configuration.h | 6 +++--- .../FolgerTech-i3-2020/Configuration.h | 8 ++++---- .../Hephestos/Configuration.h | 6 +++--- .../Hephestos_2/Configuration.h | 6 +++--- .../K8200/Configuration.h | 6 +++--- .../K8400/Configuration.h | 6 +++--- .../K8400/Dual-head/Configuration.h | 6 +++--- .../M150/Configuration.h | 8 ++++---- .../RepRapWorld/Megatronics/Configuration.h | 6 +++--- .../RigidBot/Configuration.h | 6 +++--- .../SCARA/Configuration.h | 19 ++++++++----------- .../TAZ4/Configuration.h | 6 +++--- .../TinyBoy2/Configuration.h | 6 +++--- .../WITBOX/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 | 8 ++++---- .../makibox/Configuration.h | 6 +++--- .../tvrrug/Round2/Configuration.h | 6 +++--- .../wt150/Configuration.h | 8 ++++---- 29 files changed, 98 insertions(+), 101 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 78aaa2fabe..ece9499328 100644 --- a/Marlin/Configuration.h +++ b/Marlin/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 diff --git a/Marlin/example_configurations/CL-260/Configuration.h b/Marlin/example_configurations/CL-260/Configuration.h index 9692777ef8..aab188098f 100644 --- a/Marlin/example_configurations/CL-260/Configuration.h +++ b/Marlin/example_configurations/CL-260/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 diff --git a/Marlin/example_configurations/Cartesio/Configuration.h b/Marlin/example_configurations/Cartesio/Configuration.h index b3f7c2a11b..d658a7e900 100644 --- a/Marlin/example_configurations/Cartesio/Configuration.h +++ b/Marlin/example_configurations/Cartesio/Configuration.h @@ -58,15 +58,15 @@ //=========================================================================== //============================= DELTA Printer =============================== //=========================================================================== -// For Delta printers start with one of the configuration files in the +// 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 diff --git a/Marlin/example_configurations/Felix/Configuration.h b/Marlin/example_configurations/Felix/Configuration.h index 12790b1d0b..abd4e4ceeb 100644 --- a/Marlin/example_configurations/Felix/Configuration.h +++ b/Marlin/example_configurations/Felix/Configuration.h @@ -58,15 +58,15 @@ //=========================================================================== //============================= DELTA Printer =============================== //=========================================================================== -// For Delta printers start with one of the configuration files in the +// 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 diff --git a/Marlin/example_configurations/Felix/DUAL/Configuration.h b/Marlin/example_configurations/Felix/DUAL/Configuration.h index 63fe048e05..da4cea4db3 100644 --- a/Marlin/example_configurations/Felix/DUAL/Configuration.h +++ b/Marlin/example_configurations/Felix/DUAL/Configuration.h @@ -58,15 +58,15 @@ //=========================================================================== //============================= DELTA Printer =============================== //=========================================================================== -// For Delta printers start with one of the configuration files in the +// 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 diff --git a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h index b55f79b259..126a5b4eff 100644 --- a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h +++ b/Marlin/example_configurations/FolgerTech-i3-2020/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 diff --git a/Marlin/example_configurations/Hephestos/Configuration.h b/Marlin/example_configurations/Hephestos/Configuration.h index 094cfb204f..73c4873e5e 100644 --- a/Marlin/example_configurations/Hephestos/Configuration.h +++ b/Marlin/example_configurations/Hephestos/Configuration.h @@ -58,15 +58,15 @@ //=========================================================================== //============================= DELTA Printer =============================== //=========================================================================== -// For Delta printers start with one of the configuration files in the +// 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 diff --git a/Marlin/example_configurations/Hephestos_2/Configuration.h b/Marlin/example_configurations/Hephestos_2/Configuration.h index 74a715f094..bd29017457 100644 --- a/Marlin/example_configurations/Hephestos_2/Configuration.h +++ b/Marlin/example_configurations/Hephestos_2/Configuration.h @@ -58,15 +58,15 @@ //=========================================================================== //============================= DELTA Printer =============================== //=========================================================================== -// For Delta printers start with one of the configuration files in the +// 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 diff --git a/Marlin/example_configurations/K8200/Configuration.h b/Marlin/example_configurations/K8200/Configuration.h index 64f945a0e8..811d392744 100644 --- a/Marlin/example_configurations/K8200/Configuration.h +++ b/Marlin/example_configurations/K8200/Configuration.h @@ -74,15 +74,15 @@ //=========================================================================== //============================= DELTA Printer =============================== //=========================================================================== -// For Delta printers start with one of the configuration files in the +// 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 diff --git a/Marlin/example_configurations/K8400/Configuration.h b/Marlin/example_configurations/K8400/Configuration.h index 4e06cc1c07..e256b82573 100644 --- a/Marlin/example_configurations/K8400/Configuration.h +++ b/Marlin/example_configurations/K8400/Configuration.h @@ -58,15 +58,15 @@ //=========================================================================== //============================= DELTA Printer =============================== //=========================================================================== -// For Delta printers start with one of the configuration files in the +// 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 diff --git a/Marlin/example_configurations/K8400/Dual-head/Configuration.h b/Marlin/example_configurations/K8400/Dual-head/Configuration.h index 301779ad6c..c05f6c096c 100644 --- a/Marlin/example_configurations/K8400/Dual-head/Configuration.h +++ b/Marlin/example_configurations/K8400/Dual-head/Configuration.h @@ -58,15 +58,15 @@ //=========================================================================== //============================= DELTA Printer =============================== //=========================================================================== -// For Delta printers start with one of the configuration files in the +// 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 diff --git a/Marlin/example_configurations/M150/Configuration.h b/Marlin/example_configurations/M150/Configuration.h index abc640cc92..ab2449b07b 100644 --- a/Marlin/example_configurations/M150/Configuration.h +++ b/Marlin/example_configurations/M150/Configuration.h @@ -63,15 +63,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 diff --git a/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h b/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h index 3d8b999dd1..b6a964fee2 100644 --- a/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h +++ b/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h @@ -58,15 +58,15 @@ //=========================================================================== //============================= DELTA Printer =============================== //=========================================================================== -// For Delta printers start with one of the configuration files in the +// 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 diff --git a/Marlin/example_configurations/RigidBot/Configuration.h b/Marlin/example_configurations/RigidBot/Configuration.h index 2bda3307eb..6b57a22256 100644 --- a/Marlin/example_configurations/RigidBot/Configuration.h +++ b/Marlin/example_configurations/RigidBot/Configuration.h @@ -58,15 +58,15 @@ //=========================================================================== //============================= DELTA Printer =============================== //=========================================================================== -// For Delta printers start with one of the configuration files in the +// 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 diff --git a/Marlin/example_configurations/SCARA/Configuration.h b/Marlin/example_configurations/SCARA/Configuration.h index 78a96445af..190f5ea3c0 100644 --- a/Marlin/example_configurations/SCARA/Configuration.h +++ b/Marlin/example_configurations/SCARA/Configuration.h @@ -55,20 +55,17 @@ * http://www.thingiverse.com/thing:298812 */ -//=========================================================================== -//============================= DELTA Printer =============================== -//=========================================================================== -// For Delta printers start with one of the configuration files in the -// example_configurations/delta directory and customize for your machine. -// - //=========================================================================== //============================= SCARA Printer =============================== //=========================================================================== -// MORGAN_SCARA for Marlin was developed by QHARLEY in ZA in 2012/2013. Implemented -// and slightly reworked by JCERNY in 06/2014 with the goal to bring it into Master-Branch -// QHARLEYS Autobedlevelling has not been ported, because Marlin has now Bed-levelling -// You might need Z-Min endstop on SCARA-Printer to use this feature. Actually untested! + +/** + * MORGAN_SCARA was developed by QHARLEY in South Africa in 2012-2013. + * Implemented and slightly reworked by JCERNY in June, 2014. + * + * MAKERARM_SCARA is in development, included as an alternate example. + * Other SCARA models may be added, or SCARA may be unified in the future. + */ // Specify the specific SCARA model #define MORGAN_SCARA diff --git a/Marlin/example_configurations/TAZ4/Configuration.h b/Marlin/example_configurations/TAZ4/Configuration.h index a34a74cd68..c627f6e125 100644 --- a/Marlin/example_configurations/TAZ4/Configuration.h +++ b/Marlin/example_configurations/TAZ4/Configuration.h @@ -58,15 +58,15 @@ //=========================================================================== //============================= DELTA Printer =============================== //=========================================================================== -// For Delta printers start with one of the configuration files in the +// 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 diff --git a/Marlin/example_configurations/TinyBoy2/Configuration.h b/Marlin/example_configurations/TinyBoy2/Configuration.h index c1e9a615f3..291d036c97 100644 --- a/Marlin/example_configurations/TinyBoy2/Configuration.h +++ b/Marlin/example_configurations/TinyBoy2/Configuration.h @@ -74,15 +74,15 @@ //=========================================================================== //============================= DELTA Printer =============================== //=========================================================================== -// For Delta printers start with one of the configuration files in the +// 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 diff --git a/Marlin/example_configurations/WITBOX/Configuration.h b/Marlin/example_configurations/WITBOX/Configuration.h index b1c97d3527..eabf13892d 100644 --- a/Marlin/example_configurations/WITBOX/Configuration.h +++ b/Marlin/example_configurations/WITBOX/Configuration.h @@ -58,15 +58,15 @@ //=========================================================================== //============================= DELTA Printer =============================== //=========================================================================== -// For Delta printers start with one of the configuration files in the +// 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 diff --git a/Marlin/example_configurations/adafruit/ST7565/Configuration.h b/Marlin/example_configurations/adafruit/ST7565/Configuration.h index 49c98edf5f..544ba40124 100644 --- a/Marlin/example_configurations/adafruit/ST7565/Configuration.h +++ b/Marlin/example_configurations/adafruit/ST7565/Configuration.h @@ -58,15 +58,15 @@ //=========================================================================== //============================= DELTA Printer =============================== //=========================================================================== -// For Delta printers start with one of the configuration files in the +// 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 diff --git a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h index facbfb596c..895ef1266d 100644 --- a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h +++ b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h @@ -58,15 +58,15 @@ //=========================================================================== //============================= DELTA Printer =============================== //=========================================================================== -// For Delta printers start with one of the configuration files in the +// 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 diff --git a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h index ad51210310..0c9f244730 100644 --- a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h +++ b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h @@ -58,15 +58,15 @@ //=========================================================================== //============================= DELTA Printer =============================== //=========================================================================== -// For Delta printers start with one of the configuration files in the +// 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 diff --git a/Marlin/example_configurations/delta/generic/Configuration.h b/Marlin/example_configurations/delta/generic/Configuration.h index 2c3ce91c51..bfb17ff165 100644 --- a/Marlin/example_configurations/delta/generic/Configuration.h +++ b/Marlin/example_configurations/delta/generic/Configuration.h @@ -58,15 +58,15 @@ //=========================================================================== //============================= DELTA Printer =============================== //=========================================================================== -// For Delta printers start with one of the configuration files in the +// 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 diff --git a/Marlin/example_configurations/delta/kossel_mini/Configuration.h b/Marlin/example_configurations/delta/kossel_mini/Configuration.h index ea21701b7b..3a0784f778 100644 --- a/Marlin/example_configurations/delta/kossel_mini/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_mini/Configuration.h @@ -58,15 +58,15 @@ //=========================================================================== //============================= DELTA Printer =============================== //=========================================================================== -// For Delta printers start with one of the configuration files in the +// 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 diff --git a/Marlin/example_configurations/delta/kossel_pro/Configuration.h b/Marlin/example_configurations/delta/kossel_pro/Configuration.h index 97650792fb..bc984f11ba 100644 --- a/Marlin/example_configurations/delta/kossel_pro/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_pro/Configuration.h @@ -62,15 +62,15 @@ //=========================================================================== //============================= DELTA Printer =============================== //=========================================================================== -// For Delta printers start with one of the configuration files in the +// 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 diff --git a/Marlin/example_configurations/delta/kossel_xl/Configuration.h b/Marlin/example_configurations/delta/kossel_xl/Configuration.h index 5d76043335..82cafeadcf 100644 --- a/Marlin/example_configurations/delta/kossel_xl/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_xl/Configuration.h @@ -58,15 +58,15 @@ //=========================================================================== //============================= DELTA Printer =============================== //=========================================================================== -// For Delta printers start with one of the configuration files in the +// 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 diff --git a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h index 400eb6b24e..1259d1b311 100644 --- a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h +++ b/Marlin/example_configurations/gCreate_gMax1.5+/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 diff --git a/Marlin/example_configurations/makibox/Configuration.h b/Marlin/example_configurations/makibox/Configuration.h index c23d4b747a..c5dfa10e69 100644 --- a/Marlin/example_configurations/makibox/Configuration.h +++ b/Marlin/example_configurations/makibox/Configuration.h @@ -58,15 +58,15 @@ //=========================================================================== //============================= DELTA Printer =============================== //=========================================================================== -// For Delta printers start with one of the configuration files in the +// 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 diff --git a/Marlin/example_configurations/tvrrug/Round2/Configuration.h b/Marlin/example_configurations/tvrrug/Round2/Configuration.h index 2ff81f3a1c..f67156d176 100644 --- a/Marlin/example_configurations/tvrrug/Round2/Configuration.h +++ b/Marlin/example_configurations/tvrrug/Round2/Configuration.h @@ -58,15 +58,15 @@ //=========================================================================== //============================= DELTA Printer =============================== //=========================================================================== -// For Delta printers start with one of the configuration files in the +// 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 diff --git a/Marlin/example_configurations/wt150/Configuration.h b/Marlin/example_configurations/wt150/Configuration.h index 3f62e5aeb1..5c581c9e7d 100644 --- a/Marlin/example_configurations/wt150/Configuration.h +++ b/Marlin/example_configurations/wt150/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 From 6c45fa7dcc4d23e35e9984026c4e0c0602344eee Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 24 Jun 2017 13:56:07 -0500 Subject: [PATCH 119/180] Apply #elif in LCD conditionals --- Marlin/Conditionals_LCD.h | 79 +++++++++++++++++++++------------------ 1 file changed, 42 insertions(+), 37 deletions(-) diff --git a/Marlin/Conditionals_LCD.h b/Marlin/Conditionals_LCD.h index ea998f2f1e..33bb7f90d7 100644 --- a/Marlin/Conditionals_LCD.h +++ b/Marlin/Conditionals_LCD.h @@ -31,22 +31,28 @@ #define LCD_HAS_DIRECTIONAL_BUTTONS (BUTTON_EXISTS(UP) || BUTTON_EXISTS(DWN) || BUTTON_EXISTS(LFT) || BUTTON_EXISTS(RT)) #if ENABLED(CARTESIO_UI) + #define DOGLCD #define ULTIPANEL #define NEWPANEL #define DEFAULT_LCD_CONTRAST 90 #define LCD_CONTRAST_MIN 60 #define LCD_CONTRAST_MAX 140 - #endif - #if ENABLED(MAKRPANEL) || ENABLED(MINIPANEL) + #elif ENABLED(MAKRPANEL) || ENABLED(MINIPANEL) + #define DOGLCD #define ULTIPANEL #define NEWPANEL #define DEFAULT_LCD_CONTRAST 17 - #endif - #if ENABLED(miniVIKI) || ENABLED(VIKI2) || ENABLED(ELB_FULL_GRAPHIC_CONTROLLER) + #elif ENABLED(BQ_LCD_SMART_CONTROLLER) + + #define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER + #define LONG_FILENAME_HOST_SUPPORT + + #elif ENABLED(miniVIKI) || ENABLED(VIKI2) || ENABLED(ELB_FULL_GRAPHIC_CONTROLLER) + #define ULTRA_LCD //general LCD support, also 16x2 #define DOGLCD // Support for SPI LCD 128x64 (Controller ST7565R graphic Display Family) #define ULTIMAKERCONTROLLER //as available from the Ultimaker online store. @@ -65,14 +71,28 @@ #define SD_DETECT_INVERTED #endif - #endif + #elif ENABLED(OLED_PANEL_TINYBOY2) - #if ENABLED(OLED_PANEL_TINYBOY2) #define U8GLIB_SSD1306 #define ULTIPANEL #define NEWPANEL #define REVERSE_ENCODER_DIRECTION #define REVERSE_MENU_DIRECTION + + #elif ENABLED(RA_CONTROL_PANEL) + + #define LCD_I2C_TYPE_PCA8574 + #define LCD_I2C_ADDRESS 0x27 // I2C Address of the port expander + #define ULTIPANEL + #define NEWPANEL + + #elif ENABLED(REPRAPWORLD_GRAPHICAL_LCD) + + #define DOGLCD + #define U8GLIB_ST7920 + #define ULTIPANEL + #define NEWPANEL + #endif // Generic support for SSD1306 / SH1106 OLED based LCDs. @@ -85,13 +105,6 @@ #define ULTIMAKERCONTROLLER #endif - #if ENABLED(BQ_LCD_SMART_CONTROLLER) - #define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER - #ifndef LONG_FILENAME_HOST_SUPPORT - #define LONG_FILENAME_HOST_SUPPORT - #endif - #endif - #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) #define DOGLCD #define U8GLIB_ST7920 @@ -113,48 +126,40 @@ #endif #endif - #if ENABLED(RA_CONTROL_PANEL) - #define LCD_I2C_TYPE_PCA8574 - #define LCD_I2C_ADDRESS 0x27 // I2C Address of the port expander - #define ULTIPANEL - #define NEWPANEL - #endif - - #if ENABLED(REPRAPWORLD_GRAPHICAL_LCD) - #define DOGLCD - #define U8GLIB_ST7920 - #define ULTIPANEL - #define NEWPANEL - #endif - /** * I2C PANELS */ #if ENABLED(LCD_I2C_SAINSMART_YWROBOT) + // Note: This controller requires F.Malpartida's LiquidCrystal_I2C library // https://bitbucket.org/fmalpartida/new-liquidcrystal/wiki/Home + #define LCD_I2C_TYPE_PCF8575 #define LCD_I2C_ADDRESS 0x27 // I2C Address of the port expander #define ULTIPANEL #define NEWPANEL - #endif - // PANELOLU2 LCD with status LEDs, separate encoder and click inputs - #if ENABLED(LCD_I2C_PANELOLU2) + #elif ENABLED(LCD_I2C_PANELOLU2) + + // PANELOLU2 LCD with status LEDs, separate encoder and click inputs + #define LCD_I2C_TYPE_MCP23017 #define LCD_I2C_ADDRESS 0x20 // I2C Address of the port expander #define LCD_USE_I2C_BUZZER //comment out to disable buzzer on LCD #define ULTIPANEL #define NEWPANEL - #endif - // Panucatt VIKI LCD with status LEDs, integrated click & L/R/U/P buttons, separate encoder inputs - #if ENABLED(LCD_I2C_VIKI) - // This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 ) - // Make sure the LiquidTWI2 directory is placed in the Arduino or Sketchbook libraries subdirectory. - // Note: The pause/stop/resume LCD button pin should be connected to the Arduino - // BTN_ENC pin (or set BTN_ENC to -1 if not used) + #elif ENABLED(LCD_I2C_VIKI) + + /** + * Panucatt VIKI LCD with status LEDs, integrated click & L/R/U/P buttons, separate encoder inputs + * + * This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 ) + * Make sure the LiquidTWI2 directory is placed in the Arduino or Sketchbook libraries subdirectory. + * Note: The pause/stop/resume LCD button pin should be connected to the Arduino + * BTN_ENC pin (or set BTN_ENC to -1 if not used) + */ #define LCD_I2C_TYPE_MCP23017 #define LCD_I2C_ADDRESS 0x20 // I2C Address of the port expander #define LCD_USE_I2C_BUZZER //comment out to disable buzzer on LCD (requires LiquidTWI2 v1.2.3 or later) From eb314373bb2479e6a32476c1cc579ed27b327728 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 24 Jun 2017 14:32:48 -0500 Subject: [PATCH 120/180] Config spacing & consistency, group custom LCDs --- .../CL-260/Configuration.h | 24 ++++++++-------- .../Cartesio/Configuration.h | 22 +++++++-------- .../Cartesio/Configuration_adv.h | 4 +-- .../Felix/Configuration.h | 22 +++++++-------- .../Felix/Configuration_adv.h | 4 +-- .../Felix/DUAL/Configuration.h | 22 +++++++-------- .../FolgerTech-i3-2020/Configuration.h | 22 +++++++-------- .../FolgerTech-i3-2020/Configuration_adv.h | 4 +-- .../Hephestos/Configuration.h | 22 +++++++-------- .../Hephestos/Configuration_adv.h | 4 +-- .../Hephestos_2/Configuration.h | 22 +++++++-------- .../Hephestos_2/Configuration_adv.h | 4 +-- .../K8200/Configuration.h | 17 +++++++---- .../K8200/Configuration_adv.h | 4 +-- .../K8400/Configuration.h | 22 +++++++-------- .../K8400/Configuration_adv.h | 4 +-- .../K8400/Dual-head/Configuration.h | 22 +++++++-------- .../M150/Configuration.h | 24 ++++++++-------- .../M150/Configuration_adv.h | 4 +-- .../RepRapWorld/Megatronics/Configuration.h | 22 +++++++-------- .../RigidBot/Configuration.h | 22 +++++++-------- .../RigidBot/Configuration_adv.h | 4 +-- .../SCARA/Configuration.h | 22 +++++++-------- .../SCARA/Configuration_adv.h | 4 +-- .../TAZ4/Configuration.h | 22 +++++++-------- .../TAZ4/Configuration_adv.h | 4 +-- .../TinyBoy2/Configuration.h | 17 +++++++---- .../TinyBoy2/Configuration_adv.h | 4 +-- .../WITBOX/Configuration.h | 22 +++++++-------- .../WITBOX/Configuration_adv.h | 4 +-- .../adafruit/ST7565/Configuration.h | 22 +++++++-------- .../FLSUN/auto_calibrate/Configuration.h | 22 +++++++-------- .../FLSUN/auto_calibrate/Configuration_adv.h | 4 +-- .../delta/FLSUN/kossel_mini/Configuration.h | 22 +++++++-------- .../FLSUN/kossel_mini/Configuration_adv.h | 4 +-- .../delta/generic/Configuration.h | 22 +++++++-------- .../delta/generic/Configuration_adv.h | 4 +-- .../delta/kossel_mini/Configuration.h | 22 +++++++-------- .../delta/kossel_mini/Configuration_adv.h | 4 +-- .../delta/kossel_pro/Configuration.h | 22 +++++++-------- .../delta/kossel_pro/Configuration_adv.h | 4 +-- .../delta/kossel_xl/Configuration.h | 22 +++++++-------- .../delta/kossel_xl/Configuration_adv.h | 4 +-- .../gCreate_gMax1.5+/Configuration.h | 28 +++++++++---------- .../gCreate_gMax1.5+/Configuration_adv.h | 4 +-- .../makibox/Configuration.h | 22 +++++++-------- .../makibox/Configuration_adv.h | 4 +-- .../tvrrug/Round2/Configuration.h | 22 +++++++-------- .../tvrrug/Round2/Configuration_adv.h | 4 +-- .../wt150/Configuration.h | 24 ++++++++-------- .../wt150/Configuration_adv.h | 4 +-- 51 files changed, 360 insertions(+), 350 deletions(-) diff --git a/Marlin/example_configurations/CL-260/Configuration.h b/Marlin/example_configurations/CL-260/Configuration.h index aab188098f..6dc34f701e 100644 --- a/Marlin/example_configurations/CL-260/Configuration.h +++ b/Marlin/example_configurations/CL-260/Configuration.h @@ -571,7 +571,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. */ /** @@ -1282,12 +1282,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 @@ -1370,6 +1364,12 @@ // //#define BQ_LCD_SMART_CONTROLLER +// +// Cartesio UI +// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface +// +//#define CARTESIO_UI + // // CONTROLLER TYPE: I2C // @@ -1419,6 +1419,11 @@ // //#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 // @@ -1436,11 +1441,6 @@ // //#define SAV_3DLCD -// -// TinyBoy2 128x64 OLED / Encoder Panel -// -//#define OLED_PANEL_TINYBOY2 - //============================================================================= //=============================== Extra Features ============================== //============================================================================= diff --git a/Marlin/example_configurations/Cartesio/Configuration.h b/Marlin/example_configurations/Cartesio/Configuration.h index d658a7e900..fb59f90cb6 100644 --- a/Marlin/example_configurations/Cartesio/Configuration.h +++ b/Marlin/example_configurations/Cartesio/Configuration.h @@ -1279,12 +1279,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 @@ -1367,6 +1361,12 @@ // //#define BQ_LCD_SMART_CONTROLLER +// +// Cartesio UI +// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface +// +#define CARTESIO_UI + // // CONTROLLER TYPE: I2C // @@ -1416,6 +1416,11 @@ // //#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 // @@ -1433,11 +1438,6 @@ // //#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 11bda31e50..c9a1a4fcaa 100644 --- a/Marlin/example_configurations/Cartesio/Configuration_adv.h +++ b/Marlin/example_configurations/Cartesio/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 /** diff --git a/Marlin/example_configurations/Felix/Configuration.h b/Marlin/example_configurations/Felix/Configuration.h index abd4e4ceeb..19482bdd93 100644 --- a/Marlin/example_configurations/Felix/Configuration.h +++ b/Marlin/example_configurations/Felix/Configuration.h @@ -1263,12 +1263,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 @@ -1351,6 +1345,12 @@ // //#define BQ_LCD_SMART_CONTROLLER +// +// Cartesio UI +// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface +// +//#define CARTESIO_UI + // // CONTROLLER TYPE: I2C // @@ -1400,6 +1400,11 @@ // //#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 // @@ -1417,11 +1422,6 @@ // //#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 d8fb3be6be..c5ccf0e291 100644 --- a/Marlin/example_configurations/Felix/Configuration_adv.h +++ b/Marlin/example_configurations/Felix/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 /** diff --git a/Marlin/example_configurations/Felix/DUAL/Configuration.h b/Marlin/example_configurations/Felix/DUAL/Configuration.h index da4cea4db3..e184862633 100644 --- a/Marlin/example_configurations/Felix/DUAL/Configuration.h +++ b/Marlin/example_configurations/Felix/DUAL/Configuration.h @@ -1263,12 +1263,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 @@ -1351,6 +1345,12 @@ // //#define BQ_LCD_SMART_CONTROLLER +// +// Cartesio UI +// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface +// +//#define CARTESIO_UI + // // CONTROLLER TYPE: I2C // @@ -1400,6 +1400,11 @@ // //#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 // @@ -1417,11 +1422,6 @@ // //#define SAV_3DLCD -// -// TinyBoy2 128x64 OLED / Encoder Panel -// -//#define OLED_PANEL_TINYBOY2 - //============================================================================= //=============================== Extra Features ============================== //============================================================================= diff --git a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h index 126a5b4eff..ec90ea162a 100644 --- a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h +++ b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h @@ -1285,12 +1285,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 @@ -1373,6 +1367,12 @@ // //#define BQ_LCD_SMART_CONTROLLER +// +// Cartesio UI +// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface +// +//#define CARTESIO_UI + // // CONTROLLER TYPE: I2C // @@ -1422,6 +1422,11 @@ // //#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 // @@ -1439,11 +1444,6 @@ // //#define SAV_3DLCD -// -// TinyBoy2 128x64 OLED / Encoder Panel -// -//#define OLED_PANEL_TINYBOY2 - //============================================================================= //=============================== Extra Features ============================== //============================================================================= diff --git a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h index 16912fc31f..9cd215dc9b 100644 --- a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h +++ b/Marlin/example_configurations/FolgerTech-i3-2020/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 /** diff --git a/Marlin/example_configurations/Hephestos/Configuration.h b/Marlin/example_configurations/Hephestos/Configuration.h index 73c4873e5e..a5a749ae8a 100644 --- a/Marlin/example_configurations/Hephestos/Configuration.h +++ b/Marlin/example_configurations/Hephestos/Configuration.h @@ -1271,12 +1271,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 @@ -1359,6 +1353,12 @@ // //#define BQ_LCD_SMART_CONTROLLER +// +// Cartesio UI +// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface +// +//#define CARTESIO_UI + // // CONTROLLER TYPE: I2C // @@ -1408,6 +1408,11 @@ // //#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 // @@ -1425,11 +1430,6 @@ // //#define SAV_3DLCD -// -// TinyBoy2 128x64 OLED / Encoder Panel -// -//#define OLED_PANEL_TINYBOY2 - //============================================================================= //=============================== Extra Features ============================== //============================================================================= diff --git a/Marlin/example_configurations/Hephestos/Configuration_adv.h b/Marlin/example_configurations/Hephestos/Configuration_adv.h index c5c232d750..61d381eada 100644 --- a/Marlin/example_configurations/Hephestos/Configuration_adv.h +++ b/Marlin/example_configurations/Hephestos/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 /** diff --git a/Marlin/example_configurations/Hephestos_2/Configuration.h b/Marlin/example_configurations/Hephestos_2/Configuration.h index bd29017457..e04bca553b 100644 --- a/Marlin/example_configurations/Hephestos_2/Configuration.h +++ b/Marlin/example_configurations/Hephestos_2/Configuration.h @@ -1274,12 +1274,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 @@ -1362,6 +1356,12 @@ // #define BQ_LCD_SMART_CONTROLLER +// +// Cartesio UI +// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface +// +//#define CARTESIO_UI + // // CONTROLLER TYPE: I2C // @@ -1411,6 +1411,11 @@ // //#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 // @@ -1428,11 +1433,6 @@ // //#define SAV_3DLCD -// -// TinyBoy2 128x64 OLED / Encoder Panel -// -//#define OLED_PANEL_TINYBOY2 - //============================================================================= //=============================== Extra Features ============================== //============================================================================= diff --git a/Marlin/example_configurations/Hephestos_2/Configuration_adv.h b/Marlin/example_configurations/Hephestos_2/Configuration_adv.h index ee5ebd90a4..22948c672e 100644 --- a/Marlin/example_configurations/Hephestos_2/Configuration_adv.h +++ b/Marlin/example_configurations/Hephestos_2/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 /** diff --git a/Marlin/example_configurations/K8200/Configuration.h b/Marlin/example_configurations/K8200/Configuration.h index 811d392744..3e53a914ab 100644 --- a/Marlin/example_configurations/K8200/Configuration.h +++ b/Marlin/example_configurations/K8200/Configuration.h @@ -1313,12 +1313,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 +1395,12 @@ // //#define BQ_LCD_SMART_CONTROLLER +// +// Cartesio UI +// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface +// +//#define CARTESIO_UI + // // CONTROLLER TYPE: I2C // @@ -1450,6 +1450,11 @@ // //#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/K8200/Configuration_adv.h b/Marlin/example_configurations/K8200/Configuration_adv.h index 974b848022..a30c0a62d2 100644 --- a/Marlin/example_configurations/K8200/Configuration_adv.h +++ b/Marlin/example_configurations/K8200/Configuration_adv.h @@ -136,8 +136,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 /** diff --git a/Marlin/example_configurations/K8400/Configuration.h b/Marlin/example_configurations/K8400/Configuration.h index e256b82573..b3a0efdda4 100644 --- a/Marlin/example_configurations/K8400/Configuration.h +++ b/Marlin/example_configurations/K8400/Configuration.h @@ -1281,12 +1281,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 @@ -1369,6 +1363,12 @@ // //#define BQ_LCD_SMART_CONTROLLER +// +// Cartesio UI +// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface +// +//#define CARTESIO_UI + // // CONTROLLER TYPE: I2C // @@ -1418,6 +1418,11 @@ // //#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 // @@ -1435,11 +1440,6 @@ // //#define SAV_3DLCD -// -// TinyBoy2 128x64 OLED / Encoder Panel -// -//#define OLED_PANEL_TINYBOY2 - //============================================================================= //=============================== Extra Features ============================== //============================================================================= diff --git a/Marlin/example_configurations/K8400/Configuration_adv.h b/Marlin/example_configurations/K8400/Configuration_adv.h index d0bed6cc49..2c46112f83 100644 --- a/Marlin/example_configurations/K8400/Configuration_adv.h +++ b/Marlin/example_configurations/K8400/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 /** diff --git a/Marlin/example_configurations/K8400/Dual-head/Configuration.h b/Marlin/example_configurations/K8400/Dual-head/Configuration.h index c05f6c096c..6a7578a8ff 100644 --- a/Marlin/example_configurations/K8400/Dual-head/Configuration.h +++ b/Marlin/example_configurations/K8400/Dual-head/Configuration.h @@ -1281,12 +1281,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 @@ -1369,6 +1363,12 @@ // //#define BQ_LCD_SMART_CONTROLLER +// +// Cartesio UI +// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface +// +//#define CARTESIO_UI + // // CONTROLLER TYPE: I2C // @@ -1418,6 +1418,11 @@ // //#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 // @@ -1435,11 +1440,6 @@ // //#define SAV_3DLCD -// -// TinyBoy2 128x64 OLED / Encoder Panel -// -//#define OLED_PANEL_TINYBOY2 - //============================================================================= //=============================== Extra Features ============================== //============================================================================= diff --git a/Marlin/example_configurations/M150/Configuration.h b/Marlin/example_configurations/M150/Configuration.h index ab2449b07b..d46c89bc7d 100644 --- a/Marlin/example_configurations/M150/Configuration.h +++ b/Marlin/example_configurations/M150/Configuration.h @@ -589,7 +589,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. */ /** @@ -1308,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 @@ -1396,6 +1390,12 @@ // //#define BQ_LCD_SMART_CONTROLLER +// +// Cartesio UI +// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface +// +//#define CARTESIO_UI + // // CONTROLLER TYPE: I2C // @@ -1445,6 +1445,11 @@ // //#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 // @@ -1462,11 +1467,6 @@ // //#define SAV_3DLCD -// -// TinyBoy2 128x64 OLED / Encoder Panel -// -//#define OLED_PANEL_TINYBOY2 - //============================================================================= //=============================== Extra Features ============================== //============================================================================= diff --git a/Marlin/example_configurations/M150/Configuration_adv.h b/Marlin/example_configurations/M150/Configuration_adv.h index 8be8497c13..e55f604d6e 100644 --- a/Marlin/example_configurations/M150/Configuration_adv.h +++ b/Marlin/example_configurations/M150/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 /** diff --git a/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h b/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h index b6a964fee2..1e324da607 100644 --- a/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h +++ b/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h @@ -1281,12 +1281,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 @@ -1369,6 +1363,12 @@ // //#define BQ_LCD_SMART_CONTROLLER +// +// Cartesio UI +// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface +// +//#define CARTESIO_UI + // // CONTROLLER TYPE: I2C // @@ -1418,6 +1418,11 @@ // //#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 // @@ -1435,11 +1440,6 @@ // //#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 6b57a22256..bd12ed76f9 100644 --- a/Marlin/example_configurations/RigidBot/Configuration.h +++ b/Marlin/example_configurations/RigidBot/Configuration.h @@ -1279,12 +1279,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 @@ -1369,6 +1363,12 @@ // //#define BQ_LCD_SMART_CONTROLLER +// +// Cartesio UI +// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface +// +//#define CARTESIO_UI + // // CONTROLLER TYPE: I2C // @@ -1418,6 +1418,11 @@ // //#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 // @@ -1435,11 +1440,6 @@ // //#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 8cfe7891cb..046ff52d6a 100644 --- a/Marlin/example_configurations/RigidBot/Configuration_adv.h +++ b/Marlin/example_configurations/RigidBot/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 /** diff --git a/Marlin/example_configurations/SCARA/Configuration.h b/Marlin/example_configurations/SCARA/Configuration.h index 190f5ea3c0..4b95472dbb 100644 --- a/Marlin/example_configurations/SCARA/Configuration.h +++ b/Marlin/example_configurations/SCARA/Configuration.h @@ -1293,12 +1293,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 @@ -1381,6 +1375,12 @@ // //#define BQ_LCD_SMART_CONTROLLER +// +// Cartesio UI +// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface +// +//#define CARTESIO_UI + // // CONTROLLER TYPE: I2C // @@ -1430,6 +1430,11 @@ // //#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 // @@ -1447,11 +1452,6 @@ // //#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 327fa817c9..601dead507 100644 --- a/Marlin/example_configurations/SCARA/Configuration_adv.h +++ b/Marlin/example_configurations/SCARA/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 /** diff --git a/Marlin/example_configurations/TAZ4/Configuration.h b/Marlin/example_configurations/TAZ4/Configuration.h index c627f6e125..48c565fe4e 100644 --- a/Marlin/example_configurations/TAZ4/Configuration.h +++ b/Marlin/example_configurations/TAZ4/Configuration.h @@ -1300,12 +1300,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 @@ -1388,6 +1382,12 @@ // //#define BQ_LCD_SMART_CONTROLLER +// +// Cartesio UI +// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface +// +//#define CARTESIO_UI + // // CONTROLLER TYPE: I2C // @@ -1437,6 +1437,11 @@ // //#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 // @@ -1454,11 +1459,6 @@ // //#define SAV_3DLCD -// -// TinyBoy2 128x64 OLED / Encoder Panel -// -//#define OLED_PANEL_TINYBOY2 - //============================================================================= //=============================== Extra Features ============================== //============================================================================= diff --git a/Marlin/example_configurations/TAZ4/Configuration_adv.h b/Marlin/example_configurations/TAZ4/Configuration_adv.h index 17e2f20f0d..50f67b98e2 100644 --- a/Marlin/example_configurations/TAZ4/Configuration_adv.h +++ b/Marlin/example_configurations/TAZ4/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 /** diff --git a/Marlin/example_configurations/TinyBoy2/Configuration.h b/Marlin/example_configurations/TinyBoy2/Configuration.h index 291d036c97..c3b98ce235 100644 --- a/Marlin/example_configurations/TinyBoy2/Configuration.h +++ b/Marlin/example_configurations/TinyBoy2/Configuration.h @@ -1337,12 +1337,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 @@ -1425,6 +1419,12 @@ // //#define BQ_LCD_SMART_CONTROLLER +// +// Cartesio UI +// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface +// +//#define CARTESIO_UI + // // CONTROLLER TYPE: I2C // @@ -1474,6 +1474,11 @@ // //#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 fa05c07d79..d60392bad2 100644 --- a/Marlin/example_configurations/TinyBoy2/Configuration_adv.h +++ b/Marlin/example_configurations/TinyBoy2/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 /** diff --git a/Marlin/example_configurations/WITBOX/Configuration.h b/Marlin/example_configurations/WITBOX/Configuration.h index eabf13892d..94e68004ff 100644 --- a/Marlin/example_configurations/WITBOX/Configuration.h +++ b/Marlin/example_configurations/WITBOX/Configuration.h @@ -1271,12 +1271,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 @@ -1359,6 +1353,12 @@ // //#define BQ_LCD_SMART_CONTROLLER +// +// Cartesio UI +// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface +// +//#define CARTESIO_UI + // // CONTROLLER TYPE: I2C // @@ -1408,6 +1408,11 @@ // //#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 // @@ -1425,11 +1430,6 @@ // //#define SAV_3DLCD -// -// TinyBoy2 128x64 OLED / Encoder Panel -// -//#define OLED_PANEL_TINYBOY2 - //============================================================================= //=============================== Extra Features ============================== //============================================================================= diff --git a/Marlin/example_configurations/WITBOX/Configuration_adv.h b/Marlin/example_configurations/WITBOX/Configuration_adv.h index c5c232d750..61d381eada 100644 --- a/Marlin/example_configurations/WITBOX/Configuration_adv.h +++ b/Marlin/example_configurations/WITBOX/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 /** diff --git a/Marlin/example_configurations/adafruit/ST7565/Configuration.h b/Marlin/example_configurations/adafruit/ST7565/Configuration.h index 544ba40124..aed973a9a0 100644 --- a/Marlin/example_configurations/adafruit/ST7565/Configuration.h +++ b/Marlin/example_configurations/adafruit/ST7565/Configuration.h @@ -1281,12 +1281,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 @@ -1369,6 +1363,12 @@ // //#define BQ_LCD_SMART_CONTROLLER +// +// Cartesio UI +// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface +// +//#define CARTESIO_UI + // // CONTROLLER TYPE: I2C // @@ -1418,6 +1418,11 @@ // //#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 // @@ -1435,11 +1440,6 @@ // //#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 895ef1266d..053f92fa59 100644 --- a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h +++ b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h @@ -1402,12 +1402,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 @@ -1490,6 +1484,12 @@ // //#define BQ_LCD_SMART_CONTROLLER +// +// Cartesio UI +// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface +// +//#define CARTESIO_UI + // // CONTROLLER TYPE: I2C // @@ -1539,6 +1539,11 @@ // //#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 // @@ -1556,11 +1561,6 @@ // //#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 77a0756cff..fd23ac779d 100644 --- a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h +++ b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/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 /** diff --git a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h index 0c9f244730..7a3a870af6 100644 --- a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h +++ b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h @@ -1403,12 +1403,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 @@ -1491,6 +1485,12 @@ // //#define BQ_LCD_SMART_CONTROLLER +// +// Cartesio UI +// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface +// +//#define CARTESIO_UI + // // CONTROLLER TYPE: I2C // @@ -1540,6 +1540,11 @@ // //#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 // @@ -1557,11 +1562,6 @@ // //#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 e37422f910..6900bc812f 100644 --- a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h +++ b/Marlin/example_configurations/delta/FLSUN/kossel_mini/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 /** diff --git a/Marlin/example_configurations/delta/generic/Configuration.h b/Marlin/example_configurations/delta/generic/Configuration.h index bfb17ff165..befd585f98 100644 --- a/Marlin/example_configurations/delta/generic/Configuration.h +++ b/Marlin/example_configurations/delta/generic/Configuration.h @@ -1392,12 +1392,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 @@ -1480,6 +1474,12 @@ // //#define BQ_LCD_SMART_CONTROLLER +// +// Cartesio UI +// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface +// +//#define CARTESIO_UI + // // CONTROLLER TYPE: I2C // @@ -1529,6 +1529,11 @@ // //#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 // @@ -1546,11 +1551,6 @@ // //#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 c6ec4183d5..497ae82463 100644 --- a/Marlin/example_configurations/delta/generic/Configuration_adv.h +++ b/Marlin/example_configurations/delta/generic/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 /** diff --git a/Marlin/example_configurations/delta/kossel_mini/Configuration.h b/Marlin/example_configurations/delta/kossel_mini/Configuration.h index 3a0784f778..694de7ca25 100644 --- a/Marlin/example_configurations/delta/kossel_mini/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_mini/Configuration.h @@ -1395,12 +1395,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 @@ -1483,6 +1477,12 @@ // //#define BQ_LCD_SMART_CONTROLLER +// +// Cartesio UI +// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface +// +//#define CARTESIO_UI + // // CONTROLLER TYPE: I2C // @@ -1532,6 +1532,11 @@ // //#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 // @@ -1549,11 +1554,6 @@ // //#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 c6ec4183d5..497ae82463 100644 --- a/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_mini/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 /** diff --git a/Marlin/example_configurations/delta/kossel_pro/Configuration.h b/Marlin/example_configurations/delta/kossel_pro/Configuration.h index bc984f11ba..24476bbd02 100644 --- a/Marlin/example_configurations/delta/kossel_pro/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_pro/Configuration.h @@ -1400,12 +1400,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 @@ -1488,6 +1482,12 @@ // //#define BQ_LCD_SMART_CONTROLLER +// +// Cartesio UI +// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface +// +//#define CARTESIO_UI + // // CONTROLLER TYPE: I2C // @@ -1537,6 +1537,11 @@ // //#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 // @@ -1554,11 +1559,6 @@ // //#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 ed52679ee4..20ee8ed5a3 100644 --- a/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h @@ -128,8 +128,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 /** diff --git a/Marlin/example_configurations/delta/kossel_xl/Configuration.h b/Marlin/example_configurations/delta/kossel_xl/Configuration.h index 82cafeadcf..84bfd7f03f 100644 --- a/Marlin/example_configurations/delta/kossel_xl/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_xl/Configuration.h @@ -1458,12 +1458,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 @@ -1546,6 +1540,12 @@ // //#define BQ_LCD_SMART_CONTROLLER +// +// Cartesio UI +// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface +// +//#define CARTESIO_UI + // // CONTROLLER TYPE: I2C // @@ -1595,6 +1595,11 @@ // //#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 // @@ -1612,11 +1617,6 @@ // //#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 0f8eba5360..5b7c5df696 100644 --- a/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_xl/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 /** diff --git a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h index 1259d1b311..f55d5d3379 100644 --- a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h +++ b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h @@ -582,10 +582,10 @@ //#define Z_MIN_PROBE_ENDSTOP /** - * Probe Type + * 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. + * Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, etc. + * Activate one of these to use Auto Bed Leveling below. */ /** @@ -1297,12 +1297,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 @@ -1385,6 +1379,12 @@ // //#define BQ_LCD_SMART_CONTROLLER +// +// Cartesio UI +// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface +// +//#define CARTESIO_UI + // // CONTROLLER TYPE: I2C // @@ -1434,6 +1434,11 @@ // //#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 // @@ -1451,11 +1456,6 @@ // //#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 8d46562d67..18f63570d5 100644 --- a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration_adv.h +++ b/Marlin/example_configurations/gCreate_gMax1.5+/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 /** diff --git a/Marlin/example_configurations/makibox/Configuration.h b/Marlin/example_configurations/makibox/Configuration.h index c5dfa10e69..968eebe0d9 100644 --- a/Marlin/example_configurations/makibox/Configuration.h +++ b/Marlin/example_configurations/makibox/Configuration.h @@ -1284,12 +1284,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 @@ -1372,6 +1366,12 @@ // //#define BQ_LCD_SMART_CONTROLLER +// +// Cartesio UI +// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface +// +//#define CARTESIO_UI + // // CONTROLLER TYPE: I2C // @@ -1421,6 +1421,11 @@ // //#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 // @@ -1438,11 +1443,6 @@ // //#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 cef8ddd734..f1a18f02f1 100644 --- a/Marlin/example_configurations/makibox/Configuration_adv.h +++ b/Marlin/example_configurations/makibox/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 /** diff --git a/Marlin/example_configurations/tvrrug/Round2/Configuration.h b/Marlin/example_configurations/tvrrug/Round2/Configuration.h index f67156d176..0e366f01f3 100644 --- a/Marlin/example_configurations/tvrrug/Round2/Configuration.h +++ b/Marlin/example_configurations/tvrrug/Round2/Configuration.h @@ -1276,12 +1276,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 @@ -1364,6 +1358,12 @@ // //#define BQ_LCD_SMART_CONTROLLER +// +// Cartesio UI +// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface +// +//#define CARTESIO_UI + // // CONTROLLER TYPE: I2C // @@ -1413,6 +1413,11 @@ // //#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 // @@ -1430,11 +1435,6 @@ // //#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 635c36394e..dd9573c3bf 100644 --- a/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h +++ b/Marlin/example_configurations/tvrrug/Round2/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 /** diff --git a/Marlin/example_configurations/wt150/Configuration.h b/Marlin/example_configurations/wt150/Configuration.h index 5c581c9e7d..c0d602f830 100644 --- a/Marlin/example_configurations/wt150/Configuration.h +++ b/Marlin/example_configurations/wt150/Configuration.h @@ -576,7 +576,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. */ /** @@ -1287,12 +1287,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 @@ -1375,6 +1369,12 @@ // //#define BQ_LCD_SMART_CONTROLLER +// +// Cartesio UI +// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface +// +//#define CARTESIO_UI + // // CONTROLLER TYPE: I2C // @@ -1424,6 +1424,11 @@ // //#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 // @@ -1441,11 +1446,6 @@ // //#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 f52325e9b1..4c3d4d02b8 100644 --- a/Marlin/example_configurations/wt150/Configuration_adv.h +++ b/Marlin/example_configurations/wt150/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 /** From 9651d01e1a3f59a6bf5d5324f315b86c6c9d1bd7 Mon Sep 17 00:00:00 2001 From: Bob-the-Kuhn Date: Sat, 10 Jun 2017 00:12:18 -0500 Subject: [PATCH 121/180] Add Skynet/ANET A10 support --- Marlin/Conditionals_LCD.h | 15 + Marlin/SanityCheck.h | 5 +- Marlin/boards.h | 1 + .../Anet/Configuration.h | 1607 +++++++++++++++++ .../Anet/Configuration_adv.h | 1349 ++++++++++++++ .../CL-260/Configuration.h | 10 + .../Cartesio/Configuration.h | 10 + .../Felix/Configuration.h | 10 + .../Felix/DUAL/Configuration.h | 10 + .../FolgerTech-i3-2020/Configuration.h | 10 + .../Hephestos/Configuration.h | 10 + .../Hephestos_2/Configuration.h | 10 + .../K8200/Configuration.h | 10 + .../K8400/Configuration.h | 10 + .../K8400/Dual-head/Configuration.h | 10 + .../M150/Configuration.h | 10 + .../RepRapWorld/Megatronics/Configuration.h | 10 + .../RigidBot/Configuration.h | 10 + .../SCARA/Configuration.h | 10 + .../TAZ4/Configuration.h | 10 + .../TinyBoy2/Configuration.h | 10 + .../WITBOX/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 + Marlin/pins.h | 2 + Marlin/pinsDebug.h | 5 + Marlin/pinsDebug_list.h | 3 + Marlin/pins_ANET_10.h | 274 +++ Marlin/temperature.cpp | 30 +- Marlin/temperature.h | 8 + Marlin/ultralcd.cpp | 120 +- Marlin/ultralcd.h | 20 +- 41 files changed, 3709 insertions(+), 10 deletions(-) create mode 100644 Marlin/example_configurations/Anet/Configuration.h create mode 100644 Marlin/example_configurations/Anet/Configuration_adv.h create mode 100644 Marlin/pins_ANET_10.h diff --git a/Marlin/Conditionals_LCD.h b/Marlin/Conditionals_LCD.h index 33bb7f90d7..28937590d5 100644 --- a/Marlin/Conditionals_LCD.h +++ b/Marlin/Conditionals_LCD.h @@ -46,6 +46,21 @@ #define NEWPANEL #define DEFAULT_LCD_CONTRAST 17 + #elif ENABLED(ANET_KEYPAD_LCD) + + #define REPRAPWORLD_KEYPAD + #define REPRAPWORLD_KEYPAD_MOVE_STEP 10.0 + #define ADC_KEYPAD + #define ADC_KEY_NUM 8 + #define ULTIPANEL + // this helps to implement ADC_KEYPAD menus + #define ENCODER_STEPS_PER_MENU_ITEM 1 + #define REVERSE_MENU_DIRECTION + + #elif ENABLED(ANET_FULL_GRAPHICS_LCD) + + #define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER + #elif ENABLED(BQ_LCD_SMART_CONTROLLER) #define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER diff --git a/Marlin/SanityCheck.h b/Marlin/SanityCheck.h index de5c041577..f12d37b440 100644 --- a/Marlin/SanityCheck.h +++ b/Marlin/SanityCheck.h @@ -1102,7 +1102,7 @@ static_assert(1 >= 0 #if ENABLED(MINIPANEL) + 1 #endif - #if ENABLED(REPRAPWORLD_KEYPAD) && DISABLED(CARTESIO_UI) + #if ENABLED(REPRAPWORLD_KEYPAD) && DISABLED(CARTESIO_UI) && DISABLED(ANET_KEYPAD_LCD) + 1 #endif #if ENABLED(RIGIDBOT_PANEL) @@ -1138,6 +1138,9 @@ static_assert(1 >= 0 #if ENABLED(OLED_PANEL_TINYBOY2) + 1 #endif + #if ENABLED(ANET_KEYPAD_LCD) + + 1 + #endif , "Please select no more than one LCD controller option." ); diff --git a/Marlin/boards.h b/Marlin/boards.h index 1ce5a21401..13c9ab8871 100644 --- a/Marlin/boards.h +++ b/Marlin/boards.h @@ -59,6 +59,7 @@ #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) #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) diff --git a/Marlin/example_configurations/Anet/Configuration.h b/Marlin/example_configurations/Anet/Configuration.h new file mode 100644 index 0000000000..ac16115306 --- /dev/null +++ b/Marlin/example_configurations/Anet/Configuration.h @@ -0,0 +1,1607 @@ +/** + * 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 replace the configuration files with the files in the +// example_configurations/delta directory. +// + +//=========================================================================== +//============================= SCARA Printer =============================== +//=========================================================================== +// For a Scara printer replace the configuration files with the files in the +// example_configurations/SCARA directory. +// + +// @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 "(Bob Kuhn, Anet 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 "Marlin " SHORT_BUILD_VERSION // 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_ANET_10 +#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 + +// 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 +#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 6 // (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 6 // (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 130 + +//=========================================================================== +//============================= 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 15 // If the temperature difference between the target temperature and the actual temperature + // is more than PID_FUNCTIONAL_RANGE then the PID will be shut off and the heater will be set to min/max. + #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 21.0 + //#define DEFAULT_Ki 1.25 + //#define DEFAULT_Kd 86.0 + + // 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 + + // ANET A8 Standard Extruder at 210 Degree Celsius and 100% Fan + //(measured after M106 S255 with M303 E0 S210 C8) + #define DEFAULT_Kp 21.0 + #define DEFAULT_Ki 1.25 + #define DEFAULT_Kd 86.0 + +#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 true // set to true to invert the logic of the endstop. +#define Y_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. +#define Z_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. +#define X_MAX_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop. +#define Y_MAX_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop. +#define Z_MAX_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop. +#define Z_MIN_PROBE_ENDSTOP_INVERTING true // 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 {100, 100, 400, 95} + +/** + * Default Max Feed Rate (mm/s) + * Override with M203 + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] + */ +#define DEFAULT_MAX_FEEDRATE {400, 400, 8, 50} + +/** + * Default Max Acceleration (change/s) change = mm/s + * (Maximum start speed for accelerated moves) + * Override with M201 + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] + */ +#define DEFAULT_MAX_ACCELERATION {2000, 2000, 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 400 // X, Y, Z and E acceleration for printing moves +#define DEFAULT_RETRACT_ACCELERATION 1000 // E acceleration for retracts +#define DEFAULT_TRAVEL_ACCELERATION 1000 // X, Y, Z acceleration for travel (non printing) moves + +/** + * Default Jerk (mm/s) + * 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.3 +#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 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 0 // X offset: -left +right [of the nozzle] +#define Y_PROBE_OFFSET_FROM_EXTRUDER 0 // 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 6000 + +// 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 true + +// 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 + +// Travel limits after homing (units are in mm) +#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 Z_MAX_POS 240 + +// 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 190 + #define FRONT_PROBE_BED_POSITION 15 + #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 20 + #define ABL_PROBE_PT_1_Y 160 + #define ABL_PROBE_PT_2_X 20 + #define ABL_PROBE_PT_2_Y 10 + #define ABL_PROBE_PT_3_X 180 + #define ABL_PROBE_PT_3_Y 10 + +#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 (100*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) + // 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 + +// +// 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 190 +#define PREHEAT_1_TEMP_BED 60 +#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_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, 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':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' } + */ +#define LCD_LANGUAGE en + +/** + * 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 +// +// Note: Details on connecting to the Anet V1.0 controller are in the file pins_ANET_10.h +// +//#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). + +// +// 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 +// +//#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 + +// +// TinyBoy2 128x64 OLED / Encoder Panel +// +//#define OLED_PANEL_TINYBOY2 + +// +// 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 + +//============================================================================= +//=============================== 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 + +//define BlinkM/CyzRgb Support +//#define BLINKM + +//define PCA9632 PWM LED driver Support +//#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 3.00 // (mm) Diameter of the filament generally used (3.0 or 1.75mm), also used in the slicer. Used to validate sensor reading. + +#if ENABLED(FILAMENT_WIDTH_SENSOR) + #define FILAMENT_SENSOR_EXTRUDER_NUM 0 // Index of the extruder that has the filament sensor (0,1,2,3) + #define MEASUREMENT_DELAY_CM 14 // (cm) The distance from the filament sensor to the melting chamber + + #define MEASURED_UPPER_LIMIT 3.30 // (mm) Upper limit used to validate sensor reading + #define MEASURED_LOWER_LIMIT 1.90 // (mm) Lower limit used to validate sensor reading + #define MAX_MEASUREMENT_DELAY 20 // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM. + + #define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially + + // Display filament width on the LCD status line. Status messages will expire after 5 seconds. + //#define FILAMENT_LCD_DISPLAY +#endif + +#endif // CONFIGURATION_H diff --git a/Marlin/example_configurations/Anet/Configuration_adv.h b/Marlin/example_configurations/Anet/Configuration_adv.h new file mode 100644 index 0000000000..d41f1d2082 --- /dev/null +++ b/Marlin/example_configurations/Anet/Configuration_adv.h @@ -0,0 +1,1349 @@ +/** + * 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 60 // Seconds + #define THERMAL_PROTECTION_HYSTERESIS 10 // 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 60 // Seconds + #define THERMAL_PROTECTION_BED_HYSTERESIS 5 // 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 180 // 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 // can be defined here or in the pins_XXX.h file for your board + // pins_XXX.h file overrides this one + #define INVERT_CASE_LIGHT false // set to true if case light is ON when pin is at 0 + #define CASE_LIGHT_DEFAULT_ON true // set default power up state to on or off + #define CASE_LIGHT_DEFAULT_BRIGHTNESS 105 // set power up brightness 0-255 ( only used if on PWM + // and if CASE_LIGHT_DEFAULT is set to on + //#define MENU_ITEM_CASE_LIGHT // Uncomment to have a Case Light entry in 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 command 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 Prusa Slic3r) 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 (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)) +#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)) + + // 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 + +// Arc interpretation settings: +//#define ARC_SUPPORT // Disabling this saves ~2738 bytes +#define MM_PER_ARC_SEGMENT 1 +#define N_ARC_CORRECTION 25 + +// 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 fwretract + +// Firmware based and LCD controlled retract +// M207 and M208 can be used to define parameters for the retraction. +// The retraction can be called by the slicer using G10 and G11 +// until then, intended retractions can be detected by moves that only extrude and the direction. +// the moves are than replaced by the firmware controlled ones. + +//#define FWRETRACT //ONLY PARTIALLY TESTED +#if ENABLED(FWRETRACT) + #define MIN_RETRACT 0.1 //minimum extruded mm to accept a automatic gcode retraction attempt + #define RETRACT_LENGTH 3 //default retract length (positive mm) + #define RETRACT_LENGTH_SWAP 13 //default swap retract length (positive mm), for extruder change + #define RETRACT_FEEDRATE 45 //default feedrate for retracting (mm/s) + #define RETRACT_ZLIFT 0 //default retract Z-lift + #define RETRACT_RECOVER_LENGTH 0 //default additional recover length (mm, added to retract length when recovering) + #define RETRACT_RECOVER_LENGTH_SWAP 0 //default additional swap recover length (mm, added to retract length when recovering from extruder change) + #define RETRACT_RECOVER_FEEDRATE 8 //default feedrate for recovering from retraction (mm/s) +#endif + +/** + * 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 +#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_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 + +//=========================================================================== +//============================ 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 + +#endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/CL-260/Configuration.h b/Marlin/example_configurations/CL-260/Configuration.h index 6dc34f701e..90da7b05f8 100644 --- a/Marlin/example_configurations/CL-260/Configuration.h +++ b/Marlin/example_configurations/CL-260/Configuration.h @@ -1370,6 +1370,16 @@ // //#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). + // // CONTROLLER TYPE: I2C // diff --git a/Marlin/example_configurations/Cartesio/Configuration.h b/Marlin/example_configurations/Cartesio/Configuration.h index fb59f90cb6..0d84d53bfc 100644 --- a/Marlin/example_configurations/Cartesio/Configuration.h +++ b/Marlin/example_configurations/Cartesio/Configuration.h @@ -1367,6 +1367,16 @@ // #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). + // // CONTROLLER TYPE: I2C // diff --git a/Marlin/example_configurations/Felix/Configuration.h b/Marlin/example_configurations/Felix/Configuration.h index 19482bdd93..d3e288c054 100644 --- a/Marlin/example_configurations/Felix/Configuration.h +++ b/Marlin/example_configurations/Felix/Configuration.h @@ -1351,6 +1351,16 @@ // //#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). + // // CONTROLLER TYPE: I2C // diff --git a/Marlin/example_configurations/Felix/DUAL/Configuration.h b/Marlin/example_configurations/Felix/DUAL/Configuration.h index e184862633..ad8553a945 100644 --- a/Marlin/example_configurations/Felix/DUAL/Configuration.h +++ b/Marlin/example_configurations/Felix/DUAL/Configuration.h @@ -1351,6 +1351,16 @@ // //#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). + // // CONTROLLER TYPE: I2C // diff --git a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h index ec90ea162a..13892b2771 100644 --- a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h +++ b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h @@ -1373,6 +1373,16 @@ // //#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). + // // CONTROLLER TYPE: I2C // diff --git a/Marlin/example_configurations/Hephestos/Configuration.h b/Marlin/example_configurations/Hephestos/Configuration.h index a5a749ae8a..153e6028db 100644 --- a/Marlin/example_configurations/Hephestos/Configuration.h +++ b/Marlin/example_configurations/Hephestos/Configuration.h @@ -1359,6 +1359,16 @@ // //#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). + // // CONTROLLER TYPE: I2C // diff --git a/Marlin/example_configurations/Hephestos_2/Configuration.h b/Marlin/example_configurations/Hephestos_2/Configuration.h index e04bca553b..2864c04b0c 100644 --- a/Marlin/example_configurations/Hephestos_2/Configuration.h +++ b/Marlin/example_configurations/Hephestos_2/Configuration.h @@ -1362,6 +1362,16 @@ // //#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). + // // CONTROLLER TYPE: I2C // diff --git a/Marlin/example_configurations/K8200/Configuration.h b/Marlin/example_configurations/K8200/Configuration.h index 3e53a914ab..05a6c11a89 100644 --- a/Marlin/example_configurations/K8200/Configuration.h +++ b/Marlin/example_configurations/K8200/Configuration.h @@ -1401,6 +1401,16 @@ // //#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). + // // CONTROLLER TYPE: I2C // diff --git a/Marlin/example_configurations/K8400/Configuration.h b/Marlin/example_configurations/K8400/Configuration.h index b3a0efdda4..ec265fcc95 100644 --- a/Marlin/example_configurations/K8400/Configuration.h +++ b/Marlin/example_configurations/K8400/Configuration.h @@ -1369,6 +1369,16 @@ // //#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). + // // CONTROLLER TYPE: I2C // diff --git a/Marlin/example_configurations/K8400/Dual-head/Configuration.h b/Marlin/example_configurations/K8400/Dual-head/Configuration.h index 6a7578a8ff..9b60e17404 100644 --- a/Marlin/example_configurations/K8400/Dual-head/Configuration.h +++ b/Marlin/example_configurations/K8400/Dual-head/Configuration.h @@ -1369,6 +1369,16 @@ // //#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). + // // CONTROLLER TYPE: I2C // diff --git a/Marlin/example_configurations/M150/Configuration.h b/Marlin/example_configurations/M150/Configuration.h index d46c89bc7d..d47a8526a7 100644 --- a/Marlin/example_configurations/M150/Configuration.h +++ b/Marlin/example_configurations/M150/Configuration.h @@ -1396,6 +1396,16 @@ // //#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). + // // CONTROLLER TYPE: I2C // diff --git a/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h b/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h index 1e324da607..b008062b30 100644 --- a/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h +++ b/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h @@ -1369,6 +1369,16 @@ // //#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). + // // CONTROLLER TYPE: I2C // diff --git a/Marlin/example_configurations/RigidBot/Configuration.h b/Marlin/example_configurations/RigidBot/Configuration.h index bd12ed76f9..b05d00937f 100644 --- a/Marlin/example_configurations/RigidBot/Configuration.h +++ b/Marlin/example_configurations/RigidBot/Configuration.h @@ -1369,6 +1369,16 @@ // //#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). + // // CONTROLLER TYPE: I2C // diff --git a/Marlin/example_configurations/SCARA/Configuration.h b/Marlin/example_configurations/SCARA/Configuration.h index 4b95472dbb..06c2a32300 100644 --- a/Marlin/example_configurations/SCARA/Configuration.h +++ b/Marlin/example_configurations/SCARA/Configuration.h @@ -1381,6 +1381,16 @@ // //#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). + // // CONTROLLER TYPE: I2C // diff --git a/Marlin/example_configurations/TAZ4/Configuration.h b/Marlin/example_configurations/TAZ4/Configuration.h index 48c565fe4e..86d9c1bd87 100644 --- a/Marlin/example_configurations/TAZ4/Configuration.h +++ b/Marlin/example_configurations/TAZ4/Configuration.h @@ -1388,6 +1388,16 @@ // //#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). + // // CONTROLLER TYPE: I2C // diff --git a/Marlin/example_configurations/TinyBoy2/Configuration.h b/Marlin/example_configurations/TinyBoy2/Configuration.h index c3b98ce235..4ecc19dc7f 100644 --- a/Marlin/example_configurations/TinyBoy2/Configuration.h +++ b/Marlin/example_configurations/TinyBoy2/Configuration.h @@ -1425,6 +1425,16 @@ // //#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). + // // CONTROLLER TYPE: I2C // diff --git a/Marlin/example_configurations/WITBOX/Configuration.h b/Marlin/example_configurations/WITBOX/Configuration.h index 94e68004ff..cd4df35ecb 100644 --- a/Marlin/example_configurations/WITBOX/Configuration.h +++ b/Marlin/example_configurations/WITBOX/Configuration.h @@ -1359,6 +1359,16 @@ // //#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). + // // CONTROLLER TYPE: I2C // diff --git a/Marlin/example_configurations/adafruit/ST7565/Configuration.h b/Marlin/example_configurations/adafruit/ST7565/Configuration.h index aed973a9a0..dd458267d9 100644 --- a/Marlin/example_configurations/adafruit/ST7565/Configuration.h +++ b/Marlin/example_configurations/adafruit/ST7565/Configuration.h @@ -1369,6 +1369,16 @@ // //#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). + // // CONTROLLER TYPE: I2C // diff --git a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h index 053f92fa59..66bd78c4c8 100644 --- a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h +++ b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h @@ -1490,6 +1490,16 @@ // //#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). + // // CONTROLLER TYPE: I2C // diff --git a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h index 7a3a870af6..f3d95861b7 100644 --- a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h +++ b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h @@ -1491,6 +1491,16 @@ // //#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). + // // CONTROLLER TYPE: I2C // diff --git a/Marlin/example_configurations/delta/generic/Configuration.h b/Marlin/example_configurations/delta/generic/Configuration.h index befd585f98..009e879192 100644 --- a/Marlin/example_configurations/delta/generic/Configuration.h +++ b/Marlin/example_configurations/delta/generic/Configuration.h @@ -1480,6 +1480,16 @@ // //#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). + // // CONTROLLER TYPE: I2C // diff --git a/Marlin/example_configurations/delta/kossel_mini/Configuration.h b/Marlin/example_configurations/delta/kossel_mini/Configuration.h index 694de7ca25..840f03f9d6 100644 --- a/Marlin/example_configurations/delta/kossel_mini/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_mini/Configuration.h @@ -1483,6 +1483,16 @@ // //#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). + // // CONTROLLER TYPE: I2C // diff --git a/Marlin/example_configurations/delta/kossel_pro/Configuration.h b/Marlin/example_configurations/delta/kossel_pro/Configuration.h index 24476bbd02..84ba273231 100644 --- a/Marlin/example_configurations/delta/kossel_pro/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_pro/Configuration.h @@ -1488,6 +1488,16 @@ // //#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). + // // CONTROLLER TYPE: I2C // diff --git a/Marlin/example_configurations/delta/kossel_xl/Configuration.h b/Marlin/example_configurations/delta/kossel_xl/Configuration.h index 84bfd7f03f..76ffbbcd6c 100644 --- a/Marlin/example_configurations/delta/kossel_xl/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_xl/Configuration.h @@ -1546,6 +1546,16 @@ // //#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). + // // CONTROLLER TYPE: I2C // diff --git a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h index f55d5d3379..97348c1792 100644 --- a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h +++ b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h @@ -1385,6 +1385,16 @@ // //#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). + // // CONTROLLER TYPE: I2C // diff --git a/Marlin/example_configurations/makibox/Configuration.h b/Marlin/example_configurations/makibox/Configuration.h index 968eebe0d9..dfe778b3b4 100644 --- a/Marlin/example_configurations/makibox/Configuration.h +++ b/Marlin/example_configurations/makibox/Configuration.h @@ -1372,6 +1372,16 @@ // //#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). + // // CONTROLLER TYPE: I2C // diff --git a/Marlin/example_configurations/tvrrug/Round2/Configuration.h b/Marlin/example_configurations/tvrrug/Round2/Configuration.h index 0e366f01f3..ab56d7eb03 100644 --- a/Marlin/example_configurations/tvrrug/Round2/Configuration.h +++ b/Marlin/example_configurations/tvrrug/Round2/Configuration.h @@ -1364,6 +1364,16 @@ // //#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). + // // CONTROLLER TYPE: I2C // diff --git a/Marlin/example_configurations/wt150/Configuration.h b/Marlin/example_configurations/wt150/Configuration.h index c0d602f830..a023c3f169 100644 --- a/Marlin/example_configurations/wt150/Configuration.h +++ b/Marlin/example_configurations/wt150/Configuration.h @@ -1375,6 +1375,16 @@ // //#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). + // // CONTROLLER TYPE: I2C // diff --git a/Marlin/pins.h b/Marlin/pins.h index 0b43a7a1ca..2a0b92aa93 100644 --- a/Marlin/pins.h +++ b/Marlin/pins.h @@ -107,6 +107,8 @@ #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) diff --git a/Marlin/pinsDebug.h b/Marlin/pinsDebug.h index 495513a893..3e978ecb85 100644 --- a/Marlin/pinsDebug.h +++ b/Marlin/pinsDebug.h @@ -129,6 +129,11 @@ const PinInfo pin_array[] PROGMEM = { bool get_pinMode(int8_t pin) {return *portModeRegister(digitalPinToPort_DEBUG(pin)) & digitalPinToBitMask_DEBUG(pin); } #endif +#if defined(__AVR_ATmega1284P__) // 1284 IDE extensions set this to the number of + #undef NUM_DIGITAL_PINS // digital only pins while all other CPUs have it + #define NUM_DIGITAL_PINS 32 // set to digital only + digital/analog +#endif + #define PWM_PRINT(V) do{ sprintf_P(buffer, PSTR("PWM: %4d"), V); SERIAL_ECHO(buffer); }while(0) #define PWM_CASE(N,Z) \ case TIMER##N##Z: \ diff --git a/Marlin/pinsDebug_list.h b/Marlin/pinsDebug_list.h index 9164b6b418..b4cc4c29f8 100644 --- a/Marlin/pinsDebug_list.h +++ b/Marlin/pinsDebug_list.h @@ -29,6 +29,9 @@ #line 0 // set __LINE__ to a known value for both passes +#if PIN_EXISTS(ADC_KEYPAD) && ADC_KEYPAD_PIN < NUM_ANALOG_INPUTS + REPORT_NAME_ANALOG(ADC_KEYPAD_PIN, __LINE__ ) +#endif #if defined(__FD) && __FD >= 0 REPORT_NAME_DIGITAL(__FD, __LINE__ ) #endif diff --git a/Marlin/pins_ANET_10.h b/Marlin/pins_ANET_10.h new file mode 100644 index 0000000000..cf97170bcd --- /dev/null +++ b/Marlin/pins_ANET_10.h @@ -0,0 +1,274 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (C) 2017 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (C) 2011 Camiel Gubbels / Erik van der Zalm + * + * This program is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * This program is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with this program. If not, see . + * + */ + +/** + * Anet V1.0 board pin assignments + */ + +/** + * Rev B 16 JUN 2017 + * + * 1) no longer uses Sanguino files to define some of the pins + * 2) added pointers to useable Arduino IDE extensions + * + */ + +/** + * The standard Arduino IDE extension (board manager) for this board + * is located at https://github.com/SkyNet3D/anet-board. + * + * Installation instructions are on that page. + * + * After copying the files to the appropriate location, restart Arduino and + * you'll see "Anet V1.0" and "Anet V1.0 (Optiboot)" in the boards list. + * + * "Anet V1.0" uses the bootloader that was installed on the board when + * it shipped from the factory. + * + * "Anet V1.0 (Optiboot)" frees up another 3K of FLASH. You'll need to burn + * a new bootloader to the board to be able to automatically download a + * compiled image. + * + */ + +/** + * Another usable Arduino IDE extension (board manager) can be found at + * https://github.com/Lauszus/Sanguino + * + * This extension has been tested on Arduino 1.6.12 & 1.8.0 + * + * Here's the JSON path: + * https://raw.githubusercontent.com/Lauszus/Sanguino/master/package_lauszus_sanguino_index.json + * + * When installing select 1.0.2 + * + * Installation instructions can be found at https://learn.sparkfun.com/pages/CustomBoardsArduino + * Just use the above JSON URL instead of Sparkfun's JSON. + * + * Once installed select the Sanguino board and then select the CPU. + * + */ + +/** + * To burn a new bootloader: + * + * 1. Connect your programmer to the board. + * 2. In the Arduino IDE select the board and then select the programmer. + * 3. In the Arduino IDE click on "burn bootloader". Don't worry about the "verify failed at 1F000" error message. + * 4. The programmer is no longer needed. Remove it. + */ + +/** + * Additional info: + * + * Anet Schematics - https://github.com/ralf-e/ANET-3D-Board-V1.0 + * Wiring RRDFG Smart Controller - http://www.thingiverse.com/thing:2103748 + * SkyNet3D Anet software development - https://github.com/SkyNet3D/Marlin/ + * Anet Users / Skynet SW on Facebook - https://www.facebook.com/skynet3ddevelopment/ + * + * Many thanks to Hans Raaf (@oderwat) for developing the Anet-specific software and supporting the Anet community. +*/ + +#if !defined(__AVR_ATmega1284P__) + #error "Oops! Make sure you have 'Anet V1.0', 'Anet V1.0 (Optiboot)' or 'Sanguino' selected from the 'Tools -> Boards' menu." +#endif + +#ifndef BOARD_NAME + #define BOARD_NAME "Anet" +#endif + +#define LARGE_FLASH true + +// +// Limit Switches +// +#define X_STOP_PIN 18 +#define Y_STOP_PIN 19 +#define Z_STOP_PIN 20 + +// +// Steppers +// +#define X_STEP_PIN 15 +#define X_DIR_PIN 21 +#define X_ENABLE_PIN 14 + +#define Y_STEP_PIN 22 +#define Y_DIR_PIN 23 +#define Y_ENABLE_PIN 14 + +#define Z_STEP_PIN 3 +#define Z_DIR_PIN 2 +#define Z_ENABLE_PIN 26 + +#define E0_STEP_PIN 1 +#define E0_DIR_PIN 0 +#define E0_ENABLE_PIN 14 + +// +// Temperature Sensors +// +#define TEMP_0_PIN 7 // Analog Input (pin 33 extruder) +#define TEMP_BED_PIN 6 // Analog Input (pin 34 bed) + +// +// Heaters / Fans +// +#define HEATER_0_PIN 13 // (extruder) +#define HEATER_BED_PIN 12 // (bed) +#define FAN_PIN 4 + +// +// Misc. Functions +// +#define SDSS 31 +#define LED_PIN -1 + +/** + * LCD / Controller + * + * Only the following displays are supported: + * ANET_KEYPAD_LCD + * ANET_FULL_GRAPHICS_LCD + * REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER +*/ + +#if ENABLED(ULTRA_LCD) && ENABLED(NEWPANEL) + #define LCD_SDSS 28 + #if ENABLED(ADC_KEYPAD) + #define SERVO0_PIN 27 // free for BLTouch/3D-Touch + #define LCD_PINS_RS 28 + #define LCD_PINS_ENABLE 29 + #define LCD_PINS_D4 10 + #define LCD_PINS_D5 11 + #define LCD_PINS_D6 16 + #define LCD_PINS_D7 17 + #define BTN_EN1 -1 + #define BTN_EN2 -1 + #define BTN_ENC -1 + #define ADC_KEYPAD_PIN 1 + #define ENCODER_FEEDRATE_DEADZONE 2 + #elif ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) || ENABLED(ANET_FULL_GRAPHICS_LCD) + // Pin definitions for the Anet A6 Full Graphics display and the RepRapDiscount Full Graphics + // display using an adapter board // https://go.aisler.net/benlye/anet-lcd-adapter/pcb + // See below for alternative pin definitions for use with https://www.thingiverse.com/thing:2103748 + #define SERVO0_PIN 29 // free for BLTouch/3D-Touch + #define BEEPER_PIN 17 + #define LCD_PINS_RS 27 + #define LCD_PINS_ENABLE 28 + #define LCD_PINS_D4 30 + #define BTN_EN1 11 + #define BTN_EN2 10 + #define BTN_ENC 16 + #define ST7920_DELAY_1 DELAY_0_NOP + #define ST7920_DELAY_2 DELAY_1_NOP + #define ST7920_DELAY_3 DELAY_2_NOP + #ifndef ENCODER_STEPS_PER_MENU_ITEM + #define ENCODER_STEPS_PER_MENU_ITEM 1 + #endif + #ifndef ENCODER_PULSES_PER_STEP + #define ENCODER_PULSES_PER_STEP 4 + #endif + #endif +#endif // ULTRA_LCD && NEWPANEL + +/** + * ==================================================================== + * =============== Alternative RepRapDiscount Wiring ================== + * ==================================================================== + * + * An alternative wiring scheme for the RepRapDiscount Full Graphics Display is + * published by oderwat on Thingiverse at https://www.thingiverse.com/thing:2103748. + * + * Using that adapter requires changing the pin definition as follows: + * #define SERVO0_PIN 27 // free for BLTouch/3D-Touch + * #define BEEPER_PIN 28 + * #define LCD_PINS_RS 30 + * #define LCD_PINS_ENABLE 29 + * #define LCD_PINS_D4 17 + * + * The BLTouch pin becomes LCD:3 + */ + +/** + * ==================================================================== + * ===================== LCD PINOUTS ================================== + * ==================================================================== + * + * Anet V1.0 controller | ANET_KEYPAD_LCD | ANET_FULL_ | RepRapDiscount Full | Thingiverse RepRap wiring + * physical logical alt | | GRAPHICS_LCD | Graphics Display Wiring | http://www.thingiverse + * pin pin functions | | | | .com/thing:2103748 + *------------------------------------------------------------------------------------------------------------------------ + * ANET-J3.1 8 *** | N/A | J3_TX *** | | + * ANET-J3.2 9 *** | N/A | J3_RX *** | | + * ANET-J3.3 6 MISO | N/A | MISO *** | EXP2.1 MISO | EXP2.1 MISO + * ANET-J3.4 +5V | N/A | +5V | | + * ANET-J3.5 7 SCK | N/A | SCK *** | EXP2.2 SCK | EXP2.2 SCK + * ANET-J3.6 5 MOSI | N/A | MOSI *** | EXP2.6 MOSI | EXP2.6 MOSI + * ANET-J3.7 !RESET | N/A | button | EXP2.8 panel button | EXP2.8 panel button + * ANET-J3.8 GND | N/A | GND | EXP2.9 GND | EXP2.9 GND + * ANET-J3.9 4 Don't use | N/A | N/C | | + * ANET-J3.10 +3.3V | N/A | +3.3V *** | | + * | | | | + * | | | | + * ANET-LCD.1 GND | GND | GND | EXP1.9 GND | EXP1.9 GND + * ANET-LCD.2 +5V | +5V | +5V | EXP1.10 +5V | EXP1.10 +5V + * ANET-LCD.3 27 A4 | N/C * | LCD_PINS_RS | EXP1.4 LCD_PINS_RS | EXP2.4 SDSS or N/C * + * ANET-LCD.4 10 | LCD_PINS_D4 | BTN_EN2 | EXP2.3 BTN_EN2 | EXP2.3 BTN_EN2 + * ANET-LCD.5 28 A3 | LCD_PINS_RS | LCD_PINS_ENABLE | EXP1.3 LCD_PINS_ENABLE | EXP1.1 BEEPER_PIN + * ANET-LCD.6 11 | LCD_PINS_D5 | BTN_EN1 | EXP2.5 BTN_EN1 | EXP2.5 BTN_EN1 + * ANET-LCD.7 29 A2 | LCD_PINS_ENABLE | N/C * | EXP2.4 SDSS or N/C * | EXP1.3 LCD_PINS_ENABLE + * ANET-LCD.8 16 SCL | LCD_PINS_D6 | BTN_ENC | EXP1.2 BTN_ENC | EXP1.2 BTN_ENC + * ANET-LCD.9 30 A1 | ADC_KEYPAD_PIN ** | LCD_PINS_D4 | EXP1.5 LCD_PINS_D4 | EXP1.4 LCD_PINS_RS + * ANET-LCD.10 17 SDA | LCD_PINS_D7 | BEEPER_PIN | EXP1.1 BEEPER_PIN | EXP1.5 LCD_PINS_D4 + * + * N/C * - if not connected to the LCD can be used for BLTouch servo input + * ** - analog pin -WITHOUT a pullup + * *** - only connected to something if the Bluetooth module is populated + */ + +/** + * REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER + * physical pin function + * EXP1.1 BEEPER + * EXP1.2 BTN_ENC + * EXP1.3 LCD_PINS_ENABLE + * EXP1.4 LCD_PINS_RS + * EXP1.5 LCD_PINS_D4 + * EXP1.6 LCD_PINS_D5 (not used) + * EXP1.7 LCD_PINS_D6 (not used) + * EXP1.8 LCD_PINS_D7 (not used) + * EXP1.9 GND + * EXP1.10 VCC + * + * + * EXP2.1 MISO + * EXP2.2 SCK + * EXP2.3 BTN_EN2 + * EXP2.4 SDSS + * EXP2.5 BTN_EN1 + * EXP2.6 MOSI + * EXP2.7 SD_DETECT_PIN + * EXP2.8 button + * EXP2.9 GND + * EXP2.10 NC + */ diff --git a/Marlin/temperature.cpp b/Marlin/temperature.cpp index 6111bab442..a4fdcf985c 100644 --- a/Marlin/temperature.cpp +++ b/Marlin/temperature.cpp @@ -212,6 +212,11 @@ uint8_t Temperature::soft_pwm_amount[HOTENDS], #endif #endif +#if ENABLED(ADC_KEYPAD) + uint32_t Temperature::current_ADCKey_raw = 0; + uint8_t Temperature::ADCKey_count = 0; +#endif + #if HAS_PID_HEATING void Temperature::PID_autotune(float temp, int hotend, int ncycles, bool set_result/*=false*/) { @@ -1625,6 +1630,9 @@ void Temperature::isr() { static uint8_t pwm_count = _BV(SOFT_PWM_SCALE); // avoid multiple loads of pwm_count uint8_t pwm_count_tmp = pwm_count; + #if ENABLED(ADC_KEYPAD) + static unsigned int raw_ADCKey_value = 0; + #endif // Static members for each heater #if ENABLED(SLOW_PWM_HEATERS) @@ -1997,9 +2005,29 @@ void Temperature::isr() { raw_filwidth_value -= (raw_filwidth_value >> 7); // Subtract 1/128th of the raw_filwidth_value raw_filwidth_value += ((unsigned long)ADC << 7); // Add new ADC reading, scaled by 128 } - break; + break; #endif + #if ENABLED(ADC_KEYPAD) + case Prepare_ADC_KEY: + START_ADC(ADC_KEYPAD_PIN); + break; + case Measure_ADC_KEY: + if (ADCKey_count < 16) { + raw_ADCKey_value = ADC; + if (raw_ADCKey_value > 900) { + //ADC Key release + ADCKey_count = 0; + current_ADCKey_raw = 0; + } + else { + current_ADCKey_raw += raw_ADCKey_value; + ADCKey_count++; + } + } + break; + #endif // ADC_KEYPAD + case StartupDelay: break; } // switch(adc_sensor_state) diff --git a/Marlin/temperature.h b/Marlin/temperature.h index 60a85684a2..6ce644d88e 100644 --- a/Marlin/temperature.h +++ b/Marlin/temperature.h @@ -81,6 +81,10 @@ enum ADCSensorState { Prepare_FILWIDTH, Measure_FILWIDTH, #endif + #if ENABLED(ADC_KEYPAD) + Prepare_ADC_KEY, + Measure_ADC_KEY, + #endif SensorsReady, // Temperatures ready. Delay the next round of readings to let ADC pins settle. StartupDelay // Startup, delay initial temp reading a tiny bit so the hardware can settle }; @@ -272,6 +276,10 @@ class Temperature { #endif public: + #if ENABLED(ADC_KEYPAD) + static uint32_t current_ADCKey_raw; + static uint8_t ADCKey_count; + #endif /** * Instance Methods diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index ed26888db8..808b6df49f 100644 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -3997,10 +3997,53 @@ void kill_screen(const char* lcd_msg) { /** * - * Handlers for RepRap World Keypad input + * Handlers for Keypad input * */ - #if ENABLED(REPRAPWORLD_KEYPAD) + #if ENABLED(ADC_KEYPAD) + + inline void handle_adc_keypad() { + static uint8_t adc_steps = 0; + if (buttons_reprapworld_keypad) { + adc_steps++; + NOMORE(adc_steps, 20); + + lcd_quick_feedback(); + lcdDrawUpdate = LCDVIEW_REDRAW_NOW; + return_to_status_ms = millis() + LCD_TIMEOUT_TO_STATUS; + if (encoderDirection == -1) { // side effect which signals we are inside a menu + if (buttons_reprapworld_keypad & EN_REPRAPWORLD_KEYPAD_DOWN) + encoderPosition -= ENCODER_STEPS_PER_MENU_ITEM; + else if (buttons_reprapworld_keypad & EN_REPRAPWORLD_KEYPAD_UP) + encoderPosition += ENCODER_STEPS_PER_MENU_ITEM; + else if (buttons_reprapworld_keypad & EN_REPRAPWORLD_KEYPAD_LEFT) + menu_action_back(); + else if (buttons_reprapworld_keypad & EN_REPRAPWORLD_KEYPAD_RIGHT) + // enqueue_and_echo_commands_P(PSTR("M0 Pause")); + lcd_return_to_status(); + } + else { + const int8_t step = adc_steps > 19 ? 100 : adc_steps > 10 ? 10 : 1; + if (buttons_reprapworld_keypad & EN_REPRAPWORLD_KEYPAD_DOWN) + encoderPosition += ENCODER_PULSES_PER_STEP * step; + else if (buttons_reprapworld_keypad & EN_REPRAPWORLD_KEYPAD_UP) + encoderPosition -= ENCODER_PULSES_PER_STEP * step; + else if (buttons_reprapworld_keypad & EN_REPRAPWORLD_KEYPAD_RIGHT) + encoderPosition = 0; + } + #if ENABLED(ADC_KEYPAD_DEBUG) + SERIAL_PROTOCOLLNPAIR("buttons_reprapworld_keypad = ", (uint32_t)buttons_reprapworld_keypad); + SERIAL_PROTOCOLLNPAIR("encoderPosition = ", (uint32_t)encoderPosition); + #endif + } + else if (!thermalManager.current_ADCKey_raw) { + // reset stepping acceleration + adc_steps = 0; + } + } + + #elif ENABLED(REPRAPWORLD_KEYPAD) + void _reprapworld_keypad_move(const AxisEnum axis, const int16_t dir) { move_menu_scale = REPRAPWORLD_KEYPAD_MOVE_STEP; encoderPosition = dir; @@ -4111,7 +4154,7 @@ void lcd_init() { SET_INPUT_PULLUP(BTN_ENC); #endif - #if ENABLED(REPRAPWORLD_KEYPAD) + #if ENABLED(REPRAPWORLD_KEYPAD) && DISABLED(ADC_KEYPAD) SET_OUTPUT(SHIFT_CLK); OUT_WRITE(SHIFT_LD, HIGH); SET_INPUT_PULLUP(SHIFT_OUT); @@ -4291,8 +4334,14 @@ void lcd_update() { slow_buttons = lcd_implementation_read_slow_buttons(); // buttons which take too long to read in interrupt context #endif - #if ENABLED(REPRAPWORLD_KEYPAD) + #if ENABLED(ADC_KEYPAD) + + handle_adc_keypad(); + + #elif ENABLED(REPRAPWORLD_KEYPAD) + handle_reprapworld_keypad(); + #endif bool encoderPastThreshold = (abs(encoderDiff) >= ENCODER_PULSES_PER_STEP); @@ -4305,10 +4354,10 @@ void lcd_update() { if (encoderRateMultiplierEnabled) { int32_t encoderMovementSteps = abs(encoderDiff) / ENCODER_PULSES_PER_STEP; - if (lastEncoderMovementMillis != 0) { + if (lastEncoderMovementMillis) { // Note that the rate is always calculated between two passes through the // loop and that the abs of the encoderDiff value is tracked. - float encoderStepRate = (float)(encoderMovementSteps) / ((float)(ms - lastEncoderMovementMillis)) * 1000.0; + float encoderStepRate = float(encoderMovementSteps) / float(ms - lastEncoderMovementMillis) * 1000.0; if (encoderStepRate >= ENCODER_100X_STEPS_PER_SEC) encoderMultiplier = 100; else if (encoderStepRate >= ENCODER_10X_STEPS_PER_SEC) encoderMultiplier = 10; @@ -4378,6 +4427,11 @@ void lcd_update() { break; } // switch } + + #if ENABLED(ADC_KEYPAD) + buttons_reprapworld_keypad = 0; + #endif + #if ENABLED(ULTIPANEL) #define CURRENTSCREEN() (*currentScreen)(), lcd_clicked = false #else @@ -4625,9 +4679,23 @@ void lcd_reset_alert_level() { lcd_status_message_level = 0; } #if ENABLED(LCD_HAS_SLOW_BUTTONS) buttons |= slow_buttons; #endif - #if ENABLED(REPRAPWORLD_KEYPAD) + + #if ENABLED(ADC_KEYPAD) + + uint8_t newbutton_reprapworld_keypad = 0; + buttons = 0; + if (buttons_reprapworld_keypad == 0) { + newbutton_reprapworld_keypad = get_ADC_keyValue(); + if (WITHIN(newbutton_reprapworld_keypad, 1, 8)) + buttons_reprapworld_keypad = _BV(newbutton_reprapworld_keypad - 1); + } + + #elif ENABLED(REPRAPWORLD_KEYPAD) + GET_BUTTON_STATES(buttons_reprapworld_keypad); + #endif + #else GET_BUTTON_STATES(buttons); #endif // !NEWPANEL @@ -4693,4 +4761,42 @@ void lcd_reset_alert_level() { lcd_status_message_level = 0; } #endif // ULTIPANEL +#if ENABLED(ADC_KEYPAD) + + typedef struct { + uint16_t ADCKeyValueMin, ADCKeyValueMax; + uint8_t ADCKeyNo; + } _stADCKeypadTable_; + + static const _stADCKeypadTable_ stADCKeyTable[] = PROGMEM { + // VALUE_MIN, VALUE_MAX, KEY + { 4000, 4096, BLEN_REPRAPWORLD_KEYPAD_F1 + 1 }, // F1 + { 4000, 4096, BLEN_REPRAPWORLD_KEYPAD_F2 + 1 }, // F2 + { 4000, 4096, BLEN_REPRAPWORLD_KEYPAD_F3 + 1 }, // F3 + { 300, 500, BLEN_REPRAPWORLD_KEYPAD_LEFT + 1 }, // LEFT + { 1900, 2200, BLEN_REPRAPWORLD_KEYPAD_RIGHT + 1 }, // RIGHT + { 570, 870, BLEN_REPRAPWORLD_KEYPAD_UP + 1 }, // UP + { 2670, 2870, BLEN_REPRAPWORLD_KEYPAD_DOWN + 1 }, // DOWN + { 1150, 1450, BLEN_REPRAPWORLD_KEYPAD_MIDDLE + 1 }, // ENTER + }; + + uint8_t get_ADC_keyValue(void) { + if (thermalManager.ADCKey_count >= 16) { + const uint16_t currentkpADCValue = thermalManager.current_ADCKey_raw >> 2; + #if ENABLED(ADC_KEYPAD_DEBUG) + SERIAL_PROTOCOLLN(currentkpADCValue); + #endif + thermalManager.current_ADCKey_raw = 0; + thermalManager.ADCKey_count = 0; + if (currentkpADCValue < 4000) + for (uint8_t i = 0; i < ADC_KEY_NUM; i++) { + const uint16_t lo = pgm_read_word(&stADCKeyTable[i].ADCKeyValueMin), + hi = pgm_read_word(&stADCKeyTable[i].ADCKeyValueMax); + if (WITHIN(currentkpADCValue, lo, hi)) return pgm_read_byte(&stADCKeyTable[i].ADCKeyNo); + } + } + return 0; + } +#endif + #endif // ULTRA_LCD diff --git a/Marlin/ultralcd.h b/Marlin/ultralcd.h index eb6d2e5bf5..2fb719bb8c 100644 --- a/Marlin/ultralcd.h +++ b/Marlin/ultralcd.h @@ -57,6 +57,10 @@ void dontExpireStatus(); #endif + #if ENABLED(ADC_KEYPAD) + uint8_t get_ADC_keyValue(); + #endif + #if ENABLED(DOGLCD) extern uint16_t lcd_contrast; void set_lcd_contrast(const uint16_t value); @@ -130,6 +134,21 @@ #define REPRAPWORLD_KEYPAD_MOVE_Y_UP (buttons_reprapworld_keypad & EN_REPRAPWORLD_KEYPAD_UP) #define REPRAPWORLD_KEYPAD_MOVE_X_LEFT (buttons_reprapworld_keypad & EN_REPRAPWORLD_KEYPAD_LEFT) + #if ENABLED(ADC_KEYPAD) + #define REPRAPWORLD_KEYPAD_MOVE_HOME (buttons_reprapworld_keypad & EN_REPRAPWORLD_KEYPAD_F1) + #define KEYPAD_EN_C EN_REPRAPWORLD_KEYPAD_MIDDLE + #else + #define REPRAPWORLD_KEYPAD_MOVE_HOME (buttons_reprapworld_keypad & EN_REPRAPWORLD_KEYPAD_MIDDLE) + #define KEYPAD_EN_C EN_REPRAPWORLD_KEYPAD_F1 + #endif + #define REPRAPWORLD_KEYPAD_MOVE_MENU (buttons_reprapworld_keypad & KEYPAD_EN_C) + + #if BUTTON_EXISTS(ENC) + #define LCD_CLICKED ((buttons & EN_C) || REPRAPWORLD_KEYPAD_MOVE_MENU) + #else + #define LCD_CLICKED REPRAPWORLD_KEYPAD_MOVE_MENU + #endif + #define REPRAPWORLD_KEYPAD_PRESSED (buttons_reprapworld_keypad & ( \ EN_REPRAPWORLD_KEYPAD_F3 | \ EN_REPRAPWORLD_KEYPAD_F2 | \ @@ -141,7 +160,6 @@ EN_REPRAPWORLD_KEYPAD_LEFT) \ ) - #define LCD_CLICKED ((buttons & EN_C) || (buttons_reprapworld_keypad & EN_REPRAPWORLD_KEYPAD_F1)) #elif ENABLED(NEWPANEL) #define LCD_CLICKED (buttons & EN_C) #else From 3c7bfe798d6d4c5079a56cd32caaab77bec51319 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 24 Jun 2017 22:23:45 -0500 Subject: [PATCH 122/180] Various cleanups ahead of digipot save --- .travis.yml | 6 +++--- Marlin/Makefile | 4 ++-- Marlin/Marlin_main.cpp | 6 ++++++ Marlin/stepper.cpp | 29 ++++++++++++++++------------- Marlin/stepper.h | 18 +++++++++--------- 5 files changed, 36 insertions(+), 27 deletions(-) diff --git a/.travis.yml b/.travis.yml index d3ef785f7e..4d5a00f1b2 100644 --- a/.travis.yml +++ b/.travis.yml @@ -202,9 +202,9 @@ script: # # Enable COREYX (swapped) # - - restore_configs - - opt_enable COREYX - - build_marlin + #- restore_configs + #- opt_enable COREYX + #- build_marlin # # ######## Other Standard LCD/Panels ############## diff --git a/Marlin/Makefile b/Marlin/Makefile index b6b3ebdc7e..d366f4ae5f 100644 --- a/Marlin/Makefile +++ b/Marlin/Makefile @@ -290,8 +290,8 @@ ifeq ($(HARDWARE_VARIANT), Teensy) SRC = wiring.c VPATH += $(ARDUINO_INSTALL_DIR)/hardware/teensy/cores/teensy endif -CXXSRC = WMath.cpp WString.cpp Print.cpp Marlin_main.cpp \ - MarlinSerial.cpp Sd2Card.cpp SdBaseFile.cpp SdFatUtil.cpp \ +CXXSRC = WMath.cpp WString.cpp Print.cpp Marlin_main.cpp \ + MarlinSerial.cpp Sd2Card.cpp SdBaseFile.cpp SdFatUtil.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 \ diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index de275d192c..bf5ab60467 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -9677,10 +9677,13 @@ inline void gcode_M503() { */ inline void gcode_M907() { #if HAS_DIGIPOTSS + LOOP_XYZE(i) if (parser.seen(axis_codes[i])) stepper.digipot_current(i, parser.value_int()); if (parser.seen('B')) stepper.digipot_current(4, parser.value_int()); if (parser.seen('S')) for (uint8_t i = 0; i <= 4; i++) stepper.digipot_current(i, parser.value_int()); + #elif HAS_MOTOR_CURRENT_PWM + #if PIN_EXISTS(MOTOR_CURRENT_PWM_XY) if (parser.seen('X')) stepper.digipot_current(0, parser.value_int()); #endif @@ -9690,13 +9693,16 @@ inline void gcode_M907() { #if PIN_EXISTS(MOTOR_CURRENT_PWM_E) if (parser.seen('E')) stepper.digipot_current(2, parser.value_int()); #endif + #endif + #if ENABLED(DIGIPOT_I2C) // this one uses actual amps in floating point LOOP_XYZE(i) if (parser.seen(axis_codes[i])) digipot_i2c_set_current(i, parser.value_float()); // for each additional extruder (named B,C,D,E..., channels 4,5,6,7...) for (uint8_t i = NUM_AXIS; i < DIGIPOT_I2C_NUM_CHANNELS; i++) if (parser.seen('B' + i - (NUM_AXIS))) digipot_i2c_set_current(i, parser.value_float()); #endif + #if ENABLED(DAC_STEPPER_CURRENT) if (parser.seen('S')) { const float dac_percent = parser.value_float(); diff --git a/Marlin/stepper.cpp b/Marlin/stepper.cpp index 2f8fc6dfcf..3995e0d2d0 100644 --- a/Marlin/stepper.cpp +++ b/Marlin/stepper.cpp @@ -74,8 +74,8 @@ block_t* Stepper::current_block = NULL; // A pointer to the block currently bei // private: -unsigned char Stepper::last_direction_bits = 0; // The next stepping-bits to be output -unsigned int Stepper::cleaning_buffer_counter = 0; +uint8_t Stepper::last_direction_bits = 0; // The next stepping-bits to be output +uint16_t Stepper::cleaning_buffer_counter = 0; #if ENABLED(Z_DUAL_ENDSTOPS) bool Stepper::locked_z_motor = false; @@ -1447,11 +1447,11 @@ void Stepper::report_positions() { #if HAS_DIGIPOTSS // From Arduino DigitalPotControl example - void Stepper::digitalPotWrite(int address, int value) { - WRITE(DIGIPOTSS_PIN, LOW); // take the SS pin low to select the chip - SPI.transfer(address); // send in the address and value via SPI: + void Stepper::digitalPotWrite(const int16_t address, const int16_t value) { + WRITE(DIGIPOTSS_PIN, LOW); // Take the SS pin low to select the chip + SPI.transfer(address); // Send the address and value via SPI SPI.transfer(value); - WRITE(DIGIPOTSS_PIN, HIGH); // take the SS pin high to de-select the chip: + WRITE(DIGIPOTSS_PIN, HIGH); // Take the SS pin high to de-select the chip //delay(10); } @@ -1486,21 +1486,24 @@ void Stepper::report_positions() { #endif } - void Stepper::digipot_current(uint8_t driver, int current) { + void Stepper::digipot_current(const uint8_t driver, const int current) { + #if HAS_DIGIPOTSS + const uint8_t digipot_ch[] = DIGIPOT_CHANNELS; digitalPotWrite(digipot_ch[driver], current); + #elif HAS_MOTOR_CURRENT_PWM - #define _WRITE_CURRENT_PWM(P) analogWrite(P, 255L * current / (MOTOR_CURRENT_PWM_RANGE)) + #define _WRITE_CURRENT_PWM(P) analogWrite(MOTOR_CURRENT_PWM_## P ##_PIN, 255L * current / (MOTOR_CURRENT_PWM_RANGE)) switch (driver) { #if PIN_EXISTS(MOTOR_CURRENT_PWM_XY) - case 0: _WRITE_CURRENT_PWM(MOTOR_CURRENT_PWM_XY_PIN); break; + case 0: _WRITE_CURRENT_PWM(XY); break; #endif #if PIN_EXISTS(MOTOR_CURRENT_PWM_Z) - case 1: _WRITE_CURRENT_PWM(MOTOR_CURRENT_PWM_Z_PIN); break; + case 1: _WRITE_CURRENT_PWM(Z); break; #endif #if PIN_EXISTS(MOTOR_CURRENT_PWM_E) - case 2: _WRITE_CURRENT_PWM(MOTOR_CURRENT_PWM_E_PIN); break; + case 2: _WRITE_CURRENT_PWM(E); break; #endif } #endif @@ -1550,7 +1553,7 @@ void Stepper::report_positions() { microstep_mode(i, microstep_modes[i]); } - void Stepper::microstep_ms(uint8_t driver, int8_t ms1, int8_t ms2) { + void Stepper::microstep_ms(const uint8_t driver, const int8_t ms1, const int8_t ms2) { if (ms1 >= 0) switch (driver) { case 0: WRITE(X_MS1_PIN, ms1); break; #if HAS_Y_MICROSTEPS @@ -1601,7 +1604,7 @@ void Stepper::report_positions() { } } - void Stepper::microstep_mode(uint8_t driver, uint8_t stepping_mode) { + void Stepper::microstep_mode(const uint8_t driver, const uint8_t stepping_mode) { switch (stepping_mode) { case 1: microstep_ms(driver, MICROSTEP1); break; case 2: microstep_ms(driver, MICROSTEP2); break; diff --git a/Marlin/stepper.h b/Marlin/stepper.h index 429e8f1d7a..334e0f0ee4 100644 --- a/Marlin/stepper.h +++ b/Marlin/stepper.h @@ -93,8 +93,8 @@ class Stepper { private: - static unsigned char last_direction_bits; // The next stepping-bits to be output - static unsigned int cleaning_buffer_counter; + static uint8_t last_direction_bits; // The next stepping-bits to be output + static uint16_t cleaning_buffer_counter; #if ENABLED(Z_DUAL_ENDSTOPS) static bool locked_z_motor, locked_z2_motor; @@ -243,20 +243,20 @@ class Stepper { static FORCE_INLINE bool motor_direction(AxisEnum axis) { return TEST(last_direction_bits, axis); } #if HAS_DIGIPOTSS || HAS_MOTOR_CURRENT_PWM - static void digitalPotWrite(int address, int value); - static void digipot_current(uint8_t driver, int current); + static void digitalPotWrite(const int16_t address, const int16_t value); + static void digipot_current(const uint8_t driver, const int16_t current); #endif #if HAS_MICROSTEPS - static void microstep_ms(uint8_t driver, int8_t ms1, int8_t ms2); - static void microstep_mode(uint8_t driver, uint8_t stepping); + static void microstep_ms(const uint8_t driver, const int8_t ms1, const int8_t ms2); + static void microstep_mode(const uint8_t driver, const uint8_t stepping); static void microstep_readings(); #endif #if ENABLED(Z_DUAL_ENDSTOPS) - static FORCE_INLINE void set_homing_flag(bool state) { performing_homing = state; } - static FORCE_INLINE void set_z_lock(bool state) { locked_z_motor = state; } - static FORCE_INLINE void set_z2_lock(bool state) { locked_z2_motor = state; } + static FORCE_INLINE void set_homing_flag(const bool state) { performing_homing = state; } + static FORCE_INLINE void set_z_lock(const bool state) { locked_z_motor = state; } + static FORCE_INLINE void set_z2_lock(const bool state) { locked_z2_motor = state; } #endif #if ENABLED(BABYSTEPPING) From b3c36c98fd0bb2664a1f1d6dc66d2fa315d8836e Mon Sep 17 00:00:00 2001 From: dot-bob Date: Fri, 2 Jun 2017 23:38:07 -0600 Subject: [PATCH 123/180] Edit digipot currents via LCD, save to EEPROM --- Marlin/configuration_store.cpp | 72 ++++++++++++++++++++++------ Marlin/pins_MINIRAMBO.h | 4 +- Marlin/pins_ULTIMAIN_2.h | 4 +- Marlin/stepper.cpp | 87 ++++++++++++++++++++++++---------- Marlin/stepper.h | 22 +++++---- Marlin/ultralcd.cpp | 26 +++++++++- 6 files changed, 164 insertions(+), 51 deletions(-) diff --git a/Marlin/configuration_store.cpp b/Marlin/configuration_store.cpp index 2e48701c70..840d6b88f5 100644 --- a/Marlin/configuration_store.cpp +++ b/Marlin/configuration_store.cpp @@ -36,13 +36,13 @@ * */ -#define EEPROM_VERSION "V38" +#define EEPROM_VERSION "V39" // Change EEPROM version if these are changed: #define EEPROM_OFFSET 100 /** - * V38 EEPROM Layout: + * V39 EEPROM Layout: * * 100 Version (char x4) * 104 EEPROM CRC16 (uint16_t) @@ -140,24 +140,29 @@ * 534 M200 T D filament_size (float x5) (T0..3) * * HAVE_TMC2130: 20 bytes - * 554 M906 X stepperX current (uint16_t) - * 556 M906 Y stepperY current (uint16_t) - * 558 M906 Z stepperZ current (uint16_t) - * 560 M906 X2 stepperX2 current (uint16_t) - * 562 M906 Y2 stepperY2 current (uint16_t) - * 564 M906 Z2 stepperZ2 current (uint16_t) - * 566 M906 E0 stepperE0 current (uint16_t) - * 568 M906 E1 stepperE1 current (uint16_t) - * 570 M906 E2 stepperE2 current (uint16_t) - * 572 M906 E3 stepperE3 current (uint16_t) - * 576 M906 E4 stepperE4 current (uint16_t) + * 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) * * LIN_ADVANCE: 8 bytes * 580 M900 K extruder_advance_k (float) * 584 M900 WHD advance_ed_ratio (float) * - * 588 Minimum end-point - * 1909 (588 + 36 + 9 + 288 + 988) Maximum end-point + * 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) + * + * 600 Minimum end-point + * 1921 (600 + 36 + 9 + 288 + 988) Maximum end-point * * ======================================================================== * meshes_begin (between max and min end-point, directly above) @@ -177,6 +182,7 @@ MarlinSettings settings; #include "planner.h" #include "temperature.h" #include "ultralcd.h" +#include "stepper.h" #if ENABLED(INCH_MODE_SUPPORT) || (ENABLED(ULTIPANEL) && ENABLED(TEMPERATURE_UNITS_SUPPORT)) #include "gcode.h" @@ -238,6 +244,10 @@ void MarlinSettings::postprocess() { refresh_bed_level(); //set_bed_leveling_enabled(leveling_is_on); #endif + + #if HAS_MOTOR_CURRENT_PWM + stepper.refresh_motor_power(); + #endif } #if ENABLED(EEPROM_SETTINGS) @@ -626,6 +636,13 @@ void MarlinSettings::postprocess() { EEPROM_WRITE(dummy); #endif + #if HAS_MOTOR_CURRENT_PWM + for (uint8_t q = 3; q--;) EEPROM_WRITE(stepper.motor_current_setting[q]); + #else + const uint32_t dummyui32 = 0; + for (uint8_t q = 3; q--;) EEPROM_WRITE(dummyui32); + #endif + if (!eeprom_error) { const int eeprom_size = eeprom_index; @@ -979,6 +996,13 @@ void MarlinSettings::postprocess() { EEPROM_READ(dummy); #endif + #if HAS_MOTOR_CURRENT_PWM + for (uint8_t q = 3; q--;) EEPROM_READ(stepper.motor_current_setting[q]); + #else + uint32_t dummyui32; + for (uint8_t q = 3; q--;) EEPROM_READ(dummyui32); + #endif + if (working_crc == stored_crc) { postprocess(); SERIAL_ECHO_START(); @@ -1309,6 +1333,12 @@ void MarlinSettings::reset() { planner.advance_ed_ratio = LIN_ADVANCE_E_D_RATIO; #endif + #if HAS_MOTOR_CURRENT_PWM + uint32_t tmp_motor_current_setting[3] = PWM_MOTOR_CURRENT; + for (uint8_t q = 3; q--;) + stepper.digipot_current(q, (stepper.motor_current_setting[q] = tmp_motor_current_setting[q])); + #endif + #if ENABLED(AUTO_BED_LEVELING_UBL) ubl.reset(); #endif @@ -1788,6 +1818,18 @@ void MarlinSettings::reset() { SERIAL_ECHOPAIR(" M900 K", planner.extruder_advance_k); SERIAL_ECHOLNPAIR(" R", planner.advance_ed_ratio); #endif + + #if HAS_MOTOR_CURRENT_PWM + CONFIG_ECHO_START; + if (!forReplay) { + SERIAL_ECHOLNPGM("Stepper motor currents:"); + CONFIG_ECHO_START; + } + SERIAL_ECHOPAIR(" M907 X", stepper.motor_current_setting[0]); + SERIAL_ECHOPAIR(" Z", stepper.motor_current_setting[1]); + SERIAL_ECHOPAIR(" E", stepper.motor_current_setting[2]); + SERIAL_EOL(); + #endif } #endif // !DISABLE_M503 diff --git a/Marlin/pins_MINIRAMBO.h b/Marlin/pins_MINIRAMBO.h index de3c6b08ae..6a95a3c4b1 100644 --- a/Marlin/pins_MINIRAMBO.h +++ b/Marlin/pins_MINIRAMBO.h @@ -85,7 +85,9 @@ #define MOTOR_CURRENT_PWM_Z_PIN 45 #define MOTOR_CURRENT_PWM_E_PIN 44 // Motor current PWM conversion, PWM value = MotorCurrentSetting * 255 / range -#define MOTOR_CURRENT_PWM_RANGE 2000 +#ifndef MOTOR_CURRENT_PWM_RANGE + #define MOTOR_CURRENT_PWM_RANGE 2000 +#endif #define DEFAULT_PWM_MOTOR_CURRENT {1300, 1300, 1250} // diff --git a/Marlin/pins_ULTIMAIN_2.h b/Marlin/pins_ULTIMAIN_2.h index d4b99fafc7..4ac26c6af2 100644 --- a/Marlin/pins_ULTIMAIN_2.h +++ b/Marlin/pins_ULTIMAIN_2.h @@ -74,7 +74,9 @@ #define MOTOR_CURRENT_PWM_Z_PIN 45 #define MOTOR_CURRENT_PWM_E_PIN 46 // Motor current PWM conversion, PWM value = MotorCurrentSetting * 255 / range -#define MOTOR_CURRENT_PWM_RANGE 2000 +#ifndef MOTOR_CURRENT_PWM_RANGE + #define MOTOR_CURRENT_PWM_RANGE 2000 +#endif #define DEFAULT_PWM_MOTOR_CURRENT {1300, 1300, 1250} // diff --git a/Marlin/stepper.cpp b/Marlin/stepper.cpp index 3995e0d2d0..c7ea4ba15c 100644 --- a/Marlin/stepper.cpp +++ b/Marlin/stepper.cpp @@ -72,6 +72,10 @@ block_t* Stepper::current_block = NULL; // A pointer to the block currently bei bool Stepper::performing_homing = false; #endif +#if HAS_MOTOR_CURRENT_PWM + uint32_t Stepper::motor_current_setting[3] = PWM_MOTOR_CURRENT; +#endif + // private: uint8_t Stepper::last_direction_bits = 0; // The next stepping-bits to be output @@ -1457,35 +1461,30 @@ void Stepper::report_positions() { #endif // HAS_DIGIPOTSS -#if HAS_DIGIPOTSS || HAS_MOTOR_CURRENT_PWM +#if HAS_MOTOR_CURRENT_PWM - void Stepper::digipot_init() { - #if HAS_DIGIPOTSS - static const uint8_t digipot_motor_current[] = DIGIPOT_MOTOR_CURRENT; - SPI.begin(); - SET_OUTPUT(DIGIPOTSS_PIN); - for (uint8_t i = 0; i < COUNT(digipot_motor_current); i++) { - //digitalPotWrite(digipot_ch[i], digipot_motor_current[i]); - digipot_current(i, digipot_motor_current[i]); + void Stepper::refresh_motor_power() { + for (uint8_t i = 0; i < COUNT(motor_current_setting); ++i) { + switch (i) { + #if PIN_EXISTS(MOTOR_CURRENT_PWM_XY) + case 0: + #endif + #if PIN_EXISTS(MOTOR_CURRENT_PWM_Z) + case 1: + #endif + #if PIN_EXISTS(MOTOR_CURRENT_PWM_E) + case 2: + #endif + digipot_current(i, motor_current_setting[i]); + default: break; } - #elif HAS_MOTOR_CURRENT_PWM - #if PIN_EXISTS(MOTOR_CURRENT_PWM_XY) - SET_OUTPUT(MOTOR_CURRENT_PWM_XY_PIN); - digipot_current(0, motor_current_setting[0]); - #endif - #if PIN_EXISTS(MOTOR_CURRENT_PWM_Z) - SET_OUTPUT(MOTOR_CURRENT_PWM_Z_PIN); - digipot_current(1, motor_current_setting[1]); - #endif - #if PIN_EXISTS(MOTOR_CURRENT_PWM_E) - SET_OUTPUT(MOTOR_CURRENT_PWM_E_PIN); - digipot_current(2, motor_current_setting[2]); - #endif - //Set timer5 to 31khz so the PWM of the motor power is as constant as possible. (removes a buzzing noise) - TCCR5B = (TCCR5B & ~(_BV(CS50) | _BV(CS51) | _BV(CS52))) | _BV(CS50); - #endif + } } +#endif // HAS_MOTOR_CURRENT_PWM + +#if HAS_DIGIPOTSS || HAS_MOTOR_CURRENT_PWM + void Stepper::digipot_current(const uint8_t driver, const int current) { #if HAS_DIGIPOTSS @@ -1494,6 +1493,10 @@ void Stepper::report_positions() { digitalPotWrite(digipot_ch[driver], current); #elif HAS_MOTOR_CURRENT_PWM + + if (WITHIN(driver, 0, 2)) + motor_current_setting[driver] = current; // update motor_current_setting + #define _WRITE_CURRENT_PWM(P) analogWrite(MOTOR_CURRENT_PWM_## P ##_PIN, 255L * current / (MOTOR_CURRENT_PWM_RANGE)) switch (driver) { #if PIN_EXISTS(MOTOR_CURRENT_PWM_XY) @@ -1509,6 +1512,40 @@ void Stepper::report_positions() { #endif } + void Stepper::digipot_init() { + + #if HAS_DIGIPOTSS + + static const uint8_t digipot_motor_current[] = DIGIPOT_MOTOR_CURRENT; + + SPI.begin(); + SET_OUTPUT(DIGIPOTSS_PIN); + + for (uint8_t i = 0; i < COUNT(digipot_motor_current); i++) { + //digitalPotWrite(digipot_ch[i], digipot_motor_current[i]); + digipot_current(i, digipot_motor_current[i]); + } + + #elif HAS_MOTOR_CURRENT_PWM + + #if PIN_EXISTS(MOTOR_CURRENT_PWM_XY) + SET_OUTPUT(MOTOR_CURRENT_PWM_XY_PIN); + #endif + #if PIN_EXISTS(MOTOR_CURRENT_PWM_Z) + SET_OUTPUT(MOTOR_CURRENT_PWM_Z_PIN); + #endif + #if PIN_EXISTS(MOTOR_CURRENT_PWM_E) + SET_OUTPUT(MOTOR_CURRENT_PWM_E_PIN); + #endif + + refresh_motor_power(); + + // Set Timer5 to 31khz so the PWM of the motor power is as constant as possible. (removes a buzzing noise) + SET_CS5(PRESCALER_1); + + #endif + } + #endif #if HAS_MICROSTEPS diff --git a/Marlin/stepper.h b/Marlin/stepper.h index 334e0f0ee4..3ca1926193 100644 --- a/Marlin/stepper.h +++ b/Marlin/stepper.h @@ -91,6 +91,13 @@ class Stepper { static bool performing_homing; #endif + #if HAS_MOTOR_CURRENT_PWM + #ifndef PWM_MOTOR_CURRENT + #define PWM_MOTOR_CURRENT DEFAULT_PWM_MOTOR_CURRENT + #endif + static uint32_t motor_current_setting[3]; + #endif + private: static uint8_t last_direction_bits; // The next stepping-bits to be output @@ -132,13 +139,6 @@ class Stepper { static volatile long endstops_trigsteps[XYZ]; static volatile long endstops_stepsTotal, endstops_stepsDone; - #if HAS_MOTOR_CURRENT_PWM - #ifndef PWM_MOTOR_CURRENT - #define PWM_MOTOR_CURRENT DEFAULT_PWM_MOTOR_CURRENT - #endif - static constexpr int motor_current_setting[3] = PWM_MOTOR_CURRENT; - #endif - // // Positions of stepper motors, in step units // @@ -279,6 +279,10 @@ class Stepper { return endstops_trigsteps[axis] * planner.steps_to_mm[axis]; } + #if HAS_MOTOR_CURRENT_PWM + static void refresh_motor_power(); + #endif + private: static FORCE_INLINE unsigned short calc_timer(unsigned short step_rate) { @@ -380,7 +384,9 @@ class Stepper { // SERIAL_ECHOLN(current_block->final_advance/256.0); } - static void digipot_init(); + #if HAS_DIGIPOTSS || HAS_MOTOR_CURRENT_PWM + static void digipot_init(); + #endif #if HAS_MICROSTEPS static void microstep_init(); diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index ed26888db8..a136503116 100644 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -1249,6 +1249,7 @@ void kill_screen(const char* lcd_msg) { * */ #if ENABLED(DAC_STEPPER_CURRENT) + void dac_driver_getValues() { LOOP_XYZE(i) driverPercent[i] = dac_current_get_percent((AxisEnum)i); } void dac_driver_commit() { dac_current_set_percents(driverPercent); } @@ -1266,7 +1267,27 @@ void kill_screen(const char* lcd_msg) { MENU_ITEM(function, MSG_DAC_EEPROM_WRITE, dac_driver_eeprom_write); END_MENU(); } - #endif + + #endif // DAC_STEPPER_CURRENT + + #if HAS_MOTOR_CURRENT_PWM + + void lcd_pwm_menu() { + START_MENU(); + MENU_BACK(MSG_CONTROL); + #if PIN_EXISTS(MOTOR_CURRENT_PWM_XY) + MENU_ITEM_EDIT_CALLBACK(long5, MSG_X MSG_Y, &stepper.motor_current_setting[0], 100, 2000, Stepper::refresh_motor_power); + #endif + #if PIN_EXISTS(MOTOR_CURRENT_PWM_Z) + MENU_ITEM_EDIT_CALLBACK(long5, MSG_Z, &stepper.motor_current_setting[1], 100, 2000, Stepper::refresh_motor_power); + #endif + #if PIN_EXISTS(MOTOR_CURRENT_PWM_E) + MENU_ITEM_EDIT_CALLBACK(long5, MSG_E, &stepper.motor_current_setting[2], 100, 2000, Stepper::refresh_motor_power); + #endif + END_MENU(); + } + + #endif // HAS_MOTOR_CURRENT_PWM constexpr int16_t heater_maxtemp[HOTENDS] = ARRAY_BY_HOTENDS(HEATER_0_MAXTEMP, HEATER_1_MAXTEMP, HEATER_2_MAXTEMP, HEATER_3_MAXTEMP, HEATER_4_MAXTEMP); @@ -2894,6 +2915,9 @@ void kill_screen(const char* lcd_msg) { #if ENABLED(DAC_STEPPER_CURRENT) MENU_ITEM(submenu, MSG_DRIVE_STRENGTH, lcd_dac_menu); #endif + #if HAS_MOTOR_CURRENT_PWM + MENU_ITEM(submenu, MSG_DRIVE_STRENGTH, lcd_pwm_menu); + #endif #if ENABLED(BLTOUCH) MENU_ITEM(submenu, MSG_BLTOUCH, bltouch_menu); From 1446b5f01d2f510fb5dfdb83817a9863f712d04a Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 25 Jun 2017 14:16:28 -0500 Subject: [PATCH 124/180] Allow more avr variants with build_marlin* --- buildroot/bin/build_marlin | 7 ++++++- buildroot/bin/build_marlin_fail | 7 ++----- 2 files changed, 8 insertions(+), 6 deletions(-) diff --git a/buildroot/bin/build_marlin b/buildroot/bin/build_marlin index 12c3bd4feb..3255346291 100755 --- a/buildroot/bin/build_marlin +++ b/buildroot/bin/build_marlin @@ -1,3 +1,8 @@ #!/usr/bin/env bash -arduino --verify --board arduino:avr:mega:cpu=atmega2560 Marlin/Marlin.ino +case "$#" in + 0 ) BOARD=arduino:avr:mega:cpu=atmega2560 ;; + * ) BOARD=arduino:avr:$1 ;; +esac + +arduino --verify --board $BOARD Marlin/Marlin.ino diff --git a/buildroot/bin/build_marlin_fail b/buildroot/bin/build_marlin_fail index 506426ebea..e18105cdd4 100755 --- a/buildroot/bin/build_marlin_fail +++ b/buildroot/bin/build_marlin_fail @@ -1,7 +1,4 @@ #!/usr/bin/env bash -if arduino --verify --board arduino:avr:mega:cpu=atmega2560 Marlin/Marlin.ino ; then - return 1 -else - return 0 -fi +build_marlin $@ && exit 0 +exit 1 From a1632cfa0ab4f2b52b602dfdfebc44dee576e33d Mon Sep 17 00:00:00 2001 From: dot-bob Date: Thu, 22 Jun 2017 22:38:52 -0600 Subject: [PATCH 125/180] Added option 'H' to G29 P4. - Added `H` to set a nozzle height adjustment to surface of the bed. - Updated G29 P4 comments to reflect changes. --- Marlin/ubl.h | 2 +- Marlin/ubl_G29.cpp | 247 ++++++++++++++++++++++----------------------- 2 files changed, 122 insertions(+), 127 deletions(-) diff --git a/Marlin/ubl.h b/Marlin/ubl.h index 21f83c1131..2c2ca1ec39 100644 --- a/Marlin/ubl.h +++ b/Marlin/ubl.h @@ -115,7 +115,7 @@ #endif static float measure_point_with_encoder(); - static float measure_business_card_thickness(float&); + static float measure_business_card_thickness(float); static bool g29_parameter_parsing(); static void find_mean_mesh_height(); static void shift_mesh_height(); diff --git a/Marlin/ubl_G29.cpp b/Marlin/ubl_G29.cpp index 3fe2240d76..c70755a331 100644 --- a/Marlin/ubl_G29.cpp +++ b/Marlin/ubl_G29.cpp @@ -84,25 +84,23 @@ * * A Activate Activate the Unified Bed Leveling system. * - * B # Business Use the 'Business Card' mode of the Manual Probe subsystem. This is invoked as - * G29 P2 B. The mode of G29 P2 allows you to use a business card or recipe card - * as a shim that the nozzle will pinch as it is lowered. The idea is that you - * can easily feel the nozzle getting to the same height by the amount of resistance - * the business card exhibits to movement. You should try to achieve the same amount - * of resistance on each probed point to facilitate accurate and repeatable measurements. - * You should be very careful not to drive the nozzle into the business card with a - * lot of force as it is very possible to cause damage to your printer if your are - * careless. If you use the B option with G29 P2 B you can omit the numeric value - * on first use to measure the business card's thickness. Subsequent usage of 'B' - * will apply the previously-measured thickness as the default. - * Note: A non-compressible Spark Gap feeler gauge is recommended over a Business Card. + * B # Business Use the 'Business Card' mode of the Manual Probe subsystem with P2. + * Note: A non-compressible Spark Gap feeler gauge is recommended over a business card. + * In this mode of G29 P2, a business or index card is used as a shim that the nozzle can + * grab onto as it is lowered. In principle, the nozzle-bed distance is the same when the + * same resistance is felt in the shim. You can omit the numerical value on first invocation + * of G29 P2 B to measure shim thickness. Subsequent use of 'B' will apply the previously- + * measured thickness by default. * - * C Continue Continue, Constant, Current Location. This is not a primary command. C is used to - * further refine the behaviour of several other commands. Issuing a G29 P1 C will - * continue the generation of a partially constructed Mesh without invalidating what has - * been done. Issuing a G29 P2 C will tell the Manual Probe subsystem to use the current - * location in its search for the closest unmeasured Mesh Point. When used with a G29 Z C - * it indicates to use the current location instead of defaulting to the center of the print bed. + * C Continue G29 P1 C continues the generation of a partially-constructed Mesh without invalidating + * previous measurements. + * + * C Constant G29 P2 C specifies a Constant and tells the Manual Probe subsystem to use the current + * location in its search for the closest unmeasured Mesh Point. + * + * G29 P3 C specifies the Constant for the fill. Otherwise, uses a "reasonable" value. + * + * C Current G29 Z C uses the Current location (instead of bed center or nearest edge). * * D Disable Disable the Unified Bed Leveling system. * @@ -112,17 +110,18 @@ * specified height, no correction is applied and natural printer kenimatics take over. If no * number is specified for the command, 10mm is assumed to be reasonable. * - * H # Height Specify the Height to raise the nozzle after each manual probe of the bed. The - * default is 5mm. + * H # Height With P2, 'H' specifies the Height to raise the nozzle after each manual probe of the bed. + * If omitted, the nozzle will raise by Z_CLEARANCE_BETWEEN_PROBES. * - * I # Invalidate Invalidate specified number of Mesh Points. The nozzle location is used unless - * the X and Y parameter are used. If no number is specified, only the closest Mesh - * point to the location is invalidated. The 'T' parameter is also available to produce - * a map after the operation. This command is useful to invalidate a portion of the - * Mesh so it can be adjusted using other tools in the Unified Bed Leveling System. When - * attempting to invalidate an isolated bad point in the mesh, the 'T' option will indicate - * where the nozzle is positioned in the Mesh with (#). You can move the nozzle around on - * the bed and use this feature to select the center of the area (or cell) you want to + * H # Offset With P4, 'H' specifies the Offset above the mesh height to place the nozzle. + * If omitted, Z_CLEARANCE_BETWEEN_PROBES will be used. + * + * I # Invalidate Invalidate the specified number of Mesh Points near the given 'X' 'Y'. If X or Y are omitted, + * the nozzle location is used. If no 'I' value is given, only the point nearest to the location + * is invalidated. Use 'T' to produce a map afterward. This command is useful to invalidate a + * portion of the Mesh so it can be adjusted using other UBL tools. When attempting to invalidate + * an isolated bad mesh point, the 'T' option shows the nozzle position in the Mesh with (#). You + * can move the nozzle around and use this feature to select the center of the area (or cell) to * invalidate. * * J # Grid Perform a Grid Based Leveling of the current Mesh using a grid with n points on a side. @@ -151,95 +150,81 @@ * area cannot be automatically probed. For Delta printers the area in which DELTA_PROBEABLE_RADIUS * and DELTA_PRINTABLE_RADIUS do not overlap will not be automatically probed. * - * These points will be handled in Phase 2 and Phase 3. If the Phase 1 command is given the - * C (Continue) parameter it does not invalidate the Mesh prior to automatically - * probing needed locations. This allows you to invalidate portions of the Mesh but still - * use the automatic probing capabilities of the Unified Bed Leveling System. An X and Y - * parameter can be given to prioritize where the command should be trying to measure points. - * If the X and Y parameters are not specified the current probe position is used. - * P1 accepts a 'T' (Topology) parameter so you can observe mesh generation. - * P1 also watches for the LCD Panel Encoder Switch to be held down (assuming you have one), - * and will suspend generation of the Mesh in that case. (Note: This check is only done - * between probe points, so you must press and hold the switch until the Phase 1 command - * detects it.) + * Unreachable points will be handled in Phase 2 and Phase 3. * - * P2 Phase 2 Probe areas of the Mesh that can't be automatically handled. Phase 2 respects an H - * parameter to control the height between Mesh points. The default height for movement - * between Mesh points is 5mm. A smaller number can be used to make this part of the - * calibration less time consuming. You will be running the nozzle down until it just barely - * touches the glass. You should have the nozzle clean with no plastic obstructing your view. - * Use caution and move slowly. It is possible to damage your printer if you are careless. - * Note that this command will use the configuration #define SIZE_OF_LITTLE_RAISE if the - * nozzle is moving a distance of less than BIG_RAISE_NOT_NEEDED. + * Use 'C' to leave the previous mesh intact and automatically probe needed points. This allows you + * to invalidate parts of the Mesh but still use Automatic Probing. * - * The H parameter can be set negative if your Mesh dips in a large area. You can press - * and hold the LCD Panel's encoder wheel to terminate the current Phase 2 command. You - * can then re-issue the G29 P 2 command with an H parameter that is more suitable for the - * area you are manually probing. Note that the command tries to start you in a corner - * of the bed where movement will be predictable. You can force the location to be used in - * the distance calculations by using the X and Y parameters. You may find it is helpful to - * print out a Mesh Map (G29 T) to understand where the mesh is invalidated and where - * the nozzle will need to move in order to complete the command. The C parameter is - * available on the Phase 2 command also and indicates the search for points to measure should - * be done based on the current location of the nozzle. + * The 'X' and 'Y' parameters prioritize where to try and measure points. If omitted, the current + * probe position is used. * - * A B parameter is also available for this command and described up above. It places the - * manual probe subsystem into Business Card mode where the thickness of a business card is - * measured and then used to accurately set the nozzle height in all manual probing for the - * duration of the command. (S for Shim mode would be a better parameter name, but S is needed - * for Save or Store of the Mesh to EEPROM) A Business card can be used, but you will have - * better results if you use a flexible Shim that does not compress very much. That makes it - * easier for you to get the nozzle to press with similar amounts of force against the shim so you - * can get accurate measurements. As you are starting to touch the nozzle against the shim try - * to get it to grasp the shim with the same force as when you measured the thickness of the - * shim at the start of the command. + * Use 'T' (Topology) to generate a report of mesh generation. * - * Phase 2 allows the T (Map) parameter to be specified. This helps the user see the progression - * of the Mesh being built. + * P1 will suspend Mesh generation if the controller button is held down. Note that you may need + * to press and hold the switch for several seconds if moves are underway. * - * NOTE: P2 is not available unless you have LCD support enabled! + * P2 Phase 2 Probe unreachable points. * - * P3 Phase 3 Fill the unpopulated regions of the Mesh with a fixed value. There are two different paths the - * user can go down. If the user specifies the value using the C parameter, the closest invalid - * mesh points to the nozzle will be filled. The user can specify a repeat count using the R - * parameter with the C version of the command. + * Use 'H' to set the height between Mesh points. If omitted, Z_CLEARANCE_BETWEEN_PROBES is used. + * Smaller values will be quicker. Move the nozzle down till it barely touches the bed. Make sure the + * nozzle is clean and unobstructed. Use caution and move slowly. This can damage your printer! + * (Uses SIZE_OF_LITTLE_RAISE mm if the nozzle is moving less than BIG_RAISE_NOT_NEEDED mm.) * - * A second version of the fill command is available if no C constant is specified. Not - * specifying a C constant will invoke the 'Smart Fill' algorithm. The G29 P3 command will search - * from the edges of the mesh inward looking for invalid mesh points. It will look at the next - * several mesh points to determine if the print bed is sloped up or down. If the bed is sloped - * upward from the invalid mesh point, it will be replaced with the value of the nearest mesh point. - * If the bed is sloped downward from the invalid mesh point, it will be replaced with a value that - * puts all three points in a line. The second version of the G29 P3 command is a quick, easy and - * usually safe way to populate the unprobed regions of your mesh so you can continue to the G26 - * Mesh Validation Pattern phase. Please note that you are populating your mesh with unverified - * numbers. You should use some scrutiny and caution. + * The 'H' value can be negative if the Mesh dips in a large area. Press and hold the + * controller button to terminate the current Phase 2 command. You can then re-issue "G29 P 2" + * with an 'H' parameter more suitable for the area you're manually probing. Note that the command + * tries to start in a corner of the bed where movement will be predictable. Override the distance + * calculation location with the X and Y parameters. You can print a Mesh Map (G29 T) to see where + * the mesh is invalidated and where the nozzle needs to move to complete the command. Use 'C' to + * indicate that the search should be based on the current position. * - * P4 Phase 4 Fine tune the Mesh. The Delta Mesh Compensation System assume the existence of - * an LCD Panel. It is possible to fine tune the mesh without the use of an LCD Panel using - * G42 and M421; see the UBL documentation for further details. + * The 'B' parameter for this command is described above. It places the manual probe subsystem into + * Business Card mode where the thickness of a business card is measured and then used to accurately + * set the nozzle height in all manual probing for the duration of the command. A Business card can + * be used, but you'll get better results with a flexible Shim that doesn't compress. This makes it + * easier to produce similar amounts of force and get more accurate measurements. Google if you're + * not sure how to use a shim. * - * The System will search for the closest Mesh Point to the nozzle. It will move the - * nozzle to this location. The user can use the LCD Panel to carefully adjust the nozzle - * so it is just barely touching the bed. When the user clicks the control, the System - * will lock in that height for that point in the Mesh Compensation System. + * The 'T' (Map) parameter helps track Mesh building progress. * - * Phase 4 has several additional parameters that the user may find helpful. Phase 4 - * can be started at a specific location by specifying an X and Y parameter. Phase 4 - * can be requested to continue the adjustment of Mesh Points by using the R(epeat) - * parameter. If the Repetition count is not specified, it is assumed the user wishes - * to adjust the entire matrix. The nozzle is moved to the Mesh Point being edited. - * The command can be terminated early (or after the area of interest has been edited) by - * pressing and holding the encoder wheel until the system recognizes the exit request. - * Phase 4's general form is G29 P4 [R # of points] [X position] [Y position] + * NOTE: P2 requires an LCD controller! * - * Phase 4 is intended to be used with the G26 Mesh Validation Command. Using the - * information left on the printer's bed from the G26 command it is very straight forward - * and easy to fine tune the Mesh. One concept that is important to remember and that - * will make using the Phase 4 command easy to use is this: You are editing the Mesh Points. - * If you have too little clearance and not much plastic was extruded in an area, you want to - * LOWER the Mesh Point at the location. If you did not get good adheasion, you want to - * RAISE the Mesh Point at that location. + * P3 Phase 3 Fill the unpopulated regions of the Mesh with a fixed value. There are two different paths to + * go down: + * + * - If a 'C' constant is specified, the closest invalid mesh points to the nozzle will be filled, + * and a repeat count can then also be specified with 'R'. + * + * - Leaving out 'C' invokes Smart Fill, which scans the mesh from the edges inward looking for + * invalid mesh points. Adjacent points are used to determine the bed slope. If the bed is sloped + * upward from the invalid point, it takes the value of the nearest point. If sloped downward, it's + * replaced by a value that puts all three points in a line. This version of G29 P3 is a quick, easy + * and (usually) safe way to populate unprobed mesh regions before continuing to G26 Mesh Validation + * Pattern. Note that this populates the mesh with unverified values. Pay attention and use caution. + * + * P4 Phase 4 Fine tune the Mesh. The Delta Mesh Compensation System assumes the existence of + * an LCD Panel. It is possible to fine tune the mesh without an LCD Panel using + * G42 and M421. See the UBL documentation for further details. + * + * Phase 4 is meant to be used with G26 Mesh Validation to fine tune the mesh by direct editing + * of Mesh Points. Raise and lower points to fine tune the mesh until it gives consistently reliable + * adhesion. + * + * P4 moves to the closest Mesh Point (and/or the given X Y), raises the nozzle above the mesh height + * by the given 'H' offset (or default Z_CLEARANCE_BETWEEN_PROBES), and waits while the controller is + * used to adjust the nozzle height. On click the displayed height is saved in the mesh. + * + * Start Phase 4 at a specific location with X and Y. Adjust a specific number of Mesh Points with + * the 'R' (Repeat) parameter. (If 'R' is left out, the whole matrix is assumed.) This command can be + * terminated early (e.g., after editing the area of interest) by pressing and holding the encoder button. + * + * The general form is G29 P4 [R points] [X position] [Y position] + * + * The H [offset] parameter is useful if a shim is used to fine-tune the mesh. For a 0.4mm shim the + * command would be G29 P4 H0.4. The nozzle is moved to the shim height, you adjust height to the shim, + * and on click the height minus the shim thickness will be saved in the mesh. + * + * !!Use with caution, as a very poor mesh could cause the nozzle to crash into the bed!! * * NOTE: P4 is not available unless you have LCD support enabled! * @@ -494,28 +479,29 @@ g29_y_pos = current_position[Y_AXIS]; } - float height = Z_CLEARANCE_BETWEEN_PROBES; - if (parser.seen('B')) { - g29_card_thickness = parser.has_value() ? parser.value_float() : measure_business_card_thickness(height); + g29_card_thickness = parser.has_value() ? parser.value_float() : measure_business_card_thickness(Z_CLEARANCE_BETWEEN_PROBES); if (FABS(g29_card_thickness) > 1.5) { SERIAL_PROTOCOLLNPGM("?Error in Business Card measurement."); return; } } - if (parser.seen('H') && parser.has_value()) height = parser.value_float(); - if (!position_is_reachable_xy(g29_x_pos, g29_y_pos)) { SERIAL_PROTOCOLLNPGM("XY outside printable radius."); return; } + const float height = parser.seen('H') && parser.has_value() ? parser.value_float() : Z_CLEARANCE_BETWEEN_PROBES; manually_probe_remaining_mesh(g29_x_pos, g29_y_pos, height, g29_card_thickness, parser.seen('T')); + SERIAL_PROTOCOLLNPGM("G29 P2 finished."); + #else + SERIAL_PROTOCOLLNPGM("?P2 is only available when an LCD is present."); return; + #endif } break; @@ -537,19 +523,17 @@ if (location.x_index < 0) { // No more REACHABLE INVALID mesh points to populate, so we ASSUME // user meant to populate ALL INVALID mesh points to value - for (uint8_t x = 0; x < GRID_MAX_POINTS_X; x++) { - for (uint8_t y = 0; y < GRID_MAX_POINTS_Y; y++) { - if ( isnan(z_values[x][y])) { + for (uint8_t x = 0; x < GRID_MAX_POINTS_X; x++) + for (uint8_t y = 0; y < GRID_MAX_POINTS_Y; y++) + if (isnan(z_values[x][y])) z_values[x][y] = g29_constant; - } - } - } break; // No more invalid Mesh Points to populate } z_values[location.x_index][location.y_index] = g29_constant; } } - } else { + } + else { const float cvf = parser.value_float(); switch((int)truncf(cvf * 10.0) - 30) { // 3.1 -> 1 #if ENABLED(UBL_G29_P31) @@ -967,7 +951,7 @@ static void echo_and_take_a_measurement() { SERIAL_PROTOCOLLNPGM(" and take a measurement."); } - float unified_bed_leveling::measure_business_card_thickness(float &in_height) { + float unified_bed_leveling::measure_business_card_thickness(float in_height) { has_control_of_lcd_panel = true; save_ubl_active_state_and_disable(); // Disable bed level correction for probing @@ -1466,12 +1450,21 @@ } #if ENABLED(NEWPANEL) + void unified_bed_leveling::fine_tune_mesh(const float &lx, const float &ly, const bool do_ubl_mesh_map) { if (!parser.seen('R')) // fine_tune_mesh() is special. If no repetition count flag is specified g29_repetition_cnt = 1; // do exactly one mesh location. Otherwise use what the parser decided. - + + #if ENABLED(UBL_MESH_EDIT_MOVES_Z) + const bool is_offset = parser.seen('H'); + const float h_offset = is_offset ? parser.value_linear_units() : Z_CLEARANCE_BETWEEN_PROBES; + if (is_offset && !WITHIN(h_offset, 0, 10)) { + SERIAL_PROTOCOLLNPGM("Offset out of bounds. (0 to 10mm)\n"); + return; + } + #endif + mesh_index_pair location; - uint16_t not_done[16]; if (!position_is_reachable_xy(lx, ly)) { SERIAL_PROTOCOLLNPGM("(X,Y) outside printable radius."); @@ -1480,12 +1473,13 @@ save_ubl_active_state_and_disable(); - memset(not_done, 0xFF, sizeof(not_done)); - LCD_MESSAGEPGM(MSG_UBL_FINE_TUNE_MESH); do_blocking_move_to_z(Z_CLEARANCE_BETWEEN_PROBES); do_blocking_move_to_xy(lx, ly); + + uint16_t not_done[16]; + memset(not_done, 0xFF, sizeof(not_done)); do { location = find_closest_mesh_point_of_type(SET_IN_BITMAP, lx, ly, USE_NOZZLE_AS_REFERENCE, not_done, false); @@ -1521,8 +1515,8 @@ do { new_z = lcd_mesh_edit(); - #ifdef UBL_MESH_EDIT_MOVES_Z - do_blocking_move_to_z(Z_CLEARANCE_BETWEEN_PROBES + new_z); // Move the nozzle as the point is edited + #if ENABLED(UBL_MESH_EDIT_MOVES_Z) + do_blocking_move_to_z(h_offset + new_z); // Move the nozzle as the point is edited #endif idle(); } while (!ubl_lcd_clicked()); @@ -1581,7 +1575,8 @@ } else lcd_return_to_status(); } - #endif + + #endif // NEWPANEL /** * 'Smart Fill': Scan from the outward edges of the mesh towards the center. From fe7e890b09ebb7bfbcfbc75ecb76277fcd1a6804 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 26 Jun 2017 16:01:27 -0500 Subject: [PATCH 126/180] Fix issues with ADC_KEYPAD Fixes #7150 --- Marlin/ultralcd.cpp | 43 +++++++++++++++++-------------------------- 1 file changed, 17 insertions(+), 26 deletions(-) diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index e878e8f206..67015c3226 100644 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -4026,44 +4026,34 @@ void kill_screen(const char* lcd_msg) { */ #if ENABLED(ADC_KEYPAD) - inline void handle_adc_keypad() { + inline bool handle_adc_keypad() { static uint8_t adc_steps = 0; if (buttons_reprapworld_keypad) { - adc_steps++; - NOMORE(adc_steps, 20); - + if (adc_steps < 20) ++adc_steps; lcd_quick_feedback(); lcdDrawUpdate = LCDVIEW_REDRAW_NOW; - return_to_status_ms = millis() + LCD_TIMEOUT_TO_STATUS; if (encoderDirection == -1) { // side effect which signals we are inside a menu - if (buttons_reprapworld_keypad & EN_REPRAPWORLD_KEYPAD_DOWN) - encoderPosition -= ENCODER_STEPS_PER_MENU_ITEM; - else if (buttons_reprapworld_keypad & EN_REPRAPWORLD_KEYPAD_UP) - encoderPosition += ENCODER_STEPS_PER_MENU_ITEM; - else if (buttons_reprapworld_keypad & EN_REPRAPWORLD_KEYPAD_LEFT) - menu_action_back(); - else if (buttons_reprapworld_keypad & EN_REPRAPWORLD_KEYPAD_RIGHT) - // enqueue_and_echo_commands_P(PSTR("M0 Pause")); - lcd_return_to_status(); + if (buttons_reprapworld_keypad & EN_REPRAPWORLD_KEYPAD_DOWN) encoderPosition -= ENCODER_STEPS_PER_MENU_ITEM; + else if (buttons_reprapworld_keypad & EN_REPRAPWORLD_KEYPAD_UP) encoderPosition += ENCODER_STEPS_PER_MENU_ITEM; + else if (buttons_reprapworld_keypad & EN_REPRAPWORLD_KEYPAD_LEFT) menu_action_back(); + else if (buttons_reprapworld_keypad & EN_REPRAPWORLD_KEYPAD_RIGHT) lcd_return_to_status(); } else { const int8_t step = adc_steps > 19 ? 100 : adc_steps > 10 ? 10 : 1; - if (buttons_reprapworld_keypad & EN_REPRAPWORLD_KEYPAD_DOWN) - encoderPosition += ENCODER_PULSES_PER_STEP * step; - else if (buttons_reprapworld_keypad & EN_REPRAPWORLD_KEYPAD_UP) - encoderPosition -= ENCODER_PULSES_PER_STEP * step; - else if (buttons_reprapworld_keypad & EN_REPRAPWORLD_KEYPAD_RIGHT) - encoderPosition = 0; + if (buttons_reprapworld_keypad & EN_REPRAPWORLD_KEYPAD_DOWN) encoderPosition += ENCODER_PULSES_PER_STEP * step; + else if (buttons_reprapworld_keypad & EN_REPRAPWORLD_KEYPAD_UP) encoderPosition -= ENCODER_PULSES_PER_STEP * step; + else if (buttons_reprapworld_keypad & EN_REPRAPWORLD_KEYPAD_RIGHT) encoderPosition = 0; } #if ENABLED(ADC_KEYPAD_DEBUG) SERIAL_PROTOCOLLNPAIR("buttons_reprapworld_keypad = ", (uint32_t)buttons_reprapworld_keypad); SERIAL_PROTOCOLLNPAIR("encoderPosition = ", (uint32_t)encoderPosition); #endif + return true; } - else if (!thermalManager.current_ADCKey_raw) { - // reset stepping acceleration - adc_steps = 0; - } + else if (!thermalManager.current_ADCKey_raw) + adc_steps = 0; // reset stepping acceleration + + return false; } #elif ENABLED(REPRAPWORLD_KEYPAD) @@ -4360,7 +4350,8 @@ void lcd_update() { #if ENABLED(ADC_KEYPAD) - handle_adc_keypad(); + if (handle_adc_keypad()) + return_to_status_ms = ms + LCD_TIMEOUT_TO_STATUS; #elif ENABLED(REPRAPWORLD_KEYPAD) @@ -4792,7 +4783,7 @@ void lcd_reset_alert_level() { lcd_status_message_level = 0; } uint8_t ADCKeyNo; } _stADCKeypadTable_; - static const _stADCKeypadTable_ stADCKeyTable[] = PROGMEM { + static const _stADCKeypadTable_ stADCKeyTable[] PROGMEM = { // VALUE_MIN, VALUE_MAX, KEY { 4000, 4096, BLEN_REPRAPWORLD_KEYPAD_F1 + 1 }, // F1 { 4000, 4096, BLEN_REPRAPWORLD_KEYPAD_F2 + 1 }, // F2 From e80958b631f47132aa0076fb319fa88fc0df2b3c Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Petr=20Zahradn=C3=ADk?= Date: Sat, 24 Jun 2017 19:10:22 +0200 Subject: [PATCH 127/180] CZ Translate BLTouch and UBL Fixup length --- Marlin/language_cz.h | 76 ++++++++++++++++++++++++++++++++++++++++++++ 1 file changed, 76 insertions(+) diff --git a/Marlin/language_cz.h b/Marlin/language_cz.h index 93fd475504..caa6af1ffb 100644 --- a/Marlin/language_cz.h +++ b/Marlin/language_cz.h @@ -54,6 +54,7 @@ #define MSG_LEVEL_BED_WAITING _UxGT("Kliknutim spustte") #define MSG_LEVEL_BED_NEXT_POINT _UxGT("Dalsi bod") #define MSG_LEVEL_BED_DONE _UxGT("Mereni hotovo!") +#define MSG_Z_FADE_HEIGHT _UxGT("Vyska srovnavani") #define MSG_SET_HOME_OFFSETS _UxGT("Nastavit ofsety") #define MSG_HOME_OFFSETS_APPLIED _UxGT("Ofsety nastaveny") #define MSG_SET_ORIGIN _UxGT("Nastavit pocatek") @@ -77,6 +78,68 @@ #define MSG_MOVE_AXIS _UxGT("Posunout osy") #define MSG_BED_LEVELING _UxGT("Vyrovnat podlozku") #define MSG_LEVEL_BED _UxGT("Vyrovnat podlozku") +#define MSG_EDITING_STOPPED _UxGT("Konec uprav site") + +#define MSG_UBL_DOING_G29 _UxGT("Provadim G29") +#define MSG_UBL_UNHOMED _UxGT("Prejedte domu") +#define MSG_UBL_TOOLS _UxGT("UBL nastroje") +#define MSG_UBL_LEVEL_BED _UxGT("Unified Bed Leveling") +#define MSG_UBL_MANUAL_MESH _UxGT("Manualni sit bodu") +#define MSG_UBL_BC_INSERT _UxGT("Vlozte kartu, zmerte") +#define MSG_UBL_BC_INSERT2 _UxGT("Zmerte") +#define MSG_UBL_BC_REMOVE _UxGT("Odstrante a zmerte") +#define MSG_UBL_MOVING_TO_NEXT _UxGT("Presoun na dalsi") +#define MSG_UBL_ACTIVATE_MESH _UxGT("Aktivovat UBL") +#define MSG_UBL_DEACTIVATE_MESH _UxGT("Deaktivovat UBL") +#define MSG_UBL_SET_BED_TEMP _UxGT("Teplota podlozky") +#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("Upravit vlastni sit") +#define MSG_UBL_FINE_TUNE_MESH _UxGT("Doladit sit bodu") +#define MSG_UBL_DONE_EDITING_MESH _UxGT("Konec uprav site") +#define MSG_UBL_BUILD_CUSTOM_MESH _UxGT("Vlastni sit") +#define MSG_UBL_BUILD_MESH_MENU _UxGT("Vytvorit sit") +#define MSG_UBL_BUILD_PLA_MESH _UxGT("Sit bodu PLA") +#define MSG_UBL_BUILD_ABS_MESH _UxGT("Sit bodu ABS") +#define MSG_UBL_BUILD_COLD_MESH _UxGT("Studena sit bodu") +#define MSG_UBL_MESH_HEIGHT_ADJUST _UxGT("Upravit vysku site") +#define MSG_UBL_MESH_HEIGHT_AMOUNT _UxGT("Vyska") +#define MSG_UBL_VALIDATE_MESH_MENU _UxGT("Zkontrolovat sit") +#define MSG_UBL_VALIDATE_PLA_MESH _UxGT("Kontrola site PLA") +#define MSG_UBL_VALIDATE_ABS_MESH _UxGT("Kontrola site ABS") +#define MSG_UBL_VALIDATE_CUSTOM_MESH _UxGT("Kontrola vlast. site") +#define MSG_UBL_CONTINUE_MESH _UxGT("Pokracovat v siti") +#define MSG_UBL_MESH_LEVELING _UxGT("Sitove rovnani") +#define MSG_UBL_3POINT_MESH_LEVELING _UxGT("3-bodove rovnani") +#define MSG_UBL_GRID_MESH_LEVELING _UxGT("Mrizkove rovnani") +#define MSG_UBL_MESH_LEVEL _UxGT("Srovnat podlozku") +#define MSG_UBL_SIDE_POINTS _UxGT("Postranni body") +#define MSG_UBL_MAP_TYPE _UxGT("Typ site bodu") +#define MSG_UBL_OUTPUT_MAP _UxGT("Exportovat sit") +#define MSG_UBL_OUTPUT_MAP_HOST _UxGT("Exportovat do PC") +#define MSG_UBL_OUTPUT_MAP_CSV _UxGT("Exportovat do CSV") +#define MSG_UBL_OUTPUT_MAP_BACKUP _UxGT("Zaloha do PC") +#define MSG_UBL_INFO_UBL _UxGT("Info o UBL do PC") +#define MSG_UBL_EDIT_MESH_MENU _UxGT("Upravit sit dobu") +#define MSG_UBL_FILLIN_AMOUNT _UxGT("Hustota mrizky") +#define MSG_UBL_MANUAL_FILLIN _UxGT("Rucni hustota") +#define MSG_UBL_SMART_FILLIN _UxGT("Chytra hustota") +#define MSG_UBL_FILLIN_MESH _UxGT("Zaplnit mrizku") +#define MSG_UBL_INVALIDATE_ALL _UxGT("Zrusit vsechno") +#define MSG_UBL_INVALIDATE_CLOSEST _UxGT("Zrusit posledni") +#define MSG_UBL_FINE_TUNE_ALL _UxGT("Upravit vsechny") +#define MSG_UBL_FINE_TUNE_CLOSEST _UxGT("Upravit posledni") +#define MSG_UBL_STORAGE_MESH_MENU _UxGT("Stockage maille") +#define MSG_UBL_STORAGE_SLOT _UxGT("Pametovy slot") +#define MSG_UBL_LOAD_MESH _UxGT("Nacist sit bodu") +#define MSG_UBL_SAVE_MESH _UxGT("Ulozit sit bodu") +#define MSG_UBL_SAVE_ERROR _UxGT("Err: Ulozit UBL") +#define MSG_UBL_RESTORE_ERROR _UxGT("Err: Obnovit UBL") +#define MSG_UBL_Z_OFFSET_STOPPED _UxGT("Konec Z-Offsetu") +#define MSG_UBL_STEP_BY_STEP_MENU _UxGT("UBL Postupne") + +#define MSG_USER_MENU _UxGT("Vlastni prikazy") #define MSG_MOVING _UxGT("Posunování...") #define MSG_FREE_XY _UxGT("Uvolnit XY") #define MSG_MOVE_X _UxGT("Posunout X") @@ -110,9 +173,11 @@ #define MSG_VY_JERK _UxGT("Vy-jerk") #define MSG_VZ_JERK _UxGT("Vz-jerk") #define MSG_VE_JERK _UxGT("Ve-jerk") +#define MSG_VELOCITY _UxGT("Rychlost") #define MSG_VMAX _UxGT("Vmax ") #define MSG_VMIN _UxGT("Vmin") #define MSG_VTRAV_MIN _UxGT("VTrav min") +#define MSG_ACCELERATION _UxGT("Akcelerace") #define MSG_AMAX _UxGT("Amax ") #define MSG_A_RETRACT _UxGT("A-retrakt") #define MSG_A_TRAVEL _UxGT("A-prejezd") @@ -136,6 +201,7 @@ #define MSG_STORE_EEPROM _UxGT("Ulozit nastaveni") #define MSG_LOAD_EEPROM _UxGT("Nacist nastaveni") #define MSG_RESTORE_FAILSAFE _UxGT("Obnovit vychozi") +#define MSG_INIT_EEPROM _UxGT("Inic. EEPROM") #define MSG_REFRESH _UxGT("Obnovit") #define MSG_WATCH _UxGT("Info obrazovka") #define MSG_PREPARE _UxGT("Priprava tisku") @@ -147,6 +213,7 @@ #define MSG_NO_CARD _UxGT("Zadna SD karta") #define MSG_DWELL _UxGT("Uspano...") #define MSG_USERWAIT _UxGT("Cekani na uziv...") +#define MSG_PRINT_PAUSED _UxGT("Tisk pozastaven") #define MSG_RESUMING _UxGT("Obnovovani tisku") #define MSG_PRINT_ABORTED _UxGT("Tisk zrusen") #define MSG_NO_MOVE _UxGT("Zadny pohyb.") @@ -164,8 +231,11 @@ #define MSG_INIT_SDCARD _UxGT("Nacist SD kartu") #define MSG_CNG_SDCARD _UxGT("Vymenit 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 Vysunout") +#define MSG_BLTOUCH_STOW _UxGT("BLTouch Zasunout") #define MSG_HOME _UxGT("Domu") // Used as MSG_HOME " " MSG_X MSG_Y MSG_Z " " MSG_FIRST #define MSG_FIRST _UxGT("prvni") #define MSG_ZPROBE_ZOFFSET _UxGT("Z ofset") @@ -199,6 +269,11 @@ #define MSG_DELTA_HEIGHT_CALIBRATE _UxGT("Nast.vysku delty") #define MSG_INFO_MENU _UxGT("O tiskarne") #define MSG_INFO_PRINTER_MENU _UxGT("Info o tiskarne") +#define MSG_3POINT_LEVELING _UxGT("3-bodove rovnani") +#define MSG_LINEAR_LEVELING _UxGT("Linearni rovnani") +#define MSG_BILINEAR_LEVELING _UxGT("Bilinearni rovnani") +#define MSG_UBL_LEVELING _UxGT("Unified Bed Leveling") +#define MSG_MESH_LEVELING _UxGT("Mrizkove rovnani") #define MSG_INFO_STATS_MENU _UxGT("Statistika") #define MSG_INFO_BOARD_MENU _UxGT("Info o desce") #define MSG_INFO_THERMISTOR_MENU _UxGT("Termistory") @@ -206,6 +281,7 @@ #define MSG_INFO_BAUDRATE _UxGT("Rychlost") #define MSG_INFO_PROTOCOL _UxGT("Protokol") #define MSG_CASE_LIGHT _UxGT("Osvetleni") +#define MSG_CASE_LIGHT_BRIGHTNESS _UxGT("Jas svetla") #if LCD_WIDTH >= 20 #define MSG_INFO_PRINT_COUNT _UxGT("Pocet tisku") From 31514f453a9f6315988db266249a8fcb65029715 Mon Sep 17 00:00:00 2001 From: Ben Lye Date: Tue, 27 Jun 2017 08:04:40 +0100 Subject: [PATCH 128/180] Fix #ifdef AVR_AT90USB1286_FAMILY in pinsDebug Can't compile with PINS_DEBUGING enabled on Atmega1284p because it tries to enumerate pins 46 and 47 (which don't exist) because `#ifdef AVR_AT90USB1286_FAMILY ` doesn't work as expected. --- Marlin/Marlin_main.cpp | 2 +- Marlin/pinsDebug.h | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index bf5ab60467..0cb56afa17 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -6438,7 +6438,7 @@ inline void gcode_M42() { } else { report_pin_state_extended(pin, I_flag, true, "Pulsing "); - #ifdef AVR_AT90USB1286_FAMILY // Teensy IDEs don't know about these pins so must use FASTIO + #if AVR_AT90USB1286_FAMILY // Teensy IDEs don't know about these pins so must use FASTIO if (pin == 46) { SET_OUTPUT(46); for (int16_t j = 0; j < repeat; j++) { diff --git a/Marlin/pinsDebug.h b/Marlin/pinsDebug.h index 3e978ecb85..d1390e740d 100644 --- a/Marlin/pinsDebug.h +++ b/Marlin/pinsDebug.h @@ -484,7 +484,7 @@ inline void report_pin_state_extended(int8_t pin, bool ignore, bool extended = f if (pin_is_protected(pin) && !ignore) SERIAL_ECHOPGM("protected "); else { - #ifdef AVR_AT90USB1286_FAMILY //Teensy IDEs don't know about these pins so must use FASTIO + #if AVR_AT90USB1286_FAMILY //Teensy IDEs don't know about these pins so must use FASTIO if (pin == 46 || pin == 47) { if (pin == 46) { print_input_or_output(GET_OUTPUT(46)); @@ -539,7 +539,7 @@ inline void report_pin_state_extended(int8_t pin, bool ignore, bool extended = f SERIAL_ECHO_SP(8); // add padding if not an analog pin SERIAL_ECHOPGM(""); if (extended) { - #ifdef AVR_AT90USB1286_FAMILY //Teensy IDEs don't know about these pins so must use FASTIO + #if AVR_AT90USB1286_FAMILY //Teensy IDEs don't know about these pins so must use FASTIO if (pin == 46 || pin == 47) { SERIAL_PROTOCOL_SP(12); if (pin == 46) { From 99592c84584539fb42eec447909518bc18eb4b2f Mon Sep 17 00:00:00 2001 From: LVD-AC Date: Mon, 26 Jun 2017 12:25:57 +0200 Subject: [PATCH 129/180] Update G33: Add F, fix height bug --- Marlin/Marlin_main.cpp | 56 ++++++++++++++++++++++++++++-------------- 1 file changed, 37 insertions(+), 19 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index bf5ab60467..1ec9210ca4 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -1772,8 +1772,9 @@ static void clean_up_after_endstop_or_probe_move() { float z_dest = LOGICAL_Z_POSITION(z_raise); if (zprobe_zoffset < 0) z_dest -= zprobe_zoffset; + #if ENABLED(DELTA) - z_dest -= home_offset[Z_AXIS]; + z_dest -= home_offset[Z_AXIS]; // Account for delta height adjustment #endif if (z_dest > current_position[Z_AXIS]) @@ -2263,9 +2264,11 @@ static void clean_up_after_endstop_or_probe_move() { // move down quickly before doing the slow probe float z = LOGICAL_Z_POSITION(Z_CLEARANCE_BETWEEN_PROBES); if (zprobe_zoffset < 0) z -= zprobe_zoffset; + #if ENABLED(DELTA) - z -= home_offset[Z_AXIS]; + 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)); @@ -2285,7 +2288,11 @@ 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; + return RAW_CURRENT_POSITION(Z) + zprobe_zoffset + #if ENABLED(DELTA) + + home_offset[Z_AXIS] // Account for delta height adjustment + #endif + ; } /** @@ -5134,6 +5141,8 @@ void home_all_axes() { gcode_G28(true); } * T Don't calibrate tower angle corrections * * Cn.nn Calibration precision; when omitted calibrates to maximum precision + * + * Fn Force to run at least n iterations and takes the best result * * Vn Verbose level: * @@ -5172,7 +5181,13 @@ void home_all_axes() { gcode_G28(true); } return; } - const bool towers_set = !parser.seen('T'), + const int8_t force_iterations = parser.seen('F') ? parser.value_int() : 1; + if (!WITHIN(force_iterations, 1, 30)) { + SERIAL_PROTOCOLLNPGM("?(F)orce iteration is implausible (1-30)."); + return; + } + + const bool towers_set = !parser.seen('T'), stow_after_each = parser.seen('E') && parser.value_bool(), _1p_calibration = probe_points == 1, _4p_calibration = probe_points == 2, @@ -5206,6 +5221,7 @@ void home_all_axes() { gcode_G28(true); } float test_precision, zero_std_dev = (verbose_level ? 999.0 : 0.0), // 0.0 in dry-run mode : forced end zero_std_dev_old = zero_std_dev, + zero_std_dev_min = zero_std_dev, e_old[XYZ] = { endstop_adj[A_AXIS], endstop_adj[B_AXIS], @@ -5284,9 +5300,10 @@ void home_all_axes() { gcode_G28(true); } const uint8_t start = _4p_opposite_points ? 3 : 1, step = _4p_calibration ? 4 : _7p_half_circle ? 2 : 1; for (uint8_t axis = start; axis < 13; axis += step) { - const float offset_circles = _7p_quadruple_circle ? (zig_zag ? 1.5 : 1.0) : - _7p_triple_circle ? (zig_zag ? 1.0 : 0.5) : - _7p_double_circle ? (zig_zag ? 0.5 : 0.0) : 0; + const float zigadd = (zig_zag ? 0.5 : 0.0), + offset_circles = _7p_quadruple_circle ? zigadd + 1.0 : + _7p_triple_circle ? zigadd + 0.5 : + _7p_double_circle ? zigadd : 0; for (float circles = -offset_circles ; circles <= offset_circles; circles++) { const float a = RADIANS(180 + 30 * axis), r = delta_calibration_radius * (1 + circles * (zig_zag ? 0.1 : -0.1)); @@ -5310,18 +5327,19 @@ void home_all_axes() { gcode_G28(true); } N++; } zero_std_dev_old = zero_std_dev; - zero_std_dev = round(SQRT(S2 / N) * 1000.0) / 1000.0 + 0.00001; - - if (iterations == 1) home_offset[Z_AXIS] = zh_old; // reset height after 1st probe change + NOMORE(zero_std_dev_min, zero_std_dev); + zero_std_dev = round(sqrt(S2 / N) * 1000.0) / 1000.0 + 0.00001; // Solve matrices - if (zero_std_dev < test_precision && zero_std_dev > calibration_precision) { - COPY(e_old, endstop_adj); - dr_old = delta_radius; - zh_old = home_offset[Z_AXIS]; - alpha_old = delta_tower_angle_trim[A_AXIS]; - beta_old = delta_tower_angle_trim[B_AXIS]; + if ((zero_std_dev < test_precision && zero_std_dev > calibration_precision) || iterations <= force_iterations) { + if (zero_std_dev < zero_std_dev_min) { + COPY(e_old, endstop_adj); + dr_old = delta_radius; + zh_old = home_offset[Z_AXIS]; + alpha_old = delta_tower_angle_trim[A_AXIS]; + beta_old = delta_tower_angle_trim[B_AXIS]; + } float e_delta[XYZ] = { 0.0 }, r_delta = 0.0, t_alpha = 0.0, t_beta = 0.0; const float r_diff = delta_radius - delta_calibration_radius, @@ -5420,7 +5438,7 @@ void home_all_axes() { gcode_G28(true); } } } if (test_precision != 0.0) { // !forced end - if (zero_std_dev >= test_precision || zero_std_dev <= calibration_precision) { // end iterations + if ((zero_std_dev >= test_precision || zero_std_dev <= calibration_precision) && iterations > force_iterations) { // end iterations SERIAL_PROTOCOLPGM("Calibration OK"); SERIAL_PROTOCOL_SP(36); if (zero_std_dev >= test_precision) @@ -5458,7 +5476,7 @@ void home_all_axes() { gcode_G28(true); } SERIAL_PROTOCOLPGM(" Tz:+0.00"); SERIAL_EOL(); } - if (zero_std_dev >= test_precision || zero_std_dev <= calibration_precision) + if ((zero_std_dev >= test_precision || zero_std_dev <= calibration_precision) && iterations > force_iterations) serialprintPGM(save_message); SERIAL_EOL(); } @@ -5485,7 +5503,7 @@ void home_all_axes() { gcode_G28(true); } endstops.not_homing(); } - while (zero_std_dev < test_precision && zero_std_dev > calibration_precision && iterations < 31); + while ((zero_std_dev < test_precision && zero_std_dev > calibration_precision && iterations < 31) || iterations <= force_iterations); #if ENABLED(DELTA_HOME_TO_SAFE_ZONE) do_blocking_move_to_z(delta_clip_start_height); From f0f9fb7465dd411e0c0b3a9d50d8e475bde5d773 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 27 Jun 2017 04:08:50 -0500 Subject: [PATCH 130/180] Remove line that does nothing --- Marlin/Marlin_main.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 1ec9210ca4..d93317b5c2 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -8266,7 +8266,6 @@ inline void gcode_M205() { inline void gcode_M665() { if (parser.seen('H')) { home_offset[Z_AXIS] = parser.value_linear_units() - DELTA_HEIGHT; - current_position[Z_AXIS] += parser.value_linear_units() - DELTA_HEIGHT - home_offset[Z_AXIS]; update_software_endstops(Z_AXIS); } if (parser.seen('L')) delta_diagonal_rod = parser.value_linear_units(); From ba1706a2651ecd1c0b3e2991d850c9a4c0c3b76c Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 2 Jun 2017 21:45:51 -0500 Subject: [PATCH 131/180] Fix spacing in gcode.cpp Followup to #6940 --- Marlin/gcode.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/Marlin/gcode.cpp b/Marlin/gcode.cpp index 02aaf68a3a..a2f5dcfb10 100644 --- a/Marlin/gcode.cpp +++ b/Marlin/gcode.cpp @@ -184,7 +184,7 @@ void GCodeParser::parse(char *p) { if (PARAM_TEST) { - while (*p == ' ') p++; // skip spaces vetween parameters & values + while (*p == ' ') p++; // Skip spaces between parameters & values const bool has_num = DECIMAL_SIGNED(*p); // The parameter has a number [-+0-9.] #if ENABLED(DEBUG_GCODE_PARSER) @@ -222,8 +222,8 @@ void GCodeParser::parse(char *p) { } if (!WITHIN(*p, 'A', 'Z')) { - while (*p && NUMERIC(*p)) p++; // Skip over the value section of a parameter - while (*p == ' ') p++; // Skip over all spaces + while (*p && NUMERIC(*p)) p++; // Skip over the value section of a parameter + while (*p == ' ') p++; // Skip over all spaces } } } From a4a587a8971cf3c8beecfc10b4c7d2e7b03ccd27 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 2 Jun 2017 13:57:53 -0500 Subject: [PATCH 132/180] =?UTF-8?q?Fix=20spelling=20of=20Pr=C5=AF=C5=A1a?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration_adv.h | 2 +- Marlin/example_configurations/Cartesio/Configuration_adv.h | 2 +- Marlin/example_configurations/Felix/Configuration_adv.h | 2 +- .../FolgerTech-i3-2020/Configuration_adv.h | 2 +- Marlin/example_configurations/Hephestos/Configuration_adv.h | 2 +- Marlin/example_configurations/Hephestos_2/Configuration_adv.h | 2 +- Marlin/example_configurations/K8200/Configuration_adv.h | 2 +- Marlin/example_configurations/K8400/Configuration_adv.h | 2 +- Marlin/example_configurations/M150/Configuration_adv.h | 2 +- Marlin/example_configurations/RigidBot/Configuration_adv.h | 2 +- Marlin/example_configurations/SCARA/Configuration_adv.h | 2 +- Marlin/example_configurations/TAZ4/Configuration_adv.h | 2 +- Marlin/example_configurations/TinyBoy2/Configuration_adv.h | 2 +- Marlin/example_configurations/WITBOX/Configuration_adv.h | 2 +- .../delta/FLSUN/auto_calibrate/Configuration_adv.h | 2 +- .../delta/FLSUN/kossel_mini/Configuration_adv.h | 2 +- .../example_configurations/delta/generic/Configuration_adv.h | 2 +- .../delta/kossel_mini/Configuration_adv.h | 2 +- .../delta/kossel_pro/Configuration_adv.h | 2 +- .../example_configurations/delta/kossel_xl/Configuration_adv.h | 2 +- .../gCreate_gMax1.5+/Configuration_adv.h | 2 +- Marlin/example_configurations/makibox/Configuration_adv.h | 2 +- .../example_configurations/tvrrug/Round2/Configuration_adv.h | 2 +- Marlin/example_configurations/wt150/Configuration_adv.h | 2 +- Marlin/planner.cpp | 3 ++- 25 files changed, 26 insertions(+), 25 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 76ad8bec41..4c772ec2d7 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -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 Slic3r) 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/Cartesio/Configuration_adv.h b/Marlin/example_configurations/Cartesio/Configuration_adv.h index c9a1a4fcaa..1de847b7f6 100644 --- a/Marlin/example_configurations/Cartesio/Configuration_adv.h +++ b/Marlin/example_configurations/Cartesio/Configuration_adv.h @@ -645,7 +645,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 Slic3r) 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/Felix/Configuration_adv.h b/Marlin/example_configurations/Felix/Configuration_adv.h index c5ccf0e291..8e5e5fab00 100644 --- a/Marlin/example_configurations/Felix/Configuration_adv.h +++ b/Marlin/example_configurations/Felix/Configuration_adv.h @@ -645,7 +645,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 Slic3r) 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/FolgerTech-i3-2020/Configuration_adv.h b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h index 9cd215dc9b..5031cfb2d7 100644 --- a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h +++ b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h @@ -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 Slic3r) 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/Hephestos/Configuration_adv.h b/Marlin/example_configurations/Hephestos/Configuration_adv.h index 61d381eada..bf39fff886 100644 --- a/Marlin/example_configurations/Hephestos/Configuration_adv.h +++ b/Marlin/example_configurations/Hephestos/Configuration_adv.h @@ -645,7 +645,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 Slic3r) 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/Hephestos_2/Configuration_adv.h b/Marlin/example_configurations/Hephestos_2/Configuration_adv.h index 22948c672e..4be6605e34 100644 --- a/Marlin/example_configurations/Hephestos_2/Configuration_adv.h +++ b/Marlin/example_configurations/Hephestos_2/Configuration_adv.h @@ -628,7 +628,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 Slic3r) 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/K8200/Configuration_adv.h b/Marlin/example_configurations/K8200/Configuration_adv.h index a30c0a62d2..d931ab26ce 100644 --- a/Marlin/example_configurations/K8200/Configuration_adv.h +++ b/Marlin/example_configurations/K8200/Configuration_adv.h @@ -658,7 +658,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 Slic3r) 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/K8400/Configuration_adv.h b/Marlin/example_configurations/K8400/Configuration_adv.h index 2c46112f83..0f650aa952 100644 --- a/Marlin/example_configurations/K8400/Configuration_adv.h +++ b/Marlin/example_configurations/K8400/Configuration_adv.h @@ -645,7 +645,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 Slic3r) 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/M150/Configuration_adv.h b/Marlin/example_configurations/M150/Configuration_adv.h index e55f604d6e..49bcfcf586 100644 --- a/Marlin/example_configurations/M150/Configuration_adv.h +++ b/Marlin/example_configurations/M150/Configuration_adv.h @@ -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 Slic3r) 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/RigidBot/Configuration_adv.h b/Marlin/example_configurations/RigidBot/Configuration_adv.h index 046ff52d6a..84921f2250 100644 --- a/Marlin/example_configurations/RigidBot/Configuration_adv.h +++ b/Marlin/example_configurations/RigidBot/Configuration_adv.h @@ -645,7 +645,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 Slic3r) 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/SCARA/Configuration_adv.h b/Marlin/example_configurations/SCARA/Configuration_adv.h index 601dead507..59304ae0c4 100644 --- a/Marlin/example_configurations/SCARA/Configuration_adv.h +++ b/Marlin/example_configurations/SCARA/Configuration_adv.h @@ -645,7 +645,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 Slic3r) 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/TAZ4/Configuration_adv.h b/Marlin/example_configurations/TAZ4/Configuration_adv.h index 50f67b98e2..f7184724f6 100644 --- a/Marlin/example_configurations/TAZ4/Configuration_adv.h +++ b/Marlin/example_configurations/TAZ4/Configuration_adv.h @@ -645,7 +645,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 Slic3r) 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/TinyBoy2/Configuration_adv.h b/Marlin/example_configurations/TinyBoy2/Configuration_adv.h index d60392bad2..494d58ca07 100644 --- a/Marlin/example_configurations/TinyBoy2/Configuration_adv.h +++ b/Marlin/example_configurations/TinyBoy2/Configuration_adv.h @@ -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 Slic3r) 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/WITBOX/Configuration_adv.h b/Marlin/example_configurations/WITBOX/Configuration_adv.h index 61d381eada..bf39fff886 100644 --- a/Marlin/example_configurations/WITBOX/Configuration_adv.h +++ b/Marlin/example_configurations/WITBOX/Configuration_adv.h @@ -645,7 +645,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 Slic3r) 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/delta/FLSUN/auto_calibrate/Configuration_adv.h b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h index fd23ac779d..51019d2287 100644 --- a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h +++ b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h @@ -650,7 +650,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 Slic3r) 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/delta/FLSUN/kossel_mini/Configuration_adv.h b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h index 6900bc812f..d00185a6a6 100644 --- a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h +++ b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h @@ -650,7 +650,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 Slic3r) 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/delta/generic/Configuration_adv.h b/Marlin/example_configurations/delta/generic/Configuration_adv.h index 497ae82463..6fd092e0bb 100644 --- a/Marlin/example_configurations/delta/generic/Configuration_adv.h +++ b/Marlin/example_configurations/delta/generic/Configuration_adv.h @@ -647,7 +647,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 Slic3r) 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/delta/kossel_mini/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h index 497ae82463..6fd092e0bb 100644 --- a/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h @@ -647,7 +647,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 Slic3r) 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/delta/kossel_pro/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h index 20ee8ed5a3..f2a74f2910 100644 --- a/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h @@ -652,7 +652,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 Slic3r) 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/delta/kossel_xl/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h index 5b7c5df696..00a02b39b2 100644 --- a/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h @@ -647,7 +647,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 Slic3r) 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/gCreate_gMax1.5+/Configuration_adv.h b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration_adv.h index 18f63570d5..cf0cc38efb 100644 --- a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration_adv.h +++ b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration_adv.h @@ -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 Slic3r) 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/makibox/Configuration_adv.h b/Marlin/example_configurations/makibox/Configuration_adv.h index f1a18f02f1..8a7a61da4a 100644 --- a/Marlin/example_configurations/makibox/Configuration_adv.h +++ b/Marlin/example_configurations/makibox/Configuration_adv.h @@ -645,7 +645,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 Slic3r) 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/tvrrug/Round2/Configuration_adv.h b/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h index dd9573c3bf..5de0a43bb8 100644 --- a/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h +++ b/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h @@ -645,7 +645,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 Slic3r) 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/wt150/Configuration_adv.h b/Marlin/example_configurations/wt150/Configuration_adv.h index 4c3d4d02b8..97f73b2e82 100644 --- a/Marlin/example_configurations/wt150/Configuration_adv.h +++ b/Marlin/example_configurations/wt150/Configuration_adv.h @@ -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 Slic3r) 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/planner.cpp b/Marlin/planner.cpp index 8cac74f146..1e84ae2085 100644 --- a/Marlin/planner.cpp +++ b/Marlin/planner.cpp @@ -1275,7 +1275,8 @@ void Planner::_buffer_line(const float &a, const float &b, const float &c, const #endif /** - * Adapted from Prusa MKS firmware + * Adapted from Průša MKS firmware + * https://github.com/prusa3d/Prusa-Firmware * * Start with a safe speed (from which the machine may halt to stop immediately). */ From 5b11b33854c9950b9a98005aa7783b1fe67b6269 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 2 Jun 2017 13:57:31 -0500 Subject: [PATCH 133/180] =?UTF-8?q?Add=20support=20for=20Pr=C5=AF=C5=A1a?= =?UTF-8?q?=20MK2=20Multiplexer?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Conditionals_LCD.h | 6 ++ Marlin/Configuration.h | 19 ++++++ Marlin/Marlin_main.cpp | 64 +++++++++++++++++-- Marlin/SanityCheck.h | 11 ++++ .../Anet/Configuration.h | 19 ++++++ .../CL-260/Configuration.h | 19 ++++++ .../Cartesio/Configuration.h | 19 ++++++ .../Felix/Configuration.h | 19 ++++++ .../Felix/DUAL/Configuration.h | 19 ++++++ .../FolgerTech-i3-2020/Configuration.h | 19 ++++++ .../Hephestos/Configuration.h | 19 ++++++ .../Hephestos_2/Configuration.h | 19 ++++++ .../K8200/Configuration.h | 19 ++++++ .../K8400/Configuration.h | 19 ++++++ .../K8400/Dual-head/Configuration.h | 19 ++++++ .../M150/Configuration.h | 19 ++++++ .../RepRapWorld/Megatronics/Configuration.h | 19 ++++++ .../RigidBot/Configuration.h | 19 ++++++ .../SCARA/Configuration.h | 19 ++++++ .../TAZ4/Configuration.h | 19 ++++++ .../TinyBoy2/Configuration.h | 19 ++++++ .../WITBOX/Configuration.h | 19 ++++++ .../adafruit/ST7565/Configuration.h | 19 ++++++ .../FLSUN/auto_calibrate/Configuration.h | 19 ++++++ .../delta/FLSUN/kossel_mini/Configuration.h | 19 ++++++ .../delta/generic/Configuration.h | 19 ++++++ .../delta/kossel_mini/Configuration.h | 19 ++++++ .../delta/kossel_pro/Configuration.h | 19 ++++++ .../delta/kossel_xl/Configuration.h | 19 ++++++ .../gCreate_gMax1.5+/Configuration.h | 19 ++++++ .../makibox/Configuration.h | 19 ++++++ .../tvrrug/Round2/Configuration.h | 19 ++++++ .../wt150/Configuration.h | 19 ++++++ Marlin/pins_MINIRAMBO.h | 24 ++++--- Marlin/pins_RAMBO.h | 21 ++++-- Marlin/pins_RAMPS.h | 39 ++++++----- Marlin/stepper.cpp | 10 ++- Marlin/stepper_indirection.h | 10 ++- 38 files changed, 714 insertions(+), 41 deletions(-) diff --git a/Marlin/Conditionals_LCD.h b/Marlin/Conditionals_LCD.h index 28937590d5..791a41d28c 100644 --- a/Marlin/Conditionals_LCD.h +++ b/Marlin/Conditionals_LCD.h @@ -307,6 +307,11 @@ #define HAS_DEBUG_MENU ENABLED(LCD_PROGRESS_BAR_TEST) + // MK2 Multiplexer forces SINGLENOZZLE to be enabled + #if ENABLED(MK2_MULTIPLEXER) + #define SINGLENOZZLE + #endif + /** * Extruders have some combination of stepper motors and hotends * so we separate these concepts into the defines: @@ -314,6 +319,7 @@ * EXTRUDERS - Number of Selectable Tools * HOTENDS - Number of hotends, whether connected or separate * E_STEPPERS - Number of actual E stepper motors + * E_MANUAL - Number of E steppers for LCD move options * TOOL_E_INDEX - Index to use when getting/setting the tool state * */ diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index ece9499328..9295d6774b 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -138,6 +138,25 @@ // 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) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 48cf72cc02..030a9dc7bb 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -9436,6 +9436,39 @@ inline void gcode_M503() { #endif // ADVANCED_PAUSE_FEATURE +#if ENABLED(MK2_MULTIPLEXER) + + inline void select_multiplexed_stepper(const uint8_t e) { + stepper.synchronize(); + disable_e_steppers(); + WRITE(E_MUX0_PIN, TEST(e, 0) ? HIGH : LOW); + WRITE(E_MUX1_PIN, TEST(e, 1) ? HIGH : LOW); + WRITE(E_MUX2_PIN, TEST(e, 2) ? HIGH : LOW); + safe_delay(100); + } + + /** + * M702: Unload all extruders + */ + inline void gcode_M702() { + for (uint8_t s = 0; s < E_STEPPERS; s++) { + select_multiplexed_stepper(e); + // TODO: standard unload filament function + // MK2 firmware behavior: + // - Make sure temperature is high enough + // - Raise Z to at least 15 to make room + // - Extrude 1cm of filament in 1 second + // - Under 230C quickly purge ~12mm, over 230C purge ~10mm + // - Change E max feedrate to 80, eject the filament from the tube. Sync. + // - Restore E max feedrate to 50 + } + // Go back to the last active extruder + select_multiplexed_stepper(active_extruder); + disable_e_steppers(); + } + +#endif // MK2_MULTIPLEXER + #if ENABLED(DUAL_X_CARRIAGE) /** @@ -10257,14 +10290,23 @@ void tool_change(const uint8_t tmp_extruder, const float fr_mm_s/*=0.0*/, bool n UNUSED(fr_mm_s); UNUSED(no_move); - // Set the new active extruder - active_extruder = tmp_extruder; + #if ENABLED(SWITCHING_EXTRUDER) && !DONT_SWITCH + + stepper.synchronize(); + move_extruder_servo(tmp_extruder); + + #elif 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 - move_extruder_servo(active_extruder); - #endif + active_extruder = tmp_extruder; SERIAL_ECHO_START(); SERIAL_ECHOLNPAIR(MSG_ACTIVE_EXTRUDER, (int)active_extruder); @@ -11001,6 +11043,12 @@ void process_next_command() { break; #endif // DUAL_X_CARRIAGE + #if ENABLED(MK2_MULTIPLEXER) + case 702: // M702: Unload all extruders + gcode_M702(); + break; + #endif + #if ENABLED(LIN_ADVANCE) case 900: // M900: Set advance K factor. gcode_M900(); @@ -12968,6 +13016,12 @@ void setup() { #endif #endif + #if ENABLED(MK2_MULTIPLEXER) + SET_OUTPUT(E_MUX0_PIN); + SET_OUTPUT(E_MUX1_PIN); + SET_OUTPUT(E_MUX2_PIN); + #endif + lcd_init(); #if ENABLED(SHOW_BOOTSCREEN) #if ENABLED(DOGLCD) diff --git a/Marlin/SanityCheck.h b/Marlin/SanityCheck.h index f12d37b440..d2bcda6580 100644 --- a/Marlin/SanityCheck.h +++ b/Marlin/SanityCheck.h @@ -352,10 +352,21 @@ #error "EXTRUDERS must be 1 with HEATERS_PARALLEL." #endif +#elif ENABLED(MK2_MULTIPLEXER) + #error "MK2_MULTIPLEXER requires 2 or more EXTRUDERS." #elif ENABLED(SINGLENOZZLE) #error "SINGLENOZZLE requires 2 or more EXTRUDERS." #endif +/** + * Sanity checking for the Průša MK2 Multiplexer + */ +#ifdef SNMM + #error "SNMM is now MK2_MULTIPLEXER. Please update your configuration." +#elif ENABLED(MK2_MULTIPLEXER) && DISABLED(ADVANCED_PAUSE_FEATURE) + #error "ADVANCED_PAUSE_FEATURE is required with MK2_MULTIPLEXER." +#endif + /** * A Dual Nozzle carriage with switching servo */ diff --git a/Marlin/example_configurations/Anet/Configuration.h b/Marlin/example_configurations/Anet/Configuration.h index ac16115306..042ab73395 100644 --- a/Marlin/example_configurations/Anet/Configuration.h +++ b/Marlin/example_configurations/Anet/Configuration.h @@ -138,6 +138,25 @@ // 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) diff --git a/Marlin/example_configurations/CL-260/Configuration.h b/Marlin/example_configurations/CL-260/Configuration.h index 90da7b05f8..545220f80e 100644 --- a/Marlin/example_configurations/CL-260/Configuration.h +++ b/Marlin/example_configurations/CL-260/Configuration.h @@ -138,6 +138,25 @@ // 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) diff --git a/Marlin/example_configurations/Cartesio/Configuration.h b/Marlin/example_configurations/Cartesio/Configuration.h index 0d84d53bfc..10d1f84ea6 100644 --- a/Marlin/example_configurations/Cartesio/Configuration.h +++ b/Marlin/example_configurations/Cartesio/Configuration.h @@ -139,6 +139,25 @@ // 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) diff --git a/Marlin/example_configurations/Felix/Configuration.h b/Marlin/example_configurations/Felix/Configuration.h index d3e288c054..7ca6e17f33 100644 --- a/Marlin/example_configurations/Felix/Configuration.h +++ b/Marlin/example_configurations/Felix/Configuration.h @@ -138,6 +138,25 @@ // 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) diff --git a/Marlin/example_configurations/Felix/DUAL/Configuration.h b/Marlin/example_configurations/Felix/DUAL/Configuration.h index ad8553a945..af9b9aa496 100644 --- a/Marlin/example_configurations/Felix/DUAL/Configuration.h +++ b/Marlin/example_configurations/Felix/DUAL/Configuration.h @@ -138,6 +138,25 @@ // 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) diff --git a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h index 13892b2771..a7db519e01 100644 --- a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h +++ b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h @@ -138,6 +138,25 @@ // 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) diff --git a/Marlin/example_configurations/Hephestos/Configuration.h b/Marlin/example_configurations/Hephestos/Configuration.h index 153e6028db..cd2cf20c29 100644 --- a/Marlin/example_configurations/Hephestos/Configuration.h +++ b/Marlin/example_configurations/Hephestos/Configuration.h @@ -141,6 +141,25 @@ // 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) diff --git a/Marlin/example_configurations/Hephestos_2/Configuration.h b/Marlin/example_configurations/Hephestos_2/Configuration.h index 2864c04b0c..de69aeb068 100644 --- a/Marlin/example_configurations/Hephestos_2/Configuration.h +++ b/Marlin/example_configurations/Hephestos_2/Configuration.h @@ -138,6 +138,25 @@ // 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) diff --git a/Marlin/example_configurations/K8200/Configuration.h b/Marlin/example_configurations/K8200/Configuration.h index 05a6c11a89..c6b5521f90 100644 --- a/Marlin/example_configurations/K8200/Configuration.h +++ b/Marlin/example_configurations/K8200/Configuration.h @@ -158,6 +158,25 @@ // 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) diff --git a/Marlin/example_configurations/K8400/Configuration.h b/Marlin/example_configurations/K8400/Configuration.h index ec265fcc95..53624af67f 100644 --- a/Marlin/example_configurations/K8400/Configuration.h +++ b/Marlin/example_configurations/K8400/Configuration.h @@ -138,6 +138,25 @@ // 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) diff --git a/Marlin/example_configurations/K8400/Dual-head/Configuration.h b/Marlin/example_configurations/K8400/Dual-head/Configuration.h index 9b60e17404..975997a77f 100644 --- a/Marlin/example_configurations/K8400/Dual-head/Configuration.h +++ b/Marlin/example_configurations/K8400/Dual-head/Configuration.h @@ -138,6 +138,25 @@ // 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) diff --git a/Marlin/example_configurations/M150/Configuration.h b/Marlin/example_configurations/M150/Configuration.h index d47a8526a7..d73fd6c40f 100644 --- a/Marlin/example_configurations/M150/Configuration.h +++ b/Marlin/example_configurations/M150/Configuration.h @@ -143,6 +143,25 @@ // 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) diff --git a/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h b/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h index b008062b30..201a3d2e47 100644 --- a/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h +++ b/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h @@ -138,6 +138,25 @@ // 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) diff --git a/Marlin/example_configurations/RigidBot/Configuration.h b/Marlin/example_configurations/RigidBot/Configuration.h index b05d00937f..158d42fbd3 100644 --- a/Marlin/example_configurations/RigidBot/Configuration.h +++ b/Marlin/example_configurations/RigidBot/Configuration.h @@ -141,6 +141,25 @@ // 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) diff --git a/Marlin/example_configurations/SCARA/Configuration.h b/Marlin/example_configurations/SCARA/Configuration.h index 06c2a32300..3a32e80fce 100644 --- a/Marlin/example_configurations/SCARA/Configuration.h +++ b/Marlin/example_configurations/SCARA/Configuration.h @@ -168,6 +168,25 @@ // 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) diff --git a/Marlin/example_configurations/TAZ4/Configuration.h b/Marlin/example_configurations/TAZ4/Configuration.h index 86d9c1bd87..1414d0ccaa 100644 --- a/Marlin/example_configurations/TAZ4/Configuration.h +++ b/Marlin/example_configurations/TAZ4/Configuration.h @@ -138,6 +138,25 @@ // 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) diff --git a/Marlin/example_configurations/TinyBoy2/Configuration.h b/Marlin/example_configurations/TinyBoy2/Configuration.h index 4ecc19dc7f..5ded991e54 100644 --- a/Marlin/example_configurations/TinyBoy2/Configuration.h +++ b/Marlin/example_configurations/TinyBoy2/Configuration.h @@ -160,6 +160,25 @@ // 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) diff --git a/Marlin/example_configurations/WITBOX/Configuration.h b/Marlin/example_configurations/WITBOX/Configuration.h index cd4df35ecb..53b2506ebd 100644 --- a/Marlin/example_configurations/WITBOX/Configuration.h +++ b/Marlin/example_configurations/WITBOX/Configuration.h @@ -141,6 +141,25 @@ // 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) diff --git a/Marlin/example_configurations/adafruit/ST7565/Configuration.h b/Marlin/example_configurations/adafruit/ST7565/Configuration.h index dd458267d9..245675fbaf 100644 --- a/Marlin/example_configurations/adafruit/ST7565/Configuration.h +++ b/Marlin/example_configurations/adafruit/ST7565/Configuration.h @@ -138,6 +138,25 @@ // 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) diff --git a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h index 66bd78c4c8..18bdac8728 100644 --- a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h +++ b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h @@ -138,6 +138,25 @@ // 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) diff --git a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h index f3d95861b7..5dde5f4871 100644 --- a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h +++ b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h @@ -138,6 +138,25 @@ // 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) diff --git a/Marlin/example_configurations/delta/generic/Configuration.h b/Marlin/example_configurations/delta/generic/Configuration.h index 009e879192..f13de9116c 100644 --- a/Marlin/example_configurations/delta/generic/Configuration.h +++ b/Marlin/example_configurations/delta/generic/Configuration.h @@ -138,6 +138,25 @@ // 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) diff --git a/Marlin/example_configurations/delta/kossel_mini/Configuration.h b/Marlin/example_configurations/delta/kossel_mini/Configuration.h index 840f03f9d6..c4ed97e7c9 100644 --- a/Marlin/example_configurations/delta/kossel_mini/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_mini/Configuration.h @@ -138,6 +138,25 @@ // 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) diff --git a/Marlin/example_configurations/delta/kossel_pro/Configuration.h b/Marlin/example_configurations/delta/kossel_pro/Configuration.h index 84ba273231..d53d1aa230 100644 --- a/Marlin/example_configurations/delta/kossel_pro/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_pro/Configuration.h @@ -142,6 +142,25 @@ // 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) diff --git a/Marlin/example_configurations/delta/kossel_xl/Configuration.h b/Marlin/example_configurations/delta/kossel_xl/Configuration.h index 76ffbbcd6c..9fbd10b94e 100644 --- a/Marlin/example_configurations/delta/kossel_xl/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_xl/Configuration.h @@ -138,6 +138,25 @@ // 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) diff --git a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h index 97348c1792..03b4f2440b 100644 --- a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h +++ b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h @@ -143,6 +143,25 @@ // 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) diff --git a/Marlin/example_configurations/makibox/Configuration.h b/Marlin/example_configurations/makibox/Configuration.h index dfe778b3b4..6fe07aa24f 100644 --- a/Marlin/example_configurations/makibox/Configuration.h +++ b/Marlin/example_configurations/makibox/Configuration.h @@ -138,6 +138,25 @@ // 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) diff --git a/Marlin/example_configurations/tvrrug/Round2/Configuration.h b/Marlin/example_configurations/tvrrug/Round2/Configuration.h index ab56d7eb03..015a0d327c 100644 --- a/Marlin/example_configurations/tvrrug/Round2/Configuration.h +++ b/Marlin/example_configurations/tvrrug/Round2/Configuration.h @@ -138,6 +138,25 @@ // 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) diff --git a/Marlin/example_configurations/wt150/Configuration.h b/Marlin/example_configurations/wt150/Configuration.h index a023c3f169..717b0b2055 100644 --- a/Marlin/example_configurations/wt150/Configuration.h +++ b/Marlin/example_configurations/wt150/Configuration.h @@ -138,6 +138,25 @@ // 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) diff --git a/Marlin/pins_MINIRAMBO.h b/Marlin/pins_MINIRAMBO.h index 6a95a3c4b1..9ff32207f9 100644 --- a/Marlin/pins_MINIRAMBO.h +++ b/Marlin/pins_MINIRAMBO.h @@ -115,6 +115,21 @@ #define LED_PIN 13 #define CASE_LIGHT_PIN 9 +// +// M3/M4/M5 - Spindle/Laser Control +// +// use P1 connector for spindle pins +#define SPINDLE_LASER_PWM_PIN 9 // MUST BE HARDWARE PWM +#define SPINDLE_LASER_ENABLE_PIN 18 // Pin should have a pullup! +#define SPINDLE_DIR_PIN 19 + +// +// Průša i3 MK2 Multiplexer Support +// +#define E_MUX0_PIN 17 +#define E_MUX1_PIN 16 +#define E_MUX2_PIN 78 // 84 in MK2 Firmware, with BEEPER as 78 + // // LCD / Controller // @@ -143,12 +158,3 @@ #endif // NEWPANEL #endif // ULTRA_LCD - -// -// M3/M4/M5 - Spindle/Laser Control -// - -// use P1 connector for spindle pins -#define SPINDLE_LASER_PWM_PIN 9 // MUST BE HARDWARE PWM -#define SPINDLE_LASER_ENABLE_PIN 18 // Pin should have a pullup! -#define SPINDLE_DIR_PIN 19 diff --git a/Marlin/pins_RAMBO.h b/Marlin/pins_RAMBO.h index 268ebfefcb..6ddd305eae 100644 --- a/Marlin/pins_RAMBO.h +++ b/Marlin/pins_RAMBO.h @@ -142,6 +142,20 @@ #define FILWIDTH_PIN 3 // Analog Input #endif +// +// M3/M4/M5 - Spindle/Laser Control +// +#define SPINDLE_LASER_PWM_PIN 45 // MUST BE HARDWARE PWM +#define SPINDLE_LASER_ENABLE_PIN 31 // Pin should have a pullup! +#define SPINDLE_DIR_PIN 32 + +// +// Průša i3 MK2 Multiplexer Support +// +#define E_MUX0_PIN 17 +#define E_MUX1_PIN 16 +#define E_MUX2_PIN 84 // 84 in MK2 Firmware + // // LCD / Controller // @@ -212,10 +226,3 @@ #endif // !NEWPANEL #endif // ULTRA_LCD - -// -// M3/M4/M5 - Spindle/Laser Control -// -#define SPINDLE_LASER_PWM_PIN 45 // MUST BE HARDWARE PWM -#define SPINDLE_LASER_ENABLE_PIN 31 // Pin should have a pullup! -#define SPINDLE_DIR_PIN 32 diff --git a/Marlin/pins_RAMPS.h b/Marlin/pins_RAMPS.h index 411e0f47ca..91d435afb2 100644 --- a/Marlin/pins_RAMPS.h +++ b/Marlin/pins_RAMPS.h @@ -214,6 +214,29 @@ #endif #endif +// +// M3/M4/M5 - Spindle/Laser Control +// +#if ENABLED(SPINDLE_LASER_ENABLE) && !PIN_EXISTS(SPINDLE_LASER_ENABLE) + #if !defined(NUM_SERVOS) || NUM_SERVOS == 0 // try to use servo connector first + #define SPINDLE_LASER_ENABLE_PIN 4 // Pin should have a pullup/pulldown! + #define SPINDLE_LASER_PWM_PIN 6 // MUST BE HARDWARE PWM + #define SPINDLE_DIR_PIN 5 + #elif !(ENABLED(ULTRA_LCD) && ENABLED(NEWPANEL) \ + && (ENABLED(PANEL_ONE) || ENABLED(VIKI2) || ENABLED(miniVIKI) || ENABLED(MINIPANEL) || ENABLED(REPRAPWORLD_KEYPAD))) // try to use AUX 2 + #define SPINDLE_LASER_ENABLE_PIN 40 // Pin should have a pullup/pulldown! + #define SPINDLE_LASER_PWM_PIN 44 // MUST BE HARDWARE PWM + #define SPINDLE_DIR_PIN 65 + #endif +#endif + +// +// Průša i3 MK2 Multiplexer Support +// +#define E_MUX0_PIN 40 // Z_CS_PIN +#define E_MUX1_PIN 42 // E0_CS_PIN +#define E_MUX2_PIN 44 // E1_CS_PIN + // // LCD / Controller // @@ -378,19 +401,3 @@ #endif // NEWPANEL #endif // ULTRA_LCD - -// -// M3/M4/M5 - Spindle/Laser Control -// -#if ENABLED(SPINDLE_LASER_ENABLE) && !PIN_EXISTS(SPINDLE_LASER_ENABLE) - #if !defined(NUM_SERVOS) || NUM_SERVOS == 0 // try to use servo connector first - #define SPINDLE_LASER_ENABLE_PIN 4 // Pin should have a pullup/pulldown! - #define SPINDLE_LASER_PWM_PIN 6 // MUST BE HARDWARE PWM - #define SPINDLE_DIR_PIN 5 - #elif !(ENABLED(ULTRA_LCD) && ENABLED(NEWPANEL) \ - && (ENABLED(PANEL_ONE) || ENABLED(VIKI2) || ENABLED(miniVIKI) || ENABLED(MINIPANEL) || ENABLED(REPRAPWORLD_KEYPAD))) // try to use AUX 2 - #define SPINDLE_LASER_ENABLE_PIN 40 // Pin should have a pullup/pulldown! - #define SPINDLE_LASER_PWM_PIN 44 // MUST BE HARDWARE PWM - #define SPINDLE_DIR_PIN 65 - #endif -#endif diff --git a/Marlin/stepper.cpp b/Marlin/stepper.cpp index c7ea4ba15c..717213c50b 100644 --- a/Marlin/stepper.cpp +++ b/Marlin/stepper.cpp @@ -860,8 +860,14 @@ void Stepper::isr() { nextAdvanceISR = eISR_Rate; - #define SET_E_STEP_DIR(INDEX) \ - if (e_steps[INDEX]) E## INDEX ##_DIR_WRITE(e_steps[INDEX] < 0 ? INVERT_E## INDEX ##_DIR : !INVERT_E## INDEX ##_DIR) + #if ENABLED(MK2_MULTIPLEXER) + // Even-numbered steppers are reversed + #define SET_E_STEP_DIR(INDEX) \ + if (e_steps[INDEX]) E## INDEX ##_DIR_WRITE(e_steps[INDEX] < 0 ? !INVERT_E## INDEX ##_DIR ^ TEST(INDEX, 0) : INVERT_E## INDEX ##_DIR ^ TEST(INDEX, 0)) + #else + #define SET_E_STEP_DIR(INDEX) \ + if (e_steps[INDEX]) E## INDEX ##_DIR_WRITE(e_steps[INDEX] < 0 ? INVERT_E## INDEX ##_DIR : !INVERT_E## INDEX ##_DIR) + #endif #define START_E_PULSE(INDEX) \ if (e_steps[INDEX]) E## INDEX ##_STEP_WRITE(!INVERT_E_STEP_PIN) diff --git a/Marlin/stepper_indirection.h b/Marlin/stepper_indirection.h index e9af6e43fd..8b86246412 100644 --- a/Marlin/stepper_indirection.h +++ b/Marlin/stepper_indirection.h @@ -472,8 +472,14 @@ #endif #else #define E_STEP_WRITE(v) E0_STEP_WRITE(v) - #define NORM_E_DIR() E0_DIR_WRITE(!INVERT_E0_DIR) - #define REV_E_DIR() E0_DIR_WRITE(INVERT_E0_DIR) + #if ENABLED(MK2_MULTIPLEXER) + // Even-numbered steppers are reversed + #define NORM_E_DIR() E0_DIR_WRITE(TEST(current_block->active_extruder, 0) ? !INVERT_E0_DIR: INVERT_E0_DIR) + #define REV_E_DIR() E0_DIR_WRITE(TEST(current_block->active_extruder, 0) ? INVERT_E0_DIR: !INVERT_E0_DIR) + #else + #define NORM_E_DIR() E0_DIR_WRITE(!INVERT_E0_DIR) + #define REV_E_DIR() E0_DIR_WRITE(INVERT_E0_DIR) + #endif #endif #endif // STEPPER_INDIRECTION_H From 941943c167bac5908203e7ae98f3b9f485c9fe1a Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 27 Jun 2017 02:36:19 -0500 Subject: [PATCH 134/180] Apply const, spacing, etc. --- Marlin/M100_Free_Mem_Chk.cpp | 20 +++++----- Marlin/Marlin_main.cpp | 37 ++++++++++--------- Marlin/SdFatStructs.h | 2 +- Marlin/example_configurations/K8400/README.md | 2 +- Marlin/servo.cpp | 2 +- Marlin/twibus.h | 22 +++++------ 6 files changed, 43 insertions(+), 42 deletions(-) diff --git a/Marlin/M100_Free_Mem_Chk.cpp b/Marlin/M100_Free_Mem_Chk.cpp index be418b049e..6620b0a16e 100644 --- a/Marlin/M100_Free_Mem_Chk.cpp +++ b/Marlin/M100_Free_Mem_Chk.cpp @@ -189,19 +189,17 @@ void free_memory_pool_report(char * const ptr, const int16_t size) { * This is useful to check the correctness of the M100 D and the M100 F commands. */ void corrupt_free_memory(char *ptr, const uint16_t size) { - if (parser.seen('C')) { - ptr += 8; - const uint16_t near_top = top_of_stack() - ptr - 250, // -250 to avoid interrupt activity that's altered the stack. - j = near_top / (size + 1); + ptr += 8; + const uint16_t near_top = top_of_stack() - ptr - 250, // -250 to avoid interrupt activity that's altered the stack. + j = near_top / (size + 1); - SERIAL_ECHOLNPGM("Corrupting free memory block.\n"); - for (uint16_t i = 1; i <= size; i++) { - char * const addr = ptr + i * j; - *addr = i; - SERIAL_ECHOPAIR("\nCorrupting address: ", hex_address(addr)); - } - SERIAL_EOL(); + SERIAL_ECHOLNPGM("Corrupting free memory block.\n"); + for (uint16_t i = 1; i <= size; i++) { + char * const addr = ptr + i * j; + *addr = i; + SERIAL_ECHOPAIR("\nCorrupting address: ", hex_address(addr)); } + SERIAL_EOL(); } #endif // M100_FREE_MEMORY_CORRUPTOR diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 48cf72cc02..4ea5bdf11b 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -1276,16 +1276,17 @@ void get_available_commands() { * * Returns TRUE if the target is invalid */ -bool get_target_extruder_from_command(int code) { +bool get_target_extruder_from_command(const uint16_t code) { if (parser.seen('T')) { - if (parser.value_byte() >= EXTRUDERS) { + const int8_t e = parser.value_byte(); + if (e >= EXTRUDERS) { SERIAL_ECHO_START(); SERIAL_CHAR('M'); SERIAL_ECHO(code); - SERIAL_ECHOLNPAIR(" " MSG_INVALID_EXTRUDER " ", parser.value_byte()); + SERIAL_ECHOLNPAIR(" " MSG_INVALID_EXTRUDER " ", e); return true; } - target_extruder = parser.value_byte(); + target_extruder = e; } else target_extruder = active_extruder; @@ -5676,7 +5677,7 @@ inline void gcode_G92() { #if HAS_POSITION_SHIFT const float p = current_position[i]; #endif - float v = parser.value_axis_units((AxisEnum)i); + const float v = parser.value_axis_units((AxisEnum)i); current_position[i] = v; @@ -6405,7 +6406,7 @@ static bool pin_is_protected(const int8_t pin) { inline void gcode_M42() { if (!parser.seen('S')) return; - int pin_status = parser.value_int(); + const int pin_status = parser.value_int(); if (!WITHIN(pin_status, 0, 255)) return; int pin_number = parser.seen('P') ? parser.value_int() : LED_PIN; @@ -6645,7 +6646,7 @@ inline void gcode_M42() { */ inline void gcode_M43() { - if (parser.seen('T')) { // must be first or else it's "S" and "E" parameters will execute endstop or servo test + if (parser.seen('T')) { // must be first or else its "S" and "E" parameters will execute endstop or servo test toggle_pins(); return; } @@ -8268,10 +8269,10 @@ inline void gcode_M205() { home_offset[Z_AXIS] = parser.value_linear_units() - DELTA_HEIGHT; update_software_endstops(Z_AXIS); } - if (parser.seen('L')) delta_diagonal_rod = parser.value_linear_units(); - if (parser.seen('R')) delta_radius = parser.value_linear_units(); - if (parser.seen('S')) delta_segments_per_second = parser.value_float(); - if (parser.seen('B')) delta_calibration_radius = parser.value_float(); + if (parser.seen('L')) delta_diagonal_rod = parser.value_linear_units(); + if (parser.seen('R')) delta_radius = parser.value_linear_units(); + if (parser.seen('S')) delta_segments_per_second = parser.value_float(); + if (parser.seen('B')) delta_calibration_radius = parser.value_float(); if (parser.seen('X')) delta_tower_angle_trim[A_AXIS] = parser.value_float(); if (parser.seen('Y')) delta_tower_angle_trim[B_AXIS] = parser.value_float(); if (parser.seen('Z')) { // rotate all 3 axis for Z = 0 @@ -8580,7 +8581,7 @@ inline void gcode_M226() { */ inline void gcode_M280() { if (!parser.seen('P')) return; - int servo_index = parser.value_int(); + const int servo_index = parser.value_int(); if (WITHIN(servo_index, 0, NUM_SERVOS - 1)) { if (parser.seen('S')) MOVE_SERVO(servo_index, parser.value_int()); @@ -8753,7 +8754,7 @@ inline void gcode_M226() { * M302 S170 P1 ; set min extrude temp to 170 but leave disabled */ inline void gcode_M302() { - bool seen_S = parser.seen('S'); + const bool seen_S = parser.seen('S'); if (seen_S) { thermalManager.extrude_min_temp = parser.value_celsius(); thermalManager.allow_cold_extrude = (thermalManager.extrude_min_temp == 0); @@ -8960,10 +8961,12 @@ inline void gcode_M400() { stepper.synchronize(); } * M405: Turn on filament sensor for control */ inline void gcode_M405() { - // This is technically a linear measurement, but since it's quantized to centimeters and is a different unit than - // everything else, it uses parser.value_int() instead of parser.value_linear_units(). - if (parser.seen('D')) meas_delay_cm = parser.value_byte(); - NOMORE(meas_delay_cm, MAX_MEASUREMENT_DELAY); + // This is technically a linear measurement, but since it's quantized to centimeters and is a different + // unit than everything else, it uses parser.value_byte() instead of parser.value_linear_units(). + if (parser.seen('D')) { + meas_delay_cm = parser.value_byte(); + NOMORE(meas_delay_cm, MAX_MEASUREMENT_DELAY); + } if (filwidth_delay_index[1] == -1) { // Initialize the ring buffer if not done since startup const uint8_t temp_ratio = thermalManager.widthFil_to_size_ratio() - 100; // -100 to scale within a signed byte diff --git a/Marlin/SdFatStructs.h b/Marlin/SdFatStructs.h index 3e989dea9d..3e78aa2927 100644 --- a/Marlin/SdFatStructs.h +++ b/Marlin/SdFatStructs.h @@ -523,7 +523,7 @@ struct directoryEntry { uint8_t reservedNT; /** * The granularity of the seconds part of creationTime is 2 seconds - * so this field is a count of tenths of a second and its valid + * so this field is a count of tenths of a second and it's valid * value range is 0-199 inclusive. (WHG note - seems to be hundredths) */ uint8_t creationTimeTenths; diff --git a/Marlin/example_configurations/K8400/README.md b/Marlin/example_configurations/K8400/README.md index c9089b5870..14c8f8362b 100644 --- a/Marlin/example_configurations/K8400/README.md +++ b/Marlin/example_configurations/K8400/README.md @@ -2,7 +2,7 @@ http://www.k8400.eu/ Configuration files for the K8400, ported upstream from the official Velleman firmware. -Like it's predecessor, (K8200), the K8400 is a 3Drag clone. There are some minor differences, documented in pins_K8400.h. +Like its predecessor, (K8200), the K8400 is a 3Drag clone. There are some minor differences, documented in pins_K8400.h. Single and dual head configurations provided. Copy the correct Configuration.h and Configuration_adv.h to the /Marlin/ directory. diff --git a/Marlin/servo.cpp b/Marlin/servo.cpp index 3536571c17..74feb5c614 100644 --- a/Marlin/servo.cpp +++ b/Marlin/servo.cpp @@ -95,7 +95,7 @@ static inline void handle_interrupts(timer16_Sequence_t timer, volatile uint16_t if (SERVO_INDEX(timer, Channel[timer]) < ServoCount && Channel[timer] < SERVOS_PER_TIMER) { *OCRnA = *TCNTn + SERVO(timer, Channel[timer]).ticks; if (SERVO(timer, Channel[timer]).Pin.isActive) // check if activated - digitalWrite(SERVO(timer, Channel[timer]).Pin.nbr, HIGH); // its an active channel so pulse it high + digitalWrite(SERVO(timer, Channel[timer]).Pin.nbr, HIGH); // it's an active channel so pulse it high } else { // finished all channels so wait for the refresh period to expire before starting over diff --git a/Marlin/twibus.h b/Marlin/twibus.h index b93cd1c4ca..5d49639349 100644 --- a/Marlin/twibus.h +++ b/Marlin/twibus.h @@ -38,18 +38,18 @@ typedef void (*twiRequestFunc_t)(); /** * TWIBUS class * - * This class implements a wrapper around the two wire (I2C) bus, it allows - * Marlin to send and request data from any slave device on the bus. This is - * an experimental feature and it's inner workings as well as public facing - * interface are prune to change in the future. + * This class implements a wrapper around the two wire (I2C) bus, allowing + * Marlin to send and request data from any slave device on the bus. * - * The two main consumers of this class are M260 and M261, where M260 allows - * Marlin to send a I2C packet to a device (please be aware that no repeated - * starts are possible), this can be done in caching method by calling multiple - * times M260 B or a one liner M260, have a look at - * the gcode_M260() function for more information. M261 allows Marlin to - * request data from a device, the received data is then relayed into the serial - * line for host interpretation. + * The two main consumers of this class are M260 and M261. M260 provides a way + * to send an I2C packet to a device (no repeated starts) by caching up to 32 + * bytes in a buffer and then sending the buffer. + * M261 requests data from a device. The received data is relayed to serial out + * for the host to interpret. + * + * For more information see + * - http://marlinfw.org/docs/gcode/M260.html + * - http://marlinfw.org/docs/gcode/M261.html * */ class TWIBus { From 12f092c812b9d940f93831c7af8f79f24aa16c9e Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 26 Jun 2017 23:31:45 -0500 Subject: [PATCH 135/180] Cleanups to gcode.h, use seenval() --- Marlin/G26_Mesh_Validation_Tool.cpp | 12 +-- Marlin/Marlin_main.cpp | 128 ++++++++++++++-------------- Marlin/gcode.h | 22 ++--- Marlin/ubl_G29.cpp | 12 +-- 4 files changed, 86 insertions(+), 88 deletions(-) diff --git a/Marlin/G26_Mesh_Validation_Tool.cpp b/Marlin/G26_Mesh_Validation_Tool.cpp index 4b4f6e5c0f..6442d7e5eb 100644 --- a/Marlin/G26_Mesh_Validation_Tool.cpp +++ b/Marlin/G26_Mesh_Validation_Tool.cpp @@ -638,11 +638,11 @@ g26_hotend_temp = HOTEND_TEMP; g26_prime_flag = 0; - g26_ooze_amount = parser.seen('O') && parser.has_value() ? parser.value_linear_units() : OOZE_AMOUNT; + g26_ooze_amount = parser.seenval('O') ? parser.value_linear_units() : OOZE_AMOUNT; g26_keep_heaters_on = parser.seen('K') && parser.value_bool(); g26_continue_with_closest = parser.seen('C') && parser.value_bool(); - if (parser.seen('B')) { + if (parser.seenval('B')) { g26_bed_temp = parser.value_celsius(); if (!WITHIN(g26_bed_temp, 15, 140)) { SERIAL_PROTOCOLLNPGM("?Specified bed temperature not plausible."); @@ -650,7 +650,7 @@ } } - if (parser.seen('L')) { + if (parser.seenval('L')) { g26_layer_height = parser.value_linear_units(); if (!WITHIN(g26_layer_height, 0.0, 2.0)) { SERIAL_PROTOCOLLNPGM("?Specified layer height not plausible."); @@ -672,7 +672,7 @@ } } - if (parser.seen('S')) { + if (parser.seenval('S')) { g26_nozzle = parser.value_float(); if (!WITHIN(g26_nozzle, 0.1, 1.0)) { SERIAL_PROTOCOLLNPGM("?Specified nozzle size not plausible."); @@ -699,7 +699,7 @@ } } - if (parser.seen('F')) { + if (parser.seenval('F')) { g26_filament_diameter = parser.value_linear_units(); if (!WITHIN(g26_filament_diameter, 1.0, 4.0)) { SERIAL_PROTOCOLLNPGM("?Specified filament size not plausible."); @@ -712,7 +712,7 @@ g26_extrusion_multiplier *= g26_filament_diameter * sq(g26_nozzle) / sq(0.3); // Scale up by nozzle size - if (parser.seen('H')) { + if (parser.seenval('H')) { g26_hotend_temp = parser.value_celsius(); if (!WITHIN(g26_hotend_temp, 165, 280)) { SERIAL_PROTOCOLLNPGM("?Specified nozzle temperature not plausible."); diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 4ea5bdf11b..89dbf5c868 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -1277,7 +1277,7 @@ void get_available_commands() { * Returns TRUE if the target is invalid */ bool get_target_extruder_from_command(const uint16_t code) { - if (parser.seen('T')) { + if (parser.seenval('T')) { const int8_t e = parser.value_byte(); if (e >= EXTRUDERS) { SERIAL_ECHO_START(); @@ -3135,7 +3135,7 @@ static void homeaxis(const AxisEnum axis) { const char* mixing_codes = "ABCDHI"; byte mix_bits = 0; for (uint8_t i = 0; i < MIXING_STEPPERS; i++) { - if (parser.seen(mixing_codes[i])) { + if (parser.seenval(mixing_codes[i])) { SBI(mix_bits, i); float v = parser.value_float(); NOLESS(v, 0.0); @@ -3304,7 +3304,7 @@ inline void gcode_G0_G1( #endif float arc_offset[2] = { 0.0, 0.0 }; - if (parser.seen('R')) { + if (parser.seenval('R')) { const float r = parser.value_linear_units(), p1 = current_position[X_AXIS], q1 = current_position[Y_AXIS], p2 = destination[X_AXIS], q2 = destination[Y_AXIS]; @@ -3321,8 +3321,8 @@ inline void gcode_G0_G1( } } else { - if (parser.seen('I')) arc_offset[0] = parser.value_linear_units(); - if (parser.seen('J')) arc_offset[1] = parser.value_linear_units(); + if (parser.seenval('I')) arc_offset[0] = parser.value_linear_units(); + if (parser.seenval('J')) arc_offset[1] = parser.value_linear_units(); } if (arc_offset[0] || arc_offset[1]) { @@ -3358,8 +3358,8 @@ inline void gcode_G0_G1( inline void gcode_G4() { millis_t dwell_ms = 0; - if (parser.seen('P')) dwell_ms = parser.value_millis(); // milliseconds to wait - if (parser.seen('S')) dwell_ms = parser.value_millis_from_seconds(); // seconds to wait + if (parser.seenval('P')) dwell_ms = parser.value_millis(); // milliseconds to wait + if (parser.seenval('S')) dwell_ms = parser.value_millis_from_seconds(); // seconds to wait stepper.synchronize(); refresh_cmd_timeout(); @@ -4111,7 +4111,7 @@ void home_all_axes() { gcode_G28(true); } break; case MeshSet: - if (parser.seen('X')) { + if (parser.seenval('X')) { px = parser.value_int() - 1; if (!WITHIN(px, 0, GRID_MAX_POINTS_X - 1)) { SERIAL_PROTOCOLLNPGM("X out of range (1-" STRINGIFY(GRID_MAX_POINTS_X) ")."); @@ -4123,7 +4123,7 @@ void home_all_axes() { gcode_G28(true); } return; } - if (parser.seen('Y')) { + if (parser.seenval('Y')) { py = parser.value_int() - 1; if (!WITHIN(py, 0, GRID_MAX_POINTS_Y - 1)) { SERIAL_PROTOCOLLNPGM("Y out of range (1-" STRINGIFY(GRID_MAX_POINTS_Y) ")."); @@ -4135,7 +4135,7 @@ void home_all_axes() { gcode_G28(true); } return; } - if (parser.seen('Z')) { + if (parser.seenval('Z')) { mbl.z_values[px][py] = parser.value_linear_units(); } else { @@ -4145,7 +4145,7 @@ void home_all_axes() { gcode_G28(true); } break; case MeshSetZOffset: - if (parser.seen('Z')) { + if (parser.seenval('Z')) { mbl.z_offset = parser.value_linear_units(); } else { @@ -4371,17 +4371,17 @@ void home_all_axes() { gcode_G28(true); } return; } - const float z = parser.seen('Z') && parser.has_value() ? parser.value_float() : RAW_CURRENT_POSITION(Z); + const float z = parser.seenval('Z') ? parser.value_float() : RAW_CURRENT_POSITION(Z); if (!WITHIN(z, -10, 10)) { SERIAL_ERROR_START(); SERIAL_ERRORLNPGM("Bad Z value"); return; } - const float x = parser.seen('X') && parser.has_value() ? parser.value_float() : NAN, - y = parser.seen('Y') && parser.has_value() ? parser.value_float() : NAN; - int8_t i = parser.seen('I') && parser.has_value() ? parser.value_byte() : -1, - j = parser.seen('J') && parser.has_value() ? parser.value_byte() : -1; + const float x = parser.seenval('X') ? parser.value_float() : NAN, + y = parser.seenval('Y') ? parser.value_float() : NAN; + int8_t i = parser.seenval('I') ? parser.value_byte() : -1, + j = parser.seenval('J') ? parser.value_byte() : -1; if (!isnan(x) && !isnan(y)) { // Get nearest i / j from x / y @@ -4413,7 +4413,7 @@ void home_all_axes() { gcode_G28(true); } #endif - verbose_level = parser.seen('V') && parser.has_value() ? parser.value_int() : 0; + verbose_level = parser.seenval('V') ? parser.value_int() : 0; if (!WITHIN(verbose_level, 0, 4)) { SERIAL_PROTOCOLLNPGM("?(V)erbose level is implausible (0-4)."); return; @@ -4433,7 +4433,7 @@ void home_all_axes() { gcode_G28(true); } // These values may be saved with the completed mesh abl_grid_points_x = parser.seen('X') ? parser.value_int() : GRID_MAX_POINTS_X; abl_grid_points_y = parser.seen('Y') ? parser.value_int() : GRID_MAX_POINTS_Y; - if (parser.seen('P')) abl_grid_points_x = abl_grid_points_y = parser.value_int(); + if (parser.seenval('P')) abl_grid_points_x = abl_grid_points_y = parser.value_int(); if (abl_grid_points_x < 2 || abl_grid_points_y < 2) { SERIAL_PROTOCOLLNPGM("?Number of probe points is implausible (2 minimum)."); @@ -5595,7 +5595,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.seen('F')) feedrate_mm_s = homing_feedrate(i); + if (!parser.seenval('F')) feedrate_mm_s = homing_feedrate(i); // If G38.2 fails throw an error if (!G38_run_probe() && is_38_2) { SERIAL_ERROR_START(); @@ -5616,10 +5616,10 @@ void home_all_axes() { gcode_G28(true); } */ inline void gcode_G42() { if (IsRunning()) { - const bool hasI = parser.seen('I'); - const int8_t ix = parser.has_value() ? parser.value_int() : 0; - const bool hasJ = parser.seen('J'); - const int8_t iy = parser.has_value() ? parser.value_int() : 0; + const bool hasI = parser.seenval('I'); + const int8_t ix = hasI ? parser.value_int() : 0; + const bool hasJ = parser.seenval('J'); + const int8_t iy = hasJ ? parser.value_int() : 0; if ((hasI && !WITHIN(ix, 0, GRID_MAX_POINTS_X - 1)) || (hasJ && !WITHIN(iy, 0, GRID_MAX_POINTS_Y - 1))) { SERIAL_ECHOLNPGM(MSG_ERR_MESH_XY); @@ -5664,12 +5664,12 @@ void home_all_axes() { gcode_G28(true); } */ inline void gcode_G92() { bool didXYZ = false, - didE = parser.seen('E'); + didE = parser.seenval('E'); if (!didE) stepper.synchronize(); LOOP_XYZE(i) { - if (parser.seen(axis_codes[i])) { + if (parser.seenval(axis_codes[i])) { #if IS_SCARA current_position[i] = parser.value_axis_units((AxisEnum)i); if (i != E_AXIS) didXYZ = true; @@ -5715,11 +5715,11 @@ inline void gcode_G92() { millis_t ms = 0; bool hasP = false, hasS = false; - if (parser.seen('P')) { + if (parser.seenval('P')) { ms = parser.value_millis(); // milliseconds to wait hasP = ms > 0; } - if (parser.seen('S')) { + if (parser.seenval('S')) { ms = parser.value_millis_from_seconds(); // seconds to wait hasS = ms > 0; } @@ -6272,7 +6272,7 @@ inline void gcode_M17() { * M26: Set SD Card file index */ inline void gcode_M26() { - if (card.cardOK && parser.seen('S')) + if (card.cardOK && parser.seenval('S')) card.setIndex(parser.value_long()); } @@ -6334,7 +6334,7 @@ inline void gcode_M31() { if (card.cardOK) { card.openFile(namestartpos, true, call_procedure); - if (parser.seen('S')) + if (parser.seenval('S')) card.setIndex(parser.value_long()); card.startFileprint(); @@ -6370,8 +6370,8 @@ inline void gcode_M31() { */ inline void gcode_M34() { if (parser.seen('S')) card.setSortOn(parser.value_bool()); - if (parser.seen('F')) { - int v = parser.value_long(); + if (parser.seenval('F')) { + const int v = parser.value_long(); card.setSortFolders(v < 0 ? -1 : v > 0 ? 1 : 0); } //if (parser.seen('R')) card.setSortReverse(parser.value_bool()); @@ -6404,10 +6404,8 @@ static bool pin_is_protected(const int8_t pin) { * S Pin status from 0 - 255 */ inline void gcode_M42() { - if (!parser.seen('S')) return; - - const int pin_status = parser.value_int(); - if (!WITHIN(pin_status, 0, 255)) return; + if (!parser.seenval('S')) return; + const byte pin_status = parser.value_byte(); int pin_number = parser.seen('P') ? parser.value_int() : LED_PIN; if (pin_number < 0) return; @@ -6666,8 +6664,8 @@ inline void gcode_M42() { } // Get the range of pins to test or watch - const uint8_t first_pin = parser.seen('P') ? parser.value_byte() : 0, - last_pin = parser.seen('P') ? first_pin : NUM_DIGITAL_PINS - 1; + const uint8_t first_pin = parser.seenval('P') ? parser.value_byte() : 0, + last_pin = parser.seenval('P') ? first_pin : NUM_DIGITAL_PINS - 1; if (first_pin > last_pin) return; @@ -7026,7 +7024,7 @@ inline void gcode_M104() { if (target_extruder != active_extruder) return; #endif - if (parser.seen('S')) { + if (parser.seenval('S')) { const int16_t temp = parser.value_celsius(); thermalManager.setTargetHotend(temp, target_extruder); @@ -7153,7 +7151,7 @@ inline void gcode_M105() { * M155: Set temperature auto-report interval. M155 S */ inline void gcode_M155() { - if (parser.seen('S')) { + if (parser.seenval('S')) { auto_report_temp_interval = parser.value_byte(); NOMORE(auto_report_temp_interval, 60); next_temp_report_ms = millis() + 1000UL * auto_report_temp_interval; @@ -7240,8 +7238,8 @@ inline void gcode_M109() { if (target_extruder != active_extruder) return; #endif - const bool no_wait_for_cooling = parser.seen('S'); - if (no_wait_for_cooling || parser.seen('R')) { + const bool no_wait_for_cooling = parser.seenval('S'); + if (no_wait_for_cooling || parser.seenval('R')) { const int16_t temp = parser.value_celsius(); thermalManager.setTargetHotend(temp, target_extruder); @@ -7389,8 +7387,8 @@ inline void gcode_M109() { if (DEBUGGING(DRYRUN)) return; LCD_MESSAGEPGM(MSG_BED_HEATING); - const bool no_wait_for_cooling = parser.seen('S'); - if (no_wait_for_cooling || parser.seen('R')) { + const bool no_wait_for_cooling = parser.seenval('S'); + if (no_wait_for_cooling || parser.seenval('R')) { thermalManager.setTargetBed(parser.value_celsius()); #if ENABLED(PRINTJOB_TIMER_AUTOSTART) if (parser.value_celsius() > BED_MINTEMP) @@ -7497,7 +7495,7 @@ inline void gcode_M109() { * M110: Set Current Line Number */ inline void gcode_M110() { - if (parser.seen('N')) gcode_LastN = parser.value_long(); + if (parser.seenval('N')) gcode_LastN = parser.value_long(); } /** @@ -7547,7 +7545,7 @@ inline void gcode_M111() { * S Optional. Set the keepalive interval. */ inline void gcode_M113() { - if (parser.seen('S')) { + if (parser.seenval('S')) { host_keepalive_interval = parser.value_byte(); NOMORE(host_keepalive_interval, 60); } @@ -7590,7 +7588,7 @@ inline void gcode_M111() { */ inline void gcode_M140() { if (DEBUGGING(DRYRUN)) return; - if (parser.seen('S')) thermalManager.setTargetBed(parser.value_celsius()); + if (parser.seenval('S')) thermalManager.setTargetBed(parser.value_celsius()); } #if ENABLED(ULTIPANEL) @@ -7611,16 +7609,16 @@ inline void gcode_M140() { } else { int v; - if (parser.seen('H')) { + if (parser.seenval('H')) { v = parser.value_int(); lcd_preheat_hotend_temp[material] = constrain(v, EXTRUDE_MINTEMP, HEATER_0_MAXTEMP - 15); } - if (parser.seen('F')) { + if (parser.seenval('F')) { v = parser.value_int(); lcd_preheat_fan_speed[material] = constrain(v, 0, 255); } #if TEMP_SENSOR_BED != 0 - if (parser.seen('B')) { + if (parser.seenval('B')) { v = parser.value_int(); lcd_preheat_bed_temp[material] = constrain(v, BED_MINTEMP, BED_MAXTEMP - 15); } @@ -7635,9 +7633,9 @@ inline void gcode_M140() { * M149: Set temperature units */ inline void gcode_M149() { - if (parser.seen('C')) parser.set_input_temp_units(TEMPUNIT_C); - else if (parser.seen('K')) parser.set_input_temp_units(TEMPUNIT_K); - else if (parser.seen('F')) parser.set_input_temp_units(TEMPUNIT_F); + if (parser.seenval('C')) parser.set_input_temp_units(TEMPUNIT_C); + else if (parser.seenval('K')) parser.set_input_temp_units(TEMPUNIT_K); + else if (parser.seenval('F')) parser.set_input_temp_units(TEMPUNIT_F); } #endif @@ -7726,7 +7724,7 @@ inline void gcode_M83() { axis_relative_modes[E_AXIS] = true; } * M18, M84: Disable stepper motors */ inline void gcode_M18_M84() { - if (parser.seen('S')) { + if (parser.seenval('S')) { stepper_inactive_time = parser.value_millis_from_seconds(); } else { @@ -8448,11 +8446,11 @@ inline void gcode_M211() { inline void gcode_M218() { if (get_target_extruder_from_command(218) || target_extruder == 0) return; - if (parser.seen('X')) hotend_offset[X_AXIS][target_extruder] = parser.value_linear_units(); - if (parser.seen('Y')) hotend_offset[Y_AXIS][target_extruder] = parser.value_linear_units(); + 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 (parser.seen('Z')) hotend_offset[Z_AXIS][target_extruder] = parser.value_linear_units(); + if (parser.seenval('Z')) hotend_offset[Z_AXIS][target_extruder] = parser.value_linear_units(); #endif SERIAL_ECHO_START(); @@ -8476,7 +8474,7 @@ inline void gcode_M211() { * M220: Set speed percentage factor, aka "Feed Rate" (M220 S95) */ inline void gcode_M220() { - if (parser.seen('S')) feedrate_percentage = parser.value_int(); + if (parser.seenval('S')) feedrate_percentage = parser.value_int(); } /** @@ -8484,7 +8482,7 @@ inline void gcode_M220() { */ inline void gcode_M221() { if (get_target_extruder_from_command(221)) return; - if (parser.seen('S')) + if (parser.seenval('S')) flow_percentage[target_extruder] = parser.value_int(); } @@ -9777,14 +9775,14 @@ inline void gcode_M907() { * S# determines MS1 or MS2, X# sets the pin high/low. */ inline void gcode_M351() { - if (parser.seen('S')) switch (parser.value_byte()) { + if (parser.seenval('S')) switch (parser.value_byte()) { case 1: - LOOP_XYZE(i) if (parser.seen(axis_codes[i])) stepper.microstep_ms(i, parser.value_byte(), -1); - if (parser.seen('B')) stepper.microstep_ms(4, parser.value_byte(), -1); + LOOP_XYZE(i) if (parser.seenval(axis_codes[i])) stepper.microstep_ms(i, parser.value_byte(), -1); + if (parser.seenval('B')) stepper.microstep_ms(4, parser.value_byte(), -1); break; case 2: - LOOP_XYZE(i) if (parser.seen(axis_codes[i])) stepper.microstep_ms(i, -1, parser.value_byte()); - if (parser.seen('B')) stepper.microstep_ms(4, -1, parser.value_byte()); + LOOP_XYZE(i) if (parser.seenval(axis_codes[i])) stepper.microstep_ms(i, -1, parser.value_byte()); + if (parser.seenval('B')) stepper.microstep_ms(4, -1, parser.value_byte()); break; } stepper.microstep_readings(); @@ -9827,8 +9825,8 @@ inline void gcode_M907() { inline void gcode_M355() { #if HAS_CASE_LIGHT uint8_t args = 0; - if (parser.seen('P')) ++args, case_light_brightness = parser.value_byte(); - if (parser.seen('S')) ++args, case_light_on = parser.value_bool(); + if (parser.seenval('P')) ++args, case_light_brightness = parser.value_byte(); + if (parser.seenval('S')) ++args, case_light_on = parser.value_bool(); if (args) update_case_light(); // always report case light status diff --git a/Marlin/gcode.h b/Marlin/gcode.h index 1cd1cfabcf..801ed36ca1 100644 --- a/Marlin/gcode.h +++ b/Marlin/gcode.h @@ -132,7 +132,7 @@ public: #define SEEN_TEST(L) TEST(codebits[(L - 'A') >> 3], (L - 'A') & 0x7) - #else + #else // !FASTER_GCODE_PARSER // 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. @@ -147,7 +147,7 @@ public: #define SEEN_TEST(L) !!strchr(command_args, L) - #endif // FASTER_GCODE_PARSER + #endif // !FASTER_GCODE_PARSER // Populate all fields by parsing a single line of GCode // This uses 54 bytes of SRAM to speed up seen/value @@ -157,7 +157,7 @@ public: FORCE_INLINE static bool has_value() { return value_ptr != NULL; } // Seen and has value - FORCE_INLINE static bool seenval(const char c) { return seen(c) && has_value(); } + inline static bool seenval(const char c) { return seen(c) && has_value(); } static volatile bool seen_axis() { return SEEN_TEST('X') || SEEN_TEST('Y') || SEEN_TEST('Z') || SEEN_TEST('E'); @@ -184,20 +184,20 @@ public: } // Code value as a long or ulong - inline static long value_long() { return value_ptr ? strtol(value_ptr, NULL, 10) : 0L; } - inline unsigned static long value_ulong() { return value_ptr ? strtoul(value_ptr, NULL, 10) : 0UL; } + inline static int32_t value_long() { return value_ptr ? strtol(value_ptr, NULL, 10) : 0L; } + inline static uint32_t value_ulong() { return value_ptr ? strtoul(value_ptr, NULL, 10) : 0UL; } // Code value for use as time FORCE_INLINE static millis_t value_millis() { return value_ulong(); } FORCE_INLINE static millis_t value_millis_from_seconds() { return value_float() * 1000UL; } // Reduce to fewer bits - FORCE_INLINE static int value_int() { return (int)value_long(); } - FORCE_INLINE uint16_t value_ushort() { return (uint16_t)value_long(); } - inline static uint8_t value_byte() { return (uint8_t)(constrain(value_long(), 0, 255)); } + FORCE_INLINE static int16_t value_int() { return (int16_t)value_long(); } + FORCE_INLINE static uint16_t value_ushort() { return (uint16_t)value_long(); } + inline static uint8_t value_byte() { return (uint8_t)constrain(value_long(), 0, 255); } // Bool is true with no value or non-zero - inline static bool value_bool() { return !has_value() || value_byte(); } + inline static bool value_bool() { return !has_value() || value_byte(); } // Units modes: Inches, Fahrenheit, Kelvin @@ -282,12 +282,12 @@ public: } } - #else + #else // !TEMPERATURE_UNITS_SUPPORT FORCE_INLINE static float value_celsius() { return value_float(); } FORCE_INLINE static float value_celsius_diff() { return value_float(); } - #endif + #endif // !TEMPERATURE_UNITS_SUPPORT FORCE_INLINE static float value_feedrate() { return value_linear_units(); } diff --git a/Marlin/ubl_G29.cpp b/Marlin/ubl_G29.cpp index c70755a331..0781f8fb7f 100644 --- a/Marlin/ubl_G29.cpp +++ b/Marlin/ubl_G29.cpp @@ -314,7 +314,7 @@ // Check for commands that require the printer to be homed if (axis_unhomed_error()) { - const int8_t p_val = parser.seen('P') && parser.has_value() ? parser.value_int() : -1; + const int8_t p_val = parser.seenval('P') ? parser.value_int() : -1; if (p_val == 1 || p_val == 2 || p_val == 4 || parser.seen('J')) home_all_axes(); } @@ -492,7 +492,7 @@ return; } - const float height = parser.seen('H') && parser.has_value() ? parser.value_float() : Z_CLEARANCE_BETWEEN_PROBES; + const float height = parser.seenval('H') ? parser.value_float() : Z_CLEARANCE_BETWEEN_PROBES; manually_probe_remaining_mesh(g29_x_pos, g29_y_pos, height, g29_card_thickness, parser.seen('T')); SERIAL_PROTOCOLLNPGM("G29 P2 finished."); @@ -1094,9 +1094,9 @@ g29_constant = 0.0; g29_repetition_cnt = 0; - g29_x_flag = parser.seen('X') && parser.has_value(); + g29_x_flag = parser.seenval('X'); g29_x_pos = g29_x_flag ? parser.value_float() : current_position[X_AXIS]; - g29_y_flag = parser.seen('Y') && parser.has_value(); + g29_y_flag = parser.seenval('Y'); g29_y_pos = g29_y_flag ? parser.value_float() : current_position[Y_AXIS]; if (parser.seen('R')) { @@ -1170,7 +1170,7 @@ g29_constant = parser.value_float(); #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) - if (parser.seen('F') && parser.has_value()) { + if (parser.seenval('F')) { const float fh = parser.value_float(); if (!WITHIN(fh, 0.0, 100.0)) { SERIAL_PROTOCOLLNPGM("?(F)ade height for Bed Level Correction not plausible.\n"); @@ -1180,7 +1180,7 @@ } #endif - g29_map_type = parser.seen('T') && parser.has_value() ? parser.value_int() : 0; + g29_map_type = parser.seenval('T') ? parser.value_int() : 0; if (!WITHIN(g29_map_type, 0, 2)) { SERIAL_PROTOCOLLNPGM("Invalid map type.\n"); return UBL_ERR; From 05449cf6ee62fd0534103b68b404a13c15c6b89f Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 27 Jun 2017 00:49:21 -0500 Subject: [PATCH 136/180] Add shorthand value accessors to gcode.h --- Marlin/G26_Mesh_Validation_Tool.cpp | 12 +- Marlin/Marlin_main.cpp | 260 ++++++++++++++-------------- Marlin/gcode.h | 11 ++ Marlin/ubl_G29.cpp | 6 +- 4 files changed, 147 insertions(+), 142 deletions(-) diff --git a/Marlin/G26_Mesh_Validation_Tool.cpp b/Marlin/G26_Mesh_Validation_Tool.cpp index 6442d7e5eb..7c780c676d 100644 --- a/Marlin/G26_Mesh_Validation_Tool.cpp +++ b/Marlin/G26_Mesh_Validation_Tool.cpp @@ -638,9 +638,9 @@ g26_hotend_temp = HOTEND_TEMP; g26_prime_flag = 0; - g26_ooze_amount = parser.seenval('O') ? parser.value_linear_units() : OOZE_AMOUNT; - g26_keep_heaters_on = parser.seen('K') && parser.value_bool(); - g26_continue_with_closest = parser.seen('C') && parser.value_bool(); + g26_ooze_amount = parser.linearval('O', OOZE_AMOUNT); + g26_keep_heaters_on = parser.boolval('K'); + g26_continue_with_closest = parser.boolval('C'); if (parser.seenval('B')) { g26_bed_temp = parser.value_celsius(); @@ -727,7 +727,7 @@ } #if ENABLED(NEWPANEL) - g26_repeats = parser.seen('R') && parser.has_value() ? parser.value_int() : GRID_MAX_POINTS + 1; + g26_repeats = parser.intval('R', GRID_MAX_POINTS + 1); #else if (!parser.seen('R')) { SERIAL_PROTOCOLLNPGM("?(R)epeat must be specified when not using an LCD."); @@ -741,8 +741,8 @@ return UBL_ERR; } - g26_x_pos = parser.seen('X') ? parser.value_linear_units() : current_position[X_AXIS]; - g26_y_pos = parser.seen('Y') ? parser.value_linear_units() : current_position[Y_AXIS]; + g26_x_pos = parser.linearval('X', current_position[X_AXIS]); + g26_y_pos = parser.linearval('Y', current_position[Y_AXIS]); if (!position_is_reachable_xy(g26_x_pos, g26_y_pos)) { SERIAL_PROTOCOLLNPGM("?Specified X,Y coordinate out of bounds."); return UBL_ERR; diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 89dbf5c868..f46125af7d 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -3175,7 +3175,7 @@ void gcode_get_destination() { destination[i] = current_position[i]; } - if (parser.seen('F') && parser.value_linear_units() > 0.0) + if (parser.linearval('F') > 0.0) feedrate_mm_s = MMM_TO_MMS(parser.value_feedrate()); #if ENABLED(PRINTCOUNTER) @@ -3329,7 +3329,7 @@ inline void gcode_G0_G1( #if ENABLED(ARC_P_CIRCLES) // P indicates number of circles to do - int8_t circles_to_do = parser.seen('P') ? parser.value_byte() : 0; + int8_t circles_to_do = parser.byteval('P'); if (!WITHIN(circles_to_do, 0, 100)) { SERIAL_ERROR_START(); SERIAL_ERRORLNPGM(MSG_ERR_ARC_ARGS); @@ -3388,10 +3388,10 @@ inline void gcode_G4() { gcode_get_destination(); const float offset[] = { - parser.seen('I') ? parser.value_linear_units() : 0.0, - parser.seen('J') ? parser.value_linear_units() : 0.0, - parser.seen('P') ? parser.value_linear_units() : 0.0, - parser.seen('Q') ? parser.value_linear_units() : 0.0 + parser.linearval('I'), + parser.linearval('J'), + parser.linearval('P'), + parser.linearval('Q') }; plan_cubic_move(offset); @@ -3408,9 +3408,8 @@ inline void gcode_G4() { */ inline void gcode_G10_G11(bool doRetract=false) { #if EXTRUDERS > 1 - if (doRetract) { - retracted_swap[active_extruder] = (parser.seen('S') && parser.value_bool()); // checks for swap retract argument - } + if (doRetract) + retracted_swap[active_extruder] = parser.boolval('S'); // checks for swap retract argument #endif retract(doRetract #if EXTRUDERS > 1 @@ -3429,10 +3428,10 @@ inline void gcode_G4() { // Don't allow nozzle cleaning without homing first if (axis_unhomed_error()) return; - const uint8_t pattern = parser.seen('P') ? parser.value_ushort() : 0, - strokes = parser.seen('S') ? parser.value_ushort() : NOZZLE_CLEAN_STROKES, - objects = parser.seen('T') ? parser.value_ushort() : NOZZLE_CLEAN_TRIANGLES; - const float radius = parser.seen('R') ? parser.value_float() : NOZZLE_CLEAN_CIRCLE_RADIUS; + const uint8_t pattern = parser.ushortval('P', 0), + strokes = parser.ushortval('S', NOZZLE_CLEAN_STROKES), + objects = parser.ushortval('T', NOZZLE_CLEAN_TRIANGLES); + const float radius = parser.floatval('R', NOZZLE_CLEAN_CIRCLE_RADIUS); Nozzle::clean(pattern, strokes, radius, objects); } @@ -3476,7 +3475,7 @@ inline void gcode_G4() { inline void gcode_G27() { // Don't allow nozzle parking without homing first if (axis_unhomed_error()) return; - Nozzle::park(parser.seen('P') ? parser.value_ushort() : 0); + Nozzle::park(parser.ushortval('P')); } #endif // NOZZLE_PARK_FEATURE @@ -4039,7 +4038,7 @@ void home_all_axes() { gcode_G28(true); } static bool enable_soft_endstops; #endif - const MeshLevelingState state = parser.seen('S') ? (MeshLevelingState)parser.value_byte() : MeshReport; + const MeshLevelingState state = (MeshLevelingState)parser.byteval('S', (int8_t)MeshReport); if (!WITHIN(state, 0, 5)) { SERIAL_PROTOCOLLNPGM("S out of range (0-5)."); return; @@ -4269,7 +4268,7 @@ void home_all_axes() { gcode_G28(true); } #endif #if ENABLED(DEBUG_LEVELING_FEATURE) && DISABLED(PROBE_MANUALLY) - const bool faux = parser.seen('C') && parser.value_bool(); + const bool faux = parser.boolval('C'); #elif ENABLED(PROBE_MANUALLY) const bool faux = no_action; #else @@ -4371,17 +4370,17 @@ void home_all_axes() { gcode_G28(true); } return; } - const float z = parser.seenval('Z') ? parser.value_float() : RAW_CURRENT_POSITION(Z); + const float z = parser.floatval('Z', RAW_CURRENT_POSITION(Z)); if (!WITHIN(z, -10, 10)) { SERIAL_ERROR_START(); SERIAL_ERRORLNPGM("Bad Z value"); return; } - const float x = parser.seenval('X') ? parser.value_float() : NAN, - y = parser.seenval('Y') ? parser.value_float() : NAN; - int8_t i = parser.seenval('I') ? parser.value_byte() : -1, - j = parser.seenval('J') ? parser.value_byte() : -1; + const float x = parser.floatval('X', NAN), + y = parser.floatval('Y', NAN); + int8_t i = parser.byteval('I', -1), + j = parser.byteval('J', -1); if (!isnan(x) && !isnan(y)) { // Get nearest i / j from x / y @@ -4413,13 +4412,13 @@ void home_all_axes() { gcode_G28(true); } #endif - verbose_level = parser.seenval('V') ? parser.value_int() : 0; + verbose_level = parser.intval('V'); if (!WITHIN(verbose_level, 0, 4)) { SERIAL_PROTOCOLLNPGM("?(V)erbose level is implausible (0-4)."); return; } - dryrun = (parser.seen('D') && parser.value_bool()) + dryrun = parser.boolval('D') #if ENABLED(PROBE_MANUALLY) || no_action #endif @@ -4427,12 +4426,12 @@ void home_all_axes() { gcode_G28(true); } #if ENABLED(AUTO_BED_LEVELING_LINEAR) - do_topography_map = verbose_level > 2 || parser.seen('T'); + do_topography_map = verbose_level > 2 || parser.boolval('T'); // X and Y specify points in each direction, overriding the default // These values may be saved with the completed mesh - abl_grid_points_x = parser.seen('X') ? parser.value_int() : GRID_MAX_POINTS_X; - abl_grid_points_y = parser.seen('Y') ? parser.value_int() : GRID_MAX_POINTS_Y; + abl_grid_points_x = parser.intval('X', GRID_MAX_POINTS_X); + abl_grid_points_y = parser.intval('Y', GRID_MAX_POINTS_Y); if (parser.seenval('P')) abl_grid_points_x = abl_grid_points_y = parser.value_int(); if (abl_grid_points_x < 2 || abl_grid_points_y < 2) { @@ -4444,18 +4443,18 @@ void home_all_axes() { gcode_G28(true); } #elif ENABLED(AUTO_BED_LEVELING_BILINEAR) - zoffset = parser.seen('Z') ? parser.value_linear_units() : 0; + zoffset = parser.linearval('Z'); #endif #if ABL_GRID - xy_probe_feedrate_mm_s = MMM_TO_MMS(parser.seen('S') ? parser.value_linear_units() : XY_PROBE_SPEED); + xy_probe_feedrate_mm_s = MMM_TO_MMS(parser.linearval('S', XY_PROBE_SPEED)); - left_probe_bed_position = parser.seen('L') ? (int)parser.value_linear_units() : LOGICAL_X_POSITION(LEFT_PROBE_BED_POSITION); - right_probe_bed_position = parser.seen('R') ? (int)parser.value_linear_units() : LOGICAL_X_POSITION(RIGHT_PROBE_BED_POSITION); - front_probe_bed_position = parser.seen('F') ? (int)parser.value_linear_units() : LOGICAL_Y_POSITION(FRONT_PROBE_BED_POSITION); - back_probe_bed_position = parser.seen('B') ? (int)parser.value_linear_units() : LOGICAL_Y_POSITION(BACK_PROBE_BED_POSITION); + left_probe_bed_position = (int)parser.linearval('L', LOGICAL_X_POSITION(LEFT_PROBE_BED_POSITION)); + right_probe_bed_position = (int)parser.linearval('R', LOGICAL_X_POSITION(RIGHT_PROBE_BED_POSITION)); + front_probe_bed_position = (int)parser.linearval('F', LOGICAL_Y_POSITION(FRONT_PROBE_BED_POSITION)); + back_probe_bed_position = (int)parser.linearval('B', LOGICAL_Y_POSITION(BACK_PROBE_BED_POSITION)); const bool left_out_l = left_probe_bed_position < LOGICAL_X_POSITION(MIN_PROBE_X), left_out = left_out_l || left_probe_bed_position > right_probe_bed_position - (MIN_PROBE_EDGE), @@ -4735,7 +4734,7 @@ void home_all_axes() { gcode_G28(true); } #else // !PROBE_MANUALLY - const bool stow_probe_after_each = parser.seen('E'); + const bool stow_probe_after_each = parser.boolval('E'); #if ABL_GRID @@ -5086,8 +5085,8 @@ void home_all_axes() { gcode_G28(true); } * S0 Leave the probe deployed */ inline void gcode_G30() { - const float xpos = parser.seen('X') ? parser.value_linear_units() : current_position[X_AXIS] + X_PROBE_OFFSET_FROM_EXTRUDER, - ypos = parser.seen('Y') ? parser.value_linear_units() : current_position[Y_AXIS] + Y_PROBE_OFFSET_FROM_EXTRUDER; + const float xpos = parser.linearval('X', current_position[X_AXIS] + X_PROBE_OFFSET_FROM_EXTRUDER), + ypos = parser.linearval('Y', current_position[Y_AXIS] + Y_PROBE_OFFSET_FROM_EXTRUDER); if (!position_is_reachable_by_probe_xy(xpos, ypos)) return; @@ -5098,7 +5097,7 @@ void home_all_axes() { gcode_G28(true); } setup_for_endstop_or_probe_move(); - const float measured_z = probe_pt(xpos, ypos, !parser.seen('S') || parser.value_bool(), 1); + const float measured_z = probe_pt(xpos, ypos, parser.boolval('S', true), 1); if (!isnan(measured_z)) { SERIAL_PROTOCOLPAIR("Bed X: ", FIXFLOAT(xpos)); @@ -5164,32 +5163,32 @@ void home_all_axes() { gcode_G28(true); } inline void gcode_G33() { - const int8_t probe_points = parser.seen('P') ? parser.value_int() : DELTA_CALIBRATION_DEFAULT_POINTS; + 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)."); return; } - const int8_t verbose_level = parser.seen('V') ? parser.value_byte() : 1; + const int8_t verbose_level = parser.byteval('V', 1); if (!WITHIN(verbose_level, 0, 2)) { SERIAL_PROTOCOLLNPGM("?(V)erbose level is implausible (0-2)."); return; } - const float calibration_precision = parser.seen('C') ? parser.value_float() : 0.0; + const float calibration_precision = parser.floatval('C'); if (calibration_precision < 0) { SERIAL_PROTOCOLLNPGM("?(C)alibration precision is implausible (>0)."); return; } - const int8_t force_iterations = parser.seen('F') ? parser.value_int() : 1; + const int8_t force_iterations = parser.intval('F', 1); if (!WITHIN(force_iterations, 1, 30)) { SERIAL_PROTOCOLLNPGM("?(F)orce iteration is implausible (1-30)."); return; } - const bool towers_set = !parser.seen('T'), - stow_after_each = parser.seen('E') && parser.value_bool(), + const bool towers_set = !parser.boolval('T'), + stow_after_each = parser.boolval('E'), _1p_calibration = probe_points == 1, _4p_calibration = probe_points == 2, _4p_towers_points = _4p_calibration && towers_set, @@ -5640,13 +5639,13 @@ void home_all_axes() { gcode_G28(true); } set_destination_to_current(); if (hasI) destination[X_AXIS] = LOGICAL_X_POSITION(_GET_MESH_X(ix)); if (hasJ) destination[Y_AXIS] = LOGICAL_Y_POSITION(_GET_MESH_Y(iy)); - if (parser.seen('P') && parser.value_bool()) { + if (parser.boolval('P')) { if (hasI) destination[X_AXIS] -= X_PROBE_OFFSET_FROM_EXTRUDER; if (hasJ) destination[Y_AXIS] -= Y_PROBE_OFFSET_FROM_EXTRUDER; } - if (parser.seen('F') && parser.value_linear_units() > 0.0) - feedrate_mm_s = MMM_TO_MMS(parser.value_linear_units()); + const float fval = parser.linearval('F'); + if (fval > 0.0) feedrate_mm_s = MMM_TO_MMS(fval); // SCARA kinematic has "safe" XY raw moves #if IS_SCARA @@ -5851,7 +5850,7 @@ inline void gcode_G92() { #if ENABLED(SPINDLE_LASER_PWM) if (parser.seen('O')) ocr_val_mode(); else { - const float spindle_laser_power = parser.seen('S') ? parser.value_float() : 0; + const float spindle_laser_power = parser.floatval('S'); if (spindle_laser_power == 0) { WRITE(SPINDLE_LASER_ENABLE_PIN, !SPINDLE_LASER_ENABLE_INVERT); // turn spindle off (active low) delay_for_power_down(); @@ -6329,7 +6328,7 @@ inline void gcode_M31() { stepper.synchronize(); char* namestartpos = parser.string_arg; - bool call_procedure = parser.seen('P'); + const bool call_procedure = parser.boolval('P'); if (card.cardOK) { card.openFile(namestartpos, true, call_procedure); @@ -6407,7 +6406,7 @@ inline void gcode_M42() { if (!parser.seenval('S')) return; const byte pin_status = parser.value_byte(); - int pin_number = parser.seen('P') ? parser.value_int() : LED_PIN; + const int pin_number = parser.intval('P', LED_PIN); if (pin_number < 0) return; if (pin_is_protected(pin_number)) { @@ -6440,11 +6439,11 @@ inline void gcode_M42() { #include "pinsDebug.h" inline void toggle_pins() { - const bool I_flag = parser.seen('I') && parser.value_bool(); - const int repeat = parser.seen('R') ? parser.value_int() : 1, - start = parser.seen('S') ? parser.value_int() : 0, - end = parser.seen('E') ? parser.value_int() : NUM_DIGITAL_PINS - 1, - wait = parser.seen('W') ? parser.value_int() : 500; + const bool I_flag = parser.boolval('I'); + const int repeat = parser.intval('R', 1), + start = parser.intval('S'), + end = parser.intval('E', NUM_DIGITAL_PINS - 1), + wait = parser.intval('W', 500); for (uint8_t pin = start; pin <= end; pin++) { //report_pin_state_extended(pin, I_flag, false); @@ -6503,7 +6502,7 @@ inline void gcode_M42() { #else - const uint8_t probe_index = parser.seen('P') ? parser.value_byte() : Z_ENDSTOP_SERVO_NR; + const uint8_t probe_index = parser.byteval('P', Z_ENDSTOP_SERVO_NR); SERIAL_PROTOCOLLNPGM("Servo probe test"); SERIAL_PROTOCOLLNPAIR(". using index: ", probe_index); @@ -6664,15 +6663,15 @@ inline void gcode_M42() { } // Get the range of pins to test or watch - const uint8_t first_pin = parser.seenval('P') ? parser.value_byte() : 0, + const uint8_t first_pin = parser.byteval('P'), last_pin = parser.seenval('P') ? first_pin : NUM_DIGITAL_PINS - 1; if (first_pin > last_pin) return; - const bool ignore_protection = parser.seen('I') && parser.value_bool(); + const bool ignore_protection = parser.boolval('I'); // Watch until click, M108, or reset - if (parser.seen('W') && parser.value_bool()) { + if (parser.boolval('W')) { SERIAL_PROTOCOLLNPGM("Watching pins"); byte pin_state[last_pin - first_pin + 1]; for (int8_t pin = first_pin; pin <= last_pin; pin++) { @@ -6751,7 +6750,7 @@ inline void gcode_M42() { if (axis_unhomed_error()) return; - const int8_t verbose_level = parser.seen('V') ? parser.value_byte() : 1; + const int8_t verbose_level = parser.byteval('V', 1); if (!WITHIN(verbose_level, 0, 4)) { SERIAL_PROTOCOLLNPGM("?(V)erbose level is implausible (0-4)."); return; @@ -6760,19 +6759,19 @@ inline void gcode_M42() { if (verbose_level > 0) SERIAL_PROTOCOLLNPGM("M48 Z-Probe Repeatability Test"); - int8_t n_samples = parser.seen('P') ? parser.value_byte() : 10; + const int8_t n_samples = parser.byteval('P', 10); if (!WITHIN(n_samples, 4, 50)) { SERIAL_PROTOCOLLNPGM("?Sample size not plausible (4-50)."); return; } - const bool stow_probe_after_each = parser.seen('E'); + const bool stow_probe_after_each = parser.boolval('E'); float X_current = current_position[X_AXIS], Y_current = current_position[Y_AXIS]; - const float X_probe_location = parser.seen('X') ? parser.value_linear_units() : X_current + X_PROBE_OFFSET_FROM_EXTRUDER, - Y_probe_location = parser.seen('Y') ? parser.value_linear_units() : Y_current + Y_PROBE_OFFSET_FROM_EXTRUDER; + const float X_probe_location = parser.linearval('X', X_current + X_PROBE_OFFSET_FROM_EXTRUDER), + Y_probe_location = parser.linearval('Y', Y_current + Y_PROBE_OFFSET_FROM_EXTRUDER); #if DISABLED(DELTA) if (!WITHIN(X_probe_location, LOGICAL_X_POSITION(MIN_PROBE_X), LOGICAL_X_POSITION(MAX_PROBE_X))) { @@ -6798,7 +6797,7 @@ inline void gcode_M42() { } if (n_legs == 1) n_legs = 2; - bool schizoid_flag = parser.seen('S'); + const bool schizoid_flag = parser.boolval('S'); if (schizoid_flag && !seen_L) n_legs = 7; /** @@ -7006,7 +7005,7 @@ inline void gcode_M77() { print_job_timer.stop(); } */ inline void gcode_M78() { // "M78 S78" will reset the statistics - if (parser.seen('S') && parser.value_int() == 78) + if (parser.intval('S') == 78) print_job_timer.initStats(); else print_job_timer.showStats(); @@ -7177,9 +7176,9 @@ inline void gcode_M105() { * P Fan index, if more than one fan */ inline void gcode_M106() { - uint16_t s = parser.seen('S') ? parser.value_ushort() : 255, - p = parser.seen('P') ? parser.value_ushort() : 0; + uint16_t s = parser.ushortval('S', 255); NOMORE(s, 255); + const uint8_t p = parser.byteval('P', 0); if (p < FAN_COUNT) fanSpeeds[p] = s; } @@ -7187,7 +7186,7 @@ inline void gcode_M105() { * M107: Fan Off */ inline void gcode_M107() { - uint16_t p = parser.seen('P') ? parser.value_ushort() : 0; + const uint16_t p = parser.ushortval('P'); if (p < FAN_COUNT) fanSpeeds[p] = 0; } @@ -7502,7 +7501,7 @@ inline void gcode_M110() { * M111: Set the debug level */ inline void gcode_M111() { - marlin_debug_flags = parser.seen('S') ? parser.value_byte() : (uint8_t)DEBUG_NONE; + marlin_debug_flags = parser.byteval('S', (uint8_t)DEBUG_NONE); const static char str_debug_1[] PROGMEM = MSG_DEBUG_ECHO; const static char str_debug_2[] PROGMEM = MSG_DEBUG_INFO; @@ -7563,7 +7562,7 @@ inline void gcode_M111() { /** * M126: Heater 1 valve open */ - inline void gcode_M126() { baricuda_valve_pressure = parser.seen('S') ? parser.value_byte() : 255; } + inline void gcode_M126() { baricuda_valve_pressure = parser.byteval('S', 255); } /** * M127: Heater 1 valve close */ @@ -7574,7 +7573,7 @@ inline void gcode_M111() { /** * M128: Heater 2 valve open */ - inline void gcode_M128() { baricuda_e_to_p_pressure = parser.seen('S') ? parser.value_byte() : 255; } + inline void gcode_M128() { baricuda_e_to_p_pressure = parser.byteval('S', 255); } /** * M129: Heater 2 valve close */ @@ -7602,7 +7601,7 @@ inline void gcode_M140() { * F */ inline void gcode_M145() { - uint8_t material = parser.seen('S') ? (uint8_t)parser.value_int() : 0; + const uint8_t material = (uint8_t)parser.intval('S'); if (material >= COUNT(lcd_preheat_hotend_temp)) { SERIAL_ERROR_START(); SERIAL_ERRORLNPGM(MSG_ERR_MATERIAL_INDEX); @@ -8034,16 +8033,14 @@ inline void gcode_M121() { endstops.enable_globally(false); } ; // Lift Z axis - const float z_lift = parser.seen('Z') ? parser.value_linear_units() : - #if defined(PAUSE_PARK_Z_ADD) && PAUSE_PARK_Z_ADD > 0 - PAUSE_PARK_Z_ADD - #else - 0 + const float z_lift = parser.linearval('Z') + #if PAUSE_PARK_Z_ADD > 0 + + PAUSE_PARK_Z_ADD #endif ; // Move XY axes to filament change position or given position - const float x_pos = parser.seen('X') ? parser.value_linear_units() : 0 + const float x_pos = parser.linearval('X') #ifdef PAUSE_PARK_X_POS + PAUSE_PARK_X_POS #endif @@ -8051,7 +8048,7 @@ inline void gcode_M121() { endstops.enable_globally(false); } + (active_extruder ? hotend_offset[X_AXIS][active_extruder] : 0) #endif ; - const float y_pos = parser.seen('Y') ? parser.value_linear_units() : 0 + const float y_pos = parser.linearval('Y') #ifdef PAUSE_PARK_Y_POS + PAUSE_PARK_Y_POS #endif @@ -8491,10 +8488,10 @@ inline void gcode_M221() { */ inline void gcode_M226() { if (parser.seen('P')) { - int pin_number = parser.value_int(), - pin_state = parser.seen('S') ? parser.value_int() : -1; // required pin state - default is inverted + const int pin_number = parser.value_int(), + pin_state = parser.intval('S', -1); // required pin state - default is inverted - if (pin_state >= -1 && pin_state <= 1 && pin_number > -1 && !pin_is_protected(pin_number)) { + if (WITHIN(pin_state, -1, 1) && pin_number > -1 && !pin_is_protected(pin_number)) { int target = LOW; @@ -8559,7 +8556,7 @@ inline void gcode_M226() { inline void gcode_M261() { if (parser.seen('A')) i2c.address(parser.value_byte()); - uint8_t bytes = parser.seen('B') ? parser.value_byte() : 1; + uint8_t bytes = parser.byteval('B', 1); if (i2c.addr && bytes && bytes <= TWIBUS_BUFFER_SIZE) { i2c.relay(bytes); @@ -8604,8 +8601,8 @@ inline void gcode_M226() { * M300: Play beep sound S P */ inline void gcode_M300() { - uint16_t const frequency = parser.seen('S') ? parser.value_ushort() : 260; - uint16_t duration = parser.seen('P') ? parser.value_ushort() : 1000; + uint16_t const frequency = parser.ushortval('S', 260); + uint16_t duration = parser.ushortval('P', 1000); // Limits the tone duration to 0-5 seconds. NOMORE(duration, 5000); @@ -8633,7 +8630,7 @@ inline void gcode_M226() { // multi-extruder PID patch: M301 updates or prints a single extruder's PID values // default behaviour (omitting E parameter) is to update for extruder 0 only - int e = parser.seen('E') ? parser.value_int() : 0; // extruder being updated + const uint8_t e = parser.byteval('E'); // extruder being updated if (e < HOTENDS) { // catch bad input value if (parser.seen('P')) PID_PARAM(Kp, e) = parser.value_float(); @@ -8781,11 +8778,10 @@ inline void gcode_M226() { */ inline void gcode_M303() { #if HAS_PID_HEATING - const int e = parser.seen('E') ? parser.value_int() : 0, - c = parser.seen('C') ? parser.value_int() : 5; - const bool u = parser.seen('U') && parser.value_bool(); + const int e = parser.intval('E'), c = parser.intval('C', 5); + const bool u = parser.boolval('U'); - int16_t temp = parser.seen('S') ? parser.value_celsius() : (e < 0 ? 70 : 150); + int16_t temp = parser.celsiusval('S', e < 0 ? 70 : 150); if (WITHIN(e, 0, HOTENDS - 1)) target_extruder = e; @@ -9078,11 +9074,9 @@ void quickstop_stepper() { #endif } - bool to_enable = false; - if (parser.seen('S')) { - to_enable = parser.value_bool(); + const bool to_enable = parser.boolval('S'); + if (parser.seen('S')) set_bed_leveling_enabled(to_enable); - } #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) if (parser.seen('Z')) set_z_fade_height(parser.value_linear_units()); @@ -9149,11 +9143,12 @@ void quickstop_stepper() { * M421 I J Q */ inline void gcode_M421() { - const bool hasI = parser.seen('I'); - const int8_t ix = hasI ? parser.value_int() : -1; - const bool hasJ = parser.seen('J'); - const int8_t iy = hasJ ? parser.value_int() : -1; - const bool hasZ = parser.seen('Z'), hasQ = !hasZ && parser.seen('Q'); + int8_t ix = parser.intval('I', -1), iy = parser.intval('J', -1); + const bool hasI = ix >= 0, + hasJ = iy >= 0, + hasC = parser.seen('C'), + hasZ = parser.seen('Z'), + hasQ = !hasZ && parser.seen('Q'); if (!hasI || !hasJ || !(hasZ || hasQ)) { SERIAL_ERROR_START(); @@ -9183,11 +9178,12 @@ void quickstop_stepper() { * M421 C Q */ inline void gcode_M421() { - const bool hasC = parser.seen('C'), hasI = parser.seen('I'); - int8_t ix = hasI ? parser.value_int() : -1; - const bool hasJ = parser.seen('J'); - int8_t iy = hasJ ? parser.value_int() : -1; - const bool hasZ = parser.seen('Z'), hasQ = !hasZ && parser.seen('Q'); + int8_t ix = parser.intval('I', -1), iy = parser.intval('J', -1); + const bool hasI = ix >= 0, + hasJ = iy >= 0, + hasC = parser.seen('C'), + hasZ = parser.seen('Z'), + hasQ = !hasZ && parser.seen('Q'); if (hasC) { const mesh_index_pair location = ubl.find_closest_mesh_point_of_type(REAL, current_position[X_AXIS], current_position[Y_AXIS], USE_NOZZLE_AS_REFERENCE, NULL, false); @@ -9278,7 +9274,7 @@ inline void gcode_M502() { * M503: print settings currently in memory */ inline void gcode_M503() { - (void)settings.report(parser.seen('S') && !parser.value_bool()); + (void)settings.report(!parser.boolval('S', true)); } #if ENABLED(ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED) @@ -9382,25 +9378,23 @@ inline void gcode_M503() { ; // Lift Z axis - const float z_lift = parser.seen('Z') ? parser.value_linear_units() : + const float z_lift = parser.linearval('Z', 0 #if defined(PAUSE_PARK_Z_ADD) && PAUSE_PARK_Z_ADD > 0 - PAUSE_PARK_Z_ADD - #else - 0 + + PAUSE_PARK_Z_ADD #endif - ; + ); // Move XY axes to filament exchange position - const float x_pos = parser.seen('X') ? parser.value_linear_units() : 0 + const float x_pos = parser.linearval('X', 0 #ifdef PAUSE_PARK_X_POS + PAUSE_PARK_X_POS #endif - ; - const float y_pos = parser.seen('Y') ? parser.value_linear_units() : 0 + ); + const float y_pos = parser.linearval('Y', 0 #ifdef PAUSE_PARK_Y_POS + PAUSE_PARK_Y_POS #endif - ; + ); // Unload filament const float unload_length = parser.seen('U') ? parser.value_axis_units(E_AXIS) : 0 @@ -9416,13 +9410,13 @@ inline void gcode_M503() { #endif ; - const int beep_count = parser.seen('B') ? parser.value_int() : + const int beep_count = parser.intval('B', #ifdef FILAMENT_CHANGE_NUMBER_OF_ALERT_BEEPS FILAMENT_CHANGE_NUMBER_OF_ALERT_BEEPS #else -1 #endif - ; + ); const bool job_running = print_job_timer.isRunning(); @@ -9485,7 +9479,7 @@ inline void gcode_M503() { inline void gcode_M605() { stepper.synchronize(); - extruder_duplication_enabled = parser.seen('S') && parser.value_int() == (int)DXC_DUPLICATION_MODE; + extruder_duplication_enabled = parser.intval('S') == (int)DXC_DUPLICATION_MODE; SERIAL_ECHO_START(); SERIAL_ECHOLNPAIR(MSG_DUPLICATION_MODE, extruder_duplication_enabled ? MSG_ON : MSG_OFF); } @@ -9503,14 +9497,14 @@ inline void gcode_M503() { inline void gcode_M900() { stepper.synchronize(); - const float newK = parser.seen('K') ? parser.value_float() : -1; + const float newK = parser.floatval('K', -1); if (newK >= 0) planner.extruder_advance_k = newK; - float newR = parser.seen('R') ? parser.value_float() : -1; + float newR = parser.floatval('R', -1); if (newR < 0) { - const float newD = parser.seen('D') ? parser.value_float() : -1, - newW = parser.seen('W') ? parser.value_float() : -1, - newH = parser.seen('H') ? parser.value_float() : -1; + const float newD = parser.floatval('D', -1), + newW = parser.floatval('W', -1), + newH = parser.floatval('H', -1); if (newD >= 0 && newW >= 0 && newH >= 0) newR = newD ? (newW * newH) / (sq(newD * 0.5) * M_PI) : 0; } @@ -9579,7 +9573,7 @@ inline void gcode_M503() { inline void gcode_M906() { uint16_t values[XYZE]; LOOP_XYZE(i) - values[i] = parser.seen(axis_codes[i]) ? parser.value_int() : 0; + values[i] = parser.intval(axis_codes[i]); #if ENABLED(X_IS_TMC2130) if (values[X_AXIS]) tmc2130_set_current(stepperX, 'X', values[X_AXIS]); @@ -9651,7 +9645,7 @@ inline void gcode_M503() { inline void gcode_M913() { uint16_t values[XYZE]; LOOP_XYZE(i) - values[i] = parser.seen(axis_codes[i]) ? parser.value_int() : 0; + values[i] = parser.intval(axis_codes[i]); #if ENABLED(X_IS_TMC2130) if (values[X_AXIS]) tmc2130_set_pwmthrs(stepperX, 'X', values[X_AXIS], planner.axis_steps_per_mm[X_AXIS]); @@ -9738,14 +9732,14 @@ inline void gcode_M907() { inline void gcode_M908() { #if HAS_DIGIPOTSS stepper.digitalPotWrite( - parser.seen('P') ? parser.value_int() : 0, - parser.seen('S') ? parser.value_int() : 0 + parser.intval('P'), + parser.intval('S') ); #endif #ifdef DAC_STEPPER_CURRENT dac_current_raw( - parser.seen('P') ? parser.value_byte() : -1, - parser.seen('S') ? parser.value_ushort() : 0 + parser.byteval('P', -1), + parser.ushortval('S', 0) ); #endif } @@ -9856,9 +9850,9 @@ inline void gcode_M355() { * */ inline void gcode_M163() { - const int mix_index = parser.seen('S') ? parser.value_int() : 0; + const int mix_index = parser.intval('S'); if (mix_index < MIXING_STEPPERS) { - float mix_value = parser.seen('P') ? parser.value_float() : 0.0; + float mix_value = parser.floatval('P'); NOLESS(mix_value, 0.0); mixing_factor[mix_index] = RECIPROCAL(mix_value); } @@ -9873,7 +9867,7 @@ inline void gcode_M355() { * */ inline void gcode_M164() { - const int tool_index = parser.seen('S') ? parser.value_int() : 0; + const int tool_index = parser.intval('S'); if (tool_index < MIXING_VIRTUAL_TOOLS) { normalize_mix(); for (uint8_t i = 0; i < MIXING_STEPPERS; i++) @@ -9916,7 +9910,7 @@ inline void gcode_M999() { Running = true; lcd_reset_alert_level(); - if (parser.seen('S') && parser.value_bool()) return; + if (parser.boolval('S')) return; // gcode_LastN = Stopped_gcode_LastN; FlushSerialRequestResend(); @@ -10298,8 +10292,8 @@ inline void gcode_T(uint8_t tmp_extruder) { tool_change( tmp_extruder, - parser.seen('F') ? MMM_TO_MMS(parser.value_linear_units()) : 0.0, - (tmp_extruder == active_extruder) || (parser.seen('S') && parser.value_bool()) + MMM_TO_MMS(parser.linearval('F')), + (tmp_extruder == active_extruder) || parser.boolval('S') ); #endif diff --git a/Marlin/gcode.h b/Marlin/gcode.h index 801ed36ca1..0a9c859f14 100644 --- a/Marlin/gcode.h +++ b/Marlin/gcode.h @@ -293,6 +293,17 @@ public: void unknown_command_error(); + // Provide simple value accessors with default option + FORCE_INLINE static float floatval(const char c, const float dval=0.0) { return seenval(c) ? value_float() : dval; } + FORCE_INLINE static bool boolval(const char c, const bool dval=false) { return seen(c) ? value_bool() : dval; } + FORCE_INLINE static uint8_t byteval(const char c, const uint8_t dval=0) { return seenval(c) ? value_byte() : dval; } + FORCE_INLINE static int16_t intval(const char c, const int16_t dval=0) { return seenval(c) ? value_int() : dval; } + FORCE_INLINE static uint16_t ushortval(const char c, const uint16_t dval=0) { return seenval(c) ? value_ushort() : dval; } + FORCE_INLINE static int32_t longval(const char c, const int32_t dval=0) { return seenval(c) ? value_long() : dval; } + FORCE_INLINE static uint32_t ulongval(const char c, const uint32_t dval=0) { return seenval(c) ? value_ulong() : dval; } + FORCE_INLINE static float linearval(const char c, const float dval=0.0) { return seenval(c) ? value_linear_units() : dval; } + FORCE_INLINE static float celsiusval(const char c, const float dval=0.0) { return seenval(c) ? value_celsius() : dval; } + }; extern GCodeParser parser; diff --git a/Marlin/ubl_G29.cpp b/Marlin/ubl_G29.cpp index 0781f8fb7f..294e3616a3 100644 --- a/Marlin/ubl_G29.cpp +++ b/Marlin/ubl_G29.cpp @@ -314,7 +314,7 @@ // Check for commands that require the printer to be homed if (axis_unhomed_error()) { - const int8_t p_val = parser.seenval('P') ? parser.value_int() : -1; + const int8_t p_val = parser.intval('P', -1); if (p_val == 1 || p_val == 2 || p_val == 4 || parser.seen('J')) home_all_axes(); } @@ -492,7 +492,7 @@ return; } - const float height = parser.seenval('H') ? parser.value_float() : Z_CLEARANCE_BETWEEN_PROBES; + const float height = parser.floatval('H', Z_CLEARANCE_BETWEEN_PROBES); manually_probe_remaining_mesh(g29_x_pos, g29_y_pos, height, g29_card_thickness, parser.seen('T')); SERIAL_PROTOCOLLNPGM("G29 P2 finished."); @@ -1180,7 +1180,7 @@ } #endif - g29_map_type = parser.seenval('T') ? parser.value_int() : 0; + g29_map_type = parser.intval('T'); if (!WITHIN(g29_map_type, 0, 2)) { SERIAL_PROTOCOLLNPGM("Invalid map type.\n"); return UBL_ERR; From bd776df8c10f7248b69efa0860ad7dfdd1778b89 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 27 Jun 2017 18:39:06 -0500 Subject: [PATCH 137/180] Optimize seen_axis by moving 'X' to index 24 --- Marlin/gcode.h | 44 +++++++++++++++++++++++++++++--------------- 1 file changed, 29 insertions(+), 15 deletions(-) diff --git a/Marlin/gcode.h b/Marlin/gcode.h index 0a9c859f14..42a5c89b14 100644 --- a/Marlin/gcode.h +++ b/Marlin/gcode.h @@ -97,6 +97,13 @@ public: // Reset is done before parsing static void reset(); + // Index so that 'X' falls on index 24 + #define PARAM_IND(N) ((N) >> 3) + #define PARAM_BIT(N) ((N) & 0x7) + #define LETTER_OFF(N) ((N) - 'A' + 1) + #define LETTER_IND(N) PARAM_IND(LETTER_OFF(N)) + #define LETTER_BIT(N) PARAM_BIT(LETTER_OFF(N)) + #if ENABLED(FASTER_GCODE_PARSER) // Set the flag and pointer for a parameter @@ -105,14 +112,14 @@ public: , const bool debug=false #endif ) { - const uint8_t ind = c - 'A'; + const uint8_t ind = LETTER_OFF(c); if (ind >= COUNT(param)) return; // Only A-Z - SBI(codebits[ind >> 3], ind & 0x7); // parameter exists + SBI(codebits[PARAM_IND(ind)], PARAM_BIT(ind)); // parameter exists param[ind] = ptr ? ptr - command_ptr : 0; // parameter offset or 0 #if ENABLED(DEBUG_GCODE_PARSER) if (debug) { - SERIAL_ECHOPAIR("Set bit ", (int)(ind & 0x7)); - SERIAL_ECHOPAIR(" of index ", (int)(ind >> 3)); + SERIAL_ECHOPAIR("Set bit ", (int)PARAM_BIT(ind)); + SERIAL_ECHOPAIR(" of index ", (int)PARAM_IND(ind)); SERIAL_ECHOLNPAIR(" | param = ", hex_address((void*)param[ind])); } #endif @@ -120,22 +127,28 @@ 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) { - const uint8_t ind = c - 'A'; + const uint8_t ind = LETTER_OFF(c); if (ind >= COUNT(param)) return false; // Only A-Z - const bool b = TEST(codebits[ind >> 3], ind & 0x7); + const bool b = TEST(codebits[PARAM_IND(ind)], PARAM_BIT(ind)); if (b) value_ptr = command_ptr + param[ind]; return b; } - static volatile bool seen_any() { return codebits[3] || codebits[2] || codebits[1] || codebits[0]; } + static bool seen_any() { return codebits[3] || codebits[2] || codebits[1] || codebits[0]; } - #define SEEN_TEST(L) TEST(codebits[(L - 'A') >> 3], (L - 'A') & 0x7) + #define SEEN_TEST(L) TEST(codebits[LETTER_IND(L)], LETTER_BIT(L)) + + // Seen any axis parameter + // Optimized by moving 'X' up to index 24 + FORCE_INLINE bool seen_axis() { return codebits[3] || SEEN_TEST('E'); } #else // !FASTER_GCODE_PARSER // 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) { const char *p = strchr(command_args, c); const bool b = !!p; @@ -143,26 +156,27 @@ public: return b; } - static volatile bool seen_any() { return *command_args == '\0'; } + static bool seen_any() { return *command_args == '\0'; } #define SEEN_TEST(L) !!strchr(command_args, L) + // Seen any axis parameter + static bool seen_axis() { + return SEEN_TEST('X') || SEEN_TEST('Y') || SEEN_TEST('Z') || SEEN_TEST('E'); + } + #endif // !FASTER_GCODE_PARSER // Populate all fields by parsing a single line of GCode // This uses 54 bytes of SRAM to speed up seen/value static void parse(char * p); - // Code value pointer was set + // The code value pointer was set FORCE_INLINE static bool has_value() { return value_ptr != NULL; } - // Seen and has value + // Seen a parameter with a value inline static bool seenval(const char c) { return seen(c) && has_value(); } - static volatile bool seen_axis() { - return SEEN_TEST('X') || SEEN_TEST('Y') || SEEN_TEST('Z') || SEEN_TEST('E'); - } - // Float removes 'E' to prevent scientific notation interpretation inline static float value_float() { if (value_ptr) { From fc140c49624ba845f68d0e2180b0086f585febc3 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 9 Jun 2017 10:22:49 -0500 Subject: [PATCH 138/180] Followup for I2C_POSITION_ENCODERS --- .travis.yml | 2 +- Marlin/Configuration_adv.h | 1 + Marlin/I2CPositionEncoder.cpp | 420 ++++++++++++++++++---------------- Marlin/I2CPositionEncoder.h | 235 +++++++++---------- Marlin/Marlin_main.cpp | 4 +- Marlin/SanityCheck.h | 4 +- Marlin/ubl_G29.cpp | 7 +- 7 files changed, 352 insertions(+), 321 deletions(-) diff --git a/.travis.yml b/.travis.yml index 4d5a00f1b2..f12b1e8918 100644 --- a/.travis.yml +++ b/.travis.yml @@ -93,7 +93,7 @@ script: # - restore_configs - opt_enable AUTO_BED_LEVELING_UBL UBL_G26_MESH_EDITING ENABLE_LEVELING_FADE_HEIGHT FIX_MOUNTED_PROBE EEPROM_SETTINGS G3D_PANEL - - opt_enable_adv CUSTOM_USER_MENUS + - opt_enable_adv CUSTOM_USER_MENUS I2C_POSITION_ENCODERS BABYSTEPPING - build_marlin # # Test a Sled Z Probe diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 4c772ec2d7..08d30b58e1 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1271,6 +1271,7 @@ //=========================================================================== //====================== I2C Position Encoder Settings ====================== //=========================================================================== + /** * I2C position encoders for closed loop control. * Developed by Chris Barr at Aus3D. diff --git a/Marlin/I2CPositionEncoder.cpp b/Marlin/I2CPositionEncoder.cpp index 8f226d9635..84334812f7 100644 --- a/Marlin/I2CPositionEncoder.cpp +++ b/Marlin/I2CPositionEncoder.cpp @@ -40,13 +40,14 @@ #include - void I2CPositionEncoder::init(uint8_t address, AxisEnum axis) { + + void I2CPositionEncoder::init(const uint8_t address, const AxisEnum axis) { encoderAxis = axis; i2cAddress = address; initialised++; - SERIAL_ECHOPAIR("Seetting up encoder on ", axis_codes[encoderAxis]); + SERIAL_ECHOPAIR("Setting up encoder on ", axis_codes[encoderAxis]); SERIAL_ECHOLNPAIR(" axis, addr = ", address); position = get_position(); @@ -98,13 +99,13 @@ //the encoder likely lost its place when the error occured, so we'll reset and use the printer's //idea of where it the axis is to re-initialise - double position = stepper.get_axis_position_mm(encoderAxis); - long positionInTicks = position * get_ticks_unit(); + float position = stepper.get_axis_position_mm(encoderAxis); + int32_t positionInTicks = position * get_ticks_unit(); //shift position from previous to current position zeroOffset -= (positionInTicks - get_position()); - #if defined(I2CPE_DEBUG) + #ifdef I2CPE_DEBUG SERIAL_ECHOPGM("Current position is "); SERIAL_ECHOLN(position); @@ -126,23 +127,23 @@ } lastPosition = position; - millis_t positionTime = millis(); + const millis_t positionTime = millis(); //only do error correction if setup and enabled if (ec && ecMethod != I2CPE_ECM_NONE) { - #if defined(I2CPE_EC_THRESH_PROPORTIONAL) - millis_t deltaTime = positionTime - lastPositionTime; - unsigned long distance = abs(position - lastPosition); - unsigned long speed = distance / deltaTime; - float threshold = constrain(speed / 50, 1, 50) * ecThreshold; + #ifdef I2CPE_EC_THRESH_PROPORTIONAL + const millis_t deltaTime = positionTime - lastPositionTime; + const uint32_t distance = abs(position - lastPosition), + speed = distance / deltaTime; + const float threshold = constrain((speed / 50), 1, 50) * ecThreshold; #else - float threshold = get_error_correct_threshold(); + const float threshold = get_error_correct_threshold(); #endif //check error #if ENABLED(I2CPE_ERR_ROLLING_AVERAGE) - double sum = 0, diffSum = 0; + float sum = 0, diffSum = 0; errIdx = (errIdx >= I2CPE_ERR_ARRAY_SIZE - 1) ? 0 : errIdx + 1; err[errIdx] = get_axis_error_steps(false); @@ -152,16 +153,16 @@ if (i) diffSum += abs(err[i-1] - err[i]); } - long error = (long)(sum/(I2CPE_ERR_ARRAY_SIZE + 1)); //calculate average for error + const int32_t error = int32_t(sum / (I2CPE_ERR_ARRAY_SIZE + 1)); //calculate average for error #else - long error = get_axis_error_steps(false); + const int32_t error = get_axis_error_steps(false); #endif - //SERIAL_ECHOPGM("Axis err*r steps: "); + //SERIAL_ECHOPGM("Axis error steps: "); //SERIAL_ECHOLN(error); - #if defined(I2CPE_ERR_THRESH_ABORT) + #ifdef I2CPE_ERR_THRESH_ABORT if (labs(error) > I2CPE_ERR_THRESH_ABORT * planner.axis_steps_per_mm[encoderAxis]) { //kill("Significant Error"); SERIAL_ECHOPGM("Axis error greater than set threshold, aborting!"); @@ -215,7 +216,7 @@ homed++; trusted++; - #if defined(I2CPE_DEBUG) + #ifdef I2CPE_DEBUG SERIAL_ECHO(axis_codes[encoderAxis]); SERIAL_ECHOPAIR(" axis encoder homed, offset of ", zeroOffset); SERIAL_ECHOLNPGM(" ticks."); @@ -223,36 +224,27 @@ } } - bool I2CPositionEncoder::passes_test(bool report) { - if (H == I2CPE_MAG_SIG_GOOD) { - if (report) { - SERIAL_ECHO(axis_codes[encoderAxis]); - SERIAL_ECHOLNPGM(" axis encoder passes test; field strength good."); - } - return true; - } else if (H == I2CPE_MAG_SIG_MID) { - if (report) { - SERIAL_ECHOPAIR("Warning, ", axis_codes[encoderAxis]); - SERIAL_ECHOLNPGM(" axis encoder passes test; field strength fair."); - } - return true; - } else if (H == I2CPE_MAG_SIG_BAD) { - if (report) { - SERIAL_ECHOPAIR("Warning, ", axis_codes[encoderAxis]); - SERIAL_ECHOLNPGM(" axis magnetic strip not detected!"); - } - return false; - } - + bool I2CPositionEncoder::passes_test(const bool report) { if (report) { - SERIAL_ECHOPAIR("Warning, ", axis_codes[encoderAxis]); - SERIAL_ECHOLNPGM(" axis encoder not detected!"); + if (H != I2CPE_MAG_SIG_GOOD) SERIAL_ECHOPGM("Warning. "); + SERIAL_ECHO(axis_codes[encoderAxis]); + SERIAL_ECHOPGM(" axis "); + serialprintPGM(H == I2CPE_MAG_SIG_BAD ? PSTR("magnetic strip ") : PSTR("encoder ")); + switch (H) { + case I2CPE_MAG_SIG_GOOD: + case I2CPE_MAG_SIG_MID: + SERIAL_ECHOLNPGM("passes test; field strength "); + serialprintPGM(H == I2CPE_MAG_SIG_GOOD ? PSTR("good.\n") : PSTR("fair.\n")); + break; + default: + SERIAL_ECHOLNPGM("not detected!"); + } } - return false; + return (H == I2CPE_MAG_SIG_GOOD || H == I2CPE_MAG_SIG_MID); } - double I2CPositionEncoder::get_axis_error_mm(bool report) { - double target, actual, error; + float I2CPositionEncoder::get_axis_error_mm(const bool report) { + float target, actual, error; target = stepper.get_axis_position_mm(encoderAxis); actual = mm_from_count(position); @@ -270,7 +262,7 @@ return error; } - long I2CPositionEncoder::get_axis_error_steps(bool report) { + int32_t I2CPositionEncoder::get_axis_error_steps(const bool report) { if (!active) { if (report) { SERIAL_ECHO(axis_codes[encoderAxis]); @@ -280,8 +272,8 @@ } float stepperTicksPerUnit; - long encoderTicks = position, encoderCountInStepperTicksScaled; - //long stepperTicks = stepper.position(encoderAxis); + int32_t encoderTicks = position, encoderCountInStepperTicksScaled; + //int32_t stepperTicks = stepper.position(encoderAxis); // With a rotary encoder we're concerned with ticks/rev; whereas with a linear we're concerned with ticks/mm stepperTicksPerUnit = (type == I2CPE_ENC_TYPE_ROTARY) ? stepperTicks : planner.axis_steps_per_mm[encoderAxis]; @@ -289,8 +281,8 @@ //convert both 'ticks' into same units / base encoderCountInStepperTicksScaled = LROUND((stepperTicksPerUnit * encoderTicks) / encoderTicksPerUnit); - long target = stepper.position(encoderAxis), - error = (encoderCountInStepperTicksScaled - target); + int32_t target = stepper.position(encoderAxis), + error = (encoderCountInStepperTicksScaled - target); //suppress discontinuities (might be caused by bad I2C readings...?) bool suppressOutput = (labs(error - errorPrev) > 100); @@ -309,7 +301,7 @@ return (suppressOutput ? 0 : error); } - long I2CPositionEncoder::get_raw_count() { + int32_t I2CPositionEncoder::get_raw_count() { uint8_t index = 0; i2cLong encoderCount; @@ -340,14 +332,11 @@ //only works on XYZ cartesian machines for the time being if (!(encoderAxis == X_AXIS || encoderAxis == Y_AXIS || encoderAxis == Z_AXIS)) return false; - int feedrate; - float startPosition, endPosition; - float startCoord[NUM_AXIS] = {0}, endCoord[NUM_AXIS] = {0}; + float startCoord[NUM_AXIS] = { 0 }, endCoord[NUM_AXIS] = { 0 }; - startPosition = soft_endstop_min[encoderAxis] + 10; - endPosition = soft_endstop_max[encoderAxis] - 10; - - feedrate = (int)MMM_TO_MMS((encoderAxis == Z_AXIS) ? HOMING_FEEDRATE_Z : HOMING_FEEDRATE_XY); + const float startPosition = soft_endstop_min[encoderAxis] + 10, + endPosition = soft_endstop_max[encoderAxis] - 10, + feedrate = FLOOR(MMM_TO_MMS((encoderAxis == Z_AXIS) ? HOMING_FEEDRATE_Z : HOMING_FEEDRATE_XY)); ec = false; @@ -367,7 +356,7 @@ // if the module isn't currently trusted, wait until it is (or until it should be if things are working) if (!trusted) { - long startWaitingTime = millis(); + int32_t startWaitingTime = millis(); while (!trusted && millis() - startWaitingTime < I2CPE_TIME_TRUSTED) safe_delay(500); } @@ -381,7 +370,7 @@ return trusted; } - void I2CPositionEncoder::calibrate_steps_mm(int iter) { + void I2CPositionEncoder::calibrate_steps_mm(const uint8_t iter) { if (type != I2CPE_ENC_TYPE_LINEAR) { SERIAL_ECHOLNPGM("Steps per mm calibration is only available using linear encoders."); return; @@ -392,14 +381,14 @@ return; } - float oldStepsMm, newStepsMm, + float old_steps_mm, new_steps_mm, startDistance, endDistance, travelDistance, travelledDistance, total = 0, - startCoord[NUM_AXIS] = {0}, endCoord[NUM_AXIS] = {0}; + startCoord[NUM_AXIS] = { 0 }, endCoord[NUM_AXIS] = { 0 }; - double feedrate; + float feedrate; - long startCount, stopCount; + int32_t startCount, stopCount; feedrate = MMM_TO_MMS((encoderAxis == Z_AXIS) ? HOMING_FEEDRATE_Z : HOMING_FEEDRATE_XY); @@ -447,17 +436,17 @@ SERIAL_ECHOLNPGM("mm."); //Calculate new axis steps per unit - oldStepsMm = planner.axis_steps_per_mm[encoderAxis]; - newStepsMm = (oldStepsMm * travelDistance) / travelledDistance; + old_steps_mm = planner.axis_steps_per_mm[encoderAxis]; + new_steps_mm = (old_steps_mm * travelDistance) / travelledDistance; - SERIAL_ECHOLNPAIR("Old steps per mm: ", oldStepsMm); - SERIAL_ECHOLNPAIR("New steps per mm: ", newStepsMm); + SERIAL_ECHOLNPAIR("Old steps per mm: ", old_steps_mm); + SERIAL_ECHOLNPAIR("New steps per mm: ", new_steps_mm); //Save new value - planner.axis_steps_per_mm[encoderAxis] = newStepsMm; + planner.axis_steps_per_mm[encoderAxis] = new_steps_mm; if (iter > 1) { - total += newStepsMm; + total += new_steps_mm; // swap start and end points so next loop runs from current position float tempCoord = startCoord[encoderAxis]; @@ -486,6 +475,12 @@ #endif } + + bool I2CPositionEncodersMgr::I2CPE_anyaxis; + uint8_t I2CPositionEncodersMgr::I2CPE_addr, + I2CPositionEncodersMgr::I2CPE_idx; + I2CPositionEncoder I2CPositionEncodersMgr::encoders[I2CPE_ENCODER_CNT]; + void I2CPositionEncodersMgr::init() { Wire.begin(); @@ -494,28 +489,28 @@ encoders[i].init(I2CPE_ENC_1_ADDR, I2CPE_ENC_1_AXIS); - #if defined(I2CPE_ENC_1_TYPE) + #ifdef I2CPE_ENC_1_TYPE encoders[i].set_type(I2CPE_ENC_1_TYPE); #endif - #if defined(I2CPE_ENC_1_TICKS_UNIT) + #ifdef I2CPE_ENC_1_TICKS_UNIT encoders[i].set_ticks_unit(I2CPE_ENC_1_TICKS_UNIT); #endif - #if defined(I2CPE_ENC_1_TICKS_REV) + #ifdef I2CPE_ENC_1_TICKS_REV encoders[i].set_stepper_ticks(I2CPE_ENC_1_TICKS_REV); #endif - #if defined(I2CPE_ENC_1_INVERT) + #ifdef I2CPE_ENC_1_INVERT encoders[i].set_inverted(I2CPE_ENC_1_INVERT); #endif - #if defined(I2CPE_ENC_1_EC_METHOD) + #ifdef I2CPE_ENC_1_EC_METHOD encoders[i].set_ec_method(I2CPE_ENC_1_EC_METHOD); #endif - #if defined(I2CPE_ENC_1_EC_THRESH) + #ifdef I2CPE_ENC_1_EC_THRESH encoders[i].set_ec_threshold(I2CPE_ENC_1_EC_THRESH); #endif encoders[i].set_active(encoders[i].passes_test(true)); - #if (I2CPE_ENC_1_AXIS == E_AXIS) + #if I2CPE_ENC_1_AXIS == E_AXIS encoders[i].set_homed(); #endif #endif @@ -525,28 +520,28 @@ encoders[i].init(I2CPE_ENC_2_ADDR, I2CPE_ENC_2_AXIS); - #if defined(I2CPE_ENC_2_TYPE) + #ifdef I2CPE_ENC_2_TYPE encoders[i].set_type(I2CPE_ENC_2_TYPE); #endif - #if defined(I2CPE_ENC_2_TICKS_UNIT) + #ifdef I2CPE_ENC_2_TICKS_UNIT encoders[i].set_ticks_unit(I2CPE_ENC_2_TICKS_UNIT); #endif - #if defined(I2CPE_ENC_2_TICKS_REV) + #ifdef I2CPE_ENC_2_TICKS_REV encoders[i].set_stepper_ticks(I2CPE_ENC_2_TICKS_REV); #endif - #if defined(I2CPE_ENC_2_INVERT) + #ifdef I2CPE_ENC_2_INVERT encoders[i].set_inverted(I2CPE_ENC_2_INVERT); #endif - #if defined(I2CPE_ENC_2_EC_METHOD) + #ifdef I2CPE_ENC_2_EC_METHOD encoders[i].set_ec_method(I2CPE_ENC_2_EC_METHOD); #endif - #if defined(I2CPE_ENC_2_EC_THRESH) + #ifdef I2CPE_ENC_2_EC_THRESH encoders[i].set_ec_threshold(I2CPE_ENC_2_EC_THRESH); #endif encoders[i].set_active(encoders[i].passes_test(true)); - #if (I2CPE_ENC_2_AXIS == E_AXIS) + #if I2CPE_ENC_2_AXIS == E_AXIS encoders[i].set_homed(); #endif #endif @@ -556,28 +551,28 @@ encoders[i].init(I2CPE_ENC_3_ADDR, I2CPE_ENC_3_AXIS); - #if defined(I2CPE_ENC_3_TYPE) + #ifdef I2CPE_ENC_3_TYPE encoders[i].set_type(I2CPE_ENC_3_TYPE); #endif - #if defined(I2CPE_ENC_3_TICKS_UNIT) + #ifdef I2CPE_ENC_3_TICKS_UNIT encoders[i].set_ticks_unit(I2CPE_ENC_3_TICKS_UNIT); #endif - #if defined(I2CPE_ENC_3_TICKS_REV) + #ifdef I2CPE_ENC_3_TICKS_REV encoders[i].set_stepper_ticks(I2CPE_ENC_3_TICKS_REV); #endif - #if defined(I2CPE_ENC_3_INVERT) + #ifdef I2CPE_ENC_3_INVERT encoders[i].set_inverted(I2CPE_ENC_3_INVERT); #endif - #if defined(I2CPE_ENC_3_EC_METHOD) + #ifdef I2CPE_ENC_3_EC_METHOD encoders[i].set_ec_method(I2CPE_ENC_3_EC_METHOD); #endif - #if defined(I2CPE_ENC_3_EC_THRESH) + #ifdef I2CPE_ENC_3_EC_THRESH encoders[i].set_ec_threshold(I2CPE_ENC_3_EC_THRESH); #endif encoders[i].set_active(encoders[i].passes_test(true)); - #if (I2CPE_ENC_3_AXIS == E_AXIS) + #if I2CPE_ENC_3_AXIS == E_AXIS encoders[i].set_homed(); #endif #endif @@ -587,28 +582,28 @@ encoders[i].init(I2CPE_ENC_4_ADDR, I2CPE_ENC_4_AXIS); - #if defined(I2CPE_ENC_4_TYPE) + #ifdef I2CPE_ENC_4_TYPE encoders[i].set_type(I2CPE_ENC_4_TYPE); #endif - #if defined(I2CPE_ENC_4_TICKS_UNIT) + #ifdef I2CPE_ENC_4_TICKS_UNIT encoders[i].set_ticks_unit(I2CPE_ENC_4_TICKS_UNIT); #endif - #if defined(I2CPE_ENC_4_TICKS_REV) + #ifdef I2CPE_ENC_4_TICKS_REV encoders[i].set_stepper_ticks(I2CPE_ENC_4_TICKS_REV); #endif - #if defined(I2CPE_ENC_4_INVERT) + #ifdef I2CPE_ENC_4_INVERT encoders[i].set_inverted(I2CPE_ENC_4_INVERT); #endif - #if defined(I2CPE_ENC_4_EC_METHOD) + #ifdef I2CPE_ENC_4_EC_METHOD encoders[i].set_ec_method(I2CPE_ENC_4_EC_METHOD); #endif - #if defined(I2CPE_ENC_4_EC_THRESH) + #ifdef I2CPE_ENC_4_EC_THRESH encoders[i].set_ec_threshold(I2CPE_ENC_4_EC_THRESH); #endif encoders[i].set_active(encoders[i].passes_test(true)); - #if (I2CPE_ENC_4_AXIS == E_AXIS) + #if I2CPE_ENC_4_AXIS == E_AXIS encoders[i].set_homed(); #endif #endif @@ -618,56 +613,57 @@ encoders[i].init(I2CPE_ENC_5_ADDR, I2CPE_ENC_5_AXIS); - #if defined(I2CPE_ENC_5_TYPE) + #ifdef I2CPE_ENC_5_TYPE encoders[i].set_type(I2CPE_ENC_5_TYPE); #endif - #if defined(I2CPE_ENC_5_TICKS_UNIT) + #ifdef I2CPE_ENC_5_TICKS_UNIT encoders[i].set_ticks_unit(I2CPE_ENC_5_TICKS_UNIT); #endif - #if defined(I2CPE_ENC_5_TICKS_REV) + #ifdef I2CPE_ENC_5_TICKS_REV encoders[i].set_stepper_ticks(I2CPE_ENC_5_TICKS_REV); #endif - #if defined(I2CPE_ENC_5_INVERT) + #ifdef I2CPE_ENC_5_INVERT encoders[i].set_inverted(I2CPE_ENC_5_INVERT); #endif - #if defined(I2CPE_ENC_5_EC_METHOD) + #ifdef I2CPE_ENC_5_EC_METHOD encoders[i].set_ec_method(I2CPE_ENC_5_EC_METHOD); #endif - #if defined(I2CPE_ENC_5_EC_THRESH) + #ifdef I2CPE_ENC_5_EC_THRESH encoders[i].set_ec_threshold(I2CPE_ENC_5_EC_THRESH); #endif encoders[i].set_active(encoders[i].passes_test(true)); - #if (I2CPE_ENC_5_AXIS == E_AXIS) + #if I2CPE_ENC_5_AXIS == E_AXIS encoders[i].set_homed(); #endif #endif - } - void I2CPositionEncodersMgr::report_position(uint8_t idx, bool units, bool noOffset) { - CHECK_IDX + void I2CPositionEncodersMgr::report_position(const int8_t idx, const bool units, const bool noOffset) { + CHECK_IDX(); - if (units) { + if (units) SERIAL_ECHOLN(noOffset ? encoders[idx].mm_from_count(encoders[idx].get_raw_count()) : encoders[idx].get_position_mm()); - } else { + else { if (noOffset) { - long raw_count = encoders[idx].get_raw_count(); + const int32_t raw_count = encoders[idx].get_raw_count(); SERIAL_ECHO(axis_codes[encoders[idx].get_axis()]); - SERIAL_ECHOPGM(" "); + SERIAL_CHAR(' '); for (uint8_t j = 31; j > 0; j--) SERIAL_ECHO((bool)(0x00000001 & (raw_count >> j))); - SERIAL_ECHO((bool)(0x00000001 & (raw_count))); - SERIAL_ECHOLNPAIR(" ", raw_count); - } else + SERIAL_ECHO((bool)(0x00000001 & raw_count)); + SERIAL_CHAR(' '); + SERIAL_ECHOLN(raw_count); + } + else SERIAL_ECHOLN(encoders[idx].get_position()); } } - void I2CPositionEncodersMgr::change_module_address(uint8_t oldaddr, uint8_t newaddr) { + void I2CPositionEncodersMgr::change_module_address(const uint8_t oldaddr, const uint8_t newaddr) { // First check 'new' address is not in use Wire.beginTransmission(newaddr); if (!Wire.endTransmission()) { @@ -709,7 +705,7 @@ // Now, if this module is configured, find which encoder instance it's supposed to correspond to // and enable it (it will likely have failed initialisation on power-up, before the address change). - int8_t idx = idx_from_addr(newaddr); + const int8_t idx = idx_from_addr(newaddr); if (idx >= 0 && !encoders[idx].get_active()) { SERIAL_ECHO(axis_codes[encoders[idx].get_axis()]); SERIAL_ECHOLNPGM(" axis encoder was not detected on printer startup. Trying again."); @@ -717,7 +713,7 @@ } } - void I2CPositionEncodersMgr::report_module_firmware(uint8_t address) { + void I2CPositionEncodersMgr::report_module_firmware(const uint8_t address) { // First check there is a module Wire.beginTransmission(address); if (Wire.endTransmission()) { @@ -727,7 +723,7 @@ } SERIAL_ECHOPAIR("Requesting version info from module at address ", address); - SERIAL_ECHOPGM(":\n"); + SERIAL_ECHOLNPGM(":"); Wire.beginTransmission(address); Wire.write(I2CPE_SET_REPORT_MODE); @@ -743,7 +739,7 @@ } // Set module back to normal (distance) mode - Wire.beginTransmission((int)address); + Wire.beginTransmission(address); Wire.write(I2CPE_SET_REPORT_MODE); Wire.write(I2CPE_REPORT_DISTANCE); Wire.endTransmission(); @@ -753,43 +749,43 @@ I2CPE_addr = 0; if (parser.seen('A')) { + if (!parser.has_value()) { SERIAL_PROTOCOLLNPGM("?A seen, but no address specified! [30-200]"); return I2CPE_PARSE_ERR; }; I2CPE_addr = parser.value_byte(); - if (!WITHIN(I2CPE_addr, 30, 200)) { // reserve the first 30 and last 55 SERIAL_PROTOCOLLNPGM("?Address out of range. [30-200]"); return I2CPE_PARSE_ERR; } I2CPE_idx = idx_from_addr(I2CPE_addr); - - if (!WITHIN(I2CPE_idx, 0, I2CPE_ENCODER_CNT - 1)) { + if (I2CPE_idx >= I2CPE_ENCODER_CNT) { SERIAL_PROTOCOLLNPGM("?No device with this address!"); return I2CPE_PARSE_ERR; } - } else if (parser.seenval('I')) { + } + else if (parser.seenval('I')) { + if (!parser.has_value()) { SERIAL_PROTOCOLLNPAIR("?I seen, but no index specified! [0-", I2CPE_ENCODER_CNT - 1); - SERIAL_ECHOLNPGM("]"); + SERIAL_PROTOCOLLNPGM("]"); return I2CPE_PARSE_ERR; }; I2CPE_idx = parser.value_byte(); - - if (!WITHIN(I2CPE_idx, 0, I2CPE_ENCODER_CNT - 1)) { + if (I2CPE_idx >= I2CPE_ENCODER_CNT) { SERIAL_PROTOCOLLNPAIR("?Index out of range. [0-", I2CPE_ENCODER_CNT - 1); SERIAL_ECHOLNPGM("]"); return I2CPE_PARSE_ERR; } I2CPE_addr = encoders[I2CPE_idx].get_address(); - } else { - I2CPE_idx = -1; } + else + I2CPE_idx = 0xFF; I2CPE_anyaxis = parser.seen_axis(); @@ -814,15 +810,18 @@ void I2CPositionEncodersMgr::M860() { if (parse()) return; - bool hasU = parser.seen('U'), hasO = parser.seen('O'); + const bool hasU = parser.seen('U'), hasO = parser.seen('O'); - if (I2CPE_idx < 0) { - int8_t idx; + if (I2CPE_idx == 0xFF) { LOOP_XYZE(i) { - if ((!I2CPE_anyaxis || parser.seen(axis_codes[i])) && ((idx = idx_from_axis(AxisEnum(i))) >= 0)) - report_position((uint8_t)idx, hasU, hasO); + if (!I2CPE_anyaxis || parser.seen(axis_codes[i])) { + const uint8_t idx = idx_from_axis(AxisEnum(i)); + if ((int8_t)idx >= 0) report_position(idx, hasU, hasO); + } } - } else report_position((uint8_t)I2CPE_idx, hasU, hasO); + } + else + report_position(I2CPE_idx, hasU, hasO); } /** @@ -841,13 +840,16 @@ void I2CPositionEncodersMgr::M861() { if (parse()) return; - if (I2CPE_idx < 0) { - int8_t idx; + if (I2CPE_idx == 0xFF) { LOOP_XYZE(i) { - if ((!I2CPE_anyaxis || parser.seen(axis_codes[i])) && ((idx = idx_from_axis(AxisEnum(i))) >= 0)) - report_status((uint8_t)idx); + if (!I2CPE_anyaxis || parser.seen(axis_codes[i])) { + const uint8_t idx = idx_from_axis(AxisEnum(i)); + if ((int8_t)idx >= 0) report_status(idx); + } } - } else report_status((uint8_t)I2CPE_idx); + } + else + report_status(I2CPE_idx); } /** @@ -867,13 +869,16 @@ void I2CPositionEncodersMgr::M862() { if (parse()) return; - if (I2CPE_idx < 0) { - int8_t idx; + if (I2CPE_idx == 0xFF) { LOOP_XYZE(i) { - if ((!I2CPE_anyaxis || parser.seen(axis_codes[i])) && ((idx = idx_from_axis(AxisEnum(i))) >= 0)) - test_axis((uint8_t)idx); + if (!I2CPE_anyaxis || parser.seen(axis_codes[i])) { + const uint8_t idx = idx_from_axis(AxisEnum(i)); + if ((int8_t)idx >= 0) test_axis(idx); + } } - } else test_axis((uint8_t)I2CPE_idx); + } + else + test_axis(I2CPE_idx); } /** @@ -894,15 +899,18 @@ void I2CPositionEncodersMgr::M863() { if (parse()) return; - int iterations = parser.seenval('P') ? constrain(parser.value_byte(), 1, 10) : 1; + const uint8_t iterations = constrain(parser.byteval('P', 1), 1, 10); - if (I2CPE_idx < 0) { - int8_t idx; + if (I2CPE_idx == 0xFF) { LOOP_XYZE(i) { - if ((!I2CPE_anyaxis || parser.seen(axis_codes[i])) && ((idx = idx_from_axis(AxisEnum(i))) >= 0)) - calibrate_steps_mm((uint8_t)idx, iterations); + if (!I2CPE_anyaxis || parser.seen(axis_codes[i])) { + const uint8_t idx = idx_from_axis(AxisEnum(i)); + if ((int8_t)idx >= 0) calibrate_steps_mm(idx, iterations); + } } - } else calibrate_steps_mm((uint8_t)I2CPE_idx, iterations); + } + else + calibrate_steps_mm(I2CPE_idx, iterations); } /** @@ -910,9 +918,9 @@ * * A Module current/old I2C address. If not present, * assumes default address (030). [30, 200]. - * N Module new I2C address. [30, 200]. + * S Module new I2C address. [30, 200]. * - * If N not specified: + * If S is not specified: * X Use I2CPE_PRESET_ADDR_X (030). * Y Use I2CPE_PRESET_ADDR_Y (031). * Z Use I2CPE_PRESET_ADDR_Z (032). @@ -925,23 +933,24 @@ if (!I2CPE_addr) I2CPE_addr = I2CPE_PRESET_ADDR_X; - if (parser.seen('N')) { + if (parser.seen('S')) { if (!parser.has_value()) { - SERIAL_PROTOCOLLNPGM("?N seen, but no address specified! [30-200]"); + SERIAL_PROTOCOLLNPGM("?S seen, but no address specified! [30-200]"); return; }; newAddress = parser.value_byte(); - if (!WITHIN(newAddress, 30, 200)) { SERIAL_PROTOCOLLNPGM("?New address out of range. [30-200]"); return; } - } else if (!I2CPE_anyaxis) { - SERIAL_PROTOCOLLNPGM("?You must specify N or [XYZE]."); + } + else if (!I2CPE_anyaxis) { + SERIAL_PROTOCOLLNPGM("?You must specify S or [XYZE]."); return; - } else { - if (parser.seen('X')) newAddress = I2CPE_PRESET_ADDR_X; + } + else { + if (parser.seen('X')) newAddress = I2CPE_PRESET_ADDR_X; else if (parser.seen('Y')) newAddress = I2CPE_PRESET_ADDR_Y; else if (parser.seen('Z')) newAddress = I2CPE_PRESET_ADDR_Z; else if (parser.seen('E')) newAddress = I2CPE_PRESET_ADDR_E; @@ -970,12 +979,15 @@ if (parse()) return; if (!I2CPE_addr) { - int8_t idx; LOOP_XYZE(i) { - if ((!I2CPE_anyaxis || parser.seen(axis_codes[i])) && ((idx = idx_from_axis(AxisEnum(i))) >= 0)) - report_module_firmware(encoders[idx].get_address()); + if (!I2CPE_anyaxis || parser.seen(axis_codes[i])) { + const uint8_t idx = idx_from_axis(AxisEnum(i)); + if ((int8_t)idx >= 0) report_module_firmware(encoders[idx].get_address()); + } } - } else report_module_firmware(I2CPE_addr); + } + else + report_module_firmware(I2CPE_addr); } /** @@ -995,20 +1007,25 @@ void I2CPositionEncodersMgr::M866() { if (parse()) return; - bool hasR = parser.seen('R'); + const bool hasR = parser.seen('R'); - if (I2CPE_idx < 0) { - int8_t idx; + if (I2CPE_idx == 0xFF) { LOOP_XYZE(i) { - if ((!I2CPE_anyaxis || parser.seen(axis_codes[i])) && ((idx = idx_from_axis(AxisEnum(i))) >= 0)) { - if (hasR) reset_error_count((uint8_t)idx, AxisEnum(i)); - else report_error_count((uint8_t)idx, AxisEnum(i)); + if (!I2CPE_anyaxis || parser.seen(axis_codes[i])) { + const uint8_t idx = idx_from_axis(AxisEnum(i)); + if ((int8_t)idx >= 0) { + if (hasR) + reset_error_count(idx, AxisEnum(i)); + else + report_error_count(idx, AxisEnum(i)); + } } } - } else { - if (hasR) reset_error_count((uint8_t)I2CPE_idx, encoders[I2CPE_idx].get_axis()); - else report_error_count((uint8_t)I2CPE_idx, encoders[I2CPE_idx].get_axis()); } + else if (hasR) + reset_error_count(I2CPE_idx, encoders[I2CPE_idx].get_axis()); + else + report_error_count(I2CPE_idx, encoders[I2CPE_idx].get_axis()); } /** @@ -1028,19 +1045,22 @@ void I2CPositionEncodersMgr::M867() { if (parse()) return; - int8_t onoff = parser.seenval('S') ? parser.value_int() : -1; + const int8_t onoff = parser.seenval('S') ? parser.value_int() : -1; - if (I2CPE_idx < 0) { - int8_t idx; + if (I2CPE_idx == 0xFF) { LOOP_XYZE(i) { - if ((!I2CPE_anyaxis || parser.seen(axis_codes[i])) && ((idx = idx_from_axis(AxisEnum(i))) >= 0)) { - if (onoff == -1) enable_ec((uint8_t)idx, !encoders[idx].get_ec_enabled(), AxisEnum(i)); - else enable_ec((uint8_t)idx, (bool)onoff, AxisEnum(i)); + if (!I2CPE_anyaxis || parser.seen(axis_codes[i])) { + const uint8_t idx = idx_from_axis(AxisEnum(i)); + if ((int8_t)idx >= 0) { + const bool ena = onoff == -1 ? !encoders[I2CPE_idx].get_ec_enabled() : !!onoff; + enable_ec(idx, ena, AxisEnum(i)); + } } } - } else { - if (onoff == -1) enable_ec((uint8_t)I2CPE_idx, !encoders[I2CPE_idx].get_ec_enabled(), encoders[I2CPE_idx].get_axis()); - else enable_ec((uint8_t)I2CPE_idx, (bool)onoff, encoders[I2CPE_idx].get_axis()); + } + else { + const bool ena = onoff == -1 ? !encoders[I2CPE_idx].get_ec_enabled() : !!onoff; + enable_ec(I2CPE_idx, ena, encoders[I2CPE_idx].get_axis()); } } @@ -1061,20 +1081,25 @@ void I2CPositionEncodersMgr::M868() { if (parse()) return; - float newThreshold = parser.seenval('T') ? parser.value_float() : -9999; + const float newThreshold = parser.seenval('T') ? parser.value_float() : -9999; - if (I2CPE_idx < 0) { - int8_t idx; + if (I2CPE_idx == 0xFF) { LOOP_XYZE(i) { - if ((!I2CPE_anyaxis || parser.seen(axis_codes[i])) && ((idx = idx_from_axis(AxisEnum(i))) >= 0)) { - if (newThreshold != -9999) set_ec_threshold((uint8_t)idx, newThreshold, encoders[idx].get_axis()); - else get_ec_threshold((uint8_t)idx, encoders[idx].get_axis()); + if (!I2CPE_anyaxis || parser.seen(axis_codes[i])) { + const uint8_t idx = idx_from_axis(AxisEnum(i)); + if ((int8_t)idx >= 0) { + if (newThreshold != -9999) + set_ec_threshold(idx, newThreshold, encoders[idx].get_axis()); + else + get_ec_threshold(idx, encoders[idx].get_axis()); + } } } - } else { - if (newThreshold != -9999) set_ec_threshold((uint8_t)I2CPE_idx, newThreshold, encoders[I2CPE_idx].get_axis()); - else get_ec_threshold((uint8_t)I2CPE_idx, encoders[I2CPE_idx].get_axis()); } + else if (newThreshold != -9999) + set_ec_threshold(I2CPE_idx, newThreshold, encoders[I2CPE_idx].get_axis()); + else + get_ec_threshold(I2CPE_idx, encoders[I2CPE_idx].get_axis()); } /** @@ -1092,13 +1117,16 @@ void I2CPositionEncodersMgr::M869() { if (parse()) return; - if (I2CPE_idx < 0) { - int8_t idx; + if (I2CPE_idx == 0xFF) { LOOP_XYZE(i) { - if ((!I2CPE_anyaxis || parser.seen(axis_codes[i])) && ((idx = idx_from_axis(AxisEnum(i))) >= 0)) - report_error((uint8_t)idx); + if (!I2CPE_anyaxis || parser.seen(axis_codes[i])) { + const uint8_t idx = idx_from_axis(AxisEnum(i)); + if ((int8_t)idx >= 0) report_error(idx); + } } - } else report_error((uint8_t)I2CPE_idx); + } + else + report_error(I2CPE_idx); } -#endif +#endif // I2C_POSITION_ENCODERS diff --git a/Marlin/I2CPositionEncoder.h b/Marlin/I2CPositionEncoder.h index fe0be390a5..a582a87b6d 100644 --- a/Marlin/I2CPositionEncoder.h +++ b/Marlin/I2CPositionEncoder.h @@ -95,195 +95,202 @@ #define I2CPE_PARSE_OK 0 #define LOOP_PE(VAR) LOOP_L_N(VAR, I2CPE_ENCODER_CNT) - #define CHECK_IDX if (!WITHIN(idx, 0, I2CPE_ENCODER_CNT - 1)) return; + #define CHECK_IDX() do{ if (!WITHIN(idx, 0, I2CPE_ENCODER_CNT - 1)) return; }while(0) extern const char axis_codes[XYZE]; typedef union { - volatile long val = 0; - uint8_t bval[4]; + volatile int32_t val = 0; + uint8_t bval[4]; } i2cLong; class I2CPositionEncoder { private: - AxisEnum encoderAxis = I2CPE_DEF_AXIS; + AxisEnum encoderAxis = I2CPE_DEF_AXIS; - uint8_t i2cAddress = I2CPE_DEF_ADDR, - ecMethod = I2CPE_DEF_EC_METHOD, - type = I2CPE_DEF_TYPE, - H = I2CPE_MAG_SIG_NF; // Magnetic field strength + uint8_t i2cAddress = I2CPE_DEF_ADDR, + ecMethod = I2CPE_DEF_EC_METHOD, + type = I2CPE_DEF_TYPE, + H = I2CPE_MAG_SIG_NF; // Magnetic field strength - int encoderTicksPerUnit = I2CPE_DEF_ENC_TICKS_UNIT, - stepperTicks = I2CPE_DEF_TICKS_REV; + int encoderTicksPerUnit = I2CPE_DEF_ENC_TICKS_UNIT, + stepperTicks = I2CPE_DEF_TICKS_REV, + errorCount = 0, + errorPrev = 0; - float ecThreshold = I2CPE_DEF_EC_THRESH; + float ecThreshold = I2CPE_DEF_EC_THRESH; - bool homed = false, - trusted = false, - initialised = false, - active = false, - invert = false, - ec = true; + bool homed = false, + trusted = false, + initialised = false, + active = false, + invert = false, + ec = true; - int errorCount = 0, - errorPrev = 0; + float axisOffset = 0; - float axisOffset = 0; + int32_t axisOffsetTicks = 0, + zeroOffset = 0, + lastPosition = 0, + position; - long axisOffsetTicks = 0, - zeroOffset = 0, - lastPosition = 0, - position; - - unsigned long lastPositionTime = 0, - nextErrorCountTime = 0, - lastErrorTime; + millis_t lastPositionTime = 0, + nextErrorCountTime = 0, + lastErrorTime; //double positionMm; //calculate #if ENABLED(I2CPE_ERR_ROLLING_AVERAGE) - uint8_t errIdx = 0; - int err[I2CPE_ERR_ARRAY_SIZE] = {0}; + uint8_t errIdx = 0; + int err[I2CPE_ERR_ARRAY_SIZE] = { 0 }; #endif + //float positionMm; //calculate + public: - void init(uint8_t address, AxisEnum axis); + void init(const uint8_t address, const AxisEnum axis); void reset(); void update(); void set_homed(); - long get_raw_count(); + int32_t get_raw_count(); - FORCE_INLINE double mm_from_count(long count) { - if (type == I2CPE_ENC_TYPE_LINEAR) return count / encoderTicksPerUnit; - else if (type == I2CPE_ENC_TYPE_ROTARY) - return (count * stepperTicks) / (encoderTicksPerUnit * planner.axis_steps_per_mm[encoderAxis]); - return -1; + FORCE_INLINE float mm_from_count(const int32_t count) { + switch (type) { + default: return -1; + case I2CPE_ENC_TYPE_LINEAR: + return count / encoderTicksPerUnit; + case I2CPE_ENC_TYPE_ROTARY: + return (count * stepperTicks) / (encoderTicksPerUnit * planner.axis_steps_per_mm[encoderAxis]); + } } - FORCE_INLINE double get_position_mm() { return mm_from_count(get_position()); } - FORCE_INLINE long get_position() { return get_raw_count() - zeroOffset - axisOffsetTicks; } + FORCE_INLINE float get_position_mm() { return mm_from_count(get_position()); } + FORCE_INLINE int32_t get_position() { return get_raw_count() - zeroOffset - axisOffsetTicks; } - long get_axis_error_steps(bool report); - double get_axis_error_mm(bool report); + int32_t get_axis_error_steps(const bool report); + float get_axis_error_mm(const bool report); - void calibrate_steps_mm(int iter); + void calibrate_steps_mm(const uint8_t iter); - bool passes_test(bool report); + bool passes_test(const bool report); bool test_axis(void); FORCE_INLINE int get_error_count(void) { return errorCount; } - FORCE_INLINE void set_error_count(int newCount) { errorCount = newCount; } + FORCE_INLINE void set_error_count(const int newCount) { errorCount = newCount; } FORCE_INLINE uint8_t get_address() { return i2cAddress; } - FORCE_INLINE void set_address(uint8_t addr) { i2cAddress = addr; } + FORCE_INLINE void set_address(const uint8_t addr) { i2cAddress = addr; } FORCE_INLINE bool get_active(void) { return active; } - FORCE_INLINE void set_active(bool a) { active = a; } + FORCE_INLINE void set_active(const bool a) { active = a; } - FORCE_INLINE void set_inverted(bool i) { invert = i; } + FORCE_INLINE void set_inverted(const bool i) { invert = i; } FORCE_INLINE AxisEnum get_axis() { return encoderAxis; } FORCE_INLINE bool get_ec_enabled() { return ec; } - FORCE_INLINE void set_ec_enabled(bool enabled) { ec = enabled; } + FORCE_INLINE void set_ec_enabled(const bool enabled) { ec = enabled; } FORCE_INLINE uint8_t get_ec_method() { return ecMethod; } - FORCE_INLINE void set_ec_method(byte method) { ecMethod = method; } + FORCE_INLINE void set_ec_method(const byte method) { ecMethod = method; } FORCE_INLINE float get_ec_threshold() { return ecThreshold; } - FORCE_INLINE void set_ec_threshold(float newThreshold) { ecThreshold = newThreshold; } + FORCE_INLINE void set_ec_threshold(const float newThreshold) { ecThreshold = newThreshold; } FORCE_INLINE int get_encoder_ticks_mm() { - if (type == I2CPE_ENC_TYPE_LINEAR) return encoderTicksPerUnit; - else if (type == I2CPE_ENC_TYPE_ROTARY) - return (int)((encoderTicksPerUnit / stepperTicks) * planner.axis_steps_per_mm[encoderAxis]); - return 0; + switch (type) { + default: return 0; + case I2CPE_ENC_TYPE_LINEAR: + return encoderTicksPerUnit; + case I2CPE_ENC_TYPE_ROTARY: + return (int)((encoderTicksPerUnit / stepperTicks) * planner.axis_steps_per_mm[encoderAxis]); + } } FORCE_INLINE int get_ticks_unit() { return encoderTicksPerUnit; } - FORCE_INLINE void set_ticks_unit(int ticks) { encoderTicksPerUnit = ticks; } + FORCE_INLINE void set_ticks_unit(const int ticks) { encoderTicksPerUnit = ticks; } FORCE_INLINE uint8_t get_type() { return type; } - FORCE_INLINE void set_type(byte newType) { type = newType; } + FORCE_INLINE void set_type(const byte newType) { type = newType; } FORCE_INLINE int get_stepper_ticks() { return stepperTicks; } - FORCE_INLINE void set_stepper_ticks(int ticks) { stepperTicks = ticks; } + FORCE_INLINE void set_stepper_ticks(const int ticks) { stepperTicks = ticks; } FORCE_INLINE float get_axis_offset() { return axisOffset; } - FORCE_INLINE void set_axis_offset(float newOffset) { + FORCE_INLINE void set_axis_offset(const float newOffset) { axisOffset = newOffset; - axisOffsetTicks = (long)(axisOffset * get_encoder_ticks_mm()); + axisOffsetTicks = int32_t(axisOffset * get_encoder_ticks_mm()); } - FORCE_INLINE void set_current_position(float newPositionMm) { + FORCE_INLINE void set_current_position(const float newPositionMm) { set_axis_offset(get_position_mm() - newPositionMm + axisOffset); } }; class I2CPositionEncodersMgr { private: - bool I2CPE_anyaxis; - uint8_t I2CPE_addr; - int8_t I2CPE_idx; + static bool I2CPE_anyaxis; + static uint8_t I2CPE_addr, I2CPE_idx; public: - void init(void); + + static void init(void); // consider only updating one endoder per call / tick if encoders become too time intensive - void update(void) { LOOP_PE(i) encoders[i].update(); } + static void update(void) { LOOP_PE(i) encoders[i].update(); } - void homed(AxisEnum axis) { + static void homed(const AxisEnum axis) { LOOP_PE(i) if (encoders[i].get_axis() == axis) encoders[i].set_homed(); } - void report_position(uint8_t idx, bool units, bool noOffset); + static void report_position(const int8_t idx, const bool units, const bool noOffset); - void report_status(uint8_t idx) { - CHECK_IDX + static void report_status(const int8_t idx) { + CHECK_IDX(); SERIAL_ECHOPAIR("Encoder ",idx); SERIAL_ECHOPGM(": "); encoders[idx].get_raw_count(); encoders[idx].passes_test(true); } - void report_error(uint8_t idx) { - CHECK_IDX + static void report_error(const int8_t idx) { + CHECK_IDX(); encoders[idx].get_axis_error_steps(true); } - void test_axis(uint8_t idx) { - CHECK_IDX + static void test_axis(const int8_t idx) { + CHECK_IDX(); encoders[idx].test_axis(); } - void calibrate_steps_mm(uint8_t idx, int iterations) { - CHECK_IDX + static void calibrate_steps_mm(const int8_t idx, const int iterations) { + CHECK_IDX(); encoders[idx].calibrate_steps_mm(iterations); } - void change_module_address(uint8_t oldaddr, uint8_t newaddr); - void report_module_firmware(uint8_t address); + static void change_module_address(const uint8_t oldaddr, const uint8_t newaddr); + static void report_module_firmware(const uint8_t address); - void report_error_count(uint8_t idx, AxisEnum axis) { - CHECK_IDX + static void report_error_count(const int8_t idx, const AxisEnum axis) { + CHECK_IDX(); SERIAL_ECHOPAIR("Error count on ", axis_codes[axis]); SERIAL_ECHOLNPAIR(" axis is ", encoders[idx].get_error_count()); } - void reset_error_count(uint8_t idx, AxisEnum axis) { - CHECK_IDX + static void reset_error_count(const int8_t idx, const AxisEnum axis) { + CHECK_IDX(); encoders[idx].set_error_count(0); SERIAL_ECHOPAIR("Error count on ", axis_codes[axis]); SERIAL_ECHOLNPGM(" axis has been reset."); } - void enable_ec(uint8_t idx, bool enabled, AxisEnum axis) { - CHECK_IDX + static void enable_ec(const int8_t idx, const bool enabled, const AxisEnum axis) { + CHECK_IDX(); encoders[idx].set_ec_enabled(enabled); SERIAL_ECHOPAIR("Error correction on ", axis_codes[axis]); SERIAL_ECHOPGM(" axis is "); @@ -291,66 +298,62 @@ SERIAL_ECHOLNPGM("abled."); } - void set_ec_threshold(uint8_t idx, float newThreshold, AxisEnum axis) { - CHECK_IDX + static void set_ec_threshold(const int8_t idx, const float newThreshold, const AxisEnum axis) { + CHECK_IDX(); encoders[idx].set_ec_threshold(newThreshold); SERIAL_ECHOPAIR("Error correct threshold for ", axis_codes[axis]); SERIAL_ECHOPAIR_F(" axis set to ", newThreshold); SERIAL_ECHOLNPGM("mm."); } - void get_ec_threshold(uint8_t idx, AxisEnum axis) { - CHECK_IDX - float threshold = encoders[idx].get_ec_threshold(); + static void get_ec_threshold(const int8_t idx, const AxisEnum axis) { + CHECK_IDX(); + const float threshold = encoders[idx].get_ec_threshold(); SERIAL_ECHOPAIR("Error correct threshold for ", axis_codes[axis]); SERIAL_ECHOPAIR_F(" axis is ", threshold); SERIAL_ECHOLNPGM("mm."); } - int8_t idx_from_axis(AxisEnum axis) { + static int8_t idx_from_axis(const AxisEnum axis) { LOOP_PE(i) if (encoders[i].get_axis() == axis) return i; - return -1; } - int8_t idx_from_addr(uint8_t addr) { + static int8_t idx_from_addr(const uint8_t addr) { LOOP_PE(i) if (encoders[i].get_address() == addr) return i; - return -1; } - int8_t parse(); + static int8_t parse(); - void M860(); - void M861(); - void M862(); - void M863(); - void M864(); - void M865(); - void M866(); - void M867(); - void M868(); - void M869(); + static void M860(); + static void M861(); + static void M862(); + static void M863(); + static void M864(); + static void M865(); + static void M866(); + static void M867(); + static void M868(); + static void M869(); - I2CPositionEncoder encoders[I2CPE_ENCODER_CNT]; + static I2CPositionEncoder encoders[I2CPE_ENCODER_CNT]; }; extern I2CPositionEncodersMgr I2CPEM; - FORCE_INLINE void gcode_M860() { I2CPEM.M860(); } - FORCE_INLINE void gcode_M861() { I2CPEM.M861(); } - FORCE_INLINE void gcode_M862() { I2CPEM.M862(); } - FORCE_INLINE void gcode_M863() { I2CPEM.M863(); } - FORCE_INLINE void gcode_M864() { I2CPEM.M864(); } - FORCE_INLINE void gcode_M865() { I2CPEM.M865(); } - FORCE_INLINE void gcode_M866() { I2CPEM.M866(); } - FORCE_INLINE void gcode_M867() { I2CPEM.M867(); } - FORCE_INLINE void gcode_M868() { I2CPEM.M868(); } - FORCE_INLINE void gcode_M869() { I2CPEM.M869(); } + FORCE_INLINE static void gcode_M860() { I2CPEM.M860(); } + FORCE_INLINE static void gcode_M861() { I2CPEM.M861(); } + FORCE_INLINE static void gcode_M862() { I2CPEM.M862(); } + FORCE_INLINE static void gcode_M863() { I2CPEM.M863(); } + FORCE_INLINE static void gcode_M864() { I2CPEM.M864(); } + FORCE_INLINE static void gcode_M865() { I2CPEM.M865(); } + FORCE_INLINE static void gcode_M866() { I2CPEM.M866(); } + FORCE_INLINE static void gcode_M867() { I2CPEM.M867(); } + FORCE_INLINE static void gcode_M868() { I2CPEM.M868(); } + FORCE_INLINE static void gcode_M869() { I2CPEM.M869(); } #endif //I2C_POSITION_ENCODERS #endif //I2CPOSENC_H - - diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 208abc5eb3..b6dd4c2c8c 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -5141,7 +5141,7 @@ void home_all_axes() { gcode_G28(true); } * T Don't calibrate tower angle corrections * * Cn.nn Calibration precision; when omitted calibrates to maximum precision - * + * * Fn Force to run at least n iterations and takes the best result * * Vn Verbose level: @@ -5687,7 +5687,7 @@ inline void gcode_G92() { update_software_endstops((AxisEnum)i); #if ENABLED(I2C_POSITION_ENCODERS) - I2CPEM.encoders[I2CPEM.idx_from_axis((AxisEnum) i)].set_axis_offset(position_shift[i]); + I2CPEM.encoders[I2CPEM.idx_from_axis((AxisEnum)i)].set_axis_offset(position_shift[i]); #endif #endif diff --git a/Marlin/SanityCheck.h b/Marlin/SanityCheck.h index d2bcda6580..73d0fc57b2 100644 --- a/Marlin/SanityCheck.h +++ b/Marlin/SanityCheck.h @@ -276,9 +276,7 @@ #if ENABLED(I2C_POSITION_ENCODERS) #if DISABLED(BABYSTEPPING) #error "I2C_POSITION_ENCODERS requires BABYSTEPPING." - #endif - - #if I2CPE_ENCODER_CNT > 5 || I2CPE_ENCODER_CNT < 1 + #elif !WITHIN(I2CPE_ENCODER_CNT, 1, 5) #error "I2CPE_ENCODER_CNT must be between 1 and 5." #endif #endif diff --git a/Marlin/ubl_G29.cpp b/Marlin/ubl_G29.cpp index 294e3616a3..f77f3746a0 100644 --- a/Marlin/ubl_G29.cpp +++ b/Marlin/ubl_G29.cpp @@ -328,7 +328,8 @@ g29_repetition_cnt = parser.has_value() ? parser.value_int() : 1; if (g29_repetition_cnt >= GRID_MAX_POINTS) { set_all_mesh_points_to_value(NAN); - } else { + } + else { while (g29_repetition_cnt--) { if (cnt > 20) { cnt = 0; idle(); } const mesh_index_pair location = find_closest_mesh_point_of_type(REAL, g29_x_pos, g29_y_pos, USE_NOZZLE_AS_REFERENCE, NULL, false); @@ -1454,7 +1455,7 @@ void unified_bed_leveling::fine_tune_mesh(const float &lx, const float &ly, const bool do_ubl_mesh_map) { if (!parser.seen('R')) // fine_tune_mesh() is special. If no repetition count flag is specified g29_repetition_cnt = 1; // do exactly one mesh location. Otherwise use what the parser decided. - + #if ENABLED(UBL_MESH_EDIT_MOVES_Z) const bool is_offset = parser.seen('H'); const float h_offset = is_offset ? parser.value_linear_units() : Z_CLEARANCE_BETWEEN_PROBES; @@ -1463,7 +1464,7 @@ return; } #endif - + mesh_index_pair location; if (!position_is_reachable_xy(lx, ly)) { From e90cbf5c1665e7188d91e7e7a0f2158de94f1ddf Mon Sep 17 00:00:00 2001 From: Tannoo Date: Wed, 21 Jun 2017 14:26:59 -0600 Subject: [PATCH 139/180] UBL Map Cleanup --- Marlin/ultralcd.cpp | 96 +--------------------------------- Marlin/ultralcd_impl_DOGM.h | 90 +++++++++++++++++++++++++++++++ Marlin/ultralcd_impl_HD44780.h | 66 +++++++++++++++++++++-- 3 files changed, 155 insertions(+), 97 deletions(-) diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index 67015c3226..616f8e17cf 100644 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -108,7 +108,6 @@ uint16_t max_display_update_time = 0; extern bool powersupply_on; #endif - //////////////////////////////////////////// ///////////////// Menu Tree //////////////// //////////////////////////////////////////// @@ -2163,97 +2162,6 @@ void kill_screen(const char* lcd_msg) { enqueue_and_echo_command(ubl_lcd_gcode); } - #if ENABLED(DOGLCD) - - /** - * UBL LCD "radar" map data - */ - #define MAP_UPPER_LEFT_CORNER_X 35 // These probably should be moved to the .h file But for now, - #define MAP_UPPER_LEFT_CORNER_Y 8 // it is easier to play with things having them here - #define MAP_MAX_PIXELS_X 53 - #define MAP_MAX_PIXELS_Y 49 - - void _lcd_ubl_plot_drawing_prep() { - uint8_t i, j, x_offset, y_offset, x_map_pixels, y_map_pixels, - pixels_per_X_mesh_pnt, pixels_per_Y_mesh_pnt, inverted_y; - - /*********************************************************/ - /************ Scale the box pixels appropriately *********/ - /*********************************************************/ - 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); - - 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; - - /*********************************************************/ - /************ Clear the Mesh Map Box**********************/ - /*********************************************************/ - - u8g.setColorIndex(1); // First draw the bigger box in White so we have a border around the mesh map box - u8g.drawBox(x_offset - 2, y_offset - 2, x_map_pixels + 4, y_map_pixels + 4); - - u8g.setColorIndex(0); // Now actually clear the mesh map box - u8g.drawBox(x_offset, y_offset, x_map_pixels, y_map_pixels); - - /*********************************************************/ - /************ Display Mesh Point Locations ***************/ - /*********************************************************/ - - u8g.setColorIndex(1); - for (i = 0; i < GRID_MAX_POINTS_X; i++) { - for (j = 0; j < GRID_MAX_POINTS_Y; j++) { - u8g.drawBox(x_offset + i * pixels_per_X_mesh_pnt + pixels_per_X_mesh_pnt / 2, - y_offset + j * pixels_per_Y_mesh_pnt + pixels_per_Y_mesh_pnt / 2, 1, 1); - } - } - - /*********************************************************/ - /************ Fill in the Specified Mesh Point ***********/ - /*********************************************************/ - - 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. - u8g.drawBox(x_offset + x_plot * pixels_per_X_mesh_pnt, y_offset + inverted_y * pixels_per_Y_mesh_pnt, - pixels_per_X_mesh_pnt, pixels_per_Y_mesh_pnt); - - /*********************************************************/ - /************** Put Relevent Text on Display *************/ - /*********************************************************/ - - // Show X and Y positions at top of screen - u8g.setColorIndex(1); - u8g.setPrintPos(5, 7); - lcd_print("X:"); - lcd_print(ftostr32(LOGICAL_X_POSITION(pgm_read_float(&ubl._mesh_index_to_xpos[x_plot])))); - u8g.setPrintPos(74, 7); - lcd_print("Y:"); - lcd_print(ftostr32(LOGICAL_Y_POSITION(pgm_read_float(&ubl._mesh_index_to_ypos[y_plot])))); - - // Print plot position - u8g.setPrintPos(5, 64); - lcd_print('('); - u8g.print(x_plot); - lcd_print(','); - u8g.print(y_plot); - lcd_print(')'); - - // Show the location value - u8g.setPrintPos(74, 64); - lcd_print("Z:"); - if (!isnan(ubl.z_values[x_plot][y_plot])) { - lcd_print(ftostr43sign(ubl.z_values[x_plot][y_plot])); - } - else { - lcd_print(" -----"); - } - } - - #endif // DOGLCD - /** * UBL LCD Map Movement */ @@ -2318,9 +2226,9 @@ void kill_screen(const char* lcd_msg) { if (lcdDrawUpdate) { #if ENABLED(DOGLCD) - _lcd_ubl_plot_drawing_prep(); + _lcd_ubl_plot_DOGLCD(x_plot, y_plot); #else - _lcd_ubl_output_char_lcd(); + _lcd_ubl_plot_HD44780(x_plot, y_plot); #endif ubl_map_move_to_xy(); // Move to current location diff --git a/Marlin/ultralcd_impl_DOGM.h b/Marlin/ultralcd_impl_DOGM.h index 406f1c3176..3a1ab1a701 100644 --- a/Marlin/ultralcd_impl_DOGM.h +++ b/Marlin/ultralcd_impl_DOGM.h @@ -939,6 +939,96 @@ static void lcd_implementation_status_screen() { #endif // SDSUPPORT + #if ENABLED(AUTO_BED_LEVELING_UBL) + + /** + * UBL LCD "radar" map data + */ + #define MAP_UPPER_LEFT_CORNER_X 35 // These probably should be moved to the .h file But for now, + #define MAP_UPPER_LEFT_CORNER_Y 8 // it is easier to play with things having them here + #define MAP_MAX_PIXELS_X 53 + #define MAP_MAX_PIXELS_Y 49 + + void _lcd_ubl_plot_DOGLCD(uint8_t x_plot, uint8_t y_plot) { + uint8_t i, j, x_offset, y_offset, x_map_pixels, y_map_pixels; + uint8_t pixels_per_X_mesh_pnt, pixels_per_Y_mesh_pnt, inverted_y; + + /*********************************************************/ + /************ Scale the box pixels appropriately *********/ + /*********************************************************/ + 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; + + 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; + + /*********************************************************/ + /************ Clear the Mesh Map Box**********************/ + /*********************************************************/ + + u8g.setColorIndex(1); // First draw the bigger box in White so we have a border around the mesh map box + u8g.drawBox(x_offset-2, y_offset-2, x_map_pixels+4, y_map_pixels+4); + + u8g.setColorIndex(0); // Now actually clear the mesh map box + u8g.drawBox(x_offset, y_offset, x_map_pixels, y_map_pixels); + + /*********************************************************/ + /************ Display Mesh Point Locations ***************/ + /*********************************************************/ + + u8g.setColorIndex(1); + for (i = 0; i < GRID_MAX_POINTS_X; i++) { + for (j = 0; j < GRID_MAX_POINTS_Y; j++) { + u8g.drawBox(x_offset+i*pixels_per_X_mesh_pnt+pixels_per_X_mesh_pnt/2, + y_offset+j*pixels_per_Y_mesh_pnt+pixels_per_Y_mesh_pnt/2, 1, 1); + } + } + + /*********************************************************/ + /************ Fill in the Specified Mesh Point ***********/ + /*********************************************************/ + + 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. + u8g.drawBox(x_offset+x_plot*pixels_per_X_mesh_pnt, y_offset+inverted_y*pixels_per_Y_mesh_pnt, + pixels_per_X_mesh_pnt, pixels_per_Y_mesh_pnt); + + /*********************************************************/ + /************** Put Relevent Text on Display *************/ + /*********************************************************/ + + // Show X and Y positions at top of screen + u8g.setColorIndex(1); + u8g.setPrintPos(5, 7); + lcd_print("X:"); + lcd_print(ftostr32(LOGICAL_X_POSITION(pgm_read_float(&ubl._mesh_index_to_xpos[x_plot])))); + u8g.setPrintPos(74, 7); + lcd_print("Y:"); + lcd_print(ftostr32(LOGICAL_Y_POSITION(pgm_read_float(&ubl._mesh_index_to_ypos[y_plot])))); + + // Print plot position + u8g.setPrintPos(5, 64); + lcd_print("("); + u8g.print(x_plot); + lcd_print(","); + u8g.print(y_plot); + lcd_print(")"); + + // Show the location value + u8g.setPrintPos(74, 64); + lcd_print("Z:"); + if (!isnan(ubl.z_values[x_plot][y_plot])) { + lcd_print(ftostr43sign(ubl.z_values[x_plot][y_plot])); + } + else { + lcd_print(" -----"); + } + } + #endif // AUTO_BED_LEVELING_UBL + #endif // ULTIPANEL #endif // __ULTRALCD_IMPL_DOGM_H diff --git a/Marlin/ultralcd_impl_HD44780.h b/Marlin/ultralcd_impl_HD44780.h index 71496ae75c..afebbfd4d0 100644 --- a/Marlin/ultralcd_impl_HD44780.h +++ b/Marlin/ultralcd_impl_HD44780.h @@ -31,6 +31,10 @@ #include "utility.h" #include "duration_t.h" +#if ENABLED(AUTO_BED_LEVELING_UBL) + #include "ubl.h" +#endif + extern volatile uint8_t buttons; //an extended version of the last checked buttons in a bit array. //////////////////////////////////// @@ -1080,9 +1084,65 @@ static void lcd_implementation_status_screen() { #endif // LCD_HAS_STATUS_INDICATORS #ifdef AUTO_BED_LEVELING_UBL - void lcd_return_to_status(); // These are just place holders for the 20x4 LCD work that - void _lcd_ubl_output_char_lcd() { // is coming up very soon. Soon this will morph into the - lcd_return_to_status(); // real code. + + // These are just basic data for the 20x4 LCD work that + // is coming up very soon. + // Soon this will morph into a map code. + + void _lcd_ubl_plot_HD44780(uint8_t x_plot, uint8_t y_plot) { + + uint8_t lcd_w_pos = 8, lcd_h_pos = 1; + + #if LCD_WIDTH < 20 + lcd_w_pos = 8; + #else + lcd_w_pos = 12; + #endif + #if LCD_HEIGHT > 3 + lcd_h_pos = 3; + #elif LCD_HEIGHT > 2 + lcd_h_pos = 2; + #else + lcd_h_pos = 1; + #endif + + // Show X and Y positions at top of screen + lcd.setCursor(0, 0); + #if LCD_WIDTH < 20 + lcd.print("X"); + #else + lcd.print("X:"); + #endif + lcd.print(ftostr32(LOGICAL_X_POSITION(pgm_read_float(&ubl._mesh_index_to_xpos[x_plot])))); + lcd.setCursor(lcd_w_pos, 0); + #if LCD_WIDTH < 20 + lcd.print("Y"); + #else + lcd.print("Y:"); + #endif + lcd.print(ftostr32(LOGICAL_Y_POSITION(pgm_read_float(&ubl._mesh_index_to_ypos[y_plot])))); + + // Print plot position + lcd.setCursor(0, lcd_h_pos); + lcd.print("("); + lcd.print(x_plot); + lcd.print(","); + lcd.print(y_plot); + lcd.print(")"); + + // Show the location value + lcd.setCursor(lcd_w_pos, lcd_h_pos); + #if LCD_WIDTH < 20 + lcd.print("Z"); + #else + lcd.print("Z:"); + #endif + if (!isnan(ubl.z_values[x_plot][y_plot])) { + lcd.print(ftostr43sign(ubl.z_values[x_plot][y_plot])); + } + else { + lcd.print(" -----"); + } } #endif // AUTO_BED_LEVELING_UBL From 80abc872f31e728191f94b64adfe09b68e83c237 Mon Sep 17 00:00:00 2001 From: Tannoo Date: Thu, 22 Jun 2017 09:42:50 -0600 Subject: [PATCH 140/180] Updated to better support the coming "radar" --- Marlin/ultralcd_impl_HD44780.h | 220 ++++++++++++++++++++++++++------- 1 file changed, 174 insertions(+), 46 deletions(-) diff --git a/Marlin/ultralcd_impl_HD44780.h b/Marlin/ultralcd_impl_HD44780.h index afebbfd4d0..75426f857c 100644 --- a/Marlin/ultralcd_impl_HD44780.h +++ b/Marlin/ultralcd_impl_HD44780.h @@ -1085,64 +1085,192 @@ static void lcd_implementation_status_screen() { #ifdef 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. + /* + * 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: + + 16x2 |X000.00 Y000.00| + |(00,00) Z00.000| + + 20x2 | X:000.00 Y:000.00 | + | (00,00) Z:00.000 | + + 16x4 |+-------+(00,00)| + || |X000.00| + || |Y000.00| + |+-------+Z00.000| + + 20x4 | +-------+ (00,00) | + | | | X:000.00| + | | | Y:000.00| + | +-------+ Z:00.000| + */ void _lcd_ubl_plot_HD44780(uint8_t x_plot, uint8_t y_plot) { - uint8_t lcd_w_pos = 8, lcd_h_pos = 1; + uint8_t lcd_w_pos; #if LCD_WIDTH < 20 lcd_w_pos = 8; #else lcd_w_pos = 12; #endif - #if LCD_HEIGHT > 3 - lcd_h_pos = 3; - #elif LCD_HEIGHT > 2 - lcd_h_pos = 2; - #else - lcd_h_pos = 1; - #endif - // Show X and Y positions at top of screen - lcd.setCursor(0, 0); - #if LCD_WIDTH < 20 - lcd.print("X"); - #else - lcd.print("X:"); - #endif - lcd.print(ftostr32(LOGICAL_X_POSITION(pgm_read_float(&ubl._mesh_index_to_xpos[x_plot])))); - lcd.setCursor(lcd_w_pos, 0); - #if LCD_WIDTH < 20 - lcd.print("Y"); - #else - lcd.print("Y:"); - #endif - lcd.print(ftostr32(LOGICAL_Y_POSITION(pgm_read_float(&ubl._mesh_index_to_ypos[y_plot])))); + #if LCD_HEIGHT < 3 - // Print plot position - lcd.setCursor(0, lcd_h_pos); - lcd.print("("); - lcd.print(x_plot); - lcd.print(","); - lcd.print(y_plot); - lcd.print(")"); + /* + *** 16x2 or 20x2 display ** + * + * Show X and Y positions + */ + #if LCD_WIDTH < 20 + lcd.setCursor(0, 0); + lcd.print("X"); + #else + lcd.setCursor(1, 0); + lcd.print("X:"); + #endif + lcd.print(ftostr32(LOGICAL_X_POSITION(pgm_read_float(&ubl._mesh_index_to_xpos[x_plot])))); - // Show the location value - lcd.setCursor(lcd_w_pos, lcd_h_pos); - #if LCD_WIDTH < 20 - lcd.print("Z"); - #else - lcd.print("Z:"); - #endif - if (!isnan(ubl.z_values[x_plot][y_plot])) { - lcd.print(ftostr43sign(ubl.z_values[x_plot][y_plot])); - } - else { - lcd.print(" -----"); - } + lcd.setCursor(lcd_w_pos, 0); + #if LCD_WIDTH < 20 + lcd.print("Y"); + #else + lcd.print("Y:"); + #endif + lcd.print(ftostr32(LOGICAL_Y_POSITION(pgm_read_float(&ubl._mesh_index_to_ypos[y_plot])))); + + /* + * Print plot position + */ + #if LCD_WIDTH < 20 + lcd.setCursor(0, 1); + #else + lcd.setCursor(1, 1); + #endif + lcd.print("("); + lcd.print(x_plot); + lcd.print(","); + lcd.print(y_plot); + lcd.print(")"); + + /* + * Print Z values + */ + lcd.setCursor(lcd_w_pos, 1); + #if LCD_WIDTH < 20 + lcd.print("Z"); + #else + lcd.print("Z:"); + #endif + if (!isnan(ubl.z_values[x_plot][y_plot])) { + lcd.print(ftostr43sign(ubl.z_values[x_plot][y_plot])); + } + else { + lcd.print(" -----"); + } + + #elif LCD_HEIGHT > 3 + + //#include "_ubl_lcd_map_characters.h" + + const static PROGMEM byte _lcd_box_top[8] = { + B11111, + B00000, + B00000, + B00000, + B00000, + B00000, + B00000, + B00000 + }; + + const static PROGMEM byte _lcd_box_bottom[8] = { + B00000, + B00000, + B00000, + B00000, + B00000, + B00000, + B00000, + B11111 + }; + + /* + * Draw the Mesh Map Box + */ + // First create the box custom characters + createChar_P(1, _lcd_box_top); + createChar_P(2, _lcd_box_bottom); + + // Draw the mesh map box + uint8_t m; + + #if LCD_WIDTH < 20 + + for(m = 1; m <= 5; m++) { lcd.setCursor(m, 0); lcd.write(1); } // Top + for(m = 1; m <= 5; m++) { lcd.setCursor(m, 3); lcd.write(2); } // Bottom + for(m = 0; m <= 3; m++) { lcd.setCursor(2, m); lcd.write('|'); } // Left + for(m = 0; m <= 3; m++) { lcd.setCursor(8, m); lcd.write('|'); } // Right + + #else + + for(m = 3; m <= 7; m++) { lcd.setCursor(m, 0); lcd.write(1); } // Top + for(m = 3; m <= 7; m++) { lcd.setCursor(m, 3); lcd.write(2); } // Bottom + for(m = 0; m <= 3; m++) { lcd.setCursor(2, m); lcd.write('|'); } // Left + for(m = 0; m <= 3; m++) { lcd.setCursor(8, m); lcd.write('|'); } // Right + + #endif + /* + * Print plot position + */ + lcd.setCursor(lcd_w_pos, 0); + lcd.print("("); + lcd.print(x_plot); + lcd.print(","); + lcd.print(y_plot); + lcd.print(")"); + + /* + * Show all values at right of screen + */ + lcd.setCursor(lcd_w_pos, 1); + #if LCD_WIDTH < 20 + lcd.print("X"); + #else + lcd.print("X:"); + #endif + lcd.print(ftostr32(LOGICAL_X_POSITION(pgm_read_float(&ubl._mesh_index_to_xpos[x_plot])))); + lcd.setCursor(lcd_w_pos, 2); + #if LCD_WIDTH < 20 + lcd.print("Y"); + #else + lcd.print("Y:"); + #endif + lcd.print(ftostr32(LOGICAL_Y_POSITION(pgm_read_float(&ubl._mesh_index_to_ypos[y_plot])))); + + /* + * Show the location value + */ + lcd.setCursor(lcd_w_pos, 3); + #if LCD_WIDTH < 20 + lcd.print("Z"); + #else + lcd.print("Z:"); + #endif + if (!isnan(ubl.z_values[x_plot][y_plot])) { + lcd.print(ftostr43sign(ubl.z_values[x_plot][y_plot])); + } + else { + lcd.print(" -----"); + } + + #endif // LCD_HEIGHT > 3 } #endif // AUTO_BED_LEVELING_UBL From 98d362c2da07f2179d5f7af801f513b6f5a5f8e8 Mon Sep 17 00:00:00 2001 From: Ben Lye Date: Tue, 27 Jun 2017 20:49:21 +0100 Subject: [PATCH 141/180] Adding M118 command to send text to serial Allows the user to send text to the serial console in order to communicate with a host - sending debuging information or action commands, for example. Text must begin with '//' and this is added if it is not already present at the beginning of the string. --- Marlin/Marlin_main.cpp | 12 ++++++++++++ Marlin/gcode.cpp | 2 +- 2 files changed, 13 insertions(+), 1 deletion(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index b6dd4c2c8c..d695b273ef 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -130,6 +130,7 @@ * M114 - Report current position. * M115 - Report capabilities. (Extended capabilities requires EXTENDED_CAPABILITIES_REPORT) * M117 - Display a message on the controller screen. (Requires an LCD) + * M118 - Display a message in the host console. * M119 - Report endstops status. * M120 - Enable endstops detection. * M121 - Disable endstops detection. @@ -7991,6 +7992,14 @@ inline void gcode_M115() { */ inline void gcode_M117() { lcd_setstatus(parser.string_arg); } +/** + * M118: Display a message in the host console. + */ +inline void gcode_M118() { + SERIAL_ECHO_START(); + SERIAL_ECHOLN(parser.string_arg); +} + /** * M119: Output endstop states to serial output */ @@ -10758,6 +10767,9 @@ void process_next_command() { case 117: // M117: Set LCD message text, if possible gcode_M117(); break; + case 118: // M118: Display a message in the host console + gcode_M118(); + break; case 119: // M119: Report endstop states gcode_M119(); break; diff --git a/Marlin/gcode.cpp b/Marlin/gcode.cpp index a2f5dcfb10..85b3a194ca 100644 --- a/Marlin/gcode.cpp +++ b/Marlin/gcode.cpp @@ -150,7 +150,7 @@ void GCodeParser::parse(char *p) { #endif // Only use string_arg for these M codes - if (letter == 'M') switch (codenum) { case 23: case 28: case 30: case 117: case 928: string_arg = p; return; default: break; } + if (letter == 'M') switch (codenum) { case 23: case 28: case 30: case 117: case 118: case 928: string_arg = p; return; default: break; } #if ENABLED(DEBUG_GCODE_PARSER) const bool debug = codenum == 800; From b492e0878d4fb9a92721283bdacaa631e03fac61 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 27 Jun 2017 22:19:32 -0500 Subject: [PATCH 142/180] Changes to reduce and simplify --- Marlin/ultralcd.cpp | 22 ++- Marlin/ultralcd_impl_DOGM.h | 131 ++++++++-------- Marlin/ultralcd_impl_HD44780.h | 268 ++++++++++++++------------------- 3 files changed, 188 insertions(+), 233 deletions(-) diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index 616f8e17cf..2b45f81330 100644 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -789,7 +789,7 @@ void kill_screen(const char* lcd_msg) { encoderPosition = 0; lcd_implementation_drawmenu_static(0, PSTR(MSG_PROGRESS_BAR_TEST), true, true); lcd.setCursor((LCD_WIDTH) / 2 - 2, LCD_HEIGHT - 2); - lcd.print(itostr3(bar_percent)); lcd.print('%'); + lcd.print(itostr3(bar_percent)); lcd.write('%'); lcd.setCursor(0, LCD_HEIGHT - 1); lcd_draw_progress_bar(bar_percent); } @@ -2144,8 +2144,12 @@ void kill_screen(const char* lcd_msg) { void _lcd_ubl_map_homing() { if (lcdDrawUpdate) lcd_implementation_drawedit(PSTR(MSG_LEVEL_BED_HOMING), NULL); lcdDrawUpdate = LCDVIEW_CALL_NO_REDRAW; - if (axis_homed[X_AXIS] && axis_homed[Y_AXIS] && axis_homed[Z_AXIS]) + if (axis_homed[X_AXIS] && axis_homed[Y_AXIS] && axis_homed[Z_AXIS]) { + #if DISABLED(DOGLCD) + lcd_set_ubl_map_plot_chars(); + #endif lcd_goto_screen(_lcd_ubl_output_map_lcd); + } } /** @@ -2217,19 +2221,13 @@ void kill_screen(const char* lcd_msg) { #if IS_KINEMATIC n_edit_pts = 9; //TODO: Delta accessible edit points #else - if (x_plot < 1 || x_plot >= GRID_MAX_POINTS_X - 1) - if (y_plot < 1 || y_plot >= GRID_MAX_POINTS_Y - 1) n_edit_pts = 4; // Corners - else n_edit_pts = 6; - else if (y_plot < 1 || y_plot >= GRID_MAX_POINTS_Y - 1) n_edit_pts = 6; // Edges - else n_edit_pts = 9; // Field + const bool xc = WITHIN(x_plot, 1, GRID_MAX_POINTS_X - 2), + yc = WITHIN(y_plot, 1, GRID_MAX_POINTS_Y - 2); + n_edit_pts = yc ? (xc ? 9 : 6) : (xc ? 6 : 4); // Corners #endif if (lcdDrawUpdate) { - #if ENABLED(DOGLCD) - _lcd_ubl_plot_DOGLCD(x_plot, y_plot); - #else - _lcd_ubl_plot_HD44780(x_plot, y_plot); - #endif + lcd_implementation_ubl_plot(x_plot, y_plot); ubl_map_move_to_xy(); // Move to current location diff --git a/Marlin/ultralcd_impl_DOGM.h b/Marlin/ultralcd_impl_DOGM.h index 3a1ab1a701..c9cbf452e5 100644 --- a/Marlin/ultralcd_impl_DOGM.h +++ b/Marlin/ultralcd_impl_DOGM.h @@ -688,7 +688,7 @@ static void lcd_implementation_status_screen() { #define STATUS_BASELINE (55 + INFO_FONT_HEIGHT) - if (PAGE_CONTAINS(STATUS_BASELINE + 1 - INFO_FONT_HEIGHT, STATUS_BASELINE)) { + if (PAGE_CONTAINS(STATUS_BASELINE - (INFO_FONT_HEIGHT - 1), STATUS_BASELINE)) { u8g.setPrintPos(0, STATUS_BASELINE); #if ENABLED(FILAMENT_LCD_DISPLAY) && ENABLED(SDSUPPORT) @@ -944,89 +944,88 @@ static void lcd_implementation_status_screen() { /** * UBL LCD "radar" map data */ - #define MAP_UPPER_LEFT_CORNER_X 35 // These probably should be moved to the .h file But for now, - #define MAP_UPPER_LEFT_CORNER_Y 8 // it is easier to play with things having them here - #define MAP_MAX_PIXELS_X 53 - #define MAP_MAX_PIXELS_Y 49 + #define MAP_UPPER_LEFT_CORNER_X 35 // These probably should be moved to the .h file But for now, + #define MAP_UPPER_LEFT_CORNER_Y 8 // it is easier to play with things having them here + #define MAP_MAX_PIXELS_X 53 + #define MAP_MAX_PIXELS_Y 49 - void _lcd_ubl_plot_DOGLCD(uint8_t x_plot, uint8_t y_plot) { - uint8_t i, j, x_offset, y_offset, x_map_pixels, y_map_pixels; - uint8_t pixels_per_X_mesh_pnt, pixels_per_Y_mesh_pnt, inverted_y; + void lcd_implementation_ubl_plot(const uint8_t x_plot, const uint8_t y_plot) { + // Scale the box pixels appropriately + 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), - /*********************************************************/ - /************ Scale the box pixels appropriately *********/ - /*********************************************************/ - 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; - 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; + // Clear the Mesh Map - /*********************************************************/ - /************ Clear the Mesh Map Box**********************/ - /*********************************************************/ - - u8g.setColorIndex(1); // First draw the bigger box in White so we have a border around the mesh map box - u8g.drawBox(x_offset-2, y_offset-2, x_map_pixels+4, y_map_pixels+4); - - u8g.setColorIndex(0); // Now actually clear the mesh map box - u8g.drawBox(x_offset, y_offset, x_map_pixels, y_map_pixels); - - /*********************************************************/ - /************ Display Mesh Point Locations ***************/ - /*********************************************************/ - - u8g.setColorIndex(1); - for (i = 0; i < GRID_MAX_POINTS_X; i++) { - for (j = 0; j < GRID_MAX_POINTS_Y; j++) { - u8g.drawBox(x_offset+i*pixels_per_X_mesh_pnt+pixels_per_X_mesh_pnt/2, - y_offset+j*pixels_per_Y_mesh_pnt+pixels_per_Y_mesh_pnt/2, 1, 1); + if (PAGE_CONTAINS(y_offset - 2, y_offset + y_map_pixels + 4)) { + u8g.setColorIndex(1); // First draw the bigger box in White so we have a border around the mesh map box + u8g.drawBox(x_offset - 2, y_offset - 2, x_map_pixels + 4, y_map_pixels + 4); + if (PAGE_CONTAINS(y_offset, y_offset + y_map_pixels)) { + u8g.setColorIndex(0); // Now actually clear the mesh map box + u8g.drawBox(x_offset, y_offset, x_map_pixels, y_map_pixels); } } - /*********************************************************/ - /************ Fill in the Specified Mesh Point ***********/ - /*********************************************************/ + // Display Mesh Point Locations - 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. - u8g.drawBox(x_offset+x_plot*pixels_per_X_mesh_pnt, y_offset+inverted_y*pixels_per_Y_mesh_pnt, - pixels_per_X_mesh_pnt, pixels_per_Y_mesh_pnt); + 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) + 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); - /*********************************************************/ - /************** Put Relevent Text on Display *************/ - /*********************************************************/ + // Fill in the Specified Mesh Point + + 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)) + u8g.drawBox( + 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 // Show X and Y positions at top of screen u8g.setColorIndex(1); - u8g.setPrintPos(5, 7); - lcd_print("X:"); - lcd_print(ftostr32(LOGICAL_X_POSITION(pgm_read_float(&ubl._mesh_index_to_xpos[x_plot])))); - u8g.setPrintPos(74, 7); - lcd_print("Y:"); - lcd_print(ftostr32(LOGICAL_Y_POSITION(pgm_read_float(&ubl._mesh_index_to_ypos[y_plot])))); + if (PAGE_UNDER(7)) { + u8g.setPrintPos(5, 7); + lcd_print("X:"); + lcd_print(ftostr32(LOGICAL_X_POSITION(pgm_read_float(&ubl._mesh_index_to_xpos[x_plot])))); + u8g.setPrintPos(74, 7); + lcd_print("Y:"); + lcd_print(ftostr32(LOGICAL_Y_POSITION(pgm_read_float(&ubl._mesh_index_to_ypos[y_plot])))); + } // Print plot position - u8g.setPrintPos(5, 64); - lcd_print("("); - u8g.print(x_plot); - lcd_print(","); - u8g.print(y_plot); - lcd_print(")"); + if (PAGE_CONTAINS(64 - (INFO_FONT_HEIGHT - 1), 64)) { + u8g.setPrintPos(5, 64); + lcd_print('('); + u8g.print(x_plot); + lcd_print(','); + u8g.print(y_plot); + lcd_print(')'); - // Show the location value - u8g.setPrintPos(74, 64); - lcd_print("Z:"); - if (!isnan(ubl.z_values[x_plot][y_plot])) { - lcd_print(ftostr43sign(ubl.z_values[x_plot][y_plot])); - } - else { - lcd_print(" -----"); + // Show the location value + u8g.setPrintPos(74, 64); + lcd_print("Z:"); + if (!isnan(ubl.z_values[x_plot][y_plot])) + lcd_print(ftostr43sign(ubl.z_values[x_plot][y_plot])); + else + lcd_printPGM(PSTR(" -----")); } + } + #endif // AUTO_BED_LEVELING_UBL #endif // ULTIPANEL diff --git a/Marlin/ultralcd_impl_HD44780.h b/Marlin/ultralcd_impl_HD44780.h index 75426f857c..2824ed0882 100644 --- a/Marlin/ultralcd_impl_HD44780.h +++ b/Marlin/ultralcd_impl_HD44780.h @@ -421,7 +421,7 @@ void lcd_printPGM_utf(const char *str, uint8_t n=LCD_WIDTH) { void lcd_erase_line(const int16_t line) { lcd.setCursor(0, line); for (uint8_t i = LCD_WIDTH + 1; --i;) - lcd.print(' '); + lcd.write(' '); } // Scroll the PSTR 'text' in a 'len' wide field for 'time' milliseconds at position col,line @@ -438,9 +438,9 @@ void lcd_printPGM_utf(const char *str, uint8_t n=LCD_WIDTH) { static void logo_lines(const char* const extra) { int16_t indent = (LCD_WIDTH - 8 - lcd_strlen_P(extra)) / 2; - lcd.setCursor(indent, 0); lcd.print('\x00'); lcd_printPGM(PSTR( "------" )); lcd.print('\x01'); + lcd.setCursor(indent, 0); lcd.print('\x00'); lcd_printPGM(PSTR( "------" )); lcd.write('\x01'); lcd.setCursor(indent, 1); lcd_printPGM(PSTR("|Marlin|")); lcd_printPGM(extra); - lcd.setCursor(indent, 2); lcd.print('\x02'); lcd_printPGM(PSTR( "------" )); lcd.print('\x03'); + lcd.setCursor(indent, 2); lcd.write('\x02'); lcd_printPGM(PSTR( "------" )); lcd.write('\x03'); } void bootscreen() { @@ -581,11 +581,11 @@ FORCE_INLINE void _draw_axis_label(const AxisEnum axis, const char* const pstr, lcd_printPGM(pstr); else { if (!axis_homed[axis]) - lcd.print('?'); + lcd.write('?'); else { #if DISABLED(DISABLE_REDUCED_ACCURACY_WARNING) if (!axis_known_position[axis]) - lcd.print(' '); + lcd.write(' '); else #endif lcd_printPGM(pstr); @@ -602,7 +602,7 @@ FORCE_INLINE void _draw_heater_status(const int8_t heater, const char prefix, co if (prefix >= 0) lcd.print(prefix); lcd.print(itostr3(t1 + 0.5)); - lcd.print('/'); + lcd.write('/'); #if HEATER_IDLE_HANDLER const bool is_idle = (!isBed ? thermalManager.is_heater_idle(heater) : @@ -614,9 +614,9 @@ FORCE_INLINE void _draw_heater_status(const int8_t heater, const char prefix, co ); if (!blink && is_idle) { - lcd.print(' '); - if (t2 >= 10) lcd.print(' '); - if (t2 >= 100) lcd.print(' '); + lcd.write(' '); + if (t2 >= 10) lcd.write(' '); + if (t2 >= 100) lcd.write(' '); } else #endif @@ -624,8 +624,8 @@ FORCE_INLINE void _draw_heater_status(const int8_t heater, const char prefix, co if (prefix >= 0) { lcd.print((char)LCD_DEGREE_CHAR); - lcd.print(' '); - if (t2 < 10) lcd.print(' '); + lcd.write(' '); + if (t2 < 10) lcd.write(' '); } } @@ -742,7 +742,7 @@ static void lcd_implementation_status_screen() { lcd.print(itostr3(card.percentDone())); else lcd_printPGM(PSTR("---")); - lcd.print('%'); + lcd.write('%'); #endif // SDSUPPORT #else // LCD_WIDTH >= 20 @@ -764,7 +764,7 @@ static void lcd_implementation_status_screen() { _draw_axis_label(X_AXIS, PSTR(MSG_X), blink); lcd.print(ftostr4sign(current_position[X_AXIS])); - lcd.print(' '); + lcd.write(' '); _draw_axis_label(Y_AXIS, PSTR(MSG_Y), blink); lcd.print(ftostr4sign(current_position[Y_AXIS])); @@ -788,7 +788,7 @@ static void lcd_implementation_status_screen() { lcd.setCursor(0, 2); lcd.print((char)LCD_FEEDRATE_CHAR); lcd.print(itostr3(feedrate_percentage)); - lcd.print('%'); + lcd.write('%'); #if LCD_WIDTH >= 20 && ENABLED(SDSUPPORT) @@ -798,7 +798,7 @@ static void lcd_implementation_status_screen() { lcd.print(itostr3(card.percentDone())); else lcd_printPGM(PSTR("---")); - lcd.print('%'); + lcd.write('%'); #endif // LCD_WIDTH >= 20 && SDSUPPORT @@ -837,7 +837,7 @@ static void lcd_implementation_status_screen() { lcd.print(ftostr12ns(filament_width_meas)); lcd_printPGM(PSTR(" V")); lcd.print(itostr3(100.0 * volumetric_multiplier[FILAMENT_SENSOR_EXTRUDER_NUM])); - lcd.print('%'); + lcd.write('%'); return; } @@ -858,10 +858,10 @@ static void lcd_implementation_status_screen() { lcd_print_utf(stat); // The string leaves space chars -= slen - status_scroll_pos; // Amount of space left } - lcd.print('.'); // Always at 1+ spaces left, draw a dot + lcd.write('.'); // Always at 1+ spaces left, draw a dot if (--chars) { if (status_scroll_pos < slen + 1) // Draw a second dot if there's space - --chars, lcd.print('.'); + --chars, lcd.write('.'); if (chars) lcd_print_utf(lcd_status_message, chars); // Print a second copy of the message } } @@ -897,7 +897,7 @@ static void lcd_implementation_status_screen() { lcd.setCursor(0, row); if (center && !valstr) { int8_t pad = (LCD_WIDTH - lcd_strlen_P(pstr)) / 2; - while (--pad >= 0) { lcd.print(' '); n--; } + while (--pad >= 0) { lcd.write(' '); n--; } } while (n > 0 && (c = pgm_read_byte(pstr))) { n -= charset_mapper(c); @@ -907,7 +907,7 @@ static void lcd_implementation_status_screen() { n -= charset_mapper(c); valstr++; } - while (n-- > 0) lcd.print(' '); + while (n-- > 0) lcd.write(' '); } static void lcd_implementation_drawmenu_generic(const bool sel, const uint8_t row, const char* pstr, const char pre_char, const char post_char) { @@ -919,7 +919,7 @@ static void lcd_implementation_status_screen() { n -= charset_mapper(c); pstr++; } - while (n--) lcd.print(' '); + while (n--) lcd.write(' '); lcd.print(post_char); } @@ -932,8 +932,8 @@ static void lcd_implementation_status_screen() { n -= charset_mapper(c); pstr++; } - lcd.print(':'); - while (n--) lcd.print(' '); + lcd.write(':'); + while (n--) lcd.write(' '); lcd_print(data); } static void lcd_implementation_drawmenu_setting_edit_generic_P(const bool sel, const uint8_t row, const char* pstr, const char pre_char, const char* const data) { @@ -945,8 +945,8 @@ static void lcd_implementation_status_screen() { n -= charset_mapper(c); pstr++; } - lcd.print(':'); - while (n--) lcd.print(' '); + lcd.write(':'); + while (n--) lcd.write(' '); lcd_printPGM(data); } @@ -981,10 +981,10 @@ static void lcd_implementation_status_screen() { lcd.setCursor(1, 1); lcd_printPGM(pstr); if (value != NULL) { - lcd.print(':'); + lcd.write(':'); const uint8_t valrow = (lcd_strlen_P(pstr) + 1 + lcd_strlen(value) + 1) > (LCD_WIDTH - 2) ? 2 : 1; // Value on the next row if it won't fit lcd.setCursor((LCD_WIDTH - 1) - (lcd_strlen(value) + 1), valrow); // Right-justified, padded by spaces - lcd.print(' '); // overwrite char if value gets shorter + lcd.write(' '); // overwrite char if value gets shorter lcd_print(value); } } @@ -1005,7 +1005,7 @@ static void lcd_implementation_status_screen() { n -= charset_mapper(c); filename++; } - while (n--) lcd.print(' '); + while (n--) lcd.write(' '); lcd.print(post_char); } @@ -1083,7 +1083,7 @@ static void lcd_implementation_status_screen() { #endif // LCD_HAS_STATUS_INDICATORS -#ifdef AUTO_BED_LEVELING_UBL +#if ENABLED(AUTO_BED_LEVELING_UBL) /* * These are just basic data for the 20x4 LCD work that @@ -1111,75 +1111,10 @@ static void lcd_implementation_status_screen() { | +-------+ Z:00.000| */ - void _lcd_ubl_plot_HD44780(uint8_t x_plot, uint8_t y_plot) { - - uint8_t lcd_w_pos; - - #if LCD_WIDTH < 20 - lcd_w_pos = 8; - #else - lcd_w_pos = 12; - #endif - - #if LCD_HEIGHT < 3 - - /* - *** 16x2 or 20x2 display ** - * - * Show X and Y positions - */ - #if LCD_WIDTH < 20 - lcd.setCursor(0, 0); - lcd.print("X"); - #else - lcd.setCursor(1, 0); - lcd.print("X:"); - #endif - lcd.print(ftostr32(LOGICAL_X_POSITION(pgm_read_float(&ubl._mesh_index_to_xpos[x_plot])))); - - lcd.setCursor(lcd_w_pos, 0); - #if LCD_WIDTH < 20 - lcd.print("Y"); - #else - lcd.print("Y:"); - #endif - lcd.print(ftostr32(LOGICAL_Y_POSITION(pgm_read_float(&ubl._mesh_index_to_ypos[y_plot])))); - - /* - * Print plot position - */ - #if LCD_WIDTH < 20 - lcd.setCursor(0, 1); - #else - lcd.setCursor(1, 1); - #endif - lcd.print("("); - lcd.print(x_plot); - lcd.print(","); - lcd.print(y_plot); - lcd.print(")"); - - /* - * Print Z values - */ - lcd.setCursor(lcd_w_pos, 1); - #if LCD_WIDTH < 20 - lcd.print("Z"); - #else - lcd.print("Z:"); - #endif - if (!isnan(ubl.z_values[x_plot][y_plot])) { - lcd.print(ftostr43sign(ubl.z_values[x_plot][y_plot])); - } - else { - lcd.print(" -----"); - } - - #elif LCD_HEIGHT > 3 - + void lcd_set_ubl_map_plot_chars() { + #if LCD_HEIGHT > 3 //#include "_ubl_lcd_map_characters.h" - - const static PROGMEM byte _lcd_box_top[8] = { + const static byte _lcd_box_top[8] PROGMEM = { B11111, B00000, B00000, @@ -1189,8 +1124,7 @@ static void lcd_implementation_status_screen() { B00000, B00000 }; - - const static PROGMEM byte _lcd_box_bottom[8] = { + const static byte _lcd_box_bottom[8] PROGMEM = { B00000, B00000, B00000, @@ -1200,75 +1134,99 @@ static void lcd_implementation_status_screen() { B00000, B11111 }; - - /* - * Draw the Mesh Map Box - */ - // First create the box custom characters createChar_P(1, _lcd_box_top); createChar_P(2, _lcd_box_bottom); + #endif + } - // Draw the mesh map box - uint8_t m; - - #if LCD_WIDTH < 20 + void lcd_implementation_ubl_plot(const uint8_t x_plot, const uint8_t y_plot) { - for(m = 1; m <= 5; m++) { lcd.setCursor(m, 0); lcd.write(1); } // Top - for(m = 1; m <= 5; m++) { lcd.setCursor(m, 3); lcd.write(2); } // Bottom - for(m = 0; m <= 3; m++) { lcd.setCursor(2, m); lcd.write('|'); } // Left - for(m = 0; m <= 3; m++) { lcd.setCursor(8, m); lcd.write('|'); } // Right + #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 - #else - - for(m = 3; m <= 7; m++) { lcd.setCursor(m, 0); lcd.write(1); } // Top - for(m = 3; m <= 7; m++) { lcd.setCursor(m, 3); lcd.write(2); } // Bottom - for(m = 0; m <= 3; m++) { lcd.setCursor(2, m); lcd.write('|'); } // Left - for(m = 0; m <= 3; m++) { lcd.setCursor(8, m); lcd.write('|'); } // Right + #if LCD_HEIGHT <= 3 // 16x2 or 20x2 display - #endif - /* - * Print plot position + /** + * Show X and Y positions */ - lcd.setCursor(lcd_w_pos, 0); - lcd.print("("); - lcd.print(x_plot); - lcd.print(","); - lcd.print(y_plot); - lcd.print(")"); - - /* - * Show all values at right of screen - */ - lcd.setCursor(lcd_w_pos, 1); - #if LCD_WIDTH < 20 - lcd.print("X"); - #else - lcd.print("X:"); - #endif + _XLABEL(_PLOT_X, 0); lcd.print(ftostr32(LOGICAL_X_POSITION(pgm_read_float(&ubl._mesh_index_to_xpos[x_plot])))); - lcd.setCursor(lcd_w_pos, 2); - #if LCD_WIDTH < 20 - lcd.print("Y"); - #else - lcd.print("Y:"); - #endif + + _YLABEL(_LCD_W_POS, 0); lcd.print(ftostr32(LOGICAL_Y_POSITION(pgm_read_float(&ubl._mesh_index_to_ypos[y_plot])))); - /* + lcd.setCursor(_PLOT_X, 0); + + #else // 16x4 or 20x4 display + + /** + * Draw the Mesh Map Box + */ + uint8_t m; + lcd.setCursor(_MAP_X, 0); for (m = 0; m < 5; m++) lcd.write(1); // Top + lcd.setCursor(_MAP_X, 3); for (m = 0; m < 5; m++) lcd.write(2); // Bottom + for (m = 0; m <= 3; m++) { + lcd.setCursor(2, m); lcd.write('|'); // Left + lcd.setCursor(8, m); lcd.write('|'); // Right + } + + lcd.setCursor(_LCD_W_POS, 0); + + #endif + + /** + * Print plot position + */ + lcd.write('('); + lcd.print(x_plot); + lcd.write(','); + lcd.print(y_plot); + lcd.write(')'); + + #if LCD_HEIGHT <= 3 // 16x2 or 20x2 display + + /** + * 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])); + 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_plot])))); + _YLABEL(_LCD_W_POS, 2); + lcd.print(ftostr32(LOGICAL_Y_POSITION(pgm_read_float(&ubl._mesh_index_to_ypos[y_plot])))); + + /** * Show the location value */ - lcd.setCursor(lcd_w_pos, 3); - #if LCD_WIDTH < 20 - lcd.print("Z"); - #else - lcd.print("Z:"); - #endif - if (!isnan(ubl.z_values[x_plot][y_plot])) { + _ZLABEL(_LCD_W_POS, 3); + if (!isnan(ubl.z_values[x_plot][y_plot])) lcd.print(ftostr43sign(ubl.z_values[x_plot][y_plot])); - } - else { - lcd.print(" -----"); - } + else + lcd_printPGM(PSTR(" -----")); #endif // LCD_HEIGHT > 3 } From 85777a56c67438876561994dceb0628b699254d8 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 28 Jun 2017 02:01:41 -0500 Subject: [PATCH 143/180] Add A (action) and E (echo) parameters to M118 --- 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 d695b273ef..a3045b9001 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -7994,9 +7994,13 @@ inline void gcode_M117() { lcd_setstatus(parser.string_arg); } /** * M118: Display a message in the host console. + * + * A Append '// ' for an action command, as in OctoPrint + * E Have the host 'echo:' the text */ inline void gcode_M118() { - SERIAL_ECHO_START(); + if (parser.boolval('E')) SERIAL_ECHO_START(); + if (parser.boolval('A')) SERIAL_ECHOPGM("// "); SERIAL_ECHOLN(parser.string_arg); } From bb0508b6cf4df98116b9418057add3e02bb58fb6 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 28 Jun 2017 13:08:33 -0500 Subject: [PATCH 144/180] Fix comment in M115 code --- 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 a3045b9001..6bfd52d54c 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -7957,7 +7957,7 @@ inline void gcode_M115() { SERIAL_PROTOCOLLNPGM("Cap:LEVELING_DATA:0"); #endif - // SOFTWARE_POWER (G30) + // SOFTWARE_POWER (M80, M81) #if HAS_POWER_SWITCH SERIAL_PROTOCOLLNPGM("Cap:SOFTWARE_POWER:1"); #else From e3cedfa0ec924dc9ddb9dcd2961b94ec10283b5d Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 28 Jun 2017 16:41:24 -0500 Subject: [PATCH 145/180] Fix a compiler warning --- Marlin/Marlin_main.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 6bfd52d54c..2ed85a398d 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -9159,7 +9159,6 @@ void quickstop_stepper() { int8_t ix = parser.intval('I', -1), iy = parser.intval('J', -1); const bool hasI = ix >= 0, hasJ = iy >= 0, - hasC = parser.seen('C'), hasZ = parser.seen('Z'), hasQ = !hasZ && parser.seen('Q'); From 5b03f23fa2e086cb056b6765a4824cdf3d6f7823 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 28 Jun 2017 13:44:04 -0500 Subject: [PATCH 146/180] Bring configurations up to date, fix some comments --- Marlin/Configuration.h | 18 +++++-- Marlin/Configuration_adv.h | 4 +- .../Anet/Configuration.h | 54 ++++++++++--------- .../Anet/Configuration_adv.h | 43 ++++++++------- .../CL-260/Configuration.h | 8 +-- .../Cartesio/Configuration.h | 8 +-- .../Felix/Configuration.h | 8 +-- .../Felix/DUAL/Configuration.h | 8 +-- .../FolgerTech-i3-2020/Configuration.h | 8 +-- .../Hephestos/Configuration.h | 8 +-- .../Hephestos_2/Configuration.h | 8 +-- .../K8200/Configuration.h | 8 +-- .../K8400/Configuration.h | 8 +-- .../K8400/Dual-head/Configuration.h | 8 +-- .../M150/Configuration.h | 8 +-- .../RepRapWorld/Megatronics/Configuration.h | 8 +-- .../RigidBot/Configuration.h | 8 +-- .../SCARA/Configuration.h | 8 +-- .../TAZ4/Configuration.h | 8 +-- .../TinyBoy2/Configuration.h | 8 +-- .../WITBOX/Configuration.h | 8 +-- .../adafruit/ST7565/Configuration.h | 8 +-- .../FLSUN/auto_calibrate/Configuration.h | 8 +-- .../delta/FLSUN/kossel_mini/Configuration.h | 8 +-- .../delta/generic/Configuration.h | 8 +-- .../delta/kossel_mini/Configuration.h | 8 +-- .../delta/kossel_pro/Configuration.h | 8 +-- .../delta/kossel_xl/Configuration.h | 8 +-- .../gCreate_gMax1.5+/Configuration.h | 8 +-- .../makibox/Configuration.h | 8 +-- .../tvrrug/Round2/Configuration.h | 8 +-- .../wt150/Configuration.h | 8 +-- 32 files changed, 182 insertions(+), 161 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 9295d6774b..082d5a999a 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -988,7 +988,7 @@ // 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 this to enable EEPROM support //#define EEPROM_SETTINGS #if ENABLED(EEPROM_SETTINGS) @@ -1392,6 +1392,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). + // // CONTROLLER TYPE: I2C // @@ -1501,13 +1511,13 @@ // 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 -//define PCA9632 PWM LED driver Support +// Support for PCA9632 PWM LED driver //#define PCA9632 /** diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 08d30b58e1..e68c485635 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/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 /** diff --git a/Marlin/example_configurations/Anet/Configuration.h b/Marlin/example_configurations/Anet/Configuration.h index 042ab73395..11519ab03d 100644 --- a/Marlin/example_configurations/Anet/Configuration.h +++ b/Marlin/example_configurations/Anet/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 @@ -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,14 +515,14 @@ * Override with M92 * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ -#define DEFAULT_AXIS_STEPS_PER_UNIT {100, 100, 400, 95} +#define DEFAULT_AXIS_STEPS_PER_UNIT { 100, 100, 400, 95 } /** * Default Max Feed Rate (mm/s) * Override with M203 * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ -#define DEFAULT_MAX_FEEDRATE {400, 400, 8, 50} +#define DEFAULT_MAX_FEEDRATE { 400, 400, 8, 50 } /** * Default Max Acceleration (change/s) change = mm/s @@ -527,7 +530,7 @@ * Override with M201 * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] */ -#define DEFAULT_MAX_ACCELERATION {2000, 2000, 100, 10000} +#define DEFAULT_MAX_ACCELERATION { 2000, 2000, 100, 10000 } /** * Default Acceleration (change/s) change = mm/s @@ -596,7 +599,7 @@ * Probe Type * * Allen Key Probes, Servo Probes, Z-Sled Probes, FIX_MOUNTED_PROBE, etc. - * Activate one of these to use Auto Bed Leveling below. + * You must activate one of these to use Auto Bed Leveling below. */ /** @@ -991,7 +994,7 @@ // 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 this to enable EEPROM support #define EEPROM_SETTINGS #if ENABLED(EEPROM_SETTINGS) @@ -1307,6 +1310,12 @@ // //#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 @@ -1391,12 +1400,6 @@ // //#define BQ_LCD_SMART_CONTROLLER -// -// Cartesio UI -// http://mauk.cc/webshop/cartesio-shop/electronics/user-interface -// -//#define CARTESIO_UI - // // ANET_10 Controller supported displays. // @@ -1423,6 +1426,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 // @@ -1453,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 // @@ -1475,6 +1476,11 @@ // //#define SAV_3DLCD +// +// TinyBoy2 128x64 OLED / Encoder Panel +// +//#define OLED_PANEL_TINYBOY2 + //============================================================================= //=============================== Extra Features ============================== //============================================================================= @@ -1513,13 +1519,13 @@ // 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 -//define PCA9632 PWM LED driver Support +// Support for PCA9632 PWM LED driver //#define PCA9632 /** diff --git a/Marlin/example_configurations/Anet/Configuration_adv.h b/Marlin/example_configurations/Anet/Configuration_adv.h index d41f1d2082..cc72206cf5 100644 --- a/Marlin/example_configurations/Anet/Configuration_adv.h +++ b/Marlin/example_configurations/Anet/Configuration_adv.h @@ -225,13 +225,11 @@ */ //#define CASE_LIGHT_ENABLE #if ENABLED(CASE_LIGHT_ENABLE) - #define CASE_LIGHT_PIN 4 // can be defined here or in the pins_XXX.h file for your board - // pins_XXX.h file overrides this one - #define INVERT_CASE_LIGHT false // set to true if case light is ON when pin is at 0 - #define CASE_LIGHT_DEFAULT_ON true // set default power up state to on or off - #define CASE_LIGHT_DEFAULT_BRIGHTNESS 105 // set power up brightness 0-255 ( only used if on PWM - // and if CASE_LIGHT_DEFAULT is set to on - //#define MENU_ITEM_CASE_LIGHT // Uncomment to have a Case Light entry in main menu + //#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 //=========================================================================== @@ -421,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 // 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=========================== @@ -680,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 @@ -809,6 +813,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 @@ -1201,12 +1206,12 @@ /** * Auto-report temperatures with M155 S */ -//#define AUTO_REPORT_TEMPERATURES +#define AUTO_REPORT_TEMPERATURES /** * Include capabilities in M115 output */ -//#define EXTENDED_CAPABILITIES_REPORT +#define EXTENDED_CAPABILITIES_REPORT /** * Volumetric extrusion default state @@ -1264,7 +1269,7 @@ #endif //=========================================================================== -//============================ I2C Encoder Settings ========================= +//====================== I2C Position Encoder Settings ====================== //=========================================================================== /** * I2C position encoders for closed loop control. @@ -1344,6 +1349,6 @@ // Use a rolling average to identify persistant errors that indicate skips, as opposed to vibration and noise. #define I2CPE_ERR_ROLLING_AVERAGE -#endif +#endif // I2C_POSITION_ENCODERS #endif // CONFIGURATION_ADV_H diff --git a/Marlin/example_configurations/CL-260/Configuration.h b/Marlin/example_configurations/CL-260/Configuration.h index 545220f80e..a8cad55df7 100644 --- a/Marlin/example_configurations/CL-260/Configuration.h +++ b/Marlin/example_configurations/CL-260/Configuration.h @@ -985,7 +985,7 @@ // 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 this to enable EEPROM support //#define EEPROM_SETTINGS #if ENABLED(EEPROM_SETTINGS) @@ -1508,13 +1508,13 @@ // 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 -//define PCA9632 PWM LED driver Support +// Support for PCA9632 PWM LED driver //#define PCA9632 /** diff --git a/Marlin/example_configurations/Cartesio/Configuration.h b/Marlin/example_configurations/Cartesio/Configuration.h index 10d1f84ea6..ac543164c8 100644 --- a/Marlin/example_configurations/Cartesio/Configuration.h +++ b/Marlin/example_configurations/Cartesio/Configuration.h @@ -982,7 +982,7 @@ // 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 this to enable EEPROM support //#define EEPROM_SETTINGS #if ENABLED(EEPROM_SETTINGS) @@ -1505,13 +1505,13 @@ // 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 -//define PCA9632 PWM LED driver Support +// Support for PCA9632 PWM LED driver //#define PCA9632 /** diff --git a/Marlin/example_configurations/Felix/Configuration.h b/Marlin/example_configurations/Felix/Configuration.h index 7ca6e17f33..a7dcb118cf 100644 --- a/Marlin/example_configurations/Felix/Configuration.h +++ b/Marlin/example_configurations/Felix/Configuration.h @@ -966,7 +966,7 @@ // 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 this to enable EEPROM support //#define EEPROM_SETTINGS #if ENABLED(EEPROM_SETTINGS) @@ -1489,13 +1489,13 @@ // 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 -//define PCA9632 PWM LED driver Support +// Support for PCA9632 PWM LED driver //#define PCA9632 /** diff --git a/Marlin/example_configurations/Felix/DUAL/Configuration.h b/Marlin/example_configurations/Felix/DUAL/Configuration.h index af9b9aa496..7904e3cc56 100644 --- a/Marlin/example_configurations/Felix/DUAL/Configuration.h +++ b/Marlin/example_configurations/Felix/DUAL/Configuration.h @@ -966,7 +966,7 @@ // 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 this to enable EEPROM support //#define EEPROM_SETTINGS #if ENABLED(EEPROM_SETTINGS) @@ -1489,13 +1489,13 @@ // 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 -//define PCA9632 PWM LED driver Support +// Support for PCA9632 PWM LED driver //#define PCA9632 /** diff --git a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h index a7db519e01..36ff1f2b4a 100644 --- a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h +++ b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h @@ -988,7 +988,7 @@ // 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 this to enable EEPROM support #define EEPROM_SETTINGS #if ENABLED(EEPROM_SETTINGS) @@ -1511,13 +1511,13 @@ // 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 -//define PCA9632 PWM LED driver Support +// Support for PCA9632 PWM LED driver //#define PCA9632 /** diff --git a/Marlin/example_configurations/Hephestos/Configuration.h b/Marlin/example_configurations/Hephestos/Configuration.h index cd2cf20c29..dfa01e944a 100644 --- a/Marlin/example_configurations/Hephestos/Configuration.h +++ b/Marlin/example_configurations/Hephestos/Configuration.h @@ -974,7 +974,7 @@ // 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 this to enable EEPROM support //#define EEPROM_SETTINGS #if ENABLED(EEPROM_SETTINGS) @@ -1497,13 +1497,13 @@ // 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 -//define PCA9632 PWM LED driver Support +// Support for PCA9632 PWM LED driver //#define PCA9632 /** diff --git a/Marlin/example_configurations/Hephestos_2/Configuration.h b/Marlin/example_configurations/Hephestos_2/Configuration.h index de69aeb068..63767298e5 100644 --- a/Marlin/example_configurations/Hephestos_2/Configuration.h +++ b/Marlin/example_configurations/Hephestos_2/Configuration.h @@ -977,7 +977,7 @@ // 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 this to enable EEPROM support #define EEPROM_SETTINGS #if ENABLED(EEPROM_SETTINGS) @@ -1500,13 +1500,13 @@ // 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 -//define PCA9632 PWM LED driver Support +// Support for PCA9632 PWM LED driver //#define PCA9632 /** diff --git a/Marlin/example_configurations/K8200/Configuration.h b/Marlin/example_configurations/K8200/Configuration.h index c6b5521f90..4ecaf9c8c8 100644 --- a/Marlin/example_configurations/K8200/Configuration.h +++ b/Marlin/example_configurations/K8200/Configuration.h @@ -1013,7 +1013,7 @@ // 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 this to enable EEPROM support #define EEPROM_SETTINGS // K8200: uses EEPROM by default #if ENABLED(EEPROM_SETTINGS) @@ -1546,13 +1546,13 @@ // 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 -//define PCA9632 PWM LED driver Support +// Support for PCA9632 PWM LED driver //#define PCA9632 /** diff --git a/Marlin/example_configurations/K8400/Configuration.h b/Marlin/example_configurations/K8400/Configuration.h index 53624af67f..c7b0db6b3a 100644 --- a/Marlin/example_configurations/K8400/Configuration.h +++ b/Marlin/example_configurations/K8400/Configuration.h @@ -984,7 +984,7 @@ // 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 this to enable EEPROM support #define EEPROM_SETTINGS #if ENABLED(EEPROM_SETTINGS) @@ -1507,13 +1507,13 @@ // 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 -//define PCA9632 PWM LED driver Support +// Support for PCA9632 PWM LED driver //#define PCA9632 /** diff --git a/Marlin/example_configurations/K8400/Dual-head/Configuration.h b/Marlin/example_configurations/K8400/Dual-head/Configuration.h index 975997a77f..68359941d2 100644 --- a/Marlin/example_configurations/K8400/Dual-head/Configuration.h +++ b/Marlin/example_configurations/K8400/Dual-head/Configuration.h @@ -984,7 +984,7 @@ // 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 this to enable EEPROM support #define EEPROM_SETTINGS #if ENABLED(EEPROM_SETTINGS) @@ -1507,13 +1507,13 @@ // 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 -//define PCA9632 PWM LED driver Support +// Support for PCA9632 PWM LED driver //#define PCA9632 /** diff --git a/Marlin/example_configurations/M150/Configuration.h b/Marlin/example_configurations/M150/Configuration.h index d73fd6c40f..c8043291a2 100644 --- a/Marlin/example_configurations/M150/Configuration.h +++ b/Marlin/example_configurations/M150/Configuration.h @@ -1011,7 +1011,7 @@ // 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 this to enable EEPROM support #define EEPROM_SETTINGS #if ENABLED(EEPROM_SETTINGS) @@ -1534,13 +1534,13 @@ // 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 -//define PCA9632 PWM LED driver Support +// Support for PCA9632 PWM LED driver //#define PCA9632 /** diff --git a/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h b/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h index 201a3d2e47..e3a1599559 100644 --- a/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h +++ b/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h @@ -984,7 +984,7 @@ // 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 this to enable EEPROM support //#define EEPROM_SETTINGS #if ENABLED(EEPROM_SETTINGS) @@ -1507,13 +1507,13 @@ // 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 -//define PCA9632 PWM LED driver Support +// Support for PCA9632 PWM LED driver //#define PCA9632 /** diff --git a/Marlin/example_configurations/RigidBot/Configuration.h b/Marlin/example_configurations/RigidBot/Configuration.h index 158d42fbd3..5473a32073 100644 --- a/Marlin/example_configurations/RigidBot/Configuration.h +++ b/Marlin/example_configurations/RigidBot/Configuration.h @@ -982,7 +982,7 @@ // 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 this to enable EEPROM support #define EEPROM_SETTINGS #if ENABLED(EEPROM_SETTINGS) @@ -1507,13 +1507,13 @@ // 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 -//define PCA9632 PWM LED driver Support +// Support for PCA9632 PWM LED driver //#define PCA9632 /** diff --git a/Marlin/example_configurations/SCARA/Configuration.h b/Marlin/example_configurations/SCARA/Configuration.h index 3a32e80fce..d6a97d72e1 100644 --- a/Marlin/example_configurations/SCARA/Configuration.h +++ b/Marlin/example_configurations/SCARA/Configuration.h @@ -996,7 +996,7 @@ // 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 this to enable EEPROM support //#define EEPROM_SETTINGS #if ENABLED(EEPROM_SETTINGS) @@ -1519,13 +1519,13 @@ // 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 -//define PCA9632 PWM LED driver Support +// Support for PCA9632 PWM LED driver //#define PCA9632 /** diff --git a/Marlin/example_configurations/TAZ4/Configuration.h b/Marlin/example_configurations/TAZ4/Configuration.h index 1414d0ccaa..bdf7d94193 100644 --- a/Marlin/example_configurations/TAZ4/Configuration.h +++ b/Marlin/example_configurations/TAZ4/Configuration.h @@ -1003,7 +1003,7 @@ // 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 this to enable EEPROM support #define EEPROM_SETTINGS #if ENABLED(EEPROM_SETTINGS) @@ -1526,13 +1526,13 @@ // 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 -//define PCA9632 PWM LED driver Support +// Support for PCA9632 PWM LED driver //#define PCA9632 /** diff --git a/Marlin/example_configurations/TinyBoy2/Configuration.h b/Marlin/example_configurations/TinyBoy2/Configuration.h index 5ded991e54..b3f58f0cbd 100644 --- a/Marlin/example_configurations/TinyBoy2/Configuration.h +++ b/Marlin/example_configurations/TinyBoy2/Configuration.h @@ -1040,7 +1040,7 @@ // 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 this to enable EEPROM support #define EEPROM_SETTINGS #if ENABLED(EEPROM_SETTINGS) @@ -1568,13 +1568,13 @@ // 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 -//define PCA9632 PWM LED driver Support +// Support for PCA9632 PWM LED driver //#define PCA9632 /** diff --git a/Marlin/example_configurations/WITBOX/Configuration.h b/Marlin/example_configurations/WITBOX/Configuration.h index 53b2506ebd..cb280b3446 100644 --- a/Marlin/example_configurations/WITBOX/Configuration.h +++ b/Marlin/example_configurations/WITBOX/Configuration.h @@ -974,7 +974,7 @@ // 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 this to enable EEPROM support //#define EEPROM_SETTINGS #if ENABLED(EEPROM_SETTINGS) @@ -1497,13 +1497,13 @@ // 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 -//define PCA9632 PWM LED driver Support +// Support for PCA9632 PWM LED driver //#define PCA9632 /** diff --git a/Marlin/example_configurations/adafruit/ST7565/Configuration.h b/Marlin/example_configurations/adafruit/ST7565/Configuration.h index 245675fbaf..3b3cb2c4ce 100644 --- a/Marlin/example_configurations/adafruit/ST7565/Configuration.h +++ b/Marlin/example_configurations/adafruit/ST7565/Configuration.h @@ -984,7 +984,7 @@ // 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 this to enable EEPROM support //#define EEPROM_SETTINGS #if ENABLED(EEPROM_SETTINGS) @@ -1507,13 +1507,13 @@ // 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 -//define PCA9632 PWM LED driver Support +// Support for PCA9632 PWM LED driver //#define PCA9632 /** diff --git a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h index 18bdac8728..8426456df3 100644 --- a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h +++ b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h @@ -1104,7 +1104,7 @@ // 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 this to enable EEPROM support #define EEPROM_SETTINGS #if ENABLED(EEPROM_SETTINGS) @@ -1628,13 +1628,13 @@ // 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 -//define PCA9632 PWM LED driver Support +// Support for PCA9632 PWM LED driver //#define PCA9632 /** diff --git a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h index 5dde5f4871..97ea09ca8c 100644 --- a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h +++ b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h @@ -1106,7 +1106,7 @@ // 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 this to enable EEPROM support #define EEPROM_SETTINGS #if ENABLED(EEPROM_SETTINGS) @@ -1629,13 +1629,13 @@ // 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 -//define PCA9632 PWM LED driver Support +// Support for PCA9632 PWM LED driver //#define PCA9632 /** diff --git a/Marlin/example_configurations/delta/generic/Configuration.h b/Marlin/example_configurations/delta/generic/Configuration.h index f13de9116c..2bc238b84d 100644 --- a/Marlin/example_configurations/delta/generic/Configuration.h +++ b/Marlin/example_configurations/delta/generic/Configuration.h @@ -1095,7 +1095,7 @@ // 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 this to enable EEPROM support //#define EEPROM_SETTINGS #if ENABLED(EEPROM_SETTINGS) @@ -1618,13 +1618,13 @@ // 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 -//define PCA9632 PWM LED driver Support +// Support for PCA9632 PWM LED driver //#define PCA9632 /** diff --git a/Marlin/example_configurations/delta/kossel_mini/Configuration.h b/Marlin/example_configurations/delta/kossel_mini/Configuration.h index c4ed97e7c9..d2a21e3c91 100644 --- a/Marlin/example_configurations/delta/kossel_mini/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_mini/Configuration.h @@ -1098,7 +1098,7 @@ // 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 this to enable EEPROM support //#define EEPROM_SETTINGS #if ENABLED(EEPROM_SETTINGS) @@ -1621,13 +1621,13 @@ // 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 -//define PCA9632 PWM LED driver Support +// Support for PCA9632 PWM LED driver //#define PCA9632 /** diff --git a/Marlin/example_configurations/delta/kossel_pro/Configuration.h b/Marlin/example_configurations/delta/kossel_pro/Configuration.h index d53d1aa230..d321556c0b 100644 --- a/Marlin/example_configurations/delta/kossel_pro/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_pro/Configuration.h @@ -1103,7 +1103,7 @@ // 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 this to enable EEPROM support //#define EEPROM_SETTINGS #if ENABLED(EEPROM_SETTINGS) @@ -1626,13 +1626,13 @@ // 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 -//define PCA9632 PWM LED driver Support +// Support for PCA9632 PWM LED driver //#define PCA9632 /** diff --git a/Marlin/example_configurations/delta/kossel_xl/Configuration.h b/Marlin/example_configurations/delta/kossel_xl/Configuration.h index 9fbd10b94e..d9071e3f10 100644 --- a/Marlin/example_configurations/delta/kossel_xl/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_xl/Configuration.h @@ -1161,7 +1161,7 @@ // 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 this to enable EEPROM support #define EEPROM_SETTINGS #if ENABLED(EEPROM_SETTINGS) @@ -1684,13 +1684,13 @@ // 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 -//define PCA9632 PWM LED driver Support +// Support for PCA9632 PWM LED driver //#define PCA9632 /** diff --git a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h index 03b4f2440b..727d5ac438 100644 --- a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h +++ b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h @@ -1000,7 +1000,7 @@ // 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 this to enable EEPROM support #define EEPROM_SETTINGS #if ENABLED(EEPROM_SETTINGS) @@ -1523,13 +1523,13 @@ // 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 -//define PCA9632 PWM LED driver Support +// Support for PCA9632 PWM LED driver //#define PCA9632 /** diff --git a/Marlin/example_configurations/makibox/Configuration.h b/Marlin/example_configurations/makibox/Configuration.h index 6fe07aa24f..3580a15eb7 100644 --- a/Marlin/example_configurations/makibox/Configuration.h +++ b/Marlin/example_configurations/makibox/Configuration.h @@ -987,7 +987,7 @@ // 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 this to enable EEPROM support #define EEPROM_SETTINGS #if ENABLED(EEPROM_SETTINGS) @@ -1510,13 +1510,13 @@ // 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 -//define PCA9632 PWM LED driver Support +// Support for PCA9632 PWM LED driver //#define PCA9632 /** diff --git a/Marlin/example_configurations/tvrrug/Round2/Configuration.h b/Marlin/example_configurations/tvrrug/Round2/Configuration.h index 015a0d327c..1eb267ccf0 100644 --- a/Marlin/example_configurations/tvrrug/Round2/Configuration.h +++ b/Marlin/example_configurations/tvrrug/Round2/Configuration.h @@ -979,7 +979,7 @@ // 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 this to enable EEPROM support //#define EEPROM_SETTINGS #if ENABLED(EEPROM_SETTINGS) @@ -1502,13 +1502,13 @@ // 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 -//define PCA9632 PWM LED driver Support +// Support for PCA9632 PWM LED driver //#define PCA9632 /** diff --git a/Marlin/example_configurations/wt150/Configuration.h b/Marlin/example_configurations/wt150/Configuration.h index 717b0b2055..cc324f83ec 100644 --- a/Marlin/example_configurations/wt150/Configuration.h +++ b/Marlin/example_configurations/wt150/Configuration.h @@ -990,7 +990,7 @@ // 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 this to enable EEPROM support #define EEPROM_SETTINGS #if ENABLED(EEPROM_SETTINGS) @@ -1513,13 +1513,13 @@ // 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 -//define PCA9632 PWM LED driver Support +// Support for PCA9632 PWM LED driver //#define PCA9632 /** From 379926961c8c7311134e934c882491324c6e63bd Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 28 Jun 2017 16:39:39 -0500 Subject: [PATCH 147/180] Add Anet A6 config, edit Anet A8 config --- .../Anet/A6/Configuration.h | 1782 +++++++++++++++++ .../Anet/A6/Configuration_adv.h | 1354 +++++++++++++ .../Anet/Configuration.h | 4 +- 3 files changed, 3138 insertions(+), 2 deletions(-) create mode 100644 Marlin/example_configurations/Anet/A6/Configuration.h create mode 100644 Marlin/example_configurations/Anet/A6/Configuration_adv.h diff --git a/Marlin/example_configurations/Anet/A6/Configuration.h b/Marlin/example_configurations/Anet/A6/Configuration.h new file mode 100644 index 0000000000..4e954bae10 --- /dev/null +++ b/Marlin/example_configurations/Anet/A6/Configuration.h @@ -0,0 +1,1782 @@ +/** + * 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 "(Ralf_E, ANET A6 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_ANET_10 +#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 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 130 + +//=========================================================================== +//============================= 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 + + // ANET A6 Firmware V2.0 Standard Extruder defaults: + // PID-P: +022.20, PID-I: +001.08, PID-D: +114.00, PID-C: 1 + //#define DEFAULT_Kp 22.2 + //#define DEFAULT_Ki 1.08 + //#define DEFAULT_Kd 114.0 + + // Tuned by ralf-e. Always re-tune for your machine! + #define DEFAULT_Kp 16.83 + #define DEFAULT_Ki 1.02 + #define DEFAULT_Kd 69.29 + +#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 + + // ANET A6 + // original Bed + 0.3mm Heat conducting into 4mm borosilicate (PID-Autotune: M303 E-1 S60 C5): + //#define DEFAULT_bedKp 295.00 + //#define DEFAULT_bedKi 35.65 + //#define DEFAULT_bedKd 610.21 + #define DEFAULT_bedKp 295.00 + #define DEFAULT_bedKi 35.65 + #define DEFAULT_bedKd 610.21 + + // 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 true // set to true to invert the logic of the endstop. +#define Y_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. +#define Z_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. +#define X_MAX_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop. +#define Y_MAX_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop. +#define Z_MAX_ENDSTOP_INVERTING false // set to true to invert the logic of the endstop. +#define Z_MIN_PROBE_ENDSTOP_INVERTING false // set to true to invert the logic of the 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, 4000, 500 } + +// ANET A6 Firmwae V2.0 defaults: (steps/mm) +// Xsteps/mm: +100.0, Ysteps/mm: +100.0, Zsteps/mm: +0400.0, eSteps/mm: +0095.0 +#define DEFAULT_AXIS_STEPS_PER_UNIT {100, 100, 400, 95} +//#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 { 300, 300, 5, 25 } + +// ANET A6 Firmware V2.0 defaults (Vmax): +// Vmax x: 400, Vmax y: 400, Vmax z: 4, Vmax e: 25 +#define DEFAULT_MAX_FEEDRATE {400, 400, 4, 25} +//#define DEFAULT_MAX_FEEDRATE {400, 400, 20, 50} + + +/** + * Default Max Acceleration (change/s) change = mm/s + * (Maximum start speed for accelerated moves) + * Override with M201 + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] + */ +//#define DEFAULT_MAX_ACCELERATION { 3000, 3000, 100, 10000 } + +// ANET A6 Firmware V2.0 defaults (Amax): +// Amx x: 9000, Amax Y: 5000, Amax z: 50, Amax e: 10000 +#define DEFAULT_MAX_ACCELERATION { 9000, 5000, 50, 10000 } +//#define DEFAULT_MAX_ACCELERATION { 10000, 10000, 200, 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 + +// ANET A6 Firmware V2.0 defaults: +// Accel: 1000 A-retract: 1000 +#define DEFAULT_ACCELERATION 1000 // X, Y, Z and E acceleration for printing moves +#define DEFAULT_RETRACT_ACCELERATION 1000 // E acceleration for retracts +#define DEFAULT_TRAVEL_ACCELERATION 1000 // X, Y, Z acceleration for travel (non printing) moves +//#define DEFAULT_ACCELERATION 2000 // X, Y, Z and E acceleration for printing moves +//#define DEFAULT_RETRACT_ACCELERATION 2000 // E acceleration for retracts +//#define DEFAULT_TRAVEL_ACCELERATION 4000 // 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 + +// ANET A6 Firmware V2.0 defaults (jerk): +// Vxy-jerk: 20, Vz-jerk: +000.30, Ve-jerk: 10 +#define DEFAULT_XJERK 20.0 +#define DEFAULT_YJERK 20.0 +#define DEFAULT_ZJERK 0.3 +#define DEFAULT_EJERK 10.0 +//#define DEFAULT_XJERK 20.0 +//#define DEFAULT_YJERK 20.0 +//#define DEFAULT_ZJERK 0.3 +//#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] + +// ANET A8: BELOW IS FOR THE FRONT MOUNTED SENSOR WITH 3D PRINTED MOUNT +//#define X_PROBE_OFFSET_FROM_EXTRUDER -28 // X offset: -left +right [of the nozzle] +//#define Y_PROBE_OFFSET_FROM_EXTRUDER -45 // Y offset: -front +behind [the nozzle] +//#define Z_PROBE_OFFSET_FROM_EXTRUDER 0 // Z offset: -below +above [the nozzle] + +//AND THE LINES BELOW HERE ARE FOR THE OFFICIAL ANET REAR MOUNTED SENSOR +//#define X_PROBE_OFFSET_FROM_EXTRUDER -1 // X offset: -left +right [of the nozzle] +//#define Y_PROBE_OFFSET_FROM_EXTRUDER 3 // Y offset: -front +behind [the nozzle] +//#define Z_PROBE_OFFSET_FROM_EXTRUDER 0 // Z offset: -below +above [the nozzle] + +//ANET A6 with BLTouch/3D-Touch mounted right to the nozzel +#define X_PROBE_OFFSET_FROM_EXTRUDER 39 // X offset: -left +right [of the nozzle] +#define Y_PROBE_OFFSET_FROM_EXTRUDER 0 // Y offset: -front +behind [the nozzle] +#define Z_PROBE_OFFSET_FROM_EXTRUDER 0 // Z offset: -below +above [the nozzle] + +//ANET A6 with BLTouch/3D-Touch betwen Fan and Belt +// (mount: https://github.com/ralf-e/ANET_A6_modifications/tree/master/A6_X-Axis) +//#define X_PROBE_OFFSET_FROM_EXTRUDER -30 // 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.75 // Z offset: -below +above [the nozzle] + +// X and Y axis travel speed (mm/m) between probes +#define XY_PROBE_SPEED 8000 +//#define XY_PROBE_SPEED 6000 + +// 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 / 3) + +// 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 +//#define Z_CLEARANCE_DEPLOY_PROBE 5 // 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 +#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 true +//#define INVERT_Z_DIR false +//ANET A6: +#define INVERT_Y_DIR false +#define INVERT_Z_DIR true + +// 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 + +// 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 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 + +// 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 + +// 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 + +// 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 + + + +// 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 4 + #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 + + // ANET A6 + //#define LEFT_PROBE_BED_POSITION 20 + //#define RIGHT_PROBE_BED_POSITION 190 + //#define FRONT_PROBE_BED_POSITION 20 + //#define BACK_PROBE_BED_POSITION 190 + + // ANET A6 BLTOUCH right (39mm) to the nozzle + #define LEFT_PROBE_BED_POSITION 36 + #define RIGHT_PROBE_BED_POSITION 190 + #define FRONT_PROBE_BED_POSITION 20 + #define BACK_PROBE_BED_POSITION 190 + + // ANET A6 with new X-Axis and modded Y-Axis + //#define LEFT_PROBE_BED_POSITION 20 + //#define RIGHT_PROBE_BED_POSITION 205 + //#define FRONT_PROBE_BED_POSITION 20 + //#define BACK_PROBE_BED_POSITION 205 + + // ANET A6 with new X-Axis and modded Y-Axis, X0/Y0 front left bed edge + //#define LEFT_PROBE_BED_POSITION 20 + //#define RIGHT_PROBE_BED_POSITION 194 + //#define FRONT_PROBE_BED_POSITION 20 + //#define BACK_PROBE_BED_POSITION 194 + + // 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 5 // 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 + +// ANET A6 with new X-Axis / modded Y-Axis: +//#define MANUAL_X_HOME_POS X_MIN_POS - 8 +//#define MANUAL_Y_HOME_POS Y_MIN_POS - 6 +//#define MANUAL_Z_HOME_POS Z_MIN_POS + +// 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). + + //Anet A6 with new X-Axis + //#define Z_SAFE_HOMING_X_POINT 113 // X point for Z homing when homing all axis (G28). + //#define Z_SAFE_HOMING_Y_POINT 112 // Y point for Z homing when homing all axis (G28). + + //Anet A6 with new X-Axis and defined X_HOME_POS -7, Y_HOME_POS -6 + //#define Z_SAFE_HOMING_X_POINT 107 // X point for Z homing when homing all axis (G28). + //#define Z_SAFE_HOMING_Y_POINT 107 // 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) + // 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 + +// +// 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 50 +#define PREHEAT_1_FAN_SPEED 0 // ANET A6 Default is 255 + +#define PREHEAT_2_TEMP_HOTEND 230 +#define PREHEAT_2_TEMP_BED 70 +#define PREHEAT_2_FAN_SPEED 0 // ANET A6 Default is 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, 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':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' } + */ +#define LCD_LANGUAGE en + +/** + * 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 + +// +// 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 +// +// Note: Details on connecting to the Anet V1.0 controller are in the file pins_ANET_10.h +// +//#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). + +// +// 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 3.00 // (mm) Diameter of the filament generally used (3.0 or 1.75mm), also used in the slicer. Used to validate sensor reading. + +#if ENABLED(FILAMENT_WIDTH_SENSOR) + #define FILAMENT_SENSOR_EXTRUDER_NUM 0 // Index of the extruder that has the filament sensor (0,1,2,3) + #define MEASUREMENT_DELAY_CM 14 // (cm) The distance from the filament sensor to the melting chamber + + #define MEASURED_UPPER_LIMIT 3.30 // (mm) Upper limit used to validate sensor reading + #define MEASURED_LOWER_LIMIT 1.90 // (mm) Lower limit used to validate sensor reading + #define MAX_MEASUREMENT_DELAY 20 // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM. + + #define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially + + // Display filament width on the LCD status line. Status messages will expire after 5 seconds. + //#define FILAMENT_LCD_DISPLAY +#endif + +#endif // CONFIGURATION_H diff --git a/Marlin/example_configurations/Anet/A6/Configuration_adv.h b/Marlin/example_configurations/Anet/A6/Configuration_adv.h new file mode 100644 index 0000000000..30526adf62 --- /dev/null +++ b/Marlin/example_configurations/Anet/A6/Configuration_adv.h @@ -0,0 +1,1354 @@ +/** + * 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 60 // Seconds + #define THERMAL_PROTECTION_HYSTERESIS 10 // 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 60 // Seconds + #define WATCH_TEMP_INCREASE 5 // 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 60 // Seconds + #define THERMAL_PROTECTION_BED_HYSTERESIS 5 // 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 180 // 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 command 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 Prusa Slic3r) 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 (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)) +#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)) + + // 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 fwretract + +// Firmware based and LCD controlled retract +// M207 and M208 can be used to define parameters for the retraction. +// The retraction can be called by the slicer using G10 and G11 +// until then, intended retractions can be detected by moves that only extrude and the direction. +// the moves are than replaced by the firmware controlled ones. + +//#define FWRETRACT //ONLY PARTIALLY TESTED +#if ENABLED(FWRETRACT) + #define MIN_RETRACT 0.1 //minimum extruded mm to accept a automatic gcode retraction attempt + #define RETRACT_LENGTH 3 //default retract length (positive mm) + #define RETRACT_LENGTH_SWAP 13 //default swap retract length (positive mm), for extruder change + #define RETRACT_FEEDRATE 45 //default feedrate for retracting (mm/s) + #define RETRACT_ZLIFT 0 //default retract Z-lift + #define RETRACT_RECOVER_LENGTH 0 //default additional recover length (mm, added to retract length when recovering) + #define RETRACT_RECOVER_LENGTH_SWAP 0 //default additional swap recover length (mm, added to retract length when recovering from extruder change) + #define RETRACT_RECOVER_FEEDRATE 8 //default feedrate for recovering from retraction (mm/s) +#endif + +/** + * 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_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 + +//=========================================================================== +//====================== 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/Anet/Configuration.h b/Marlin/example_configurations/Anet/Configuration.h index 11519ab03d..070121fa61 100644 --- a/Marlin/example_configurations/Anet/Configuration.h +++ b/Marlin/example_configurations/Anet/Configuration.h @@ -77,7 +77,7 @@ #define STRING_CONFIG_H_AUTHOR "(Bob Kuhn, Anet 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 "Marlin " SHORT_BUILD_VERSION // will be shown during bootup in line 2 +#define STRING_SPLASH_LINE2 WEBSITE_URL // will be shown during bootup in line 2 // // *** VENDORS PLEASE READ ***************************************************** @@ -1403,7 +1403,7 @@ // // ANET_10 Controller supported displays. // -#define ANET_KEYPAD_LCD // Requires ADC_KEYPAD_PIN to be assigned to an analog pin. +#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 From 406ef697022747dfbf368fe57d360fcaf512d5d0 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 28 Jun 2017 16:40:25 -0500 Subject: [PATCH 148/180] Move Anet A8 config to subfolder --- Marlin/example_configurations/Anet/{ => A8}/Configuration.h | 0 Marlin/example_configurations/Anet/{ => A8}/Configuration_adv.h | 0 2 files changed, 0 insertions(+), 0 deletions(-) rename Marlin/example_configurations/Anet/{ => A8}/Configuration.h (100%) rename Marlin/example_configurations/Anet/{ => A8}/Configuration_adv.h (100%) diff --git a/Marlin/example_configurations/Anet/Configuration.h b/Marlin/example_configurations/Anet/A8/Configuration.h similarity index 100% rename from Marlin/example_configurations/Anet/Configuration.h rename to Marlin/example_configurations/Anet/A8/Configuration.h diff --git a/Marlin/example_configurations/Anet/Configuration_adv.h b/Marlin/example_configurations/Anet/A8/Configuration_adv.h similarity index 100% rename from Marlin/example_configurations/Anet/Configuration_adv.h rename to Marlin/example_configurations/Anet/A8/Configuration_adv.h From bfbf5f820063a4cb64533036d1bca61873187c35 Mon Sep 17 00:00:00 2001 From: Bob-the-Kuhn Date: Wed, 28 Jun 2017 19:42:54 -0500 Subject: [PATCH 149/180] correct value_bool() when FASTER_GCODE_PARSER is enabled Also corrected compile issue when DEBUG_GCODE_PARSER and AUTO_BED_LEVELING_UBL are both enabled. --- Marlin/gcode.h | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/Marlin/gcode.h b/Marlin/gcode.h index 42a5c89b14..b819fd075d 100644 --- a/Marlin/gcode.h +++ b/Marlin/gcode.h @@ -36,7 +36,11 @@ //#define DEBUG_GCODE_PARSER #if ENABLED(DEBUG_GCODE_PARSER) - #include "hex_print_routines.h" + #if ENABLED(AUTO_BED_LEVELING_UBL) + extern char* hex_address(const void * const w); + #else + #include "hex_print_routines.h" + #endif #include "serial.h" #endif @@ -132,7 +136,7 @@ public: 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)); - if (b) value_ptr = command_ptr + param[ind]; + if (b) value_ptr = param[ind] ? command_ptr + param[ind] : (char*)NULL; return b; } From e6e3132f7973df0a342e52bcc28006b425378f9b Mon Sep 17 00:00:00 2001 From: Bob-the-Kuhn Date: Thu, 29 Jun 2017 08:59:13 -0500 Subject: [PATCH 150/180] make LETTTER_OFF return values that match param indices range --- Marlin/gcode.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/gcode.h b/Marlin/gcode.h index b819fd075d..ac3268d7d4 100644 --- a/Marlin/gcode.h +++ b/Marlin/gcode.h @@ -104,7 +104,7 @@ public: // Index so that 'X' falls on index 24 #define PARAM_IND(N) ((N) >> 3) #define PARAM_BIT(N) ((N) & 0x7) - #define LETTER_OFF(N) ((N) - 'A' + 1) + #define LETTER_OFF(N) ((N) - 'A') #define LETTER_IND(N) PARAM_IND(LETTER_OFF(N)) #define LETTER_BIT(N) PARAM_BIT(LETTER_OFF(N)) From 6c97c5595cfdbd88b01a10b5558b184c9b8c4514 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 29 Jun 2017 15:03:04 -0500 Subject: [PATCH 151/180] Add a sanity check for DELTA_AUTO_CALIBRATION --- Marlin/SanityCheck.h | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Marlin/SanityCheck.h b/Marlin/SanityCheck.h index 73d0fc57b2..19a78c4bf9 100644 --- a/Marlin/SanityCheck.h +++ b/Marlin/SanityCheck.h @@ -480,6 +480,8 @@ static_assert(1 >= 0 #error "You probably want to use Max Endstops for DELTA!" #elif ENABLED(ENABLE_LEVELING_FADE_HEIGHT) && DISABLED(AUTO_BED_LEVELING_BILINEAR) && !UBL_DELTA #error "ENABLE_LEVELING_FADE_HEIGHT on DELTA requires AUTO_BED_LEVELING_BILINEAR or AUTO_BED_LEVELING_UBL." + #elif ENABLED(DELTA_AUTO_CALIBRATION) && !HAS_BED_PROBE + #error "DELTA_AUTO_CALIBRATION requires a probe: FIX_MOUNTED_PROBE, BLTOUCH, SOLENOID_PROBE, Z_PROBE_ALLEN_KEY, Z_PROBE_SLED, or Z Servo." #elif ABL_GRID #if (GRID_MAX_POINTS_X & 1) == 0 || (GRID_MAX_POINTS_Y & 1) == 0 #error "DELTA requires GRID_MAX_POINTS_X and GRID_MAX_POINTS_Y to be odd numbers." From 30b327d24c272ea4e5f98179eced17e969c75b09 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 29 Jun 2017 15:11:22 -0500 Subject: [PATCH 152/180] Finish the solution for #7166 --- Marlin/gcode.h | 14 +++++--------- 1 file changed, 5 insertions(+), 9 deletions(-) diff --git a/Marlin/gcode.h b/Marlin/gcode.h index ac3268d7d4..aa51a57b01 100644 --- a/Marlin/gcode.h +++ b/Marlin/gcode.h @@ -144,10 +144,6 @@ public: #define SEEN_TEST(L) TEST(codebits[LETTER_IND(L)], LETTER_BIT(L)) - // Seen any axis parameter - // Optimized by moving 'X' up to index 24 - FORCE_INLINE bool seen_axis() { return codebits[3] || SEEN_TEST('E'); } - #else // !FASTER_GCODE_PARSER // Code is found in the string. If not found, value_ptr is unchanged. @@ -164,13 +160,13 @@ public: #define SEEN_TEST(L) !!strchr(command_args, L) - // Seen any axis parameter - static bool seen_axis() { - return SEEN_TEST('X') || SEEN_TEST('Y') || SEEN_TEST('Z') || SEEN_TEST('E'); - } - #endif // !FASTER_GCODE_PARSER + // Seen any axis parameter + static bool seen_axis() { + return SEEN_TEST('X') || SEEN_TEST('Y') || SEEN_TEST('Z') || SEEN_TEST('E'); + } + // Populate all fields by parsing a single line of GCode // This uses 54 bytes of SRAM to speed up seen/value static void parse(char * p); From fcceed5be63094963023794d77ad886a8259da3c Mon Sep 17 00:00:00 2001 From: Bob-the-Kuhn Date: Sat, 1 Jul 2017 10:26:57 -0500 Subject: [PATCH 153/180] intermittent Teensy & G26 compile problem =============================================== also an issue with ubl_motion.cpp --- Marlin/G26_Mesh_Validation_Tool.cpp | 3 ++- Marlin/ubl_motion.cpp | 7 ++++++- 2 files changed, 8 insertions(+), 2 deletions(-) diff --git a/Marlin/G26_Mesh_Validation_Tool.cpp b/Marlin/G26_Mesh_Validation_Tool.cpp index 7c780c676d..80f6782aa4 100644 --- a/Marlin/G26_Mesh_Validation_Tool.cpp +++ b/Marlin/G26_Mesh_Validation_Tool.cpp @@ -135,12 +135,13 @@ #endif extern float destination[XYZE]; void set_destination_to_current(); - void set_current_to_destination(); void prepare_move_to_destination(); #if AVR_AT90USB1286_FAMILY // Teensyduino & Printrboard IDE extensions have compile errors without this inline void sync_plan_position_e() { planner.set_e_position_mm(current_position[E_AXIS]); } + inline void set_current_to_destination() { COPY(current_position, destination); } #else void sync_plan_position_e(); + void set_current_to_destination(); #endif #if ENABLED(NEWPANEL) void lcd_setstatusPGM(const char* const message, const int8_t level); diff --git a/Marlin/ubl_motion.cpp b/Marlin/ubl_motion.cpp index 6d39f9570b..7e037d40a4 100644 --- a/Marlin/ubl_motion.cpp +++ b/Marlin/ubl_motion.cpp @@ -31,7 +31,12 @@ #include extern float destination[XYZE]; - extern void set_current_to_destination(); + + #if AVR_AT90USB1286_FAMILY // Teensyduino & Printrboard IDE extensions have compile errors without this + inline void set_current_to_destination() { COPY(current_position, destination); } + #else + extern void set_current_to_destination(); + #endif #if ENABLED(DELTA) From 8e0f3b7eba0bff68d58f3938d4c5a9dddee273db Mon Sep 17 00:00:00 2001 From: Tannoo Date: Wed, 28 Jun 2017 20:56:36 -0600 Subject: [PATCH 154/180] UBL radar map corrections --- Marlin/ubl_G29.cpp | 13 ++++--------- Marlin/ultralcd.cpp | 14 ++++++++++++-- 2 files changed, 16 insertions(+), 11 deletions(-) diff --git a/Marlin/ubl_G29.cpp b/Marlin/ubl_G29.cpp index f77f3746a0..84faa29dfe 100644 --- a/Marlin/ubl_G29.cpp +++ b/Marlin/ubl_G29.cpp @@ -45,9 +45,7 @@ void lcd_mesh_edit_setup(float initial); float lcd_mesh_edit(); void lcd_z_offset_edit_setup(float); - #if ENABLED(DOGLCD) - extern void _lcd_ubl_output_map_lcd(); - #endif + extern void _lcd_ubl_output_map_lcd(); float lcd_z_offset_edit(); #endif @@ -1522,7 +1520,7 @@ idle(); } while (!ubl_lcd_clicked()); - lcd_return_to_status(); + if (!ubl_lcd_map_control) lcd_return_to_status(); // The technique used here generates a race condition for the encoder click. // It could get detected in lcd_mesh_edit (actually _lcd_mesh_fine_tune) or here. @@ -1569,11 +1567,8 @@ LCD_MESSAGEPGM(MSG_UBL_DONE_EDITING_MESH); SERIAL_ECHOLNPGM("Done Editing Mesh"); - if (ubl_lcd_map_control) { - #if ENABLED(DOGLCD) - lcd_goto_screen(_lcd_ubl_output_map_lcd); - #endif - } + if (ubl_lcd_map_control) + lcd_goto_screen(_lcd_ubl_output_map_lcd); else lcd_return_to_status(); } diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index 2b45f81330..3cd0dac5dc 100644 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -547,6 +547,15 @@ uint16_t max_display_update_time = 0; void lcd_status_screen() { + #if DISABLED(DOGLCD) && ENABLED(AUTO_BED_LEVELING_UBL) + if(!ubl_lcd_map_control) + lcd_set_custom_characters( + #if ENABLED(LCD_PROGRESS_BAR) + const bool info_screen_charset = true + #endif + ); + #endif + #if ENABLED(ULTIPANEL) ENCODER_DIRECTION_NORMAL(); ENCODER_RATE_MULTIPLY(false); @@ -2158,8 +2167,6 @@ void kill_screen(const char* lcd_msg) { void _lcd_ubl_map_lcd_edit_cmd() { char ubl_lcd_gcode [50], str[10], str2[10]; - ubl_lcd_map_control = true; // Used for returning to the map screen - dtostrf(pgm_read_float(&ubl._mesh_index_to_xpos[x_plot]), 0, 2, str); dtostrf(pgm_read_float(&ubl._mesh_index_to_ypos[y_plot]), 0, 2, str2); snprintf_P(ubl_lcd_gcode, sizeof(ubl_lcd_gcode), PSTR("G29 P4 X%s Y%s R%i"), str, str2, n_edit_pts); @@ -2253,6 +2260,7 @@ void kill_screen(const char* lcd_msg) { * UBL Homing before LCD map */ void _lcd_ubl_output_map_lcd_cmd() { + ubl_lcd_map_control = true; // Used for returning to the map screen if (!(axis_known_position[X_AXIS] && axis_known_position[Y_AXIS] && axis_known_position[Z_AXIS])) enqueue_and_echo_commands_P(PSTR("G28")); lcd_goto_screen(_lcd_ubl_map_homing); @@ -2393,6 +2401,8 @@ 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")); #endif #if HAS_M206_COMMAND From f17bae1f703356005b997422e32f5ac231659193 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 1 Jul 2017 18:33:54 -0500 Subject: [PATCH 155/180] Changes for ubl_lcd_map_control patch --- Marlin/Marlin_main.cpp | 12 ++++-------- Marlin/ubl_G29.cpp | 4 ++-- Marlin/ultralcd.cpp | 22 ++++++++++------------ Marlin/ultralcd.h | 1 + 4 files changed, 17 insertions(+), 22 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 2ed85a398d..98fb0e60b0 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -333,7 +333,6 @@ #if ENABLED(AUTO_BED_LEVELING_UBL) #include "ubl.h" extern bool defer_return_to_status; - extern bool ubl_lcd_map_control; unified_bed_leveling ubl; #define UBL_MESH_VALID !( ( ubl.z_values[0][0] == ubl.z_values[0][1] && ubl.z_values[0][1] == ubl.z_values[0][2] \ && ubl.z_values[1][0] == ubl.z_values[1][1] && ubl.z_values[1][1] == ubl.z_values[1][2] \ @@ -7742,11 +7741,9 @@ inline void gcode_M18_M84() { #endif } - #if ENABLED(AUTO_BED_LEVELING_UBL) && ENABLED(ULTRA_LCD) //only needed if have an LCD - ubl_lcd_map_control = false; - defer_return_to_status = false; + #if ENABLED(AUTO_BED_LEVELING_UBL) && ENABLED(ULTRA_LCD) // Only needed with an LCD + ubl_lcd_map_control = defer_return_to_status = false; #endif - } } @@ -12637,9 +12634,8 @@ void manage_inactivity(bool ignore_stepper_queue/*=false*/) { #if ENABLED(DISABLE_INACTIVE_E) disable_e_steppers(); #endif - #if ENABLED(AUTO_BED_LEVELING_UBL) && ENABLED(ULTRA_LCD) //only needed if have an LCD - ubl_lcd_map_control = false; - defer_return_to_status = false; + #if ENABLED(AUTO_BED_LEVELING_UBL) && ENABLED(ULTRA_LCD) // Only needed with an LCD + ubl_lcd_map_control = defer_return_to_status = false; #endif } diff --git a/Marlin/ubl_G29.cpp b/Marlin/ubl_G29.cpp index 84faa29dfe..e0b27cb9c0 100644 --- a/Marlin/ubl_G29.cpp +++ b/Marlin/ubl_G29.cpp @@ -54,7 +54,6 @@ extern float probe_pt(const float &x, const float &y, bool, int); extern bool set_probe_deployed(bool); extern void set_bed_leveling_enabled(bool); - extern bool ubl_lcd_map_control; typedef void (*screenFunc_t)(); extern void lcd_goto_screen(screenFunc_t screen, const uint32_t encoder = 0); @@ -1569,7 +1568,8 @@ if (ubl_lcd_map_control) lcd_goto_screen(_lcd_ubl_output_map_lcd); - else lcd_return_to_status(); + else + lcd_return_to_status(); } #endif // NEWPANEL diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index 3cd0dac5dc..c9168db977 100644 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -470,8 +470,14 @@ uint16_t max_display_update_time = 0; screen_history_depth = 0; } lcd_implementation_clear(); - #if ENABLED(LCD_PROGRESS_BAR) - // For LCD_PROGRESS_BAR re-initialize custom characters + // Re-initialize custom characters that may be re-used + #if DISABLED(DOGLCD) && ENABLED(AUTO_BED_LEVELING_UBL) + if (!ubl_lcd_map_control) lcd_set_custom_characters( + #if ENABLED(LCD_PROGRESS_BAR) + screen == lcd_status_screen + #endif + ); + #elif ENABLED(LCD_PROGRESS_BAR) lcd_set_custom_characters(screen == lcd_status_screen); #endif lcdDrawUpdate = LCDVIEW_CALL_REDRAW_NEXT; @@ -547,15 +553,6 @@ uint16_t max_display_update_time = 0; void lcd_status_screen() { - #if DISABLED(DOGLCD) && ENABLED(AUTO_BED_LEVELING_UBL) - if(!ubl_lcd_map_control) - lcd_set_custom_characters( - #if ENABLED(LCD_PROGRESS_BAR) - const bool info_screen_charset = true - #endif - ); - #endif - #if ENABLED(ULTIPANEL) ENCODER_DIRECTION_NORMAL(); ENCODER_RATE_MULTIPLY(false); @@ -2151,6 +2148,7 @@ void kill_screen(const char* lcd_msg) { void _lcd_ubl_output_map_lcd(); void _lcd_ubl_map_homing() { + defer_return_to_status = true; if (lcdDrawUpdate) lcd_implementation_drawedit(PSTR(MSG_LEVEL_BED_HOMING), NULL); lcdDrawUpdate = LCDVIEW_CALL_NO_REDRAW; if (axis_homed[X_AXIS] && axis_homed[Y_AXIS] && axis_homed[Z_AXIS]) { @@ -2260,7 +2258,7 @@ void kill_screen(const char* lcd_msg) { * UBL Homing before LCD map */ void _lcd_ubl_output_map_lcd_cmd() { - ubl_lcd_map_control = true; // Used for returning to the map screen + 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])) enqueue_and_echo_commands_P(PSTR("G28")); lcd_goto_screen(_lcd_ubl_map_homing); diff --git a/Marlin/ultralcd.h b/Marlin/ultralcd.h index 2fb719bb8c..909c13d408 100644 --- a/Marlin/ultralcd.h +++ b/Marlin/ultralcd.h @@ -188,6 +188,7 @@ void lcd_reset_status(); #if ENABLED(AUTO_BED_LEVELING_UBL) + extern bool ubl_lcd_map_control; void lcd_mesh_edit_setup(float initial); float lcd_mesh_edit(); void lcd_z_offset_edit_setup(float); From abd6ba62b4a13f24bbdbfc2a358b43b43d3f50d4 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 1 Jul 2017 18:34:52 -0500 Subject: [PATCH 156/180] Some cleanups for ubl lcd mesh map --- Marlin/Conditionals_LCD.h | 6 ++++++ Marlin/ultralcd.cpp | 29 +++++++---------------------- Marlin/ultralcd_impl_HD44780.h | 8 ++++---- 3 files changed, 17 insertions(+), 26 deletions(-) diff --git a/Marlin/Conditionals_LCD.h b/Marlin/Conditionals_LCD.h index 791a41d28c..7aa96deae4 100644 --- a/Marlin/Conditionals_LCD.h +++ b/Marlin/Conditionals_LCD.h @@ -273,6 +273,12 @@ #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/ultralcd.cpp b/Marlin/ultralcd.cpp index c9168db977..d58b2dc37e 100644 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -2188,28 +2188,24 @@ void kill_screen(const char* lcd_msg) { void _lcd_ubl_output_map_lcd() { static int16_t step_scaler = 0; - int32_t signed_enc_pos; - defer_return_to_status = true; + if (!(axis_known_position[X_AXIS] && axis_known_position[Y_AXIS] && axis_known_position[Z_AXIS])) + return lcd_goto_screen(_lcd_ubl_map_homing); - if (axis_known_position[X_AXIS] && axis_known_position[Y_AXIS] && axis_known_position[Z_AXIS]) { - - if (lcd_clicked) { return _lcd_ubl_map_lcd_edit_cmd(); } + if (lcd_clicked) return _lcd_ubl_map_lcd_edit_cmd(); ENCODER_DIRECTION_NORMAL(); if (encoderPosition) { - signed_enc_pos = (int32_t)encoderPosition; - step_scaler += signed_enc_pos; + step_scaler += (int32_t)encoderPosition; x_plot += step_scaler / (ENCODER_STEPS_PER_MENU_ITEM); if (abs(step_scaler) >= ENCODER_STEPS_PER_MENU_ITEM) step_scaler = 0; refresh_cmd_timeout(); + encoderPosition = 0; lcdDrawUpdate = LCDVIEW_REDRAW_NOW; } - encoderPosition = 0; - // Encoder to the right (++) if (x_plot >= GRID_MAX_POINTS_X) { x_plot = 0; y_plot++; } if (y_plot >= GRID_MAX_POINTS_Y) y_plot = 0; @@ -2236,22 +2232,11 @@ 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 - #define ENABLE_STEPPER_DRIVER_INTERRUPT() SBI(TIMSK1, OCIE1A) - #define DISABLE_STEPPER_DRIVER_INTERRUPT() CBI(TIMSK1, OCIE1A) - DISABLE_STEPPER_DRIVER_INTERRUPT(); - while (planner.blocks_queued()) planner.discard_current_block(); - stepper.current_block = NULL; - planner.clear_block_buffer_runtime(); - ENABLE_STEPPER_DRIVER_INTERRUPT(); - set_current_from_steppers_for_axis(ALL_AXES); - sync_plan_position(); + if (planner.movesplanned() > 1) { // if the nozzle is moving, cancel the move. There is a new location + quickstop_stepper(); ubl_map_move_to_xy(); // Move to new location } } - safe_delay(10); - } - else lcd_goto_screen(_lcd_ubl_map_homing); } /** diff --git a/Marlin/ultralcd_impl_HD44780.h b/Marlin/ultralcd_impl_HD44780.h index 2824ed0882..24280f7889 100644 --- a/Marlin/ultralcd_impl_HD44780.h +++ b/Marlin/ultralcd_impl_HD44780.h @@ -1134,8 +1134,8 @@ static void lcd_implementation_status_screen() { B00000, B11111 }; - createChar_P(1, _lcd_box_top); - createChar_P(2, _lcd_box_bottom); + createChar_P(LCD_UBL_BOXTOP_CHAR, _lcd_box_top); + createChar_P(LCD_UBL_BOXBOT_CHAR, _lcd_box_bottom); #endif } @@ -1178,8 +1178,8 @@ static void lcd_implementation_status_screen() { * Draw the Mesh Map Box */ uint8_t m; - lcd.setCursor(_MAP_X, 0); for (m = 0; m < 5; m++) lcd.write(1); // Top - lcd.setCursor(_MAP_X, 3); for (m = 0; m < 5; m++) lcd.write(2); // Bottom + 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 From 4cb45c10dd51150d932db9b33f75cdcf21fbd23a Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 1 Jul 2017 18:37:33 -0500 Subject: [PATCH 157/180] Patch ubl lcd mesh map indentation --- Marlin/ultralcd.cpp | 84 +++++------ Marlin/ultralcd_impl_HD44780.h | 254 ++++++++++++++++----------------- 2 files changed, 169 insertions(+), 169 deletions(-) diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index d58b2dc37e..7803a72c4a 100644 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -2192,51 +2192,51 @@ void kill_screen(const char* lcd_msg) { if (!(axis_known_position[X_AXIS] && axis_known_position[Y_AXIS] && axis_known_position[Z_AXIS])) return lcd_goto_screen(_lcd_ubl_map_homing); - if (lcd_clicked) return _lcd_ubl_map_lcd_edit_cmd(); - ENCODER_DIRECTION_NORMAL(); + if (lcd_clicked) return _lcd_ubl_map_lcd_edit_cmd(); + ENCODER_DIRECTION_NORMAL(); - if (encoderPosition) { - step_scaler += (int32_t)encoderPosition; - x_plot += step_scaler / (ENCODER_STEPS_PER_MENU_ITEM); - if (abs(step_scaler) >= ENCODER_STEPS_PER_MENU_ITEM) - step_scaler = 0; - refresh_cmd_timeout(); + if (encoderPosition) { + step_scaler += (int32_t)encoderPosition; + x_plot += step_scaler / (ENCODER_STEPS_PER_MENU_ITEM); + if (abs(step_scaler) >= ENCODER_STEPS_PER_MENU_ITEM) + step_scaler = 0; + refresh_cmd_timeout(); - encoderPosition = 0; - lcdDrawUpdate = LCDVIEW_REDRAW_NOW; - } - - // Encoder to the right (++) - if (x_plot >= GRID_MAX_POINTS_X) { x_plot = 0; y_plot++; } - if (y_plot >= GRID_MAX_POINTS_Y) y_plot = 0; - - // Encoder to the left (--) - if (x_plot <= GRID_MAX_POINTS_X - (GRID_MAX_POINTS_X + 1)) { x_plot = GRID_MAX_POINTS_X - 1; y_plot--; } - if (y_plot <= GRID_MAX_POINTS_Y - (GRID_MAX_POINTS_Y + 1)) y_plot = GRID_MAX_POINTS_Y - 1; - - // Prevent underrun/overrun of plot numbers - x_plot = constrain(x_plot, GRID_MAX_POINTS_X - (GRID_MAX_POINTS_X + 1), GRID_MAX_POINTS_X + 1); - y_plot = constrain(y_plot, GRID_MAX_POINTS_Y - (GRID_MAX_POINTS_Y + 1), GRID_MAX_POINTS_Y + 1); - - // Determine number of points to edit - #if IS_KINEMATIC - n_edit_pts = 9; //TODO: Delta accessible edit points - #else - const bool xc = WITHIN(x_plot, 1, GRID_MAX_POINTS_X - 2), - yc = WITHIN(y_plot, 1, GRID_MAX_POINTS_Y - 2); - n_edit_pts = yc ? (xc ? 9 : 6) : (xc ? 6 : 4); // Corners - #endif - - if (lcdDrawUpdate) { - lcd_implementation_ubl_plot(x_plot, y_plot); - - 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(); - ubl_map_move_to_xy(); // Move to new location - } + encoderPosition = 0; + lcdDrawUpdate = LCDVIEW_REDRAW_NOW; + } + + // Encoder to the right (++) + if (x_plot >= GRID_MAX_POINTS_X) { x_plot = 0; y_plot++; } + if (y_plot >= GRID_MAX_POINTS_Y) y_plot = 0; + + // Encoder to the left (--) + if (x_plot <= GRID_MAX_POINTS_X - (GRID_MAX_POINTS_X + 1)) { x_plot = GRID_MAX_POINTS_X - 1; y_plot--; } + if (y_plot <= GRID_MAX_POINTS_Y - (GRID_MAX_POINTS_Y + 1)) y_plot = GRID_MAX_POINTS_Y - 1; + + // Prevent underrun/overrun of plot numbers + x_plot = constrain(x_plot, GRID_MAX_POINTS_X - (GRID_MAX_POINTS_X + 1), GRID_MAX_POINTS_X + 1); + y_plot = constrain(y_plot, GRID_MAX_POINTS_Y - (GRID_MAX_POINTS_Y + 1), GRID_MAX_POINTS_Y + 1); + + // Determine number of points to edit + #if IS_KINEMATIC + n_edit_pts = 9; //TODO: Delta accessible edit points + #else + const bool xc = WITHIN(x_plot, 1, GRID_MAX_POINTS_X - 2), + yc = WITHIN(y_plot, 1, GRID_MAX_POINTS_Y - 2); + n_edit_pts = yc ? (xc ? 9 : 6) : (xc ? 6 : 4); // Corners + #endif + + if (lcdDrawUpdate) { + lcd_implementation_ubl_plot(x_plot, y_plot); + + 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(); + ubl_map_move_to_xy(); // Move to new location } + } } /** diff --git a/Marlin/ultralcd_impl_HD44780.h b/Marlin/ultralcd_impl_HD44780.h index 24280f7889..40187f79a8 100644 --- a/Marlin/ultralcd_impl_HD44780.h +++ b/Marlin/ultralcd_impl_HD44780.h @@ -1085,151 +1085,151 @@ static void lcd_implementation_status_screen() { #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. - */ + /* + * 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| + */ - 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 - } + 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 + } - void lcd_implementation_ubl_plot(const uint8_t x_plot, const uint8_t y_plot) { + void lcd_implementation_ubl_plot(const uint8_t x_plot, const uint8_t y_plot) { - #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 + #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 - #if LCD_HEIGHT <= 3 // 16x2 or 20x2 display - - /** - * 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])))); - - _YLABEL(_LCD_W_POS, 0); - lcd.print(ftostr32(LOGICAL_Y_POSITION(pgm_read_float(&ubl._mesh_index_to_ypos[y_plot])))); - - lcd.setCursor(_PLOT_X, 0); - - #else // 16x4 or 20x4 display - - /** - * Draw the Mesh Map Box - */ - 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 - } - - lcd.setCursor(_LCD_W_POS, 0); - - #endif + #if LCD_HEIGHT <= 3 // 16x2 or 20x2 display /** - * Print plot position + * Show X and Y positions */ - lcd.write('('); - lcd.print(x_plot); - lcd.write(','); - lcd.print(y_plot); - lcd.write(')'); + _XLABEL(_PLOT_X, 0); + lcd.print(ftostr32(LOGICAL_X_POSITION(pgm_read_float(&ubl._mesh_index_to_xpos[x_plot])))); - #if LCD_HEIGHT <= 3 // 16x2 or 20x2 display + _YLABEL(_LCD_W_POS, 0); + lcd.print(ftostr32(LOGICAL_Y_POSITION(pgm_read_float(&ubl._mesh_index_to_ypos[y_plot])))); - /** - * 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])); - else - lcd_printPGM(PSTR(" -----")); + lcd.setCursor(_PLOT_X, 0); - #else // 16x4 or 20x4 display + #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_plot])))); - _YLABEL(_LCD_W_POS, 2); - lcd.print(ftostr32(LOGICAL_Y_POSITION(pgm_read_float(&ubl._mesh_index_to_ypos[y_plot])))); + /** + * Draw the Mesh Map Box + */ + 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 + } - /** - * 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])); - else - lcd_printPGM(PSTR(" -----")); + lcd.setCursor(_LCD_W_POS, 0); - #endif // LCD_HEIGHT > 3 - } + #endif + + /** + * Print plot position + */ + lcd.write('('); + lcd.print(x_plot); + lcd.write(','); + lcd.print(y_plot); + lcd.write(')'); + + #if LCD_HEIGHT <= 3 // 16x2 or 20x2 display + + /** + * 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])); + 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_plot])))); + _YLABEL(_LCD_W_POS, 2); + lcd.print(ftostr32(LOGICAL_Y_POSITION(pgm_read_float(&ubl._mesh_index_to_ypos[y_plot])))); + + /** + * 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])); + else + lcd_printPGM(PSTR(" -----")); + + #endif // LCD_HEIGHT > 3 + } #endif // AUTO_BED_LEVELING_UBL From 1ff7d10c8002be37ef419029f1f84df21620da65 Mon Sep 17 00:00:00 2001 From: Tom Date: Wed, 31 May 2017 16:44:25 +0200 Subject: [PATCH 158/180] Add configuration for Infitary M508 (i3 clone) Based on Infitary's own firmware settings. --- .../Infitary-i3-M508/Configuration.h | 1588 +++++++++++++++++ .../Infitary-i3-M508/Configuration_adv.h | 1260 +++++++++++++ 2 files changed, 2848 insertions(+) create mode 100644 Marlin/example_configurations/Infitary-i3-M508/Configuration.h create mode 100644 Marlin/example_configurations/Infitary-i3-M508/Configuration_adv.h diff --git a/Marlin/example_configurations/Infitary-i3-M508/Configuration.h b/Marlin/example_configurations/Infitary-i3-M508/Configuration.h new file mode 100644 index 0000000000..78c3a341d0 --- /dev/null +++ b/Marlin/example_configurations/Infitary-i3-M508/Configuration.h @@ -0,0 +1,1588 @@ +/** + * 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 replace the configuration files with the files in the +// example_configurations/delta directory. +// + +//=========================================================================== +//============================= SCARA Printer =============================== +//=========================================================================== +// For a Scara printer replace the configuration files with the files in the +// example_configurations/SCARA directory. +// + +// @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 "(tjclement, Infitary M508)" // 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_RAMPS_13_EFB +#endif + +// Optional custom name for your RepStrap or other custom machine +// Displayed in the LCD "Ready" message +#define CUSTOM_MACHINE_NAME "Infitary M508" + +// 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 + +// 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 +#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 125 + +//=========================================================================== +//============================= 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 + + #define DEFAULT_Kp 213.2 + #define DEFAULT_Ki 1.54 + #define DEFAULT_Kd 765 + +#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 true // set to true to invert the logic of the endstop. +#define Y_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. +#define Z_MIN_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. +#define X_MAX_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. +#define Y_MAX_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. +#define Z_MAX_ENDSTOP_INVERTING true // set to true to invert the logic of the endstop. +#define Z_MIN_PROBE_ENDSTOP_INVERTING true // 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 { 100, 100, 400, 92.6 } + +/** + * Default Max Feed Rate (mm/s) + * Override with M203 + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] + */ +#define DEFAULT_MAX_FEEDRATE { 400, 400, 5, 25 } + +/** + * Default Max Acceleration (change/s) change = mm/s + * (Maximum start speed for accelerated moves) + * Override with M201 + * X, Y, Z, E0 [, E1[, E2[, E3[, E4]]]] + */ +#define DEFAULT_MAX_ACCELERATION { 9000, 9000, 100, 10000 } + +/** + * Default Acceleration (change/s) change = mm/s + * Override with M204 + * + * M204 P Acceleration + * M204 R Retract Acceleration + * M204 T Travel Acceleration + */ +#define DEFAULT_ACCELERATION 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 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 +//#define Z_MIN_PROBE_PIN Z_MAX_PIN + +/** + * 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 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 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 + +// 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 205 +#define Y_MAX_POS 205 +#define Z_MAX_POS 185 + +// 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 // 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_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) + // 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 + +// +// 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 50 +#define PREHEAT_1_FAN_SPEED 0 // Value from 0 to 255 + +#define PREHEAT_2_TEMP_HOTEND 245 +#define PREHEAT_2_TEMP_BED 100 +#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, 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':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cn':'Chinese', 'cz':'Czech', 'de':'German', 'el':'Greek', 'el-gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'it':'Italian', 'kana':'Japanese', 'kana_utf8':'Japanese (UTF8)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt-br':'Portuguese (Brazilian)', 'pt-br_utf8':'Portuguese (Brazilian UTF8)', 'pt_utf8':'Portuguese (UTF8)', 'ru':'Russian', 'tr':'Turkish', 'uk':'Ukrainian', 'test':'TEST' } + */ +#define LCD_LANGUAGE en + +/** + * 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 + +// +// 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 + +// +// 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 +// +//#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 + +//define BlinkM/CyzRgb Support +//#define BLINKM + +/** + * 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) + #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 3.00 // (mm) Diameter of the filament generally used (3.0 or 1.75mm), also used in the slicer. Used to validate sensor reading. + +#if ENABLED(FILAMENT_WIDTH_SENSOR) + #define FILAMENT_SENSOR_EXTRUDER_NUM 0 // Index of the extruder that has the filament sensor (0,1,2,3) + #define MEASUREMENT_DELAY_CM 14 // (cm) The distance from the filament sensor to the melting chamber + + #define MEASURED_UPPER_LIMIT 3.30 // (mm) Upper limit used to validate sensor reading + #define MEASURED_LOWER_LIMIT 1.90 // (mm) Lower limit used to validate sensor reading + #define MAX_MEASUREMENT_DELAY 20 // (bytes) Buffer size for stored measurements (1 byte per cm). Must be larger than MEASUREMENT_DELAY_CM. + + #define DEFAULT_MEASURED_FILAMENT_DIA DEFAULT_NOMINAL_FILAMENT_DIA // Set measured to nominal initially + + // Display filament width on the LCD status line. Status messages will expire after 5 seconds. + //#define FILAMENT_LCD_DISPLAY +#endif + +#endif // CONFIGURATION_H diff --git a/Marlin/example_configurations/Infitary-i3-M508/Configuration_adv.h b/Marlin/example_configurations/Infitary-i3-M508/Configuration_adv.h new file mode 100644 index 0000000000..373783338b --- /dev/null +++ b/Marlin/example_configurations/Infitary-i3-M508/Configuration_adv.h @@ -0,0 +1,1260 @@ +/** + * 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 +//The M105 command return, besides traditional information, the ADC value 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 + +// Define a pin to turn case light on/off +//#define CASE_LIGHT_PIN 4 +#if PIN_EXISTS(CASE_LIGHT) + #define INVERT_CASE_LIGHT false // Set to true if HIGH is the OFF state (active low) + //#define CASE_LIGHT_DEFAULT_ON // Uncomment to set default state to on + //#define MENU_ITEM_CASE_LIGHT // Uncomment to have a Case Light On / Off entry in main menu +#endif + +//=========================================================================== +//============================ Mechanical Settings ========================== +//=========================================================================== + +// @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 command 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 1 +#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 +#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 Prusa Slic3r) 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 (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)) +#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)) + + // 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 + +// Arc interpretation settings: +#define ARC_SUPPORT // Disabling this saves ~2738 bytes +#define MM_PER_ARC_SEGMENT 1 +#define N_ARC_CORRECTION 25 + +// 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 fwretract + +// Firmware based and LCD controlled retract +// M207 and M208 can be used to define parameters for the retraction. +// The retraction can be called by the slicer using G10 and G11 +// until then, intended retractions can be detected by moves that only extrude and the direction. +// the moves are than replaced by the firmware controlled ones. + +//#define FWRETRACT //ONLY PARTIALLY TESTED +#if ENABLED(FWRETRACT) + #define MIN_RETRACT 0.1 //minimum extruded mm to accept a automatic gcode retraction attempt + #define RETRACT_LENGTH 3 //default retract length (positive mm) + #define RETRACT_LENGTH_SWAP 13 //default swap retract length (positive mm), for extruder change + #define RETRACT_FEEDRATE 45 //default feedrate for retracting (mm/s) + #define RETRACT_ZLIFT 0 //default retract Z-lift + #define RETRACT_RECOVER_LENGTH 0 //default additional recover length (mm, added to retract length when recovering) + #define RETRACT_RECOVER_LENGTH_SWAP 0 //default additional swap recover length (mm, added to retract length when recovering from extruder change) + #define RETRACT_RECOVER_FEEDRATE 8 //default feedrate for recovering from retraction (mm/s) +#endif + +/** + * 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 +#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 // ENABLED(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_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 + +#endif // CONFIGURATION_ADV_H From dcec7178d17445be1b4181131ab82645a6057042 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 1 Jul 2017 21:30:46 -0500 Subject: [PATCH 159/180] Expose DISABLE_M503 option as a test option --- Marlin/Configuration.h | 4 ++-- Marlin/Marlin_main.cpp | 23 +++++++++++-------- Marlin/configuration_store.cpp | 2 +- Marlin/configuration_store.h | 2 +- .../Anet/A6/Configuration.h | 4 ++-- .../Anet/A8/Configuration.h | 4 ++-- .../CL-260/Configuration.h | 4 ++-- .../Cartesio/Configuration.h | 4 ++-- .../Felix/Configuration.h | 4 ++-- .../Felix/DUAL/Configuration.h | 4 ++-- .../FolgerTech-i3-2020/Configuration.h | 4 ++-- .../Hephestos/Configuration.h | 4 ++-- .../Hephestos_2/Configuration.h | 4 ++-- .../K8200/Configuration.h | 4 ++-- .../K8400/Configuration.h | 4 ++-- .../K8400/Dual-head/Configuration.h | 4 ++-- .../M150/Configuration.h | 4 ++-- .../RepRapWorld/Megatronics/Configuration.h | 4 ++-- .../RigidBot/Configuration.h | 4 ++-- .../SCARA/Configuration.h | 4 ++-- .../TAZ4/Configuration.h | 4 ++-- .../TinyBoy2/Configuration.h | 4 ++-- .../WITBOX/Configuration.h | 4 ++-- .../adafruit/ST7565/Configuration.h | 4 ++-- .../FLSUN/auto_calibrate/Configuration.h | 4 ++-- .../delta/FLSUN/kossel_mini/Configuration.h | 4 ++-- .../delta/generic/Configuration.h | 4 ++-- .../delta/kossel_mini/Configuration.h | 4 ++-- .../delta/kossel_pro/Configuration.h | 4 ++-- .../delta/kossel_xl/Configuration.h | 4 ++-- .../gCreate_gMax1.5+/Configuration.h | 4 ++-- .../makibox/Configuration.h | 4 ++-- .../tvrrug/Round2/Configuration.h | 4 ++-- .../wt150/Configuration.h | 4 ++-- 34 files changed, 78 insertions(+), 73 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 082d5a999a..05e193f13a 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -992,8 +992,8 @@ //#define EEPROM_SETTINGS #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. + //#define DISABLE_M503 // Saves ~2700 bytes of PROGMEM. Disable for release! + #define EEPROM_CHITCHAT // Print a report on M500. Please keep turned on. #endif // diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 98fb0e60b0..f19a89818b 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -9279,12 +9279,14 @@ inline void gcode_M502() { (void)settings.reset(); } -/** - * M503: print settings currently in memory - */ -inline void gcode_M503() { - (void)settings.report(!parser.boolval('S', true)); -} +#if DISABLED(DISABLE_M503) + /** + * M503: print settings currently in memory + */ + inline void gcode_M503() { + (void)settings.report(!parser.boolval('S', true)); + } +#endif #if ENABLED(ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED) @@ -11022,9 +11024,12 @@ void process_next_command() { case 502: // M502: Revert to default settings gcode_M502(); break; - case 503: // M503: print settings currently in memory - gcode_M503(); - break; + + #if DISABLED(DISABLE_M503) + case 503: // M503: print settings currently in memory + gcode_M503(); + break; + #endif #if ENABLED(ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED) case 540: // M540: Set abort on endstop hit for SD printing diff --git a/Marlin/configuration_store.cpp b/Marlin/configuration_store.cpp index 840d6b88f5..8dd5eedef1 100644 --- a/Marlin/configuration_store.cpp +++ b/Marlin/configuration_store.cpp @@ -1051,7 +1051,7 @@ void MarlinSettings::postprocess() { #endif } - #if ENABLED(EEPROM_CHITCHAT) + #if ENABLED(EEPROM_CHITCHAT) && DISABLED(DISABLE_M503) report(); #endif diff --git a/Marlin/configuration_store.h b/Marlin/configuration_store.h index 23a716a94f..99e9511209 100644 --- a/Marlin/configuration_store.h +++ b/Marlin/configuration_store.h @@ -55,7 +55,7 @@ class MarlinSettings { static void report(bool forReplay=false); #else FORCE_INLINE - static void report(bool forReplay=false) { } + static void report(bool forReplay=false) { UNUSED(forReplay); } #endif private: diff --git a/Marlin/example_configurations/Anet/A6/Configuration.h b/Marlin/example_configurations/Anet/A6/Configuration.h index 4e954bae10..a05c5864ac 100644 --- a/Marlin/example_configurations/Anet/A6/Configuration.h +++ b/Marlin/example_configurations/Anet/A6/Configuration.h @@ -1148,8 +1148,8 @@ #define EEPROM_SETTINGS #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. + //#define DISABLE_M503 // Saves ~2700 bytes of PROGMEM. Disable for release! + #define EEPROM_CHITCHAT // Print a report on M500. Please keep turned on. #endif // diff --git a/Marlin/example_configurations/Anet/A8/Configuration.h b/Marlin/example_configurations/Anet/A8/Configuration.h index 070121fa61..3cae7b59ba 100644 --- a/Marlin/example_configurations/Anet/A8/Configuration.h +++ b/Marlin/example_configurations/Anet/A8/Configuration.h @@ -998,8 +998,8 @@ #define EEPROM_SETTINGS #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. + //#define DISABLE_M503 // Saves ~2700 bytes of PROGMEM. Disable for release! + #define EEPROM_CHITCHAT // Print a report on M500. Please keep turned on. #endif // diff --git a/Marlin/example_configurations/CL-260/Configuration.h b/Marlin/example_configurations/CL-260/Configuration.h index a8cad55df7..f10203a21c 100644 --- a/Marlin/example_configurations/CL-260/Configuration.h +++ b/Marlin/example_configurations/CL-260/Configuration.h @@ -989,8 +989,8 @@ //#define EEPROM_SETTINGS #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. + //#define DISABLE_M503 // Saves ~2700 bytes of PROGMEM. Disable for release! + #define EEPROM_CHITCHAT // Print a report on M500. Please keep turned on. #endif // diff --git a/Marlin/example_configurations/Cartesio/Configuration.h b/Marlin/example_configurations/Cartesio/Configuration.h index ac543164c8..1e195fff02 100644 --- a/Marlin/example_configurations/Cartesio/Configuration.h +++ b/Marlin/example_configurations/Cartesio/Configuration.h @@ -986,8 +986,8 @@ //#define EEPROM_SETTINGS #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. + //#define DISABLE_M503 // Saves ~2700 bytes of PROGMEM. Disable for release! + #define EEPROM_CHITCHAT // Print a report on M500. Please keep turned on. #endif // diff --git a/Marlin/example_configurations/Felix/Configuration.h b/Marlin/example_configurations/Felix/Configuration.h index a7dcb118cf..c339a163c0 100644 --- a/Marlin/example_configurations/Felix/Configuration.h +++ b/Marlin/example_configurations/Felix/Configuration.h @@ -970,8 +970,8 @@ //#define EEPROM_SETTINGS #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. + //#define DISABLE_M503 // Saves ~2700 bytes of PROGMEM. Disable for release! + #define EEPROM_CHITCHAT // Print a report on M500. Please keep turned on. #endif // diff --git a/Marlin/example_configurations/Felix/DUAL/Configuration.h b/Marlin/example_configurations/Felix/DUAL/Configuration.h index 7904e3cc56..26cfe57745 100644 --- a/Marlin/example_configurations/Felix/DUAL/Configuration.h +++ b/Marlin/example_configurations/Felix/DUAL/Configuration.h @@ -970,8 +970,8 @@ //#define EEPROM_SETTINGS #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. + //#define DISABLE_M503 // Saves ~2700 bytes of PROGMEM. Disable for release! + #define EEPROM_CHITCHAT // Print a report on M500. Please keep turned on. #endif // diff --git a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h index 36ff1f2b4a..ac04018735 100644 --- a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h +++ b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h @@ -992,8 +992,8 @@ #define EEPROM_SETTINGS #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. + //#define DISABLE_M503 // Saves ~2700 bytes of PROGMEM. Disable for release! + #define EEPROM_CHITCHAT // Print a report on M500. Please keep turned on. #endif // diff --git a/Marlin/example_configurations/Hephestos/Configuration.h b/Marlin/example_configurations/Hephestos/Configuration.h index dfa01e944a..a5d558f85d 100644 --- a/Marlin/example_configurations/Hephestos/Configuration.h +++ b/Marlin/example_configurations/Hephestos/Configuration.h @@ -978,8 +978,8 @@ //#define EEPROM_SETTINGS #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. + //#define DISABLE_M503 // Saves ~2700 bytes of PROGMEM. Disable for release! + #define EEPROM_CHITCHAT // Print a report on M500. Please keep turned on. #endif // diff --git a/Marlin/example_configurations/Hephestos_2/Configuration.h b/Marlin/example_configurations/Hephestos_2/Configuration.h index 63767298e5..bcb6765744 100644 --- a/Marlin/example_configurations/Hephestos_2/Configuration.h +++ b/Marlin/example_configurations/Hephestos_2/Configuration.h @@ -981,8 +981,8 @@ #define EEPROM_SETTINGS #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. + //#define DISABLE_M503 // Saves ~2700 bytes of PROGMEM. Disable for release! + #define EEPROM_CHITCHAT // Print a report on M500. Please keep turned on. #endif // diff --git a/Marlin/example_configurations/K8200/Configuration.h b/Marlin/example_configurations/K8200/Configuration.h index 4ecaf9c8c8..6842ecf92b 100644 --- a/Marlin/example_configurations/K8200/Configuration.h +++ b/Marlin/example_configurations/K8200/Configuration.h @@ -1017,8 +1017,8 @@ #define EEPROM_SETTINGS // K8200: uses EEPROM by default #if ENABLED(EEPROM_SETTINGS) - // To disable EEPROM Serial responses and decrease program space by ~1700 byte: comment this out: - #define EEPROM_CHITCHAT // Please keep turned on if you can. + //#define DISABLE_M503 // Saves ~2700 bytes of PROGMEM. Disable for release! + #define EEPROM_CHITCHAT // Print a report on M500. Please keep turned on. #endif // diff --git a/Marlin/example_configurations/K8400/Configuration.h b/Marlin/example_configurations/K8400/Configuration.h index c7b0db6b3a..9a1dacf393 100644 --- a/Marlin/example_configurations/K8400/Configuration.h +++ b/Marlin/example_configurations/K8400/Configuration.h @@ -988,8 +988,8 @@ #define EEPROM_SETTINGS #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. + //#define DISABLE_M503 // Saves ~2700 bytes of PROGMEM. Disable for release! + #define EEPROM_CHITCHAT // Print a report on M500. Please keep turned on. #endif // diff --git a/Marlin/example_configurations/K8400/Dual-head/Configuration.h b/Marlin/example_configurations/K8400/Dual-head/Configuration.h index 68359941d2..8f23d29f46 100644 --- a/Marlin/example_configurations/K8400/Dual-head/Configuration.h +++ b/Marlin/example_configurations/K8400/Dual-head/Configuration.h @@ -988,8 +988,8 @@ #define EEPROM_SETTINGS #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. + //#define DISABLE_M503 // Saves ~2700 bytes of PROGMEM. Disable for release! + #define EEPROM_CHITCHAT // Print a report on M500. Please keep turned on. #endif // diff --git a/Marlin/example_configurations/M150/Configuration.h b/Marlin/example_configurations/M150/Configuration.h index c8043291a2..5e99290d83 100644 --- a/Marlin/example_configurations/M150/Configuration.h +++ b/Marlin/example_configurations/M150/Configuration.h @@ -1015,8 +1015,8 @@ #define EEPROM_SETTINGS #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. + //#define DISABLE_M503 // Saves ~2700 bytes of PROGMEM. Disable for release! + #define EEPROM_CHITCHAT // Print a report on M500. Please keep turned on. #endif // diff --git a/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h b/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h index e3a1599559..7369f7ac8d 100644 --- a/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h +++ b/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h @@ -988,8 +988,8 @@ //#define EEPROM_SETTINGS #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. + //#define DISABLE_M503 // Saves ~2700 bytes of PROGMEM. Disable for release! + #define EEPROM_CHITCHAT // Print a report on M500. Please keep turned on. #endif // diff --git a/Marlin/example_configurations/RigidBot/Configuration.h b/Marlin/example_configurations/RigidBot/Configuration.h index 5473a32073..799ad46dc3 100644 --- a/Marlin/example_configurations/RigidBot/Configuration.h +++ b/Marlin/example_configurations/RigidBot/Configuration.h @@ -986,8 +986,8 @@ #define EEPROM_SETTINGS #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. + //#define DISABLE_M503 // Saves ~2700 bytes of PROGMEM. Disable for release! + #define EEPROM_CHITCHAT // Print a report on M500. Please keep turned on. #endif // diff --git a/Marlin/example_configurations/SCARA/Configuration.h b/Marlin/example_configurations/SCARA/Configuration.h index d6a97d72e1..e04d12e863 100644 --- a/Marlin/example_configurations/SCARA/Configuration.h +++ b/Marlin/example_configurations/SCARA/Configuration.h @@ -1000,8 +1000,8 @@ //#define EEPROM_SETTINGS #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. + //#define DISABLE_M503 // Saves ~2700 bytes of PROGMEM. Disable for release! + #define EEPROM_CHITCHAT // Print a report on M500. Please keep turned on. #endif // diff --git a/Marlin/example_configurations/TAZ4/Configuration.h b/Marlin/example_configurations/TAZ4/Configuration.h index bdf7d94193..0b2897bced 100644 --- a/Marlin/example_configurations/TAZ4/Configuration.h +++ b/Marlin/example_configurations/TAZ4/Configuration.h @@ -1007,8 +1007,8 @@ #define EEPROM_SETTINGS #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. + //#define DISABLE_M503 // Saves ~2700 bytes of PROGMEM. Disable for release! + #define EEPROM_CHITCHAT // Print a report on M500. Please keep turned on. #endif // diff --git a/Marlin/example_configurations/TinyBoy2/Configuration.h b/Marlin/example_configurations/TinyBoy2/Configuration.h index b3f58f0cbd..4d35c063a6 100644 --- a/Marlin/example_configurations/TinyBoy2/Configuration.h +++ b/Marlin/example_configurations/TinyBoy2/Configuration.h @@ -1044,8 +1044,8 @@ #define EEPROM_SETTINGS #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. + //#define DISABLE_M503 // Saves ~2700 bytes of PROGMEM. Disable for release! + #define EEPROM_CHITCHAT // Print a report on M500. Please keep turned on. #endif // diff --git a/Marlin/example_configurations/WITBOX/Configuration.h b/Marlin/example_configurations/WITBOX/Configuration.h index cb280b3446..691abb4977 100644 --- a/Marlin/example_configurations/WITBOX/Configuration.h +++ b/Marlin/example_configurations/WITBOX/Configuration.h @@ -978,8 +978,8 @@ //#define EEPROM_SETTINGS #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. + //#define DISABLE_M503 // Saves ~2700 bytes of PROGMEM. Disable for release! + #define EEPROM_CHITCHAT // Print a report on M500. Please keep turned on. #endif // diff --git a/Marlin/example_configurations/adafruit/ST7565/Configuration.h b/Marlin/example_configurations/adafruit/ST7565/Configuration.h index 3b3cb2c4ce..5b1dbf648f 100644 --- a/Marlin/example_configurations/adafruit/ST7565/Configuration.h +++ b/Marlin/example_configurations/adafruit/ST7565/Configuration.h @@ -988,8 +988,8 @@ //#define EEPROM_SETTINGS #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. + //#define DISABLE_M503 // Saves ~2700 bytes of PROGMEM. Disable for release! + #define EEPROM_CHITCHAT // Print a report on M500. Please keep turned on. #endif // diff --git a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h index 8426456df3..6706efd51c 100644 --- a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h +++ b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h @@ -1108,8 +1108,8 @@ #define EEPROM_SETTINGS #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. + //#define DISABLE_M503 // Saves ~2700 bytes of PROGMEM. Disable for release! + #define EEPROM_CHITCHAT // Print a report on M500. Please keep turned on. #endif // diff --git a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h index 97ea09ca8c..8e402bcb0f 100644 --- a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h +++ b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h @@ -1110,8 +1110,8 @@ #define EEPROM_SETTINGS #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. + //#define DISABLE_M503 // Saves ~2700 bytes of PROGMEM. Disable for release! + #define EEPROM_CHITCHAT // Print a report on M500. Please keep turned on. #endif // diff --git a/Marlin/example_configurations/delta/generic/Configuration.h b/Marlin/example_configurations/delta/generic/Configuration.h index 2bc238b84d..2f69a232e1 100644 --- a/Marlin/example_configurations/delta/generic/Configuration.h +++ b/Marlin/example_configurations/delta/generic/Configuration.h @@ -1099,8 +1099,8 @@ //#define EEPROM_SETTINGS #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. + //#define DISABLE_M503 // Saves ~2700 bytes of PROGMEM. Disable for release! + #define EEPROM_CHITCHAT // Print a report on M500. Please keep turned on. #endif // diff --git a/Marlin/example_configurations/delta/kossel_mini/Configuration.h b/Marlin/example_configurations/delta/kossel_mini/Configuration.h index d2a21e3c91..9596a58c47 100644 --- a/Marlin/example_configurations/delta/kossel_mini/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_mini/Configuration.h @@ -1102,8 +1102,8 @@ //#define EEPROM_SETTINGS #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. + //#define DISABLE_M503 // Saves ~2700 bytes of PROGMEM. Disable for release! + #define EEPROM_CHITCHAT // Print a report on M500. Please keep turned on. #endif // diff --git a/Marlin/example_configurations/delta/kossel_pro/Configuration.h b/Marlin/example_configurations/delta/kossel_pro/Configuration.h index d321556c0b..6219756021 100644 --- a/Marlin/example_configurations/delta/kossel_pro/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_pro/Configuration.h @@ -1107,8 +1107,8 @@ //#define EEPROM_SETTINGS #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. + //#define DISABLE_M503 // Saves ~2700 bytes of PROGMEM. Disable for release! + #define EEPROM_CHITCHAT // Print a report on M500. Please keep turned on. #endif // diff --git a/Marlin/example_configurations/delta/kossel_xl/Configuration.h b/Marlin/example_configurations/delta/kossel_xl/Configuration.h index d9071e3f10..99271bf5f8 100644 --- a/Marlin/example_configurations/delta/kossel_xl/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_xl/Configuration.h @@ -1165,8 +1165,8 @@ #define EEPROM_SETTINGS #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. + //#define DISABLE_M503 // Saves ~2700 bytes of PROGMEM. Disable for release! + #define EEPROM_CHITCHAT // Print a report on M500. Please keep turned on. #endif // diff --git a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h index 727d5ac438..cde1f76480 100644 --- a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h +++ b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h @@ -1004,8 +1004,8 @@ #define EEPROM_SETTINGS #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. + //#define DISABLE_M503 // Saves ~2700 bytes of PROGMEM. Disable for release! + #define EEPROM_CHITCHAT // Print a report on M500. Please keep turned on. #endif // diff --git a/Marlin/example_configurations/makibox/Configuration.h b/Marlin/example_configurations/makibox/Configuration.h index 3580a15eb7..7992697dfc 100644 --- a/Marlin/example_configurations/makibox/Configuration.h +++ b/Marlin/example_configurations/makibox/Configuration.h @@ -991,8 +991,8 @@ #define EEPROM_SETTINGS #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. + //#define DISABLE_M503 // Saves ~2700 bytes of PROGMEM. Disable for release! + #define EEPROM_CHITCHAT // Print a report on M500. Please keep turned on. #endif // diff --git a/Marlin/example_configurations/tvrrug/Round2/Configuration.h b/Marlin/example_configurations/tvrrug/Round2/Configuration.h index 1eb267ccf0..8a54d17340 100644 --- a/Marlin/example_configurations/tvrrug/Round2/Configuration.h +++ b/Marlin/example_configurations/tvrrug/Round2/Configuration.h @@ -983,8 +983,8 @@ //#define EEPROM_SETTINGS #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. + //#define DISABLE_M503 // Saves ~2700 bytes of PROGMEM. Disable for release! + #define EEPROM_CHITCHAT // Print a report on M500. Please keep turned on. #endif // diff --git a/Marlin/example_configurations/wt150/Configuration.h b/Marlin/example_configurations/wt150/Configuration.h index cc324f83ec..9be759d373 100644 --- a/Marlin/example_configurations/wt150/Configuration.h +++ b/Marlin/example_configurations/wt150/Configuration.h @@ -994,8 +994,8 @@ #define EEPROM_SETTINGS #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. + //#define DISABLE_M503 // Saves ~2700 bytes of PROGMEM. Disable for release! + #define EEPROM_CHITCHAT // Print a report on M500. Please keep turned on. #endif // From cf96109056a303eda0bb45bdfc11f72bb884dfcd Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 1 Jul 2017 21:48:18 -0500 Subject: [PATCH 160/180] Implement the EEPROM_CHITCHAT option --- Marlin/configuration_store.cpp | 104 +++++++++++++++++++++------------ 1 file changed, 66 insertions(+), 38 deletions(-) diff --git a/Marlin/configuration_store.cpp b/Marlin/configuration_store.cpp index 8dd5eedef1..c86ba08599 100644 --- a/Marlin/configuration_store.cpp +++ b/Marlin/configuration_store.cpp @@ -655,10 +655,12 @@ void MarlinSettings::postprocess() { EEPROM_WRITE(final_crc); // Report storage size - SERIAL_ECHO_START(); - SERIAL_ECHOPAIR("Settings Stored (", eeprom_size - (EEPROM_OFFSET)); - SERIAL_ECHOPAIR(" bytes; crc ", final_crc); - SERIAL_ECHOLNPGM(")"); + #if ENABLED(EEPROM_CHITCHAT) + SERIAL_ECHO_START(); + SERIAL_ECHOPAIR("Settings Stored (", eeprom_size - (EEPROM_OFFSET)); + SERIAL_ECHOPAIR(" bytes; crc ", final_crc); + SERIAL_ECHOLNPGM(")"); + #endif } #if ENABLED(UBL_SAVE_ACTIVE_ON_M500) @@ -689,10 +691,12 @@ void MarlinSettings::postprocess() { stored_ver[0] = '?'; stored_ver[1] = '\0'; } - SERIAL_ECHO_START(); - SERIAL_ECHOPGM("EEPROM version mismatch "); - SERIAL_ECHOPAIR("(EEPROM=", stored_ver); - SERIAL_ECHOLNPGM(" Marlin=" EEPROM_VERSION ")"); + #if ENABLED(EEPROM_CHITCHAT) + SERIAL_ECHO_START(); + SERIAL_ECHOPGM("EEPROM version mismatch "); + SERIAL_ECHOPAIR("(EEPROM=", stored_ver); + SERIAL_ECHOLNPGM(" Marlin=" EEPROM_VERSION ")"); + #endif reset(); } else { @@ -1004,20 +1008,24 @@ void MarlinSettings::postprocess() { #endif if (working_crc == stored_crc) { - postprocess(); + postprocess(); + #if ENABLED(EEPROM_CHITCHAT) SERIAL_ECHO_START(); SERIAL_ECHO(version); SERIAL_ECHOPAIR(" stored settings retrieved (", eeprom_index - (EEPROM_OFFSET)); SERIAL_ECHOPAIR(" bytes; crc ", working_crc); SERIAL_ECHOLNPGM(")"); + #endif } else { - SERIAL_ERROR_START(); - SERIAL_ERRORPGM("EEPROM CRC mismatch - (stored) "); - SERIAL_ERROR(stored_crc); - SERIAL_ERRORPGM(" != "); - SERIAL_ERROR(working_crc); - SERIAL_ERRORLNPGM(" (calculated)!"); + #if ENABLED(EEPROM_CHITCHAT) + SERIAL_ERROR_START(); + SERIAL_ERRORPGM("EEPROM CRC mismatch - (stored) "); + SERIAL_ERROR(stored_crc); + SERIAL_ERRORPGM(" != "); + SERIAL_ERROR(working_crc); + SERIAL_ERRORLNPGM(" (calculated)!"); + #endif reset(); } @@ -1029,24 +1037,32 @@ void MarlinSettings::postprocess() { if (!ubl.sanity_check()) { SERIAL_EOL(); - ubl.echo_name(); - SERIAL_ECHOLNPGM(" initialized.\n"); + #if ENABLED(EEPROM_CHITCHAT) + ubl.echo_name(); + SERIAL_ECHOLNPGM(" initialized.\n"); + #endif } else { - SERIAL_PROTOCOLPGM("?Can't enable "); - ubl.echo_name(); - SERIAL_PROTOCOLLNPGM("."); + #if ENABLED(EEPROM_CHITCHAT) + SERIAL_PROTOCOLPGM("?Can't enable "); + ubl.echo_name(); + SERIAL_PROTOCOLLNPGM("."); + #endif ubl.reset(); } if (ubl.state.storage_slot >= 0) { load_mesh(ubl.state.storage_slot); - SERIAL_ECHOPAIR("Mesh ", ubl.state.storage_slot); - SERIAL_ECHOLNPGM(" loaded from storage."); + #if ENABLED(EEPROM_CHITCHAT) + SERIAL_ECHOPAIR("Mesh ", ubl.state.storage_slot); + SERIAL_ECHOLNPGM(" loaded from storage."); + #endif } else { ubl.reset(); - SERIAL_ECHOLNPGM("UBL System reset()"); + #if ENABLED(EEPROM_CHITCHAT) + SERIAL_ECHOLNPGM("UBL System reset()"); + #endif } #endif } @@ -1060,11 +1076,13 @@ void MarlinSettings::postprocess() { #if ENABLED(AUTO_BED_LEVELING_UBL) - void ubl_invalid_slot(const int s) { - SERIAL_PROTOCOLLNPGM("?Invalid slot."); - SERIAL_PROTOCOL(s); - SERIAL_PROTOCOLLNPGM(" mesh slots available."); - } + #if ENABLED(EEPROM_CHITCHAT) + void ubl_invalid_slot(const int s) { + SERIAL_PROTOCOLLNPGM("?Invalid slot."); + SERIAL_PROTOCOL(s); + SERIAL_PROTOCOLLNPGM(" mesh slots available."); + } + #endif int MarlinSettings::calc_num_meshes() { //obviously this will get more sophisticated once we've added an actual MAT @@ -1079,11 +1097,13 @@ void MarlinSettings::postprocess() { #if ENABLED(AUTO_BED_LEVELING_UBL) const int a = calc_num_meshes(); if (!WITHIN(slot, 0, a - 1)) { - ubl_invalid_slot(a); - SERIAL_PROTOCOLPAIR("E2END=", E2END); - SERIAL_PROTOCOLPAIR(" meshes_end=", meshes_end); - SERIAL_PROTOCOLLNPAIR(" slot=", slot); - SERIAL_EOL(); + #if ENABLED(EEPROM_CHITCHAT) + ubl_invalid_slot(a); + SERIAL_PROTOCOLPAIR("E2END=", E2END); + SERIAL_PROTOCOLPAIR(" meshes_end=", meshes_end); + SERIAL_PROTOCOLLNPAIR(" slot=", slot); + SERIAL_EOL(); + #endif return; } @@ -1094,7 +1114,9 @@ void MarlinSettings::postprocess() { // Write crc to MAT along with other data, or just tack on to the beginning or end - SERIAL_PROTOCOLLNPAIR("Mesh saved in slot ", slot); + #if ENABLED(EEPROM_CHITCHAT) + SERIAL_PROTOCOLLNPAIR("Mesh saved in slot ", slot); + #endif #else @@ -1110,7 +1132,9 @@ void MarlinSettings::postprocess() { const int16_t a = settings.calc_num_meshes(); if (!WITHIN(slot, 0, a - 1)) { - ubl_invalid_slot(a); + #if ENABLED(EEPROM_CHITCHAT) + ubl_invalid_slot(a); + #endif return; } @@ -1121,7 +1145,9 @@ void MarlinSettings::postprocess() { // Compare crc with crc from MAT, or read from end - SERIAL_PROTOCOLLNPAIR("Mesh loaded from slot ", slot); + #if ENABLED(EEPROM_CHITCHAT) + SERIAL_PROTOCOLLNPAIR("Mesh loaded from slot ", slot); + #endif #else @@ -1345,8 +1371,10 @@ void MarlinSettings::reset() { postprocess(); - SERIAL_ECHO_START(); - SERIAL_ECHOLNPGM("Hardcoded Default Settings Loaded"); + #if ENABLED(EEPROM_CHITCHAT) + SERIAL_ECHO_START(); + SERIAL_ECHOLNPGM("Hardcoded Default Settings Loaded"); + #endif } #if DISABLED(DISABLE_M503) From 76c92a1fab3b74ff92ea3ec4c54f49c7a353e7fd Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 1 Jul 2017 22:32:04 -0500 Subject: [PATCH 161/180] Clean up some trailing spaces --- Marlin/gcode.h | 2 +- Marlin/twibus.h | 4 ++-- Marlin/ubl_motion.cpp | 2 +- Marlin/ultralcd_impl_HD44780.h | 2 +- 4 files changed, 5 insertions(+), 5 deletions(-) diff --git a/Marlin/gcode.h b/Marlin/gcode.h index aa51a57b01..3884bd60d2 100644 --- a/Marlin/gcode.h +++ b/Marlin/gcode.h @@ -38,7 +38,7 @@ #if ENABLED(DEBUG_GCODE_PARSER) #if ENABLED(AUTO_BED_LEVELING_UBL) extern char* hex_address(const void * const w); - #else + #else #include "hex_print_routines.h" #endif #include "serial.h" diff --git a/Marlin/twibus.h b/Marlin/twibus.h index 5d49639349..03763972a7 100644 --- a/Marlin/twibus.h +++ b/Marlin/twibus.h @@ -48,8 +48,8 @@ typedef void (*twiRequestFunc_t)(); * for the host to interpret. * * For more information see - * - http://marlinfw.org/docs/gcode/M260.html - * - http://marlinfw.org/docs/gcode/M261.html + * - http://marlinfw.org/docs/gcode/M260.html + * - http://marlinfw.org/docs/gcode/M261.html * */ class TWIBus { diff --git a/Marlin/ubl_motion.cpp b/Marlin/ubl_motion.cpp index 7e037d40a4..45fe4caf91 100644 --- a/Marlin/ubl_motion.cpp +++ b/Marlin/ubl_motion.cpp @@ -31,7 +31,7 @@ #include extern float destination[XYZE]; - + #if AVR_AT90USB1286_FAMILY // Teensyduino & Printrboard IDE extensions have compile errors without this inline void set_current_to_destination() { COPY(current_position, destination); } #else diff --git a/Marlin/ultralcd_impl_HD44780.h b/Marlin/ultralcd_impl_HD44780.h index 40187f79a8..554c54c362 100644 --- a/Marlin/ultralcd_impl_HD44780.h +++ b/Marlin/ultralcd_impl_HD44780.h @@ -1085,7 +1085,7 @@ static void lcd_implementation_status_screen() { #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. From 232a10410d32bac2780077880550152a6397cfe5 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 1 Jul 2017 22:23:03 -0500 Subject: [PATCH 162/180] LCD_FOR_MELZI --- Marlin/Conditionals_LCD.h | 2 +- Marlin/Configuration.h | 5 ++++ Marlin/SanityCheck.h | 3 +++ .../Anet/A6/Configuration.h | 5 ++++ .../Anet/A8/Configuration.h | 5 ++++ .../CL-260/Configuration.h | 5 ++++ .../Cartesio/Configuration.h | 5 ++++ .../Felix/Configuration.h | 5 ++++ .../Felix/DUAL/Configuration.h | 5 ++++ .../FolgerTech-i3-2020/Configuration.h | 5 ++++ .../Hephestos/Configuration.h | 5 ++++ .../Hephestos_2/Configuration.h | 5 ++++ .../Infitary-i3-M508/Configuration.h | 5 ++++ .../K8200/Configuration.h | 5 ++++ .../K8400/Configuration.h | 5 ++++ .../K8400/Dual-head/Configuration.h | 5 ++++ .../M150/Configuration.h | 5 ++++ .../RepRapWorld/Megatronics/Configuration.h | 5 ++++ .../RigidBot/Configuration.h | 5 ++++ .../SCARA/Configuration.h | 5 ++++ .../TAZ4/Configuration.h | 5 ++++ .../TinyBoy2/Configuration.h | 5 ++++ .../WITBOX/Configuration.h | 5 ++++ .../adafruit/ST7565/Configuration.h | 5 ++++ .../FLSUN/auto_calibrate/Configuration.h | 5 ++++ .../delta/FLSUN/kossel_mini/Configuration.h | 5 ++++ .../delta/generic/Configuration.h | 5 ++++ .../delta/kossel_mini/Configuration.h | 5 ++++ .../delta/kossel_pro/Configuration.h | 5 ++++ .../delta/kossel_xl/Configuration.h | 5 ++++ .../gCreate_gMax1.5+/Configuration.h | 5 ++++ .../makibox/Configuration.h | 5 ++++ .../tvrrug/Round2/Configuration.h | 5 ++++ .../wt150/Configuration.h | 5 ++++ Marlin/pins_SANGUINOLOLU_11.h | 27 +++++++++++++++++-- 35 files changed, 189 insertions(+), 3 deletions(-) diff --git a/Marlin/Conditionals_LCD.h b/Marlin/Conditionals_LCD.h index 7aa96deae4..deb89fb51f 100644 --- a/Marlin/Conditionals_LCD.h +++ b/Marlin/Conditionals_LCD.h @@ -120,7 +120,7 @@ #define ULTIMAKERCONTROLLER #endif - #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) + #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) || ENABLED(LCD_FOR_MELZI) #define DOGLCD #define U8GLIB_ST7920 #define REPRAP_DISCOUNT_SMART_CONTROLLER diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 05e193f13a..1da8ecc5a9 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -1402,6 +1402,11 @@ // 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 // diff --git a/Marlin/SanityCheck.h b/Marlin/SanityCheck.h index 19a78c4bf9..27022e6fb5 100644 --- a/Marlin/SanityCheck.h +++ b/Marlin/SanityCheck.h @@ -1086,6 +1086,9 @@ static_assert(1 >= 0 #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) && DISABLED(BQ_LCD_SMART_CONTROLLER) + 1 #endif + #if ENABLED(LCD_FOR_MELZI) + + 1 + #endif #if ENABLED(CARTESIO_UI) + 1 #endif diff --git a/Marlin/example_configurations/Anet/A6/Configuration.h b/Marlin/example_configurations/Anet/A6/Configuration.h index a05c5864ac..5d3edc5a78 100644 --- a/Marlin/example_configurations/Anet/A6/Configuration.h +++ b/Marlin/example_configurations/Anet/A6/Configuration.h @@ -1560,6 +1560,11 @@ // 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 // diff --git a/Marlin/example_configurations/Anet/A8/Configuration.h b/Marlin/example_configurations/Anet/A8/Configuration.h index 3cae7b59ba..5fcc0bb86a 100644 --- a/Marlin/example_configurations/Anet/A8/Configuration.h +++ b/Marlin/example_configurations/Anet/A8/Configuration.h @@ -1410,6 +1410,11 @@ // 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 // diff --git a/Marlin/example_configurations/CL-260/Configuration.h b/Marlin/example_configurations/CL-260/Configuration.h index f10203a21c..68dd02dbef 100644 --- a/Marlin/example_configurations/CL-260/Configuration.h +++ b/Marlin/example_configurations/CL-260/Configuration.h @@ -1399,6 +1399,11 @@ // 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 // diff --git a/Marlin/example_configurations/Cartesio/Configuration.h b/Marlin/example_configurations/Cartesio/Configuration.h index 1e195fff02..4993a749f2 100644 --- a/Marlin/example_configurations/Cartesio/Configuration.h +++ b/Marlin/example_configurations/Cartesio/Configuration.h @@ -1396,6 +1396,11 @@ // 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 // diff --git a/Marlin/example_configurations/Felix/Configuration.h b/Marlin/example_configurations/Felix/Configuration.h index c339a163c0..ebe75ffbcd 100644 --- a/Marlin/example_configurations/Felix/Configuration.h +++ b/Marlin/example_configurations/Felix/Configuration.h @@ -1380,6 +1380,11 @@ // 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 // diff --git a/Marlin/example_configurations/Felix/DUAL/Configuration.h b/Marlin/example_configurations/Felix/DUAL/Configuration.h index 26cfe57745..cd44443f4e 100644 --- a/Marlin/example_configurations/Felix/DUAL/Configuration.h +++ b/Marlin/example_configurations/Felix/DUAL/Configuration.h @@ -1380,6 +1380,11 @@ // 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 // diff --git a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h index ac04018735..d4b961f2af 100644 --- a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h +++ b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h @@ -1402,6 +1402,11 @@ // 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 // diff --git a/Marlin/example_configurations/Hephestos/Configuration.h b/Marlin/example_configurations/Hephestos/Configuration.h index a5d558f85d..8703990be8 100644 --- a/Marlin/example_configurations/Hephestos/Configuration.h +++ b/Marlin/example_configurations/Hephestos/Configuration.h @@ -1388,6 +1388,11 @@ // 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 // diff --git a/Marlin/example_configurations/Hephestos_2/Configuration.h b/Marlin/example_configurations/Hephestos_2/Configuration.h index bcb6765744..8a150d6814 100644 --- a/Marlin/example_configurations/Hephestos_2/Configuration.h +++ b/Marlin/example_configurations/Hephestos_2/Configuration.h @@ -1391,6 +1391,11 @@ // 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 // diff --git a/Marlin/example_configurations/Infitary-i3-M508/Configuration.h b/Marlin/example_configurations/Infitary-i3-M508/Configuration.h index 78c3a341d0..31d384da6f 100644 --- a/Marlin/example_configurations/Infitary-i3-M508/Configuration.h +++ b/Marlin/example_configurations/Infitary-i3-M508/Configuration.h @@ -1372,6 +1372,11 @@ // //#define BQ_LCD_SMART_CONTROLLER +// +// LCD for Melzi Card with Graphical LCD +// +//#define LCD_FOR_MELZI + // // CONTROLLER TYPE: I2C // diff --git a/Marlin/example_configurations/K8200/Configuration.h b/Marlin/example_configurations/K8200/Configuration.h index 6842ecf92b..e7542ef652 100644 --- a/Marlin/example_configurations/K8200/Configuration.h +++ b/Marlin/example_configurations/K8200/Configuration.h @@ -1430,6 +1430,11 @@ // 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 // diff --git a/Marlin/example_configurations/K8400/Configuration.h b/Marlin/example_configurations/K8400/Configuration.h index 9a1dacf393..d586dc9eef 100644 --- a/Marlin/example_configurations/K8400/Configuration.h +++ b/Marlin/example_configurations/K8400/Configuration.h @@ -1398,6 +1398,11 @@ // 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 // diff --git a/Marlin/example_configurations/K8400/Dual-head/Configuration.h b/Marlin/example_configurations/K8400/Dual-head/Configuration.h index 8f23d29f46..50890b1fb4 100644 --- a/Marlin/example_configurations/K8400/Dual-head/Configuration.h +++ b/Marlin/example_configurations/K8400/Dual-head/Configuration.h @@ -1398,6 +1398,11 @@ // 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 // diff --git a/Marlin/example_configurations/M150/Configuration.h b/Marlin/example_configurations/M150/Configuration.h index 5e99290d83..e3493203c2 100644 --- a/Marlin/example_configurations/M150/Configuration.h +++ b/Marlin/example_configurations/M150/Configuration.h @@ -1425,6 +1425,11 @@ // 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 // diff --git a/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h b/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h index 7369f7ac8d..a3ab9103a6 100644 --- a/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h +++ b/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h @@ -1398,6 +1398,11 @@ // 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 // diff --git a/Marlin/example_configurations/RigidBot/Configuration.h b/Marlin/example_configurations/RigidBot/Configuration.h index 799ad46dc3..51879d1522 100644 --- a/Marlin/example_configurations/RigidBot/Configuration.h +++ b/Marlin/example_configurations/RigidBot/Configuration.h @@ -1398,6 +1398,11 @@ // 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 // diff --git a/Marlin/example_configurations/SCARA/Configuration.h b/Marlin/example_configurations/SCARA/Configuration.h index e04d12e863..d2bf864fa0 100644 --- a/Marlin/example_configurations/SCARA/Configuration.h +++ b/Marlin/example_configurations/SCARA/Configuration.h @@ -1410,6 +1410,11 @@ // 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 // diff --git a/Marlin/example_configurations/TAZ4/Configuration.h b/Marlin/example_configurations/TAZ4/Configuration.h index 0b2897bced..fedf767be9 100644 --- a/Marlin/example_configurations/TAZ4/Configuration.h +++ b/Marlin/example_configurations/TAZ4/Configuration.h @@ -1417,6 +1417,11 @@ // 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 // diff --git a/Marlin/example_configurations/TinyBoy2/Configuration.h b/Marlin/example_configurations/TinyBoy2/Configuration.h index 4d35c063a6..aad2a90908 100644 --- a/Marlin/example_configurations/TinyBoy2/Configuration.h +++ b/Marlin/example_configurations/TinyBoy2/Configuration.h @@ -1454,6 +1454,11 @@ // 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 // diff --git a/Marlin/example_configurations/WITBOX/Configuration.h b/Marlin/example_configurations/WITBOX/Configuration.h index 691abb4977..0154727f9c 100644 --- a/Marlin/example_configurations/WITBOX/Configuration.h +++ b/Marlin/example_configurations/WITBOX/Configuration.h @@ -1388,6 +1388,11 @@ // 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 // diff --git a/Marlin/example_configurations/adafruit/ST7565/Configuration.h b/Marlin/example_configurations/adafruit/ST7565/Configuration.h index 5b1dbf648f..4cb5eb5866 100644 --- a/Marlin/example_configurations/adafruit/ST7565/Configuration.h +++ b/Marlin/example_configurations/adafruit/ST7565/Configuration.h @@ -1398,6 +1398,11 @@ // 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 // diff --git a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h index 6706efd51c..7952f1989f 100644 --- a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h +++ b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h @@ -1519,6 +1519,11 @@ // 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 // diff --git a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h index 8e402bcb0f..0d0a3dc3ee 100644 --- a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h +++ b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h @@ -1520,6 +1520,11 @@ // 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 // diff --git a/Marlin/example_configurations/delta/generic/Configuration.h b/Marlin/example_configurations/delta/generic/Configuration.h index 2f69a232e1..fe6b678701 100644 --- a/Marlin/example_configurations/delta/generic/Configuration.h +++ b/Marlin/example_configurations/delta/generic/Configuration.h @@ -1509,6 +1509,11 @@ // 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 // diff --git a/Marlin/example_configurations/delta/kossel_mini/Configuration.h b/Marlin/example_configurations/delta/kossel_mini/Configuration.h index 9596a58c47..8dc758c332 100644 --- a/Marlin/example_configurations/delta/kossel_mini/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_mini/Configuration.h @@ -1512,6 +1512,11 @@ // 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 // diff --git a/Marlin/example_configurations/delta/kossel_pro/Configuration.h b/Marlin/example_configurations/delta/kossel_pro/Configuration.h index 6219756021..64ed4fa276 100644 --- a/Marlin/example_configurations/delta/kossel_pro/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_pro/Configuration.h @@ -1517,6 +1517,11 @@ // 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 // diff --git a/Marlin/example_configurations/delta/kossel_xl/Configuration.h b/Marlin/example_configurations/delta/kossel_xl/Configuration.h index 99271bf5f8..0afc96ea6d 100644 --- a/Marlin/example_configurations/delta/kossel_xl/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_xl/Configuration.h @@ -1575,6 +1575,11 @@ // 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 // diff --git a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h index cde1f76480..98661d21df 100644 --- a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h +++ b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h @@ -1414,6 +1414,11 @@ // 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 // diff --git a/Marlin/example_configurations/makibox/Configuration.h b/Marlin/example_configurations/makibox/Configuration.h index 7992697dfc..ca473aeeda 100644 --- a/Marlin/example_configurations/makibox/Configuration.h +++ b/Marlin/example_configurations/makibox/Configuration.h @@ -1401,6 +1401,11 @@ // 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 // diff --git a/Marlin/example_configurations/tvrrug/Round2/Configuration.h b/Marlin/example_configurations/tvrrug/Round2/Configuration.h index 8a54d17340..6b86fc1873 100644 --- a/Marlin/example_configurations/tvrrug/Round2/Configuration.h +++ b/Marlin/example_configurations/tvrrug/Round2/Configuration.h @@ -1393,6 +1393,11 @@ // 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 // diff --git a/Marlin/example_configurations/wt150/Configuration.h b/Marlin/example_configurations/wt150/Configuration.h index 9be759d373..851ee11dce 100644 --- a/Marlin/example_configurations/wt150/Configuration.h +++ b/Marlin/example_configurations/wt150/Configuration.h @@ -1404,6 +1404,11 @@ // 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 // diff --git a/Marlin/pins_SANGUINOLOLU_11.h b/Marlin/pins_SANGUINOLOLU_11.h index 6bac9d7a8a..e6769f533a 100644 --- a/Marlin/pins_SANGUINOLOLU_11.h +++ b/Marlin/pins_SANGUINOLOLU_11.h @@ -209,16 +209,39 @@ #define BTN_EN2 10 #if ENABLED(LCD_I2C_PANELOLU2) + #if IS_MELZI #define BTN_ENC 29 #define LCD_SDSS 30 // Panelolu2 SD card reader rather than the Melzi #else #define BTN_ENC 30 #endif - #else // !Panelolu2 + + #elif ENABLED(LCD_FOR_MELZI) + + #define LCD_PINS_RS 17 + #define LCD_PINS_ENABLE 16 + #define LCD_PINS_D4 11 + #define BTN_ENC 28 + #define BTN_EN1 29 + #define BTN_EN2 30 + + #ifndef ST7920_DELAY_1 + #define ST7920_DELAY_1 DELAY_0_NOP + #endif + #ifndef ST7920_DELAY_3 + #define ST7920_DELAY_2 DELAY_3_NOP + #endif + #ifndef ST7920_DELAY_3 + #define ST7920_DELAY_3 DELAY_0_NOP + #endif + + #else // !LCD_I2C_PANELOLU2 && !LCD_FOR_MELZI + #define BTN_ENC 16 #define LCD_SDSS 28 // Smart Controller SD card reader rather than the Melzi - #endif // !Panelolu2 + + #endif #define SD_DETECT_PIN -1 From 09c90c2f6c7b6e5b3913578f366529df94af77a5 Mon Sep 17 00:00:00 2001 From: Dave Johnson Date: Sat, 1 Jul 2017 22:33:39 -0700 Subject: [PATCH 163/180] Printrboard RevF Cleanup -Update Arduino IDE extension descriptions -Set default motor currents if not defined in Configuration_adv.h -Support for MINIPANEL LCD -Support for choosing internal or panel SD --- Marlin/pins_PRINTRBOARD_REVF.h | 81 ++++++++++++++++++++++++++++------ 1 file changed, 67 insertions(+), 14 deletions(-) mode change 100755 => 100644 Marlin/pins_PRINTRBOARD_REVF.h diff --git a/Marlin/pins_PRINTRBOARD_REVF.h b/Marlin/pins_PRINTRBOARD_REVF.h old mode 100755 new mode 100644 index f83bdf5ab0..3adeb12034 --- a/Marlin/pins_PRINTRBOARD_REVF.h +++ b/Marlin/pins_PRINTRBOARD_REVF.h @@ -31,10 +31,12 @@ * and with the mainstream Marlin software. * * 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 - * - * Installation instructions are at the above URL. Don't bother loading the - * libraries - they are not used with the Marlin software. + * + * 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. * * Printrboard - https://github.com/scwimbush/Printrboard-HID-Arduino-IDE-Support * @@ -48,12 +50,11 @@ * 3. Restart Arduino. * 4. Select "Printrboard" from the 'Tools -> Boards' menu. * - * Teensyduino is the most popular option. Printrboard is used if your board doesn't have - * the Teensyduino bootloader on it. + * Teensyduino is the most popular and easiest option. */ /** - * To burn the bootloader that comes with Printrboard: + * To burn the bootloader that comes with Printrboard HID extension: * * 1. Connect your programmer to the board. * 2. In the Arduino IDE select "Printrboard" and then select the programmer. @@ -94,9 +95,15 @@ #define E0_DIR_PIN 35 // A7 #define E0_ENABLE_PIN 13 // C3 -// uncomment to enable an I2C based DAC like on the Printrboard REVF +// Enable control of stepper motor currents with the I2C based MCP4728 DAC used on Printrboard REVF #define DAC_STEPPER_CURRENT -// Number of channels available for DAC, For Printrboar REVF there are 4 + +// 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 } +#endif + +// Number of channels available for DAC #define DAC_STEPPER_ORDER { 3, 2, 1, 0 } #define DAC_STEPPER_SENSE 0.11 @@ -122,15 +129,11 @@ #define FAN_PIN 16 // C6 PWM3A -// -// Misc. Functions -// -#define SDSS 20 // B0 SS -#define FILWIDTH_PIN 2 // Analog Input - // // LCD / Controller // +//#define USE_INTERNAL_SD + #if ENABLED(ULTRA_LCD) #define BEEPER_PIN -1 @@ -164,3 +167,53 @@ #define STAT_LED_RED_PIN 12 // C2 JP11-14 #define STAT_LED_BLUE_PIN 10 // C0 JP11-12 #endif + +#if ENABLED(MINIPANEL) + #if ENABLED(USE_INTERNAL_SD) + // 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# + #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 + #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 + #define KILL_PIN 8 // 33 E0 EXP2-10 EXP2-03 + #define BTN_EN1 10 // 35 C0 EXP2-12 EXP2-06 + #define BTN_EN2 12 // 37 C2 EXP2-14 EXP2-08 + //#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 + + // encoder connections present + #define BLEN_A 0 + #define BLEN_B 1 + #define BLEN_C 2 + + // encoder rotation values + #define encrot0 0 + #define encrot1 2 + #define encrot2 3 + #define encrot3 1 + + // increase delays to max + #define ST7920_DELAY_1 DELAY_5_NOP + #define ST7920_DELAY_2 DELAY_5_NOP + #define ST7920_DELAY_3 DELAY_5_NOP +#endif + +// +// Misc. Functions +// +#ifndef SDSS + #define SDSS 20 // B0 SS +#endif + +#define FILWIDTH_PIN 2 // Analog Input From 859248433f5e6d6466ef92f6eff23fbd6b994eec Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 2 Jul 2017 00:35:52 -0500 Subject: [PATCH 164/180] Patch for gcode debug --- Marlin/gcode.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/gcode.h b/Marlin/gcode.h index 3884bd60d2..7b58576406 100644 --- a/Marlin/gcode.h +++ b/Marlin/gcode.h @@ -124,7 +124,7 @@ public: if (debug) { SERIAL_ECHOPAIR("Set bit ", (int)PARAM_BIT(ind)); SERIAL_ECHOPAIR(" of index ", (int)PARAM_IND(ind)); - SERIAL_ECHOLNPAIR(" | param = ", hex_address((void*)param[ind])); + SERIAL_ECHOLNPAIR(" | param = ", (int)param[ind]); } #endif } From ae5923a3d019131b42c27ea243524495c59e4021 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 2 Jul 2017 00:35:41 -0500 Subject: [PATCH 165/180] Make lcd_bootscreen common to both --- Marlin/Marlin_main.cpp | 11 ++-- Marlin/ultralcd.h | 6 ++- Marlin/ultralcd_impl_DOGM.h | 92 +++++++++++++++++++--------------- Marlin/ultralcd_impl_HD44780.h | 2 +- 4 files changed, 65 insertions(+), 46 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index f19a89818b..c280c10027 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -13034,11 +13034,16 @@ void setup() { #endif lcd_init(); + #if ENABLED(SHOW_BOOTSCREEN) - #if ENABLED(DOGLCD) - safe_delay(BOOTSCREEN_TIMEOUT); + #if ENABLED(DOGLCD) // On DOGM the first bootscreen is already drawn + #if ENABLED(SHOW_CUSTOM_BOOTSCREEN) + safe_delay(CUSTOM_BOOTSCREEN_TIMEOUT); // Custom boot screen pause + lcd_bootscreen(); // Show Marlin boot screen + #endif + safe_delay(BOOTSCREEN_TIMEOUT); // Pause #elif ENABLED(ULTRA_LCD) - bootscreen(); + lcd_bootscreen(); #if DISABLED(SDSUPPORT) lcd_init(); #endif diff --git a/Marlin/ultralcd.h b/Marlin/ultralcd.h index 909c13d408..f1087616fa 100644 --- a/Marlin/ultralcd.h +++ b/Marlin/ultralcd.h @@ -64,8 +64,10 @@ #if ENABLED(DOGLCD) extern uint16_t lcd_contrast; void set_lcd_contrast(const uint16_t value); - #elif ENABLED(SHOW_BOOTSCREEN) - void bootscreen(); + #endif + + #if ENABLED(SHOW_BOOTSCREEN) + void lcd_bootscreen(); #endif #define LCD_UPDATE_INTERVAL 100 diff --git a/Marlin/ultralcd_impl_DOGM.h b/Marlin/ultralcd_impl_DOGM.h index c9cbf452e5..392e812c99 100644 --- a/Marlin/ultralcd_impl_DOGM.h +++ b/Marlin/ultralcd_impl_DOGM.h @@ -256,6 +256,55 @@ void lcd_printPGM_utf(const char *str, uint8_t n=LCD_WIDTH) { while (n && (c = pgm_read_byte(str))) n -= charset_mapper(c), ++str; } +#if ENABLED(SHOW_BOOTSCREEN) + + #if ENABLED(SHOW_CUSTOM_BOOTSCREEN) + + void lcd_custom_bootscreen() { + u8g.firstPage(); + do { + u8g.drawBitmapP( + (128 - (CUSTOM_BOOTSCREEN_BMPWIDTH)) /2, + ( 64 - (CUSTOM_BOOTSCREEN_BMPHEIGHT)) /2, + CEILING(CUSTOM_BOOTSCREEN_BMPWIDTH, 8), CUSTOM_BOOTSCREEN_BMPHEIGHT, custom_start_bmp); + } while (u8g.nextPage()); + } + + #endif // SHOW_CUSTOM_BOOTSCREEN + + void lcd_bootscreen() { + + static bool show_bootscreen = true; + + if (show_bootscreen) { + show_bootscreen = false; + + #if ENABLED(START_BMPHIGH) + constexpr uint8_t offy = 0; + #else + constexpr uint8_t offy = DOG_CHAR_HEIGHT; + #endif + + const uint8_t offx = (u8g.getWidth() - (START_BMPWIDTH)) / 2, + txt1X = (u8g.getWidth() - (sizeof(STRING_SPLASH_LINE1) - 1) * (DOG_CHAR_WIDTH)) / 2; + + u8g.firstPage(); + do { + u8g.drawBitmapP(offx, offy, START_BMPBYTEWIDTH, START_BMPHEIGHT, start_bmp); + lcd_setFont(FONT_MENU); + #ifndef STRING_SPLASH_LINE2 + u8g.drawStr(txt1X, u8g.getHeight() - (DOG_CHAR_HEIGHT), STRING_SPLASH_LINE1); + #else + const uint8_t txt2X = (u8g.getWidth() - (sizeof(STRING_SPLASH_LINE2) - 1) * (DOG_CHAR_WIDTH)) / 2; + u8g.drawStr(txt1X, u8g.getHeight() - (DOG_CHAR_HEIGHT) * 3 / 2, STRING_SPLASH_LINE1); + u8g.drawStr(txt2X, u8g.getHeight() - (DOG_CHAR_HEIGHT) * 1 / 2, STRING_SPLASH_LINE2); + #endif + } while (u8g.nextPage()); + } + } + +#endif // SHOW_BOOTSCREEN + // Initialize or re-initialize the LCD static void lcd_implementation_init() { @@ -284,49 +333,12 @@ static void lcd_implementation_init() { #endif #if ENABLED(SHOW_BOOTSCREEN) - static bool show_bootscreen = true; - #if ENABLED(SHOW_CUSTOM_BOOTSCREEN) - if (show_bootscreen) { - u8g.firstPage(); - do { - u8g.drawBitmapP( - (128 - (CUSTOM_BOOTSCREEN_BMPWIDTH)) /2, - ( 64 - (CUSTOM_BOOTSCREEN_BMPHEIGHT)) /2, - CEILING(CUSTOM_BOOTSCREEN_BMPWIDTH, 8), CUSTOM_BOOTSCREEN_BMPHEIGHT, custom_start_bmp); - } while (u8g.nextPage()); - safe_delay(CUSTOM_BOOTSCREEN_TIMEOUT); - } - #endif // SHOW_CUSTOM_BOOTSCREEN - - const uint8_t offx = (u8g.getWidth() - (START_BMPWIDTH)) / 2; - - #if ENABLED(START_BMPHIGH) - constexpr uint8_t offy = 0; + lcd_custom_bootscreen(); #else - constexpr uint8_t offy = DOG_CHAR_HEIGHT; + lcd_bootscreen(); #endif - - const uint8_t txt1X = (u8g.getWidth() - (sizeof(STRING_SPLASH_LINE1) - 1) * (DOG_CHAR_WIDTH)) / 2; - - if (show_bootscreen) { - u8g.firstPage(); - do { - u8g.drawBitmapP(offx, offy, START_BMPBYTEWIDTH, START_BMPHEIGHT, start_bmp); - lcd_setFont(FONT_MENU); - #ifndef STRING_SPLASH_LINE2 - u8g.drawStr(txt1X, u8g.getHeight() - (DOG_CHAR_HEIGHT), STRING_SPLASH_LINE1); - #else - const uint8_t txt2X = (u8g.getWidth() - (sizeof(STRING_SPLASH_LINE2) - 1) * (DOG_CHAR_WIDTH)) / 2; - u8g.drawStr(txt1X, u8g.getHeight() - (DOG_CHAR_HEIGHT) * 3 / 2, STRING_SPLASH_LINE1); - u8g.drawStr(txt2X, u8g.getHeight() - (DOG_CHAR_HEIGHT) * 1 / 2, STRING_SPLASH_LINE2); - #endif - } while (u8g.nextPage()); - } - - show_bootscreen = false; - - #endif // SHOW_BOOTSCREEN + #endif } // The kill screen is displayed for unrecoverable conditions diff --git a/Marlin/ultralcd_impl_HD44780.h b/Marlin/ultralcd_impl_HD44780.h index 554c54c362..c2642b4d75 100644 --- a/Marlin/ultralcd_impl_HD44780.h +++ b/Marlin/ultralcd_impl_HD44780.h @@ -443,7 +443,7 @@ void lcd_printPGM_utf(const char *str, uint8_t n=LCD_WIDTH) { lcd.setCursor(indent, 2); lcd.write('\x02'); lcd_printPGM(PSTR( "------" )); lcd.write('\x03'); } - void bootscreen() { + void lcd_bootscreen() { const static PROGMEM byte corner[4][8] = { { B00000, B00000, From 167169e1bfab43e3c6279d491c829d7e2237a4dd Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 2 Jul 2017 02:26:35 -0500 Subject: [PATCH 166/180] Sanity check for a real probe with M48 --- Marlin/SanityCheck.h | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/Marlin/SanityCheck.h b/Marlin/SanityCheck.h index 27022e6fb5..1b96714862 100644 --- a/Marlin/SanityCheck.h +++ b/Marlin/SanityCheck.h @@ -599,12 +599,14 @@ static_assert(1 >= 0 #else #error "Auto Bed Leveling requires one of these: PROBE_MANUALLY, FIX_MOUNTED_PROBE, BLTOUCH, SOLENOID_PROBE, Z_PROBE_ALLEN_KEY, Z_PROBE_SLED, or a Z Servo." #endif - #elif ENABLED(Z_MIN_PROBE_REPEATABILITY_TEST) - #error "Z_MIN_PROBE_REPEATABILITY_TEST requires a probe: FIX_MOUNTED_PROBE, BLTOUCH, SOLENOID_PROBE, Z_PROBE_ALLEN_KEY, Z_PROBE_SLED, or Z Servo." #endif #endif +#if ENABLED(Z_MIN_PROBE_REPEATABILITY_TEST) && !HAS_BED_PROBE + #error "Z_MIN_PROBE_REPEATABILITY_TEST requires a probe: FIX_MOUNTED_PROBE, BLTOUCH, SOLENOID_PROBE, Z_PROBE_ALLEN_KEY, Z_PROBE_SLED, or Z Servo." +#endif + /** * Allow only one bed leveling option to be defined */ From d609489b22443bac1d253e7480d8d5d7d8af733f Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 2 Jul 2017 02:26:49 -0500 Subject: [PATCH 167/180] Drop setup_homepin --- Marlin/Marlin_main.cpp | 10 +++------- 1 file changed, 3 insertions(+), 7 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index c280c10027..81fdda8047 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -906,12 +906,6 @@ void setup_killpin() { #endif -void setup_homepin(void) { - #if HAS_HOME - SET_INPUT_PULLUP(HOME_PIN); - #endif -} - void setup_powerhold() { #if HAS_SUICIDE OUT_WRITE(SUICIDE_PIN, HIGH); @@ -13008,7 +13002,9 @@ void setup() { OUT_WRITE(SOL1_PIN, LOW); // turn it off #endif - setup_homepin(); + #if HAS_HOME + SET_INPUT_PULLUP(HOME_PIN); + #endif #if PIN_EXISTS(STAT_LED_RED) OUT_WRITE(STAT_LED_RED_PIN, LOW); // turn it off From 69297b2d7bdeef3f4ab1b38edd54fd8d0db9761f Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 2 Jul 2017 19:43:34 -0500 Subject: [PATCH 168/180] Make all EEPROM optimization options available --- Marlin/Configuration.h | 12 +++++------- .../example_configurations/Anet/A6/Configuration.h | 12 +++++------- .../example_configurations/Anet/A8/Configuration.h | 12 +++++------- Marlin/example_configurations/CL-260/Configuration.h | 12 +++++------- .../example_configurations/Cartesio/Configuration.h | 12 +++++------- Marlin/example_configurations/Felix/Configuration.h | 12 +++++------- .../Felix/DUAL/Configuration.h | 12 +++++------- .../FolgerTech-i3-2020/Configuration.h | 12 +++++------- .../example_configurations/Hephestos/Configuration.h | 12 +++++------- .../Hephestos_2/Configuration.h | 12 +++++------- .../Infitary-i3-M508/Configuration.h | 5 +++-- Marlin/example_configurations/K8200/Configuration.h | 12 +++++------- Marlin/example_configurations/K8400/Configuration.h | 12 +++++------- .../K8400/Dual-head/Configuration.h | 12 +++++------- Marlin/example_configurations/M150/Configuration.h | 12 +++++------- .../RepRapWorld/Megatronics/Configuration.h | 12 +++++------- .../example_configurations/RigidBot/Configuration.h | 12 +++++------- Marlin/example_configurations/SCARA/Configuration.h | 12 +++++------- Marlin/example_configurations/TAZ4/Configuration.h | 12 +++++------- .../example_configurations/TinyBoy2/Configuration.h | 12 +++++------- Marlin/example_configurations/WITBOX/Configuration.h | 12 +++++------- .../adafruit/ST7565/Configuration.h | 12 +++++------- .../delta/FLSUN/auto_calibrate/Configuration.h | 12 +++++------- .../delta/FLSUN/kossel_mini/Configuration.h | 12 +++++------- .../delta/generic/Configuration.h | 12 +++++------- .../delta/kossel_mini/Configuration.h | 12 +++++------- .../delta/kossel_pro/Configuration.h | 12 +++++------- .../delta/kossel_xl/Configuration.h | 12 +++++------- .../gCreate_gMax1.5+/Configuration.h | 12 +++++------- .../example_configurations/makibox/Configuration.h | 12 +++++------- .../tvrrug/Round2/Configuration.h | 12 +++++------- Marlin/example_configurations/wt150/Configuration.h | 12 +++++------- 32 files changed, 158 insertions(+), 219 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 1da8ecc5a9..2537051245 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -964,6 +964,7 @@ // - 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) @@ -988,13 +989,10 @@ // 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 +// +//#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 diff --git a/Marlin/example_configurations/Anet/A6/Configuration.h b/Marlin/example_configurations/Anet/A6/Configuration.h index 5d3edc5a78..b68d501dab 100644 --- a/Marlin/example_configurations/Anet/A6/Configuration.h +++ b/Marlin/example_configurations/Anet/A6/Configuration.h @@ -1111,6 +1111,7 @@ // - 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) @@ -1144,13 +1145,10 @@ // 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 +// +#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 diff --git a/Marlin/example_configurations/Anet/A8/Configuration.h b/Marlin/example_configurations/Anet/A8/Configuration.h index 5fcc0bb86a..102eb6d382 100644 --- a/Marlin/example_configurations/Anet/A8/Configuration.h +++ b/Marlin/example_configurations/Anet/A8/Configuration.h @@ -970,6 +970,7 @@ // - 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) @@ -994,13 +995,10 @@ // 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 +// +#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 diff --git a/Marlin/example_configurations/CL-260/Configuration.h b/Marlin/example_configurations/CL-260/Configuration.h index 68dd02dbef..2789fc1929 100644 --- a/Marlin/example_configurations/CL-260/Configuration.h +++ b/Marlin/example_configurations/CL-260/Configuration.h @@ -961,6 +961,7 @@ // - 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) @@ -985,13 +986,10 @@ // 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 +// +//#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 diff --git a/Marlin/example_configurations/Cartesio/Configuration.h b/Marlin/example_configurations/Cartesio/Configuration.h index 4993a749f2..e434ab36cc 100644 --- a/Marlin/example_configurations/Cartesio/Configuration.h +++ b/Marlin/example_configurations/Cartesio/Configuration.h @@ -958,6 +958,7 @@ // - 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) @@ -982,13 +983,10 @@ // 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 +// +//#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 diff --git a/Marlin/example_configurations/Felix/Configuration.h b/Marlin/example_configurations/Felix/Configuration.h index ebe75ffbcd..fc95ab86e8 100644 --- a/Marlin/example_configurations/Felix/Configuration.h +++ b/Marlin/example_configurations/Felix/Configuration.h @@ -942,6 +942,7 @@ // - 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) @@ -966,13 +967,10 @@ // 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 +// +//#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 diff --git a/Marlin/example_configurations/Felix/DUAL/Configuration.h b/Marlin/example_configurations/Felix/DUAL/Configuration.h index cd44443f4e..6c9957190a 100644 --- a/Marlin/example_configurations/Felix/DUAL/Configuration.h +++ b/Marlin/example_configurations/Felix/DUAL/Configuration.h @@ -942,6 +942,7 @@ // - 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) @@ -966,13 +967,10 @@ // 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 +// +//#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 diff --git a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h index d4b961f2af..9c3c4f21c6 100644 --- a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h +++ b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h @@ -964,6 +964,7 @@ // - 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) @@ -988,13 +989,10 @@ // 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 +// +#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 diff --git a/Marlin/example_configurations/Hephestos/Configuration.h b/Marlin/example_configurations/Hephestos/Configuration.h index 8703990be8..b78fd16b6e 100644 --- a/Marlin/example_configurations/Hephestos/Configuration.h +++ b/Marlin/example_configurations/Hephestos/Configuration.h @@ -950,6 +950,7 @@ // - 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) @@ -974,13 +975,10 @@ // 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 +// +//#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 diff --git a/Marlin/example_configurations/Hephestos_2/Configuration.h b/Marlin/example_configurations/Hephestos_2/Configuration.h index 8a150d6814..d8204cf843 100644 --- a/Marlin/example_configurations/Hephestos_2/Configuration.h +++ b/Marlin/example_configurations/Hephestos_2/Configuration.h @@ -953,6 +953,7 @@ // - 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) @@ -977,13 +978,10 @@ // 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 +// +#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 diff --git a/Marlin/example_configurations/Infitary-i3-M508/Configuration.h b/Marlin/example_configurations/Infitary-i3-M508/Configuration.h index 31d384da6f..1abb8f8f0f 100644 --- a/Marlin/example_configurations/Infitary-i3-M508/Configuration.h +++ b/Marlin/example_configurations/Infitary-i3-M508/Configuration.h @@ -944,6 +944,7 @@ // - 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) @@ -968,8 +969,8 @@ // 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 +// +//#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: diff --git a/Marlin/example_configurations/K8200/Configuration.h b/Marlin/example_configurations/K8200/Configuration.h index e7542ef652..da28640a68 100644 --- a/Marlin/example_configurations/K8200/Configuration.h +++ b/Marlin/example_configurations/K8200/Configuration.h @@ -989,6 +989,7 @@ // - 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) @@ -1013,13 +1014,10 @@ // 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 // K8200: uses EEPROM by default - -#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 +// +#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 diff --git a/Marlin/example_configurations/K8400/Configuration.h b/Marlin/example_configurations/K8400/Configuration.h index d586dc9eef..dc2ddef719 100644 --- a/Marlin/example_configurations/K8400/Configuration.h +++ b/Marlin/example_configurations/K8400/Configuration.h @@ -960,6 +960,7 @@ // - 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) @@ -984,13 +985,10 @@ // 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 +// +#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 diff --git a/Marlin/example_configurations/K8400/Dual-head/Configuration.h b/Marlin/example_configurations/K8400/Dual-head/Configuration.h index 50890b1fb4..8d054cf3c8 100644 --- a/Marlin/example_configurations/K8400/Dual-head/Configuration.h +++ b/Marlin/example_configurations/K8400/Dual-head/Configuration.h @@ -960,6 +960,7 @@ // - 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) @@ -984,13 +985,10 @@ // 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 +// +#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 diff --git a/Marlin/example_configurations/M150/Configuration.h b/Marlin/example_configurations/M150/Configuration.h index e3493203c2..80a3fd8037 100644 --- a/Marlin/example_configurations/M150/Configuration.h +++ b/Marlin/example_configurations/M150/Configuration.h @@ -987,6 +987,7 @@ // - 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) @@ -1011,13 +1012,10 @@ // 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 +// +#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 diff --git a/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h b/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h index a3ab9103a6..2ba532f0a2 100644 --- a/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h +++ b/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h @@ -960,6 +960,7 @@ // - 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) @@ -984,13 +985,10 @@ // 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 +// +//#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 diff --git a/Marlin/example_configurations/RigidBot/Configuration.h b/Marlin/example_configurations/RigidBot/Configuration.h index 51879d1522..822eb2f9cb 100644 --- a/Marlin/example_configurations/RigidBot/Configuration.h +++ b/Marlin/example_configurations/RigidBot/Configuration.h @@ -958,6 +958,7 @@ // - 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) @@ -982,13 +983,10 @@ // 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 +// +#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 diff --git a/Marlin/example_configurations/SCARA/Configuration.h b/Marlin/example_configurations/SCARA/Configuration.h index d2bf864fa0..3f507c554d 100644 --- a/Marlin/example_configurations/SCARA/Configuration.h +++ b/Marlin/example_configurations/SCARA/Configuration.h @@ -972,6 +972,7 @@ // - 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) @@ -996,13 +997,10 @@ // 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 +// +//#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 diff --git a/Marlin/example_configurations/TAZ4/Configuration.h b/Marlin/example_configurations/TAZ4/Configuration.h index fedf767be9..57e1ec05ba 100644 --- a/Marlin/example_configurations/TAZ4/Configuration.h +++ b/Marlin/example_configurations/TAZ4/Configuration.h @@ -979,6 +979,7 @@ // - 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) @@ -1003,13 +1004,10 @@ // 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 +// +#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 diff --git a/Marlin/example_configurations/TinyBoy2/Configuration.h b/Marlin/example_configurations/TinyBoy2/Configuration.h index aad2a90908..12040db8f9 100644 --- a/Marlin/example_configurations/TinyBoy2/Configuration.h +++ b/Marlin/example_configurations/TinyBoy2/Configuration.h @@ -1016,6 +1016,7 @@ // - 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) @@ -1040,13 +1041,10 @@ // 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 +// +#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 diff --git a/Marlin/example_configurations/WITBOX/Configuration.h b/Marlin/example_configurations/WITBOX/Configuration.h index 0154727f9c..2c85b8136d 100644 --- a/Marlin/example_configurations/WITBOX/Configuration.h +++ b/Marlin/example_configurations/WITBOX/Configuration.h @@ -950,6 +950,7 @@ // - 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) @@ -974,13 +975,10 @@ // 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 +// +//#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 diff --git a/Marlin/example_configurations/adafruit/ST7565/Configuration.h b/Marlin/example_configurations/adafruit/ST7565/Configuration.h index 4cb5eb5866..cf9526bd5b 100644 --- a/Marlin/example_configurations/adafruit/ST7565/Configuration.h +++ b/Marlin/example_configurations/adafruit/ST7565/Configuration.h @@ -960,6 +960,7 @@ // - 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) @@ -984,13 +985,10 @@ // 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 +// +//#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 diff --git a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h index 7952f1989f..cebc4f21b7 100644 --- a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h +++ b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h @@ -1081,6 +1081,7 @@ // - 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) @@ -1104,13 +1105,10 @@ // 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 +// +#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 diff --git a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h index 0d0a3dc3ee..21cde2c919 100644 --- a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h +++ b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h @@ -1083,6 +1083,7 @@ // - 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) @@ -1106,13 +1107,10 @@ // 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 +// +#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 diff --git a/Marlin/example_configurations/delta/generic/Configuration.h b/Marlin/example_configurations/delta/generic/Configuration.h index fe6b678701..4eeb5fa549 100644 --- a/Marlin/example_configurations/delta/generic/Configuration.h +++ b/Marlin/example_configurations/delta/generic/Configuration.h @@ -1072,6 +1072,7 @@ // - 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) @@ -1095,13 +1096,10 @@ // 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 +// +//#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 diff --git a/Marlin/example_configurations/delta/kossel_mini/Configuration.h b/Marlin/example_configurations/delta/kossel_mini/Configuration.h index 8dc758c332..a443734c9a 100644 --- a/Marlin/example_configurations/delta/kossel_mini/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_mini/Configuration.h @@ -1075,6 +1075,7 @@ // - 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) @@ -1098,13 +1099,10 @@ // 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 +// +//#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 diff --git a/Marlin/example_configurations/delta/kossel_pro/Configuration.h b/Marlin/example_configurations/delta/kossel_pro/Configuration.h index 64ed4fa276..a7f99428af 100644 --- a/Marlin/example_configurations/delta/kossel_pro/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_pro/Configuration.h @@ -1080,6 +1080,7 @@ // - 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) @@ -1103,13 +1104,10 @@ // 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 +// +//#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 diff --git a/Marlin/example_configurations/delta/kossel_xl/Configuration.h b/Marlin/example_configurations/delta/kossel_xl/Configuration.h index 0afc96ea6d..689b4b400a 100644 --- a/Marlin/example_configurations/delta/kossel_xl/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_xl/Configuration.h @@ -1138,6 +1138,7 @@ // - 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) @@ -1161,13 +1162,10 @@ // 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 +// +#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 diff --git a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h index 98661d21df..acd6514b78 100644 --- a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h +++ b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h @@ -976,6 +976,7 @@ // - 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) @@ -1000,13 +1001,10 @@ // 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 +// +#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 diff --git a/Marlin/example_configurations/makibox/Configuration.h b/Marlin/example_configurations/makibox/Configuration.h index ca473aeeda..71d65aeb9d 100644 --- a/Marlin/example_configurations/makibox/Configuration.h +++ b/Marlin/example_configurations/makibox/Configuration.h @@ -963,6 +963,7 @@ // - 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) @@ -987,13 +988,10 @@ // 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 +// +#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 diff --git a/Marlin/example_configurations/tvrrug/Round2/Configuration.h b/Marlin/example_configurations/tvrrug/Round2/Configuration.h index 6b86fc1873..bd74eba1ed 100644 --- a/Marlin/example_configurations/tvrrug/Round2/Configuration.h +++ b/Marlin/example_configurations/tvrrug/Round2/Configuration.h @@ -955,6 +955,7 @@ // - 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) @@ -979,13 +980,10 @@ // 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 +// +//#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 diff --git a/Marlin/example_configurations/wt150/Configuration.h b/Marlin/example_configurations/wt150/Configuration.h index 851ee11dce..3a0e403c52 100644 --- a/Marlin/example_configurations/wt150/Configuration.h +++ b/Marlin/example_configurations/wt150/Configuration.h @@ -966,6 +966,7 @@ // - 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) @@ -990,13 +991,10 @@ // 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 +// +#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 From ab79933d1fd2b4f761810f8911cb6abb14a1690c Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 2 Jul 2017 20:43:57 -0500 Subject: [PATCH 169/180] Update Marlin+Github helper scripts --- buildroot/share/git/firstpush | 6 +++-- buildroot/share/git/mfadd | 16 +++++-------- buildroot/share/git/mfclean | 3 ++- buildroot/share/git/mfdoc | 11 ++++----- buildroot/share/git/mfinfo | 32 +++++++++++-------------- buildroot/share/git/mfinit | 13 ++++++----- buildroot/share/git/mfnew | 5 ++-- buildroot/share/git/mfpr | 14 ++++++----- buildroot/share/git/mfpub | 4 +++- buildroot/share/git/mfqp | 24 ++++++++----------- buildroot/share/git/mfrb | 15 ++++++------ buildroot/share/git/mfup | 44 +++++++++++++++++++++-------------- 12 files changed, 94 insertions(+), 93 deletions(-) diff --git a/buildroot/share/git/firstpush b/buildroot/share/git/firstpush index 0d8e71c796..60767f04bc 100755 --- a/buildroot/share/git/firstpush +++ b/buildroot/share/git/firstpush @@ -6,11 +6,13 @@ # commit log to watch Travis CI progress. # -MFINFO=$(mfinfo) || exit +[[ $# == 0 ]] || { echo "Usage: `basename $0`" 1>&2 ; exit 1; } + +MFINFO=$(mfinfo) || exit 1 IFS=' ' read -a INFO <<< "$MFINFO" FORK=${INFO[1]} REPO=${INFO[2]} -BRANCH=${INFO[4]} +BRANCH=${INFO[5]} git push --set-upstream origin $BRANCH diff --git a/buildroot/share/git/mfadd b/buildroot/share/git/mfadd index 6d69124498..8b6ded3666 100755 --- a/buildroot/share/git/mfadd +++ b/buildroot/share/git/mfadd @@ -5,20 +5,16 @@ # Add a remote and fetch it # -MFINFO=$(mfinfo) || exit +[[ $# == 1 ]] || { echo "Usage: `basename $0` user" 1>&2 ; exit 1; } +USER=$1 + +MFINFO=$(mfinfo) || exit 1 IFS=' ' read -a INFO <<< "$MFINFO" - REPO=${INFO[2]} -OLDBRANCH=${INFO[4]} - -case "$#" in - 1 ) USER=$1 ;; - * ) echo "Usage: `basename $0` [user]" 1>&2 ; exit 1 ;; -esac set -e echo "Adding and fetching $USER..." - -git remote add -f "$USER" "git@github.com:$USER/$REPO.git" +git remote add "$USER" "git@github.com:$USER/$REPO.git" +git fetch "$USER" diff --git a/buildroot/share/git/mfclean b/buildroot/share/git/mfclean index 4ce0faa8f5..99fd227d2c 100755 --- a/buildroot/share/git/mfclean +++ b/buildroot/share/git/mfclean @@ -21,9 +21,10 @@ echo "Pruning Remotely-deleted Branches..." git branch -vv | egrep -v "^\*|$KEEP" | grep ': gone]' | gawk '{print $1}' | xargs -n 1 git branch -D echo +# List fork branches that don't match local branches echo "You may want to remove (or checkout) these refs..." comm -23 \ <(git branch --all | sed 's/^[\* ] //' | grep origin/ | grep -v "\->" | awk '{ print $1; }' | sed 's/remotes\/origin\///') \ <(git branch --all | sed 's/^[\* ] //' | grep -v remotes/ | awk '{ print $1; }') \ - | awk '{ print "git branch -d -r origin/" $1; print "git checkout origin/" $1 " -b " $1; }' + | awk '{ print "git branch -d -r origin/" $1; print "git checkout origin/" $1 " -b " $1; print ""; }' echo diff --git a/buildroot/share/git/mfdoc b/buildroot/share/git/mfdoc index 4b28e9ca14..dde571dd04 100755 --- a/buildroot/share/git/mfdoc +++ b/buildroot/share/git/mfdoc @@ -5,16 +5,15 @@ # Start Jekyll in watch mode to work on Marlin Documentation and preview locally # -MFINFO=$(mfinfo "$@") || exit +[[ $# == 0 ]] || { echo "Usage: `basename $0`" 1>&2 ; exit 1; } + +MFINFO=$(mfinfo "$@") || exit 1 IFS=' ' read -a INFO <<< "$MFINFO" ORG=${INFO[0]} REPO=${INFO[2]} -BRANCH=${INFO[4]} +BRANCH=${INFO[5]} -if [[ $ORG != "MarlinFirmware" || $REPO != "MarlinDocumentation" ]]; then - echo "Wrong repository." - exit -fi +[[ $ORG == "MarlinFirmware" && $REPO == "MarlinDocumentation" ]] || { echo "Wrong repository." 1>&2; exit 1; } opensite() { TOOL=$(which gnome-open xdg-open open | awk '{ print $1 }') diff --git a/buildroot/share/git/mfinfo b/buildroot/share/git/mfinfo index e22744fe90..febbcc3ecf 100755 --- a/buildroot/share/git/mfinfo +++ b/buildroot/share/git/mfinfo @@ -2,27 +2,25 @@ # # mfinfo # -# Get the following helpful git info about the working directory: +# Provide the following info about the working directory: # # - Remote (upstream) Org name (MarlinFirmware) # - Remote (origin) Org name (your Github username) -# - Repo Name (Marlin or MarlinDev) -# - Marlin Target branch (RCBugFix or dev) -# - Branch Name (the current branch or the one that was passed) +# - Repo Name (Marlin, MarlinDev, MarlinDocumentation) +# - PR Target branch (bugfix-1.1.x, dev, or master) +# - Branch Arg (the branch argument or current branch) +# - Current Branch # -REPO=$(git remote get-url upstream 2>/dev/null | sed -E 's/.*\/(.*)\.git/\1/') +CURR=$(git branch 2>/dev/null | grep ^* | sed 's/\* //g') +[[ -z $CURR ]] && { echo "No git repository here!" 1>&2 ; exit 1; } +[[ $CURR == "(no"* ]] && { echo "Git is busy with merge, rebase, etc." 1>&2 ; exit 1; } -if [[ -z $REPO ]]; then - echo "`basename $0`: No 'upstream' remote found." 1>&2 ; exit 1 -fi +REPO=$(git remote get-url upstream 2>/dev/null | sed -E 's/.*\/(.*)\.git/\1/') +[[ -z $REPO ]] && { echo "`basename $0`: No 'upstream' remote found. (Did you run mfinit?)" 1>&2 ; exit 1; } ORG=$(git remote get-url upstream 2>/dev/null | sed -E 's/.*[\/:](.*)\/.*$/\1/') - -if [[ $ORG != MarlinFirmware ]]; then - echo "`basename $0`: Not a Marlin repository." - exit 1 -fi +[[ $ORG == MarlinFirmware ]] || { echo "`basename $0`: Not a Marlin repository." 1>&2 ; exit 1; } case "$REPO" in Marlin ) TARG=bugfix-1.1.x ;; @@ -33,13 +31,9 @@ esac FORK=$(git remote get-url origin 2>/dev/null | sed -E 's/.*[\/:](.*)\/.*$/\1/') case "$#" in - 0 ) BRANCH=$(git branch 2>/dev/null | grep ^* | sed 's/\* //g') ;; + 0 ) BRANCH=$CURR ;; 1 ) BRANCH=$1 ;; * ) echo "Usage: `basename $0` [branch]" 1>&2 ; exit 1 ;; esac -if [[ $BRANCH == "(no" ]]; then - echo "Git is busy with merge, rebase, etc." 1>&2 ; exit 1 -fi - -echo "$ORG $FORK $REPO $TARG $BRANCH" +echo "$ORG $FORK $REPO $TARG $BRANCH $CURR" diff --git a/buildroot/share/git/mfinit b/buildroot/share/git/mfinit index 2a37914601..05bab8767d 100755 --- a/buildroot/share/git/mfinit +++ b/buildroot/share/git/mfinit @@ -5,12 +5,13 @@ # Create the upstream remote for a forked repository # +[[ $# == 0 ]] || { echo "Usage: `basename $0`" 1>&2 ; exit 1; } + +[[ -z $(git branch 2>/dev/null | grep ^* | sed 's/\* //g') ]] && { echo "No git repository here!" 1>&2 ; exit 1; } + REPO=$(git remote get-url origin 2>/dev/null | sed -E 's/.*\/(.*)\.git/\1/') +[[ -z $REPO ]] && { echo "`basename $0`: No 'origin' remote found." 1>&2 ; exit 1; } -if [[ -z $REPO ]]; then - echo "`basename $0`: No 'origin' remote found." 1>&2 ; exit 1 -fi - +echo "Adding 'upstream' remote for convenience." git remote add upstream "git@github.com:MarlinFirmware/$REPO.git" - -git fetch upstream \ No newline at end of file +git fetch upstream diff --git a/buildroot/share/git/mfnew b/buildroot/share/git/mfnew index 42f233bf64..f1e495cbc4 100755 --- a/buildroot/share/git/mfnew +++ b/buildroot/share/git/mfnew @@ -5,14 +5,15 @@ # Create a new branch from the default target with the given name # -MFINFO=$(mfinfo) || exit +[[ $# < 2 ]] || { echo "Usage: `basename $0` [branch]" 1>&2 ; exit 1; } + +MFINFO=$(mfinfo) || exit 1 IFS=' ' read -a INFO <<< "$MFINFO" TARG=${INFO[3]} case "$#" in 0 ) BRANCH=pr_for_$TARG-$(date +"%G-%m-%d_%H.%M.%S") ;; 1 ) BRANCH=$1 ;; - * ) echo "Usage: `basename $0` [branch]" 1>&2 ; exit 1 ;; esac git fetch upstream diff --git a/buildroot/share/git/mfpr b/buildroot/share/git/mfpr index eb2e102aed..025b68692f 100755 --- a/buildroot/share/git/mfpr +++ b/buildroot/share/git/mfpr @@ -5,22 +5,22 @@ # Make a PR of the current branch against RCBugFix or dev # -MFINFO=$(mfinfo "$@") || exit +[[ $# < 2 ]] || { echo "Usage: `basename $0` [branch]" 1>&2 ; exit 1; } +MFINFO=$(mfinfo "$@") || exit 1 IFS=' ' read -a INFO <<< "$MFINFO" - ORG=${INFO[0]} FORK=${INFO[1]} REPO=${INFO[2]} TARG=${INFO[3]} BRANCH=${INFO[4]} +OLDBRANCH=${INFO[5]} -if [[ ! -z "$1" ]]; then { BRANCH=$1 ; git checkout $1 || exit 1; } fi +[[ $BRANCH == $TARG ]] && { echo "Can't create a PR from the PR Target ($BRANCH). Make a copy first." 1>&2 ; exit 1; } -if [[ $BRANCH == $TARG ]]; then - echo "Can't make a PR from $BRANCH" ; exit -fi +[[ $BRANCH != $OLDBRANCH ]] && { git checkout $BRANCH || exit 1; } +# See if it's been pushed yet if [ -z "$(git branch -vv | grep ^\* | grep \\[origin)" ]; then firstpush; fi TOOL=$(which gnome-open xdg-open open | awk '{ print $1 }') @@ -33,3 +33,5 @@ else echo "Opening a New PR Form..." "$TOOL" "$URL" fi + +[[ $BRANCH != $OLDBRANCH ]] && git checkout $OLDBRANCH diff --git a/buildroot/share/git/mfpub b/buildroot/share/git/mfpub index 9e590eb074..9b48480d0e 100755 --- a/buildroot/share/git/mfpub +++ b/buildroot/share/git/mfpub @@ -9,7 +9,9 @@ # any permanent changes to 'master'. # -MFINFO=$(mfinfo "$@") || exit +[[ $# < 2 ]] || { echo "Usage: `basename $0` [branch]" 1>&2 ; exit 1; } + +MFINFO=$(mfinfo "$@") || exit 1 IFS=' ' read -a INFO <<< "$MFINFO" ORG=${INFO[0]} FORK=${INFO[1]} diff --git a/buildroot/share/git/mfqp b/buildroot/share/git/mfqp index 67a385c2ef..97cac5dbef 100755 --- a/buildroot/share/git/mfqp +++ b/buildroot/share/git/mfqp @@ -5,26 +5,22 @@ # Add all changed files, commit as "patch", do `mfrb` and `git push -f` # -MFINFO=$(mfinfo) || exit +[[ $# == 0 ]] || { echo "Usage: `basename $0`" 1>&2 ; exit 1; } + +MFINFO=$(mfinfo) || exit 1 IFS=' ' read -a INFO <<< "$MFINFO" +REPO=${INFO[2]} +TARG=${INFO[3]} +BRANCH=${INFO[5]} -if [[ ${INFO[4]} == "(no" ]]; then - echo "Branch is unavailable!" ; exit 1 -fi - -case "$#" in - 0 ) ;; - * ) echo "Usage: `basename $0`" 1>&2 ; exit 1 ;; -esac - -git add * .travis.yml +git add . git commit -m "patch" -if [[ ${INFO[3]} == ${INFO[4]} ]]; then - if [[ ${INFO[2]} == "MarlinDocumentation" ]]; then +if [[ $BRANCH == $TARG ]]; then + if [[ $REPO == "MarlinDocumentation" ]]; then git rebase -i HEAD~2 else - echo "Don't alter the PR target branch."; exit 1 + echo "Don't alter the PR Target branch."; exit 1 fi else mfrb diff --git a/buildroot/share/git/mfrb b/buildroot/share/git/mfrb index 954556d0e0..b376b40746 100755 --- a/buildroot/share/git/mfrb +++ b/buildroot/share/git/mfrb @@ -5,16 +5,15 @@ # Do "git rebase -i" against the "target" branch (RCBugFix or dev) # -MFINFO=$(mfinfo) || exit -IFS=' ' read -a INFO <<< "$MFINFO" +[[ $# == 0 ]] || { echo "Usage: `basename $0`" 1>&2 ; exit 1; } -case "$#" in - 0 ) ;; - * ) echo "Usage: `basename $0`" 1>&2 ; exit 1 ;; -esac +MFINFO=$(mfinfo) || exit 1 +IFS=' ' read -a INFO <<< "$MFINFO" +TARG=${INFO[3]} +BRANCH=${INFO[5]} # If the branch isn't currently the PR target -if [[ ${INFO[3]} != ${INFO[4]} ]]; then +if [[ $TARG != $BRANCH ]]; then git fetch upstream - git rebase upstream/${INFO[3]} && git rebase -i upstream/${INFO[3]} + git rebase upstream/$TARG && git rebase -i upstream/$TARG fi diff --git a/buildroot/share/git/mfup b/buildroot/share/git/mfup index 8d339c0685..cb6abda9ae 100755 --- a/buildroot/share/git/mfup +++ b/buildroot/share/git/mfup @@ -2,47 +2,55 @@ # # mfup # -# Fetch and merge upstream changes, optionally with a branch +# - 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' +# - # -MFINFO=$(mfinfo) || exit +[[ $# < 2 ]] || { echo "Usage: `basename $0` [branch]" 1>&2 ; exit 1; } +MFINFO=$(mfinfo "$@") || exit 1 IFS=' ' read -a INFO <<< "$MFINFO" - ORG=${INFO[0]} FORK=${INFO[1]} REPO=${INFO[2]} TARG=${INFO[3]} -OLDBRANCH=${INFO[4]} - -case "$#" in - 0 ) BRANCH=$OLDBRANCH ;; - 1 ) BRANCH=$1 ;; - * ) echo "Usage: `basename $0` [branch]" 1>&2 ; exit 1 ;; -esac +BRANCH=${INFO[4]} +OLDBRANCH=${INFO[5]} set -e +# Prevent accidental loss of current changes +[[ $(git stash) != "No local "* ]] && HAS_STASH=1 + echo "Fetching upstream ($ORG/$REPO)..." git fetch upstream echo ; echo "Bringing $TARG up to date..." -git checkout -q $TARG || git branch checkout upstream/$TARG -b $TARG && git push --set-upstream origin $TARG -git merge upstream/$TARG -git push origin +if [[ git checkout -q $TARG ]]; then + git reset --hard upstream/$TARG + git push -f origin +else + git checkout upstream/$TARG -b $TARG + git push --set-upstream origin $TARG +fi if [[ $BRANCH != $TARG ]]; then echo ; echo "Rebasing $BRANCH on $TARG..." if git checkout $BRANCH; then echo if git rebase $TARG; then - git push -f ; echo - [[ $BRANCH != $OLDBRANCH ]] && git checkout $OLDBRANCH + git push -f else - echo "Looks like merge conflicts. Stopping here." + echo "Looks like merge conflicts. Stopping here." ; exit fi else - echo "No such branch!" ; echo - git checkout $OLDBRANCH + echo "No such branch!" fi fi + +echo +[[ $BRANCH != $OLDBRANCH ]] && git checkout $OLDBRANCH + +[[ $HAS_STASH == 1 ]] && git stash pop From e1e1a0c344d987acba62b7c1164cee9ed363f714 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 2 Jul 2017 22:35:28 -0500 Subject: [PATCH 170/180] Provide a default CUSTOM_BOOTSCREEN_TIMEOUT --- Marlin/Marlin_main.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 81fdda8047..39f090b256 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -13031,6 +13031,10 @@ void setup() { lcd_init(); + #ifndef CUSTOM_BOOTSCREEN_TIMEOUT + #define CUSTOM_BOOTSCREEN_TIMEOUT 2500 + #endif + #if ENABLED(SHOW_BOOTSCREEN) #if ENABLED(DOGLCD) // On DOGM the first bootscreen is already drawn #if ENABLED(SHOW_CUSTOM_BOOTSCREEN) From 534bffa7a97a8970bbf5146059744adeb13a901f Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 3 Jul 2017 01:08:59 -0500 Subject: [PATCH 171/180] Correct comment on ABL G29 --- Marlin/Marlin_main.cpp | 12 ++++++++---- 1 file changed, 8 insertions(+), 4 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 39f090b256..7cd18b02be 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -4228,10 +4228,14 @@ void home_all_axes() { gcode_G28(true); } * * A Abort current leveling procedure * - * W Write a mesh point. (Ignored during leveling.) - * X Required X for mesh point - * Y Required Y for mesh point - * Z Z for mesh point. Otherwise, current Z minus Z probe offset. + * Extra parameters with BILINEAR only: + * + * W Write a mesh point. (If G29 is idle.) + * I X index for mesh point + * J Y index for mesh point + * X X for mesh point, overrides I + * Y Y for mesh point, overrides J + * Z Z for mesh point. Otherwise, raw current Z. * * Without PROBE_MANUALLY: * From 6a3967ee331d1816f7bb4f246c95d5ddcae1f100 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 3 Jul 2017 01:09:34 -0500 Subject: [PATCH 172/180] Corrections for probe_pt parameters --- Marlin/Marlin_main.cpp | 2 +- Marlin/ubl_G29.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 7cd18b02be..9eb09cff0b 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -2299,7 +2299,7 @@ static void clean_up_after_endstop_or_probe_move() { * - Raise to the BETWEEN height * - Return the probed Z position */ - float probe_pt(const float &x, const float &y, const bool stow/*=true*/, const int verbose_level/*=1*/) { + float probe_pt(const float &x, const float &y, const bool stow, const uint8_t verbose_level) { #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) { SERIAL_ECHOPAIR(">>> probe_pt(", x); diff --git a/Marlin/ubl_G29.cpp b/Marlin/ubl_G29.cpp index e0b27cb9c0..d8a26c1353 100644 --- a/Marlin/ubl_G29.cpp +++ b/Marlin/ubl_G29.cpp @@ -51,7 +51,7 @@ extern float meshedit_done; extern long babysteps_done; - extern float probe_pt(const float &x, const float &y, bool, int); + extern float probe_pt(const float &x, const float &y, const bool, const uint8_t); extern bool set_probe_deployed(bool); extern void set_bed_leveling_enabled(bool); typedef void (*screenFunc_t)(); From 567941e341a1bb35d183cc0b4b584c1e0dbd7de9 Mon Sep 17 00:00:00 2001 From: LVD-AC Date: Thu, 29 Jun 2017 16:42:42 +0200 Subject: [PATCH 173/180] Fix for issues #6997 and #7152 Probing with the effector in the printing area, but an eccentric probe (e.g. allen key) outside it but still touching the bed gives meaninfull information for calibration. Since calibration is most accurate when probing as close to the towers as possible the testing was way to restrictive hence this fix. --- Marlin/Marlin_main.cpp | 72 +++++++++--------- .../FLSUN/auto_calibrate/Configuration.h | 52 +++++++------ .../delta/FLSUN/kossel_mini/Configuration.h | 59 +++++++-------- .../delta/generic/Configuration.h | 74 +++++++++---------- .../delta/kossel_mini/Configuration.h | 74 +++++++++---------- .../delta/kossel_pro/Configuration.h | 74 +++++++++---------- .../delta/kossel_xl/Configuration.h | 74 +++++++++---------- Marlin/ubl_G29.cpp | 2 +- 8 files changed, 238 insertions(+), 243 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 9eb09cff0b..d7625a1cb0 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -2299,18 +2299,23 @@ static void clean_up_after_endstop_or_probe_move() { * - Raise to the BETWEEN height * - Return the probed Z position */ - float probe_pt(const float &x, const float &y, const bool stow, const uint8_t verbose_level) { + float probe_pt(const float &lx, const float &ly, const bool stow, const uint8_t verbose_level, const bool printable=true) { #if ENABLED(DEBUG_LEVELING_FEATURE) if (DEBUGGING(LEVELING)) { - SERIAL_ECHOPAIR(">>> probe_pt(", x); - SERIAL_ECHOPAIR(", ", y); + SERIAL_ECHOPAIR(">>> probe_pt(", lx); + SERIAL_ECHOPAIR(", ", ly); SERIAL_ECHOPAIR(", ", stow ? "" : "no "); SERIAL_ECHOLNPGM("stow)"); DEBUG_POS("", current_position); } #endif - if (!position_is_reachable_by_probe_xy(x, y)) return NAN; + 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; const float old_feedrate_mm_s = feedrate_mm_s; @@ -2325,7 +2330,7 @@ static void clean_up_after_endstop_or_probe_move() { feedrate_mm_s = XY_PROBE_FEEDRATE_MM_S; // Move the probe to the given XY - do_blocking_move_to_xy(x - (X_PROBE_OFFSET_FROM_EXTRUDER), y - (Y_PROBE_OFFSET_FROM_EXTRUDER)); + do_blocking_move_to_xy(nx, ny); if (DEPLOY_PROBE()) return NAN; @@ -2338,9 +2343,9 @@ static void clean_up_after_endstop_or_probe_move() { if (verbose_level > 2) { SERIAL_PROTOCOLPGM("Bed X: "); - SERIAL_PROTOCOL_F(x, 3); + SERIAL_PROTOCOL_F(lx, 3); SERIAL_PROTOCOLPGM(" Y: "); - SERIAL_PROTOCOL_F(y, 3); + SERIAL_PROTOCOL_F(ly, 3); SERIAL_PROTOCOLPGM(" Z: "); SERIAL_PROTOCOL_F(measured_z, 3); SERIAL_EOL(); @@ -5136,7 +5141,7 @@ void home_all_axes() { gcode_G28(true); } * P3 Probe all positions: center, towers and opposite towers. Set all. * P4-P7 Probe all positions at different locations and average them. * - * T Don't calibrate tower angle corrections + * T0 Don't calibrate tower angle corrections * * Cn.nn Calibration precision; when omitted calibrates to maximum precision * @@ -5185,7 +5190,7 @@ void home_all_axes() { gcode_G28(true); } return; } - const bool towers_set = !parser.boolval('T'), + const bool towers_set = parser.boolval('T', true), stow_after_each = parser.boolval('E'), _1p_calibration = probe_points == 1, _4p_calibration = probe_points == 2, @@ -5198,20 +5203,6 @@ void home_all_axes() { gcode_G28(true); } _7p_quadruple_circle = probe_points == 7, _7p_multi_circle = _7p_double_circle || _7p_triple_circle || _7p_quadruple_circle, _7p_intermed_points = _7p_calibration && !_7p_half_circle; - - if (!_1p_calibration) { // test if the outer radius is reachable - const float circles = (_7p_quadruple_circle ? 1.5 : - _7p_triple_circle ? 1.0 : - _7p_double_circle ? 0.5 : 0), - radius = (1 + circles * 0.1) * delta_calibration_radius; - for (uint8_t axis = 1; axis < 13; ++axis) { - if (!position_is_reachable_xy(cos(RADIANS(180 + 30 * axis)) * radius, sin(RADIANS(180 + 30 * axis)) * radius)) { - SERIAL_PROTOCOLLNPGM("?(M665 B)ed radius is implausible."); - return; - } - } - } - const static char save_message[] PROGMEM = "Save with M500 and/or copy to Configuration.h"; const float dx = (X_PROBE_OFFSET_FROM_EXTRUDER), dy = (Y_PROBE_OFFSET_FROM_EXTRUDER); @@ -5230,6 +5221,19 @@ void home_all_axes() { gcode_G28(true); } alpha_old = delta_tower_angle_trim[A_AXIS], beta_old = delta_tower_angle_trim[B_AXIS]; + if (!_1p_calibration) { // test if the outer radius is reachable + const float circles = (_7p_quadruple_circle ? 1.5 : + _7p_triple_circle ? 1.0 : + _7p_double_circle ? 0.5 : 0), + r = (1 + circles * 0.1) * delta_calibration_radius; + for (uint8_t axis = 1; axis < 13; ++axis) { + const float a = RADIANS(180 + 30 * axis); + if (!position_is_reachable_xy(cos(a) * r, sin(a) * r)) { + SERIAL_PROTOCOLLNPGM("?(M665 B)ed radius is implausible."); + return; + } + } + } SERIAL_PROTOCOLLNPGM("G33 Auto Calibrate"); stepper.synchronize(); @@ -5269,13 +5273,11 @@ void home_all_axes() { gcode_G28(true); } SERIAL_EOL(); } - home_offset[Z_AXIS] -= probe_pt(dx, dy, stow_after_each, 1); // 1st probe to set height - do_probe_raise(Z_CLEARANCE_BETWEEN_PROBES); - + home_offset[Z_AXIS] -= probe_pt(dx, dy, stow_after_each, 1, false); // 1st probe to set height + do { - float z_at_pt[13] = { 0.0 }, S1 = 0.0, S2 = 0.0; - int16_t N = 0; + float z_at_pt[13] = { 0.0 }; test_precision = zero_std_dev_old != 999.0 ? (zero_std_dev + zero_std_dev_old) / 2 : zero_std_dev; @@ -5284,12 +5286,12 @@ void home_all_axes() { gcode_G28(true); } // Probe the points if (!_7p_half_circle && !_7p_triple_circle) { // probe the center - z_at_pt[0] += probe_pt(dx, dy, stow_after_each, 1); + z_at_pt[0] += probe_pt(dx, dy, stow_after_each, 1, false); } if (_7p_calibration) { // probe extra center points for (int8_t axis = _7p_multi_circle ? 11 : 9; axis > 0; axis -= _7p_multi_circle ? 2 : 4) { const float a = RADIANS(180 + 30 * axis), r = delta_calibration_radius * 0.1; - z_at_pt[0] += probe_pt(cos(a) * r + dx, sin(a) * r + dy, stow_after_each, 1); + z_at_pt[0] += probe_pt(cos(a) * r + dx, sin(a) * r + dy, stow_after_each, 1, false); } z_at_pt[0] /= float(_7p_double_circle ? 7 : probe_points); } @@ -5305,19 +5307,19 @@ void home_all_axes() { gcode_G28(true); } for (float circles = -offset_circles ; circles <= offset_circles; circles++) { const float a = RADIANS(180 + 30 * axis), r = delta_calibration_radius * (1 + circles * (zig_zag ? 0.1 : -0.1)); - z_at_pt[axis] += probe_pt(cos(a) * r + dx, sin(a) * r + dy, stow_after_each, 1); + z_at_pt[axis] += probe_pt(cos(a) * r + dx, sin(a) * r + dy, stow_after_each, 1, false); } zig_zag = !zig_zag; z_at_pt[axis] /= (2 * offset_circles + 1); } } if (_7p_intermed_points) // average intermediates to tower and opposites - for (uint8_t axis = 1; axis <= 11; axis += 2) + for (uint8_t axis = 1; axis < 13; axis += 2) z_at_pt[axis] = (z_at_pt[axis] + (z_at_pt[axis + 1] + z_at_pt[(axis + 10) % 12 + 1]) / 2.0) / 2.0; - S1 += z_at_pt[0]; - S2 += sq(z_at_pt[0]); - N++; + float S1 = z_at_pt[0], + S2 = sq(z_at_pt[0]); + int16_t N = 1; if (!_1p_calibration) // std dev from zero plane for (uint8_t axis = (_4p_opposite_points ? 3 : 1); axis < 13; axis += (_4p_calibration ? 4 : 2)) { S1 += z_at_pt[axis]; diff --git a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h index cebc4f21b7..a5841ca4c9 100644 --- a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h +++ b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h @@ -461,47 +461,51 @@ // and processor overload (too many expensive sqrt calls). #define DELTA_SEGMENTS_PER_SECOND 160 - // NOTE NB all values for DELTA_* values MUST be floating point, so always have a decimal point in them - - // Center-to-center distance of the holes in the diagonal push rods. - #define DELTA_DIAGONAL_ROD 218.0 // mm - - // Horizontal distance bridged by diagonal push rods when effector is centered. - #define DELTA_RADIUS 100.00 //mm Get this value from auto calibrate - - // height from z=0 to home position - #define DELTA_HEIGHT 295.00 // get this value from auto calibrate - use G33 P1 at 1st time calibration - - // Print surface diameter/2 minus unreachable space (avoid collisions with vertical towers). - #define DELTA_PRINTABLE_RADIUS 85.0 + // After homing move down to a height where XY movement is unconstrained + //#define DELTA_HOME_TO_SAFE_ZONE // Delta calibration menu // uncomment to add three points calibration menu option. // See http://minow.blogspot.com/index.html#4918805519571907051 #define DELTA_CALIBRATION_MENU - // set the radius for the calibration probe points - max DELTA_PRINTABLE_RADIUS*0.869 if DELTA_AUTO_CALIBRATION enabled - #define DELTA_CALIBRATION_RADIUS ((DELTA_PRINTABLE_RADIUS) * 0.869) // mm - - // G33 Delta Auto-Calibration (Enable EEPROM_SETTINGS to store results) + // uncomment to add G33 Delta Auto-Calibration (Enable EEPROM_SETTINGS to store results) #define DELTA_AUTO_CALIBRATION + + // NOTE NB all values for DELTA_* values MUST be floating point, so always have a decimal point in them + #if ENABLED(DELTA_AUTO_CALIBRATION) - #define DELTA_CALIBRATION_DEFAULT_POINTS 4 // set the default number of probe points : n*n (-7 -> +7) + // set the default number of probe points : n*n (1 -> 7) + #define DELTA_CALIBRATION_DEFAULT_POINTS 4 #endif - // After homing move down to a height where XY movement is unconstrained - #define DELTA_HOME_TO_SAFE_ZONE + #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 + #endif - #define DELTA_ENDSTOP_ADJ { 0, 0, 0 } // get these from auto calibrate + // Print surface diameter/2 minus unreachable space (avoid collisions with vertical towers). + #define DELTA_PRINTABLE_RADIUS 85.0 // mm + // Center-to-center distance of the holes in the diagonal push rods. + #define DELTA_DIAGONAL_ROD 218.0 // mm + + // height from z=0 to home position + #define DELTA_HEIGHT 295.00 // get this value from auto calibrate + + #define DELTA_ENDSTOP_ADJ { 0.0, 0.0, 0.0 } // get these from auto calibrate + + // 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 - #define DELTA_TOWER_ANGLE_TRIM { 0, 0, 0 } // get these from auto calibrate + #define DELTA_TOWER_ANGLE_TRIM { 0.0, 0.0, 0.0 } // get these values from auto calibrate // delta radius and diaginal rod adjustments measured in mm - //#define DELTA_RADIUS_TRIM_TOWER {0, 0, 0} - //#define DELTA_DIAGONAL_ROD_TRIM_TOWER {0, 0, 0} + //#define DELTA_RADIUS_TRIM_TOWER { 0.0, 0.0, 0.0 } + //#define DELTA_DIAGONAL_ROD_TRIM_TOWER { 0.0, 0.0, 0.0 } #endif diff --git a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h index 21cde2c919..4740af68ee 100644 --- a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h +++ b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h @@ -461,54 +461,51 @@ // and processor overload (too many expensive sqrt calls). #define DELTA_SEGMENTS_PER_SECOND 160 - // Center-to-center distance of the holes in the diagonal push rods. - #define DELTA_DIAGONAL_ROD 218.0 // mm - - // Horizontal offset from middle of printer to smooth rod center. - #define DELTA_SMOOTH_ROD_OFFSET 150.0 // mm - - // Horizontal offset of the universal joints on the end effector. - #define DELTA_EFFECTOR_OFFSET 24.0 // mm - - // Horizontal offset of the universal joints on the carriages. - #define DELTA_CARRIAGE_OFFSET 22.0 // mm - - // Horizontal distance bridged by diagonal push rods when effector is centered. - #define DELTA_RADIUS (DELTA_SMOOTH_ROD_OFFSET - DELTA_EFFECTOR_OFFSET - DELTA_CARRIAGE_OFFSET) //mm Get this value from auto calibrate - - // height from z=0.00 to home position - #define DELTA_HEIGHT 280 // get this value from auto calibrate - use G33 P1 at 1st time calibration - - // Print surface diameter/2 minus unreachable space (avoid collisions with vertical towers). - #define DELTA_PRINTABLE_RADIUS 85.0 + // After homing move down to a height where XY movement is unconstrained + //#define DELTA_HOME_TO_SAFE_ZONE // Delta calibration menu // uncomment to add three points calibration menu option. // See http://minow.blogspot.com/index.html#4918805519571907051 //#define DELTA_CALIBRATION_MENU - // set the radius for the calibration probe points - max DELTA_PRINTABLE_RADIUS*0.869 if DELTA_AUTO_CALIBRATION enabled - #define DELTA_CALIBRATION_RADIUS ((DELTA_PRINTABLE_RADIUS) * 0.869) // mm - - // G33 Delta Auto-Calibration (Enable EEPROM_SETTINGS to store results) + // uncomment to add G33 Delta Auto-Calibration (Enable EEPROM_SETTINGS to store results) //#define DELTA_AUTO_CALIBRATION + + // NOTE NB all values for DELTA_* values MUST be floating point, so always have a decimal point in them + #if ENABLED(DELTA_AUTO_CALIBRATION) - #define DELTA_CALIBRATION_DEFAULT_POINTS 3 // set the default number of probe points : n*n (-7 -> +7) + // set the default number of probe points : n*n (1 -> 7) + #define DELTA_CALIBRATION_DEFAULT_POINTS 4 #endif - // After homing move down to a height where XY movement is unconstrained - //#define DELTA_HOME_TO_SAFE_ZONE + #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 + #endif - #define DELTA_ENDSTOP_ADJ { 0, 0, 0 } // get these from auto calibrate + // Print surface diameter/2 minus unreachable space (avoid collisions with vertical towers). + #define DELTA_PRINTABLE_RADIUS 85.0 // mm + // Center-to-center distance of the holes in the diagonal push rods. + #define DELTA_DIAGONAL_ROD 218.0 // mm + + // height from z=0 to home position + #define DELTA_HEIGHT 280.00 // get this value from auto calibrate + + #define DELTA_ENDSTOP_ADJ { 0.0, 0.0, 0.0 } // get these from auto calibrate + + // 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 - #define DELTA_TOWER_ANGLE_TRIM { 0, 0, 0 } // get these from auto calibrate + #define DELTA_TOWER_ANGLE_TRIM { 0.0, 0.0, 0.0 } // get these values from auto calibrate // delta radius and diaginal rod adjustments measured in mm - //#define DELTA_RADIUS_TRIM_TOWER {0, 0, 0} - //#define DELTA_DIAGONAL_ROD_TRIM_TOWER {0, 0, 0} + //#define DELTA_RADIUS_TRIM_TOWER { 0.0, 0.0, 0.0 } + //#define DELTA_DIAGONAL_ROD_TRIM_TOWER { 0.0, 0.0, 0.0 } #endif diff --git a/Marlin/example_configurations/delta/generic/Configuration.h b/Marlin/example_configurations/delta/generic/Configuration.h index 4eeb5fa549..7832d8498c 100644 --- a/Marlin/example_configurations/delta/generic/Configuration.h +++ b/Marlin/example_configurations/delta/generic/Configuration.h @@ -451,53 +451,51 @@ // and processor overload (too many expensive sqrt calls). #define DELTA_SEGMENTS_PER_SECOND 200 - // Center-to-center distance of the holes in the diagonal push rods. - #define DELTA_DIAGONAL_ROD 250.0 // mm - - // Horizontal offset from middle of printer to smooth rod center. - #define DELTA_SMOOTH_ROD_OFFSET 175.0 // mm - - // Horizontal offset of the universal joints on the end effector. - #define DELTA_EFFECTOR_OFFSET 33.0 // mm - - // Horizontal offset of the universal joints on the carriages. - #define DELTA_CARRIAGE_OFFSET 18.0 // mm - - // Horizontal distance bridged by diagonal push rods when effector is centered. - #define DELTA_RADIUS (DELTA_SMOOTH_ROD_OFFSET - DELTA_EFFECTOR_OFFSET - DELTA_CARRIAGE_OFFSET) //mm Get this value from auto calibrate - - // height from z=0.00 to home position - #define DELTA_HEIGHT 250 // get this value from auto calibrate - use G33 P1 at 1st time calibration - - // Print surface diameter/2 minus unreachable space (avoid collisions with vertical towers). - #define DELTA_PRINTABLE_RADIUS 140.0 - - // Delta calibration menu - // See http://minow.blogspot.com/index.html#4918805519571907051 - //#define DELTA_CALIBRATION_MENU - - // set the radius for the calibration probe points - max DELTA_PRINTABLE_RADIUS*0.869 if DELTA_AUTO_CALIBRATION enabled - #define DELTA_CALIBRATION_RADIUS ((DELTA_PRINTABLE_RADIUS) * 0.869) // mm - - // G33 Delta Auto-Calibration (Enable EEPROM_SETTINGS to store results) - //#define DELTA_AUTO_CALIBRATION - #if ENABLED(DELTA_AUTO_CALIBRATION) - #define DELTA_CALIBRATION_DEFAULT_POINTS 3 // set the default number of probe points : n*n (-7 -> +7) - #endif - // After homing move down to a height where XY movement is unconstrained //#define DELTA_HOME_TO_SAFE_ZONE - #define DELTA_ENDSTOP_ADJ { 0, 0, 0 } // get these from auto calibrate + // Delta calibration menu + // uncomment to add three points calibration menu option. + // See http://minow.blogspot.com/index.html#4918805519571907051 + //#define DELTA_CALIBRATION_MENU + // uncomment to add G33 Delta Auto-Calibration (Enable EEPROM_SETTINGS to store results) + //#define DELTA_AUTO_CALIBRATION + + // NOTE NB all values for DELTA_* values MUST be floating point, so always have a decimal point in them + + #if ENABLED(DELTA_AUTO_CALIBRATION) + // set the default number of probe points : n*n (1 -> 7) + #define DELTA_CALIBRATION_DEFAULT_POINTS 4 + #endif + + #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 + #endif + + // Print surface diameter/2 minus unreachable space (avoid collisions with vertical towers). + #define DELTA_PRINTABLE_RADIUS 140.0 // mm + + // Center-to-center distance of the holes in the diagonal push rods. + #define DELTA_DIAGONAL_ROD 250.0 // mm + + // height from z=0 to home position + #define DELTA_HEIGHT 250.00 // get this value from auto calibrate + + #define DELTA_ENDSTOP_ADJ { 0.0, 0.0, 0.0 } // get these from auto calibrate + + // 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 - #define DELTA_TOWER_ANGLE_TRIM { 0, 0, 0 } // get these from auto calibrate + #define DELTA_TOWER_ANGLE_TRIM { 0.0, 0.0, 0.0 } // get these values from auto calibrate // delta radius and diaginal rod adjustments measured in mm - //#define DELTA_RADIUS_TRIM_TOWER {0, 0, 0} - //#define DELTA_DIAGONAL_ROD_TRIM_TOWER {0, 0, 0} + //#define DELTA_RADIUS_TRIM_TOWER { 0.0, 0.0, 0.0 } + //#define DELTA_DIAGONAL_ROD_TRIM_TOWER { 0.0, 0.0, 0.0 } #endif diff --git a/Marlin/example_configurations/delta/kossel_mini/Configuration.h b/Marlin/example_configurations/delta/kossel_mini/Configuration.h index a443734c9a..67c53fea87 100644 --- a/Marlin/example_configurations/delta/kossel_mini/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_mini/Configuration.h @@ -451,53 +451,51 @@ // and processor overload (too many expensive sqrt calls). #define DELTA_SEGMENTS_PER_SECOND 200 - // Center-to-center distance of the holes in the diagonal push rods. - #define DELTA_DIAGONAL_ROD 215.0 // mm - - // Horizontal offset from middle of printer to smooth rod center. - #define DELTA_SMOOTH_ROD_OFFSET 145.0 // mm - - // Horizontal offset of the universal joints on the end effector. - #define DELTA_EFFECTOR_OFFSET 19.9 // mm - - // Horizontal offset of the universal joints on the carriages. - #define DELTA_CARRIAGE_OFFSET 19.5 // mm - - // Horizontal distance bridged by diagonal push rods when effector is centered. - #define DELTA_RADIUS (DELTA_SMOOTH_ROD_OFFSET - DELTA_EFFECTOR_OFFSET - DELTA_CARRIAGE_OFFSET) //mm Get this value from auto calibrate - - // height from z=0.00 to home position - #define DELTA_HEIGHT 250 // get this value from auto calibrate - use G33 P1 at 1st time calibration - - // Print surface diameter/2 minus unreachable space (avoid collisions with vertical towers). - #define DELTA_PRINTABLE_RADIUS 90.0 - - // Delta calibration menu - // See http://minow.blogspot.com/index.html#4918805519571907051 - //#define DELTA_CALIBRATION_MENU - - // set the radius for the calibration probe points - max DELTA_PRINTABLE_RADIUS*0.869 if DELTA_AUTO_CALIBRATION enabled - #define DELTA_CALIBRATION_RADIUS ((DELTA_PRINTABLE_RADIUS) * 0.869) // mm - - // G33 Delta Auto-Calibration (Enable EEPROM_SETTINGS to store results) - //#define DELTA_AUTO_CALIBRATION - #if ENABLED(DELTA_AUTO_CALIBRATION) - #define DELTA_CALIBRATION_DEFAULT_POINTS 3 // set the default number of probe points : n*n (-7 -> +7) - #endif - // After homing move down to a height where XY movement is unconstrained //#define DELTA_HOME_TO_SAFE_ZONE - #define DELTA_ENDSTOP_ADJ { 0, 0, 0 } // get these from auto calibrate + // Delta calibration menu + // uncomment to add three points calibration menu option. + // See http://minow.blogspot.com/index.html#4918805519571907051 + //#define DELTA_CALIBRATION_MENU + // uncomment to add G33 Delta Auto-Calibration (Enable EEPROM_SETTINGS to store results) + //#define DELTA_AUTO_CALIBRATION + + // NOTE NB all values for DELTA_* values MUST be floating point, so always have a decimal point in them + + #if ENABLED(DELTA_AUTO_CALIBRATION) + // set the default number of probe points : n*n (1 -> 7) + #define DELTA_CALIBRATION_DEFAULT_POINTS 4 + #endif + + #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 + #endif + + // Print surface diameter/2 minus unreachable space (avoid collisions with vertical towers). + #define DELTA_PRINTABLE_RADIUS 90.0 // mm + + // Center-to-center distance of the holes in the diagonal push rods. + #define DELTA_DIAGONAL_ROD 215.0 // mm + + // height from z=0 to home position + #define DELTA_HEIGHT 250.00 // get this value from auto calibrate + + #define DELTA_ENDSTOP_ADJ { 0.0, 0.0, 0.0 } // get these from auto calibrate + + // 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 - #define DELTA_TOWER_ANGLE_TRIM { 0, 0, 0 } // get these from auto calibrate + #define DELTA_TOWER_ANGLE_TRIM { 0.0, 0.0, 0.0 } // get these values from auto calibrate // delta radius and diaginal rod adjustments measured in mm - //#define DELTA_RADIUS_TRIM_TOWER {0, 0, 0} - //#define DELTA_DIAGONAL_ROD_TRIM_TOWER {0, 0, 0} + //#define DELTA_RADIUS_TRIM_TOWER { 0.0, 0.0, 0.0 } + //#define DELTA_DIAGONAL_ROD_TRIM_TOWER { 0.0, 0.0, 0.0 } #endif diff --git a/Marlin/example_configurations/delta/kossel_pro/Configuration.h b/Marlin/example_configurations/delta/kossel_pro/Configuration.h index a7f99428af..bee38afde0 100644 --- a/Marlin/example_configurations/delta/kossel_pro/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_pro/Configuration.h @@ -437,53 +437,51 @@ // and processor overload (too many expensive sqrt calls). #define DELTA_SEGMENTS_PER_SECOND 160 - // Center-to-center distance of the holes in the diagonal push rods. - #define DELTA_DIAGONAL_ROD 301.0 // mm - - // Horizontal offset from middle of printer to smooth rod center. - #define DELTA_SMOOTH_ROD_OFFSET 212.357 // mm - - // Horizontal offset of the universal joints on the end effector. - #define DELTA_EFFECTOR_OFFSET 30.0 // mm - - // Horizontal offset of the universal joints on the carriages. - #define DELTA_CARRIAGE_OFFSET 30.0 // mm - - // Horizontal distance bridged by diagonal push rods when effector is centered. - #define DELTA_RADIUS (DELTA_SMOOTH_ROD_OFFSET - DELTA_EFFECTOR_OFFSET - DELTA_CARRIAGE_OFFSET) //mm Get this value from auto calibrate - - // height from z=0.00 to home position - #define DELTA_HEIGHT 277 // get this value from auto calibrate - use G33 P1 at 1st time calibration - - // Print surface diameter/2 minus unreachable space (avoid collisions with vertical towers). - #define DELTA_PRINTABLE_RADIUS 127.0 - - // Delta calibration menu - // See http://minow.blogspot.com/index.html#4918805519571907051 - //#define DELTA_CALIBRATION_MENU - - // set the radius for the calibration probe points - max DELTA_PRINTABLE_RADIUS*0.869 if DELTA_AUTO_CALIBRATION enabled - #define DELTA_CALIBRATION_RADIUS ((DELTA_PRINTABLE_RADIUS) * 0.869) // mm - - // G33 Delta Auto-Calibration (Enable EEPROM_SETTINGS to store results) - //#define DELTA_AUTO_CALIBRATION - #if ENABLED(DELTA_AUTO_CALIBRATION) - #define DELTA_CALIBRATION_DEFAULT_POINTS 3 // set the default number of probe points : n*n (-7 -> +7) - #endif - // After homing move down to a height where XY movement is unconstrained //#define DELTA_HOME_TO_SAFE_ZONE - #define DELTA_ENDSTOP_ADJ { 0, 0, 0 } // get these from auto calibrate + // Delta calibration menu + // uncomment to add three points calibration menu option. + // See http://minow.blogspot.com/index.html#4918805519571907051 + //#define DELTA_CALIBRATION_MENU + // uncomment to add G33 Delta Auto-Calibration (Enable EEPROM_SETTINGS to store results) + //#define DELTA_AUTO_CALIBRATION + + // NOTE NB all values for DELTA_* values MUST be floating point, so always have a decimal point in them + + #if ENABLED(DELTA_AUTO_CALIBRATION) + // set the default number of probe points : n*n (1 -> 7) + #define DELTA_CALIBRATION_DEFAULT_POINTS 4 + #endif + + #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 + #endif + + // Print surface diameter/2 minus unreachable space (avoid collisions with vertical towers). + #define DELTA_PRINTABLE_RADIUS 127.0 // mm + + // Center-to-center distance of the holes in the diagonal push rods. + #define DELTA_DIAGONAL_ROD 301.0 // mm + + // height from z=0 to home position + #define DELTA_HEIGHT 277.00 // get this value from auto calibrate + + #define DELTA_ENDSTOP_ADJ { 0.0, 0.0, 0.0 } // get these from auto calibrate + + // 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 - #define DELTA_TOWER_ANGLE_TRIM { 0, 0, 0 } // get these from auto calibrate + #define DELTA_TOWER_ANGLE_TRIM { 0.0, 0.0, 0.0 } // get these values from auto calibrate // delta radius and diaginal rod adjustments measured in mm - //#define DELTA_RADIUS_TRIM_TOWER {0, 0, 0} - //#define DELTA_DIAGONAL_ROD_TRIM_TOWER {0, 0, 0} + //#define DELTA_RADIUS_TRIM_TOWER { 0.0, 0.0, 0.0 } + //#define DELTA_DIAGONAL_ROD_TRIM_TOWER { 0.0, 0.0, 0.0 } #endif diff --git a/Marlin/example_configurations/delta/kossel_xl/Configuration.h b/Marlin/example_configurations/delta/kossel_xl/Configuration.h index 689b4b400a..b46e688f11 100644 --- a/Marlin/example_configurations/delta/kossel_xl/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_xl/Configuration.h @@ -455,53 +455,51 @@ // and processor overload (too many expensive sqrt calls). #define DELTA_SEGMENTS_PER_SECOND 160 - // Center-to-center distance of the holes in the diagonal push rods. - #define DELTA_DIAGONAL_ROD 317.3 + 2.5 // mm - - // Horizontal offset from middle of printer to smooth rod center. - #define DELTA_SMOOTH_ROD_OFFSET 220.1 // mm - - // Horizontal offset of the universal joints on the end effector. - #define DELTA_EFFECTOR_OFFSET 24.0 // mm - - // Horizontal offset of the universal joints on the carriages. - #define DELTA_CARRIAGE_OFFSET 22.0 // mm - - // Horizontal distance bridged by diagonal push rods when effector is centered. - #define DELTA_RADIUS (DELTA_SMOOTH_ROD_OFFSET - DELTA_EFFECTOR_OFFSET - DELTA_CARRIAGE_OFFSET) //mm Get this value from auto calibrate - - // height from z=0.00 to home position - #define DELTA_HEIGHT 380 // get this value from auto calibrate - use G33 P1 at 1st time calibration - - // Print surface diameter/2 minus unreachable space (avoid collisions with vertical towers). - #define DELTA_PRINTABLE_RADIUS 140.0 - - // Delta calibration menu - // See http://minow.blogspot.com/index.html#4918805519571907051 - //#define DELTA_CALIBRATION_MENU - - // set the radius for the calibration probe points - max DELTA_PRINTABLE_RADIUS*0.869 if DELTA_AUTO_CALIBRATION enabled - #define DELTA_CALIBRATION_RADIUS ((DELTA_PRINTABLE_RADIUS) * 0.869) // mm - - // G33 Delta Auto-Calibration (Enable EEPROM_SETTINGS to store results) - //#define DELTA_AUTO_CALIBRATION - #if ENABLED(DELTA_AUTO_CALIBRATION) - #define DELTA_CALIBRATION_DEFAULT_POINTS 3 // set the default number of probe points : n*n (-7 -> +7) - #endif - // After homing move down to a height where XY movement is unconstrained //#define DELTA_HOME_TO_SAFE_ZONE - #define DELTA_ENDSTOP_ADJ { 0, 0, 0 } // get these from auto calibrate + // Delta calibration menu + // uncomment to add three points calibration menu option. + // See http://minow.blogspot.com/index.html#4918805519571907051 + //#define DELTA_CALIBRATION_MENU + // uncomment to add G33 Delta Auto-Calibration (Enable EEPROM_SETTINGS to store results) + //#define DELTA_AUTO_CALIBRATION + + // NOTE NB all values for DELTA_* values MUST be floating point, so always have a decimal point in them + + #if ENABLED(DELTA_AUTO_CALIBRATION) + // set the default number of probe points : n*n (1 -> 7) + #define DELTA_CALIBRATION_DEFAULT_POINTS 4 + #endif + + #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 + #endif + + // Print surface diameter/2 minus unreachable space (avoid collisions with vertical towers). + #define DELTA_PRINTABLE_RADIUS 140.0 // mm + + // Center-to-center distance of the holes in the diagonal push rods. + #define DELTA_DIAGONAL_ROD 319.5 // mm + + // height from z=0 to home position + #define DELTA_HEIGHT 380.00 // get this value from auto calibrate + + #define DELTA_ENDSTOP_ADJ { 0.0, 0.0, 0.0 } // get these from auto calibrate + + // 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 - #define DELTA_TOWER_ANGLE_TRIM { 0, 0, 0 } // get these from auto calibrate + #define DELTA_TOWER_ANGLE_TRIM { 0.0, 0.0, 0.0 } // get these values from auto calibrate // delta radius and diaginal rod adjustments measured in mm - //#define DELTA_RADIUS_TRIM_TOWER {0, 0, 0} - //#define DELTA_DIAGONAL_ROD_TRIM_TOWER {0, 0, 0} + //#define DELTA_RADIUS_TRIM_TOWER { 0.0, 0.0, 0.0 } + //#define DELTA_DIAGONAL_ROD_TRIM_TOWER { 0.0, 0.0, 0.0 } #endif diff --git a/Marlin/ubl_G29.cpp b/Marlin/ubl_G29.cpp index d8a26c1353..162e27c0fe 100644 --- a/Marlin/ubl_G29.cpp +++ b/Marlin/ubl_G29.cpp @@ -51,7 +51,7 @@ extern float meshedit_done; extern long babysteps_done; - extern float probe_pt(const float &x, const float &y, const bool, const uint8_t); + extern float probe_pt(const float &lx, const float &ly, const bool, const uint8_t, const bool=true); extern bool set_probe_deployed(bool); extern void set_bed_leveling_enabled(bool); typedef void (*screenFunc_t)(); From 4be8d7720e5766b2a68fd293e10213bfb2d0c4b3 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 3 Jul 2017 15:24:49 -0500 Subject: [PATCH 174/180] Fix spelling of "Chinese" --- Marlin/language_zh_CN.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/language_zh_CN.h b/Marlin/language_zh_CN.h index deefcf6c54..4ee33b4c74 100644 --- a/Marlin/language_zh_CN.h +++ b/Marlin/language_zh_CN.h @@ -21,7 +21,7 @@ */ /** - * Simplified Chineses + * Simplified Chinese * * LCD Menu Messages * See also https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language From df87278fced7c290656242cdae58e535e40d2811 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 3 Jul 2017 15:59:06 -0500 Subject: [PATCH 175/180] Add "CAP:PRINT_JOB:1" (M75 / M76 / M77) to M115 output --- Marlin/Marlin_main.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index d7625a1cb0..a70e9cc8de 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -7933,6 +7933,9 @@ inline void gcode_M115() { // PROGRESS (M530 S L, M531 , M532 X L) SERIAL_PROTOCOLLNPGM("Cap:PROGRESS:0"); + // Print Job timer M75, M76, M77 + SERIAL_PROTOCOLLNPGM("Cap:PRINT_JOB:1"); + // AUTOLEVEL (G29) #if HAS_ABL SERIAL_PROTOCOLLNPGM("Cap:AUTOLEVEL:1"); From c28749a5677f941ca45945bc1bd9cafc45802368 Mon Sep 17 00:00:00 2001 From: Ben Lye Date: Sun, 2 Jul 2017 09:44:24 +0100 Subject: [PATCH 176/180] Add kill action Sends pre-defined string as action command when printer is kill. --- Marlin/Configuration_adv.h | 7 +++++++ Marlin/Marlin_main.cpp | 4 ++++ Marlin/example_configurations/Anet/A6/Configuration_adv.h | 7 +++++++ Marlin/example_configurations/Anet/A8/Configuration_adv.h | 7 +++++++ Marlin/example_configurations/Cartesio/Configuration_adv.h | 7 +++++++ Marlin/example_configurations/Felix/Configuration_adv.h | 7 +++++++ .../FolgerTech-i3-2020/Configuration_adv.h | 7 +++++++ .../example_configurations/Hephestos/Configuration_adv.h | 7 +++++++ .../example_configurations/Hephestos_2/Configuration_adv.h | 7 +++++++ Marlin/example_configurations/K8200/Configuration_adv.h | 7 +++++++ Marlin/example_configurations/K8400/Configuration_adv.h | 7 +++++++ Marlin/example_configurations/M150/Configuration_adv.h | 7 +++++++ Marlin/example_configurations/RigidBot/Configuration_adv.h | 7 +++++++ Marlin/example_configurations/SCARA/Configuration_adv.h | 7 +++++++ Marlin/example_configurations/TAZ4/Configuration_adv.h | 7 +++++++ Marlin/example_configurations/TinyBoy2/Configuration_adv.h | 7 +++++++ Marlin/example_configurations/WITBOX/Configuration_adv.h | 7 +++++++ .../delta/FLSUN/auto_calibrate/Configuration_adv.h | 7 +++++++ .../delta/FLSUN/kossel_mini/Configuration_adv.h | 7 +++++++ .../delta/generic/Configuration_adv.h | 7 +++++++ .../delta/kossel_mini/Configuration_adv.h | 7 +++++++ .../delta/kossel_pro/Configuration_adv.h | 7 +++++++ .../delta/kossel_xl/Configuration_adv.h | 7 +++++++ .../gCreate_gMax1.5+/Configuration_adv.h | 7 +++++++ Marlin/example_configurations/makibox/Configuration_adv.h | 7 +++++++ .../tvrrug/Round2/Configuration_adv.h | 7 +++++++ Marlin/example_configurations/wt150/Configuration_adv.h | 7 +++++++ 27 files changed, 186 insertions(+) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index e68c485635..57c3716132 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1268,6 +1268,13 @@ #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 ====================== //=========================================================================== diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index c280c10027..0b2765acb7 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -12836,6 +12836,10 @@ 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) + SERIAL_ECHOLNPGM("//action:" ACTION_ON_KILL); + #endif + #if HAS_POWER_SWITCH SET_INPUT(PS_ON_PIN); #endif diff --git a/Marlin/example_configurations/Anet/A6/Configuration_adv.h b/Marlin/example_configurations/Anet/A6/Configuration_adv.h index 30526adf62..ea27f9331f 100644 --- a/Marlin/example_configurations/Anet/A6/Configuration_adv.h +++ b/Marlin/example_configurations/Anet/A6/Configuration_adv.h @@ -1268,6 +1268,13 @@ #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 ====================== //=========================================================================== diff --git a/Marlin/example_configurations/Anet/A8/Configuration_adv.h b/Marlin/example_configurations/Anet/A8/Configuration_adv.h index cc72206cf5..c264b17be2 100644 --- a/Marlin/example_configurations/Anet/A8/Configuration_adv.h +++ b/Marlin/example_configurations/Anet/A8/Configuration_adv.h @@ -1268,6 +1268,13 @@ #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 ====================== //=========================================================================== diff --git a/Marlin/example_configurations/Cartesio/Configuration_adv.h b/Marlin/example_configurations/Cartesio/Configuration_adv.h index 1de847b7f6..f71292cbd5 100644 --- a/Marlin/example_configurations/Cartesio/Configuration_adv.h +++ b/Marlin/example_configurations/Cartesio/Configuration_adv.h @@ -1261,6 +1261,13 @@ #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 ====================== //=========================================================================== diff --git a/Marlin/example_configurations/Felix/Configuration_adv.h b/Marlin/example_configurations/Felix/Configuration_adv.h index 8e5e5fab00..94fcbf30bf 100644 --- a/Marlin/example_configurations/Felix/Configuration_adv.h +++ b/Marlin/example_configurations/Felix/Configuration_adv.h @@ -1261,6 +1261,13 @@ //#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 ====================== //=========================================================================== diff --git a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h index 5031cfb2d7..4b3fb35682 100644 --- a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h +++ b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration_adv.h @@ -1274,6 +1274,13 @@ //#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 ====================== //=========================================================================== diff --git a/Marlin/example_configurations/Hephestos/Configuration_adv.h b/Marlin/example_configurations/Hephestos/Configuration_adv.h index bf39fff886..89f30b1fe2 100644 --- a/Marlin/example_configurations/Hephestos/Configuration_adv.h +++ b/Marlin/example_configurations/Hephestos/Configuration_adv.h @@ -1261,6 +1261,13 @@ //#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 ====================== //=========================================================================== diff --git a/Marlin/example_configurations/Hephestos_2/Configuration_adv.h b/Marlin/example_configurations/Hephestos_2/Configuration_adv.h index 4be6605e34..8ee2095aae 100644 --- a/Marlin/example_configurations/Hephestos_2/Configuration_adv.h +++ b/Marlin/example_configurations/Hephestos_2/Configuration_adv.h @@ -1244,6 +1244,13 @@ //#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 ====================== //=========================================================================== diff --git a/Marlin/example_configurations/K8200/Configuration_adv.h b/Marlin/example_configurations/K8200/Configuration_adv.h index d931ab26ce..5adbc19d82 100644 --- a/Marlin/example_configurations/K8200/Configuration_adv.h +++ b/Marlin/example_configurations/K8200/Configuration_adv.h @@ -1274,6 +1274,13 @@ //#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 ====================== //=========================================================================== diff --git a/Marlin/example_configurations/K8400/Configuration_adv.h b/Marlin/example_configurations/K8400/Configuration_adv.h index 0f650aa952..04ed926e1f 100644 --- a/Marlin/example_configurations/K8400/Configuration_adv.h +++ b/Marlin/example_configurations/K8400/Configuration_adv.h @@ -1261,6 +1261,13 @@ //#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 ====================== //=========================================================================== diff --git a/Marlin/example_configurations/M150/Configuration_adv.h b/Marlin/example_configurations/M150/Configuration_adv.h index 49bcfcf586..d31f0320a3 100644 --- a/Marlin/example_configurations/M150/Configuration_adv.h +++ b/Marlin/example_configurations/M150/Configuration_adv.h @@ -1268,6 +1268,13 @@ #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 ====================== //=========================================================================== diff --git a/Marlin/example_configurations/RigidBot/Configuration_adv.h b/Marlin/example_configurations/RigidBot/Configuration_adv.h index 84921f2250..ac15cd3561 100644 --- a/Marlin/example_configurations/RigidBot/Configuration_adv.h +++ b/Marlin/example_configurations/RigidBot/Configuration_adv.h @@ -1261,6 +1261,13 @@ //#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 ====================== //=========================================================================== diff --git a/Marlin/example_configurations/SCARA/Configuration_adv.h b/Marlin/example_configurations/SCARA/Configuration_adv.h index 59304ae0c4..d820ed78be 100644 --- a/Marlin/example_configurations/SCARA/Configuration_adv.h +++ b/Marlin/example_configurations/SCARA/Configuration_adv.h @@ -1261,6 +1261,13 @@ //#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 ====================== //=========================================================================== diff --git a/Marlin/example_configurations/TAZ4/Configuration_adv.h b/Marlin/example_configurations/TAZ4/Configuration_adv.h index f7184724f6..6800a96bc0 100644 --- a/Marlin/example_configurations/TAZ4/Configuration_adv.h +++ b/Marlin/example_configurations/TAZ4/Configuration_adv.h @@ -1261,6 +1261,13 @@ //#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 ====================== //=========================================================================== diff --git a/Marlin/example_configurations/TinyBoy2/Configuration_adv.h b/Marlin/example_configurations/TinyBoy2/Configuration_adv.h index 494d58ca07..5f332f31a7 100644 --- a/Marlin/example_configurations/TinyBoy2/Configuration_adv.h +++ b/Marlin/example_configurations/TinyBoy2/Configuration_adv.h @@ -1264,6 +1264,13 @@ //#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 ====================== //=========================================================================== diff --git a/Marlin/example_configurations/WITBOX/Configuration_adv.h b/Marlin/example_configurations/WITBOX/Configuration_adv.h index bf39fff886..89f30b1fe2 100644 --- a/Marlin/example_configurations/WITBOX/Configuration_adv.h +++ b/Marlin/example_configurations/WITBOX/Configuration_adv.h @@ -1261,6 +1261,13 @@ //#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 ====================== //=========================================================================== 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 51019d2287..66b681d177 100644 --- a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h +++ b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration_adv.h @@ -1266,6 +1266,13 @@ #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 ====================== //=========================================================================== 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 d00185a6a6..8de3b0bdf8 100644 --- a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h +++ b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration_adv.h @@ -1265,6 +1265,13 @@ #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 ====================== //=========================================================================== diff --git a/Marlin/example_configurations/delta/generic/Configuration_adv.h b/Marlin/example_configurations/delta/generic/Configuration_adv.h index 6fd092e0bb..fd2bdf30f1 100644 --- a/Marlin/example_configurations/delta/generic/Configuration_adv.h +++ b/Marlin/example_configurations/delta/generic/Configuration_adv.h @@ -1263,6 +1263,13 @@ #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 ====================== //=========================================================================== diff --git a/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h index 6fd092e0bb..fd2bdf30f1 100644 --- a/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_mini/Configuration_adv.h @@ -1263,6 +1263,13 @@ #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 ====================== //=========================================================================== diff --git a/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h index f2a74f2910..f7ae11b992 100644 --- a/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_pro/Configuration_adv.h @@ -1268,6 +1268,13 @@ #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 ====================== //=========================================================================== diff --git a/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h b/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h index 00a02b39b2..ef02e75594 100644 --- a/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h +++ b/Marlin/example_configurations/delta/kossel_xl/Configuration_adv.h @@ -1263,6 +1263,13 @@ //#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 ====================== //=========================================================================== diff --git a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration_adv.h b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration_adv.h index cf0cc38efb..7846249545 100644 --- a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration_adv.h +++ b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration_adv.h @@ -1270,6 +1270,13 @@ //#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 ====================== //=========================================================================== diff --git a/Marlin/example_configurations/makibox/Configuration_adv.h b/Marlin/example_configurations/makibox/Configuration_adv.h index 8a7a61da4a..58b2a842d7 100644 --- a/Marlin/example_configurations/makibox/Configuration_adv.h +++ b/Marlin/example_configurations/makibox/Configuration_adv.h @@ -1261,6 +1261,13 @@ //#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 ====================== //=========================================================================== diff --git a/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h b/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h index 5de0a43bb8..de5a967b7e 100644 --- a/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h +++ b/Marlin/example_configurations/tvrrug/Round2/Configuration_adv.h @@ -1261,6 +1261,13 @@ //#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 ====================== //=========================================================================== diff --git a/Marlin/example_configurations/wt150/Configuration_adv.h b/Marlin/example_configurations/wt150/Configuration_adv.h index 97f73b2e82..bf612de948 100644 --- a/Marlin/example_configurations/wt150/Configuration_adv.h +++ b/Marlin/example_configurations/wt150/Configuration_adv.h @@ -1351,6 +1351,13 @@ #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 ====================== //=========================================================================== From 20f6676d63c8922615462bddae27ae0a1f608c12 Mon Sep 17 00:00:00 2001 From: Dave Johnson Date: Mon, 3 Jul 2017 17:23:53 -0700 Subject: [PATCH 177/180] DISABLE_[XYZ] compatibility check DISABLE_[XYZ] is incompatible with HOME_AFTER_DEACTIVATE and Z_SAFE_HOMING --- Marlin/SanityCheck.h | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/Marlin/SanityCheck.h b/Marlin/SanityCheck.h index 1b96714862..bd33460cb8 100644 --- a/Marlin/SanityCheck.h +++ b/Marlin/SanityCheck.h @@ -752,6 +752,15 @@ static_assert(1 >= 0 #endif #endif // Z_SAFE_HOMING +/** + * Make sure DISABLE_[XYZ] compatible with selected homing options + */ +#if ENABLED(DISABLE_X) || ENABLED(DISABLE_Y) || ENABLED(DISABLE_Z) + #if ENABLED(HOME_AFTER_DEACTIVATE) || ENABLED(Z_SAFE_HOMING) + #error "DISABLE_[XYZ] not compatible with HOME_AFTER_DEACTIVATE or Z_SAFE_HOMING." + #endif +#endif // DISABLE_[XYZ] + /** * Advance Extrusion */ From 8c34233452c9c0360ec93c1645a8a1a57364647f Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Petr=20Zahradn=C3=ADk?= Date: Sat, 1 Jul 2017 14:50:26 +0200 Subject: [PATCH 178/180] UTF-8 mapper for Czech --- Marlin/Configuration.h | 7 +- Marlin/dogm_font_data_ISO10646_CZ.h | 192 ++++++++++ .../Anet/A6/Configuration.h | 7 +- .../Anet/A8/Configuration.h | 7 +- .../CL-260/Configuration.h | 7 +- .../Cartesio/Configuration.h | 7 +- .../Felix/Configuration.h | 7 +- .../Felix/DUAL/Configuration.h | 7 +- .../FolgerTech-i3-2020/Configuration.h | 7 +- .../Hephestos/Configuration.h | 7 +- .../Hephestos_2/Configuration.h | 7 +- .../K8200/Configuration.h | 7 +- .../K8400/Configuration.h | 7 +- .../K8400/Dual-head/Configuration.h | 7 +- .../M150/Configuration.h | 7 +- .../RepRapWorld/Megatronics/Configuration.h | 7 +- .../RigidBot/Configuration.h | 7 +- .../SCARA/Configuration.h | 7 +- .../TAZ4/Configuration.h | 7 +- .../TinyBoy2/Configuration.h | 7 +- .../WITBOX/Configuration.h | 7 +- .../adafruit/ST7565/Configuration.h | 7 +- .../FLSUN/auto_calibrate/Configuration.h | 7 +- .../delta/FLSUN/kossel_mini/Configuration.h | 7 +- .../delta/generic/Configuration.h | 7 +- .../delta/kossel_mini/Configuration.h | 7 +- .../delta/kossel_pro/Configuration.h | 7 +- .../delta/kossel_xl/Configuration.h | 7 +- .../gCreate_gMax1.5+/Configuration.h | 7 +- .../makibox/Configuration.h | 7 +- .../tvrrug/Round2/Configuration.h | 7 +- .../wt150/Configuration.h | 7 +- Marlin/language.h | 6 +- Marlin/language_cz.h | 4 +- Marlin/language_cz_utf8.h | 351 ++++++++++++++++++ Marlin/language_kana_utf8.h | 3 +- Marlin/language_pt-br_utf8.h | 1 + Marlin/language_pt_utf8.h | 1 + Marlin/ultralcd_impl_DOGM.h | 3 + Marlin/utf_mapper.h | 134 +++++-- buildroot/share/fonts/ISO10646_CZ.fon | Bin 0 -> 4224 bytes 41 files changed, 793 insertions(+), 119 deletions(-) create mode 100644 Marlin/dogm_font_data_ISO10646_CZ.h create mode 100644 Marlin/language_cz_utf8.h create mode 100644 buildroot/share/fonts/ISO10646_CZ.fon diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 2537051245..46bc9aeafa 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -1151,10 +1151,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 diff --git a/Marlin/dogm_font_data_ISO10646_CZ.h b/Marlin/dogm_font_data_ISO10646_CZ.h new file mode 100644 index 0000000000..671ad8ea2d --- /dev/null +++ b/Marlin/dogm_font_data_ISO10646_CZ.h @@ -0,0 +1,192 @@ +/* + Fontname: ISO10646_CZ + Copyright: A. Hardtung, public domain + Modified for Czech accents by Petr Zahradnik, http://www.zahradniksebavi.cz + Capital A Height: 7, '1' Height: 7 + Calculated Max Values w= 6 h= 9 x= 2 y= 7 dx= 6 dy= 0 ascent= 8 len= 9 + Font Bounding box w= 6 h= 9 x= 0 y=-2 + Calculated Min Values x= 0 y=-1 dx= 0 dy= 0 + Pure Font ascent = 7 descent=-1 + X Font ascent = 7 descent=-1 + Max Font ascent = 8 descent=-1 +*/ +#include +const u8g_fntpgm_uint8_t ISO10646_CZ[2832] U8G_SECTION(".progmem.ISO10646_CZ") = { + 0,6,9,0,254,7,1,146,3,33,32,255,255,8,255,7, + 255,0,0,0,6,0,0,1,7,7,6,2,0,128,128,128, + 128,128,0,128,3,2,2,6,1,5,160,160,5,7,7,6, + 0,0,80,80,248,80,248,80,80,5,7,7,6,0,0,32, + 120,160,112,40,240,32,5,7,7,6,0,0,192,200,16,32, + 64,152,24,5,7,7,6,0,0,96,144,160,64,168,144,104, + 2,3,3,6,1,4,192,64,128,3,7,7,6,1,0,32, + 64,128,128,128,64,32,3,7,7,6,1,0,128,64,32,32, + 32,64,128,5,5,5,6,0,1,32,168,112,168,32,5,5, + 5,6,0,1,32,32,248,32,32,2,3,3,6,2,255,192, + 64,128,5,1,1,6,0,3,248,2,2,2,6,2,0,192, + 192,5,5,5,6,0,1,8,16,32,64,128,5,7,7,6, + 0,0,112,136,136,136,136,136,112,3,7,7,6,1,0,64, + 192,64,64,64,64,224,5,7,7,6,0,0,112,136,8,112, + 128,128,248,5,7,7,6,0,0,248,16,32,16,8,8,240, + 5,7,7,6,0,0,16,48,80,144,248,16,16,5,7,7, + 6,0,0,248,128,240,8,8,136,112,5,7,7,6,0,0, + 112,128,128,240,136,136,112,5,7,7,6,0,0,248,8,16, + 32,32,32,32,5,7,7,6,0,0,112,136,136,112,136,136, + 112,5,7,7,6,0,0,112,136,136,120,8,8,112,2,5, + 5,6,2,0,192,192,0,192,192,2,6,6,6,2,255,192, + 192,0,192,64,128,4,7,7,6,0,0,16,32,64,128,64, + 32,16,5,3,3,6,0,2,248,0,248,4,7,7,6,1, + 0,128,64,32,16,32,64,128,5,7,7,6,0,0,112,136, + 8,16,32,0,32,5,7,7,6,0,0,112,136,8,104,168, + 168,112,5,7,7,6,0,0,112,136,136,248,136,136,136,5, + 7,7,6,0,0,240,136,136,240,136,136,240,5,7,7,6, + 0,0,112,136,128,128,128,136,112,5,7,7,6,0,0,240, + 136,136,136,136,136,240,5,7,7,6,0,0,248,128,128,240, + 128,128,248,5,7,7,6,0,0,248,128,128,240,128,128,128, + 5,7,7,6,0,0,112,136,128,184,136,136,112,5,7,7, + 6,0,0,136,136,136,248,136,136,136,1,7,7,6,2,0, + 128,128,128,128,128,128,128,5,7,7,6,0,0,56,16,16, + 16,16,144,96,5,7,7,6,0,0,136,144,160,192,160,144, + 136,5,7,7,6,0,0,128,128,128,128,128,128,248,5,7, + 7,6,0,0,136,216,168,136,136,136,136,5,7,7,6,0, + 0,136,136,200,168,152,136,136,5,7,7,6,0,0,112,136, + 136,136,136,136,112,5,7,7,6,0,0,240,136,136,240,128, + 128,128,5,7,7,6,0,0,112,136,136,136,168,144,104,5, + 7,7,6,0,0,240,136,136,240,160,144,136,5,7,7,6, + 0,0,120,128,128,112,8,8,240,5,7,7,6,0,0,248, + 32,32,32,32,32,32,5,7,7,6,0,0,136,136,136,136, + 136,136,112,5,7,7,6,0,0,136,136,136,136,136,80,32, + 5,7,7,6,0,0,136,136,136,136,136,168,80,5,7,7, + 6,0,0,136,136,80,32,80,136,136,5,7,7,6,0,0, + 136,136,136,80,32,32,32,5,7,7,6,0,0,248,8,16, + 32,64,128,248,3,7,7,6,1,0,224,128,128,128,128,128, + 224,5,5,5,6,0,1,128,64,32,16,8,3,7,7,6, + 1,0,224,32,32,32,32,32,224,5,3,3,6,0,4,32, + 80,136,5,1,1,6,0,0,248,2,2,2,6,2,5,128, + 64,5,5,5,6,0,0,112,8,120,136,120,5,7,7,6, + 0,0,128,128,176,200,136,136,240,5,5,5,6,0,0,112, + 128,128,136,112,5,7,7,6,0,0,8,8,104,152,136,136, + 120,5,5,5,6,0,0,112,136,248,128,112,5,7,7,6, + 0,0,48,72,224,64,64,64,64,5,6,6,6,0,255,112, + 136,136,120,8,112,5,7,7,6,0,0,128,128,176,200,136, + 136,136,1,7,7,6,2,0,128,0,128,128,128,128,128,3, + 8,8,6,1,255,32,0,32,32,32,32,160,64,4,7,7, + 6,0,0,128,128,144,160,192,160,144,3,7,7,6,1,0, + 192,64,64,64,64,64,224,5,5,5,6,0,0,208,168,168, + 168,168,5,5,5,6,0,0,176,200,136,136,136,5,5,5, + 6,0,0,112,136,136,136,112,5,6,6,6,0,255,240,136, + 136,240,128,128,5,6,6,6,0,255,120,136,136,120,8,8, + 5,5,5,6,0,0,176,200,128,128,128,5,5,5,6,0, + 0,112,128,112,8,240,4,7,7,6,0,0,64,64,224,64, + 64,64,48,5,5,5,6,0,0,136,136,136,152,104,5,5, + 5,6,0,0,136,136,136,80,32,5,5,5,6,0,0,136, + 136,168,168,80,5,5,5,6,0,0,136,80,32,80,136,5, + 6,6,6,0,255,136,136,136,120,8,112,5,5,5,6,0, + 0,248,16,32,64,248,3,7,7,6,1,0,32,64,64,128, + 64,64,32,1,7,7,6,2,0,128,128,128,128,128,128,128, + 3,7,7,6,1,0,128,64,64,32,64,64,128,5,2,2, + 6,0,2,104,144,0,0,0,6,0,0,5,8,8,6,0, + 0,16,32,112,136,136,248,136,136,5,8,8,6,0,0,8, + 16,248,128,128,240,128,248,3,8,8,6,1,0,32,64,224, + 64,64,64,64,224,5,8,8,6,0,0,16,32,112,136,136, + 136,136,112,5,8,8,6,0,0,16,32,136,136,136,136,136, + 112,5,8,8,6,0,0,16,32,136,136,80,32,32,32,5, + 8,8,6,0,0,16,32,0,112,8,120,136,120,5,8,8, + 6,0,0,16,32,0,112,136,248,128,112,2,8,8,6,2, + 0,64,128,0,128,128,128,128,128,5,8,8,6,0,0,16, + 32,0,112,136,136,136,112,5,8,8,6,0,0,16,32,0, + 136,136,136,152,104,5,9,9,6,0,255,16,32,0,136,136, + 136,120,8,112,5,8,8,6,0,0,80,32,112,136,128,128, + 136,112,5,8,8,6,0,0,80,32,0,112,128,128,136,112, + 5,8,8,6,0,0,80,32,240,136,136,136,136,240,6,8, + 8,6,0,0,4,20,24,112,144,144,144,112,5,8,8,6, + 0,0,80,32,248,128,128,240,128,248,5,8,8,6,0,0, + 80,32,0,112,136,248,128,112,5,8,8,6,0,0,80,32, + 136,200,168,152,136,136,5,8,8,6,0,0,80,32,0,176, + 200,136,136,136,5,8,8,6,0,0,80,32,240,136,240,160, + 144,136,5,8,8,6,0,0,80,32,0,176,200,128,128,128, + 5,8,8,6,0,0,80,32,120,128,128,112,8,240,5,8, + 8,6,0,0,80,32,0,112,128,112,8,240,5,8,8,6, + 0,0,80,32,248,32,32,32,32,32,6,8,8,6,0,0, + 4,68,72,224,64,64,64,48,5,8,8,6,0,0,32,80, + 168,136,136,136,136,112,5,8,8,6,0,0,32,80,32,136, + 136,136,152,104,5,8,8,6,0,0,80,32,248,8,48,64, + 128,248,5,8,8,6,0,0,80,32,0,248,16,32,64,248, + 0,0,0,6,0,0,0,0,0,6,0,0,0,0,0,6, + 0,0,1,7,7,6,2,0,128,0,128,128,128,128,128,5, + 7,7,6,0,0,32,112,168,160,168,112,32,5,7,7,6, + 0,0,48,64,64,224,64,80,168,5,5,5,6,0,0,136, + 112,80,112,136,5,7,7,6,0,0,136,80,32,248,32,248, + 32,1,7,7,6,2,0,128,128,128,0,128,128,128,5,8, + 8,6,0,0,48,72,32,80,80,32,144,96,3,1,1,6, + 1,7,160,5,7,7,6,0,0,248,136,184,184,184,136,248, + 5,7,7,6,0,1,112,8,120,136,120,0,248,5,5,5, + 6,0,1,40,80,160,80,40,5,3,3,6,0,1,248,8, + 8,2,2,2,6,2,6,64,128,5,7,7,6,0,0,248, + 136,168,136,152,168,248,5,1,1,6,0,6,248,4,4,4, + 6,0,3,96,144,144,96,5,7,7,6,0,0,32,32,248, + 32,32,0,248,4,5,5,6,0,3,96,144,32,64,240,3, + 5,5,6,0,3,224,32,224,32,224,2,2,2,6,2,6, + 64,128,5,8,8,6,0,255,136,136,136,136,152,232,128,128, + 5,7,7,6,0,0,120,152,152,120,24,24,24,2,2,2, + 6,2,2,192,192,2,2,2,6,2,255,64,128,3,5,5, + 6,0,3,64,192,64,64,224,5,7,7,6,0,1,112,136, + 136,136,112,0,248,5,5,5,6,0,1,160,80,40,80,160, + 5,7,7,6,0,0,136,144,168,88,184,8,8,5,7,7, + 6,0,0,136,144,184,72,152,32,56,5,8,8,6,0,0, + 192,64,192,72,216,56,8,8,5,7,7,6,0,0,32,0, + 32,64,128,136,112,5,8,8,6,0,0,64,32,0,112,136, + 248,136,136,5,8,8,6,0,0,16,32,0,112,136,248,136, + 136,5,8,8,6,0,0,32,80,0,112,136,248,136,136,5, + 8,8,6,0,0,104,144,0,112,136,248,136,136,5,8,8, + 6,0,0,80,0,112,136,136,248,136,136,5,8,8,6,0, + 0,32,80,32,112,136,248,136,136,5,7,7,6,0,0,56, + 96,160,184,224,160,184,5,8,8,6,0,255,112,136,128,128, + 136,112,32,96,5,8,8,6,0,0,64,32,0,248,128,240, + 128,248,5,8,8,6,0,0,8,16,0,248,128,240,128,248, + 5,8,8,6,0,0,32,80,0,248,128,240,128,248,5,7, + 7,6,0,0,80,0,248,128,240,128,248,3,8,8,6,1, + 0,128,64,0,224,64,64,64,224,3,8,8,6,1,0,32, + 64,0,224,64,64,64,224,3,8,8,6,1,0,64,160,0, + 224,64,64,64,224,3,7,7,6,1,0,160,0,224,64,64, + 64,224,5,9,9,6,0,255,80,32,112,136,128,184,136,136, + 112,5,8,8,6,0,0,104,144,0,136,200,168,152,136,5, + 8,8,6,0,0,64,32,112,136,136,136,136,112,5,8,8, + 6,0,0,16,32,112,136,136,136,136,112,5,8,8,6,0, + 0,32,80,0,112,136,136,136,112,5,8,8,6,0,0,104, + 144,0,112,136,136,136,112,5,8,8,6,0,0,80,0,112, + 136,136,136,136,112,5,5,5,6,0,1,136,80,32,80,136, + 5,8,8,6,0,255,16,112,168,168,168,168,112,64,5,8, + 8,6,0,0,64,32,136,136,136,136,136,112,5,8,8,6, + 0,0,16,32,136,136,136,136,136,112,5,8,8,6,0,0, + 32,80,0,136,136,136,136,112,5,8,8,6,0,0,80,0, + 136,136,136,136,136,112,1,7,7,6,2,0,128,0,128,128, + 128,128,128,5,9,9,6,0,255,120,128,128,112,8,8,240, + 32,96,4,8,8,6,1,255,96,144,144,160,144,144,224,128, + 5,8,8,6,0,0,64,32,0,112,8,120,136,120,5,8, + 8,6,0,0,16,32,0,112,8,120,136,120,5,8,8,6, + 0,0,32,80,0,112,8,120,136,120,5,8,8,6,0,0, + 104,144,0,112,8,120,136,120,5,7,7,6,0,0,80,0, + 112,8,120,136,120,5,8,8,6,0,0,32,80,32,112,8, + 120,136,120,5,6,6,6,0,0,208,40,120,160,168,80,5, + 7,7,6,0,255,112,128,128,136,112,32,96,5,8,8,6, + 0,0,64,32,0,112,136,248,128,112,5,8,8,6,0,0, + 16,32,0,112,136,248,128,112,5,8,8,6,0,0,32,80, + 0,112,136,248,128,112,5,7,7,6,0,0,80,0,112,136, + 248,128,112,3,8,8,6,1,0,128,64,0,64,192,64,64, + 224,3,8,8,6,1,0,32,64,0,64,192,64,64,224,3, + 8,8,6,1,0,64,160,0,64,192,64,64,224,3,7,7, + 6,1,0,160,0,64,192,64,64,224,5,8,8,6,0,255, + 80,32,112,136,136,120,8,112,5,8,8,6,0,0,104,144, + 0,176,200,136,136,136,5,8,8,6,0,0,64,32,0,112, + 136,136,136,112,5,8,8,6,0,0,16,32,0,112,136,136, + 136,112,5,8,8,6,0,0,32,80,0,112,136,136,136,112, + 5,8,8,6,0,0,104,144,0,112,136,136,136,112,5,7, + 7,6,0,0,80,0,112,136,136,136,112,5,5,5,6,0, + 1,32,0,248,0,32,5,7,7,6,0,255,16,112,168,168, + 168,112,64,5,8,8,6,0,0,64,32,0,136,136,136,152, + 104,5,8,8,6,0,0,16,32,0,136,136,136,152,104,5, + 8,8,6,0,0,32,80,0,136,136,136,152,104,5,7,7, + 6,0,0,80,0,136,136,136,152,104,1,5,5,6,2,0, + 128,128,128,128,128,5,7,7,6,0,255,112,128,112,8,240, + 32,96,5,8,8,6,0,255,80,0,136,136,136,120,8,112 + }; diff --git a/Marlin/example_configurations/Anet/A6/Configuration.h b/Marlin/example_configurations/Anet/A6/Configuration.h index b68d501dab..c007dfd871 100644 --- a/Marlin/example_configurations/Anet/A6/Configuration.h +++ b/Marlin/example_configurations/Anet/A6/Configuration.h @@ -1307,10 +1307,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 diff --git a/Marlin/example_configurations/Anet/A8/Configuration.h b/Marlin/example_configurations/Anet/A8/Configuration.h index 102eb6d382..cf307c20a6 100644 --- a/Marlin/example_configurations/Anet/A8/Configuration.h +++ b/Marlin/example_configurations/Anet/A8/Configuration.h @@ -1157,10 +1157,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 diff --git a/Marlin/example_configurations/CL-260/Configuration.h b/Marlin/example_configurations/CL-260/Configuration.h index 2789fc1929..368ac8583d 100644 --- a/Marlin/example_configurations/CL-260/Configuration.h +++ b/Marlin/example_configurations/CL-260/Configuration.h @@ -1148,10 +1148,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 diff --git a/Marlin/example_configurations/Cartesio/Configuration.h b/Marlin/example_configurations/Cartesio/Configuration.h index e434ab36cc..18e5c7bbce 100644 --- a/Marlin/example_configurations/Cartesio/Configuration.h +++ b/Marlin/example_configurations/Cartesio/Configuration.h @@ -1145,10 +1145,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 diff --git a/Marlin/example_configurations/Felix/Configuration.h b/Marlin/example_configurations/Felix/Configuration.h index fc95ab86e8..dac548dcd0 100644 --- a/Marlin/example_configurations/Felix/Configuration.h +++ b/Marlin/example_configurations/Felix/Configuration.h @@ -1129,10 +1129,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 diff --git a/Marlin/example_configurations/Felix/DUAL/Configuration.h b/Marlin/example_configurations/Felix/DUAL/Configuration.h index 6c9957190a..9289dafb77 100644 --- a/Marlin/example_configurations/Felix/DUAL/Configuration.h +++ b/Marlin/example_configurations/Felix/DUAL/Configuration.h @@ -1129,10 +1129,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 diff --git a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h index 9c3c4f21c6..0bc709730d 100644 --- a/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h +++ b/Marlin/example_configurations/FolgerTech-i3-2020/Configuration.h @@ -1151,10 +1151,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 diff --git a/Marlin/example_configurations/Hephestos/Configuration.h b/Marlin/example_configurations/Hephestos/Configuration.h index b78fd16b6e..f5e915c319 100644 --- a/Marlin/example_configurations/Hephestos/Configuration.h +++ b/Marlin/example_configurations/Hephestos/Configuration.h @@ -1137,10 +1137,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 diff --git a/Marlin/example_configurations/Hephestos_2/Configuration.h b/Marlin/example_configurations/Hephestos_2/Configuration.h index d8204cf843..31d3e90c48 100644 --- a/Marlin/example_configurations/Hephestos_2/Configuration.h +++ b/Marlin/example_configurations/Hephestos_2/Configuration.h @@ -1140,10 +1140,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 diff --git a/Marlin/example_configurations/K8200/Configuration.h b/Marlin/example_configurations/K8200/Configuration.h index da28640a68..170a018fc0 100644 --- a/Marlin/example_configurations/K8200/Configuration.h +++ b/Marlin/example_configurations/K8200/Configuration.h @@ -1179,10 +1179,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 diff --git a/Marlin/example_configurations/K8400/Configuration.h b/Marlin/example_configurations/K8400/Configuration.h index dc2ddef719..e647c8dd2a 100644 --- a/Marlin/example_configurations/K8400/Configuration.h +++ b/Marlin/example_configurations/K8400/Configuration.h @@ -1147,10 +1147,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 diff --git a/Marlin/example_configurations/K8400/Dual-head/Configuration.h b/Marlin/example_configurations/K8400/Dual-head/Configuration.h index 8d054cf3c8..4fdebe88aa 100644 --- a/Marlin/example_configurations/K8400/Dual-head/Configuration.h +++ b/Marlin/example_configurations/K8400/Dual-head/Configuration.h @@ -1147,10 +1147,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 diff --git a/Marlin/example_configurations/M150/Configuration.h b/Marlin/example_configurations/M150/Configuration.h index 80a3fd8037..9ff8c97bb2 100644 --- a/Marlin/example_configurations/M150/Configuration.h +++ b/Marlin/example_configurations/M150/Configuration.h @@ -1174,10 +1174,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 diff --git a/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h b/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h index 2ba532f0a2..40ce7aee3c 100644 --- a/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h +++ b/Marlin/example_configurations/RepRapWorld/Megatronics/Configuration.h @@ -1147,10 +1147,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 diff --git a/Marlin/example_configurations/RigidBot/Configuration.h b/Marlin/example_configurations/RigidBot/Configuration.h index 822eb2f9cb..a51bfc7cfa 100644 --- a/Marlin/example_configurations/RigidBot/Configuration.h +++ b/Marlin/example_configurations/RigidBot/Configuration.h @@ -1145,10 +1145,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 diff --git a/Marlin/example_configurations/SCARA/Configuration.h b/Marlin/example_configurations/SCARA/Configuration.h index 3f507c554d..f9e9de755f 100644 --- a/Marlin/example_configurations/SCARA/Configuration.h +++ b/Marlin/example_configurations/SCARA/Configuration.h @@ -1159,10 +1159,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 diff --git a/Marlin/example_configurations/TAZ4/Configuration.h b/Marlin/example_configurations/TAZ4/Configuration.h index 57e1ec05ba..470a4ad73c 100644 --- a/Marlin/example_configurations/TAZ4/Configuration.h +++ b/Marlin/example_configurations/TAZ4/Configuration.h @@ -1166,10 +1166,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 diff --git a/Marlin/example_configurations/TinyBoy2/Configuration.h b/Marlin/example_configurations/TinyBoy2/Configuration.h index 12040db8f9..a5a7cf47e9 100644 --- a/Marlin/example_configurations/TinyBoy2/Configuration.h +++ b/Marlin/example_configurations/TinyBoy2/Configuration.h @@ -1203,10 +1203,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 diff --git a/Marlin/example_configurations/WITBOX/Configuration.h b/Marlin/example_configurations/WITBOX/Configuration.h index 2c85b8136d..266a1ae2b5 100644 --- a/Marlin/example_configurations/WITBOX/Configuration.h +++ b/Marlin/example_configurations/WITBOX/Configuration.h @@ -1137,10 +1137,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 diff --git a/Marlin/example_configurations/adafruit/ST7565/Configuration.h b/Marlin/example_configurations/adafruit/ST7565/Configuration.h index cf9526bd5b..19f2021c66 100644 --- a/Marlin/example_configurations/adafruit/ST7565/Configuration.h +++ b/Marlin/example_configurations/adafruit/ST7565/Configuration.h @@ -1147,10 +1147,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 diff --git a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h index a5841ca4c9..c336127b33 100644 --- a/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h +++ b/Marlin/example_configurations/delta/FLSUN/auto_calibrate/Configuration.h @@ -1271,10 +1271,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 diff --git a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h index 4740af68ee..eaa3364ee5 100644 --- a/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h +++ b/Marlin/example_configurations/delta/FLSUN/kossel_mini/Configuration.h @@ -1266,10 +1266,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 diff --git a/Marlin/example_configurations/delta/generic/Configuration.h b/Marlin/example_configurations/delta/generic/Configuration.h index 7832d8498c..36ae17e975 100644 --- a/Marlin/example_configurations/delta/generic/Configuration.h +++ b/Marlin/example_configurations/delta/generic/Configuration.h @@ -1256,10 +1256,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 diff --git a/Marlin/example_configurations/delta/kossel_mini/Configuration.h b/Marlin/example_configurations/delta/kossel_mini/Configuration.h index 67c53fea87..c1e6749099 100644 --- a/Marlin/example_configurations/delta/kossel_mini/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_mini/Configuration.h @@ -1259,10 +1259,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 diff --git a/Marlin/example_configurations/delta/kossel_pro/Configuration.h b/Marlin/example_configurations/delta/kossel_pro/Configuration.h index bee38afde0..59fe5dc428 100644 --- a/Marlin/example_configurations/delta/kossel_pro/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_pro/Configuration.h @@ -1264,10 +1264,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 diff --git a/Marlin/example_configurations/delta/kossel_xl/Configuration.h b/Marlin/example_configurations/delta/kossel_xl/Configuration.h index b46e688f11..0b682d3d62 100644 --- a/Marlin/example_configurations/delta/kossel_xl/Configuration.h +++ b/Marlin/example_configurations/delta/kossel_xl/Configuration.h @@ -1322,10 +1322,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 diff --git a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h index acd6514b78..6667ef1473 100644 --- a/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h +++ b/Marlin/example_configurations/gCreate_gMax1.5+/Configuration.h @@ -1163,10 +1163,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 diff --git a/Marlin/example_configurations/makibox/Configuration.h b/Marlin/example_configurations/makibox/Configuration.h index 71d65aeb9d..e45e8d2e6a 100644 --- a/Marlin/example_configurations/makibox/Configuration.h +++ b/Marlin/example_configurations/makibox/Configuration.h @@ -1150,10 +1150,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 diff --git a/Marlin/example_configurations/tvrrug/Round2/Configuration.h b/Marlin/example_configurations/tvrrug/Round2/Configuration.h index bd74eba1ed..9edc8914cc 100644 --- a/Marlin/example_configurations/tvrrug/Round2/Configuration.h +++ b/Marlin/example_configurations/tvrrug/Round2/Configuration.h @@ -1142,10 +1142,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 diff --git a/Marlin/example_configurations/wt150/Configuration.h b/Marlin/example_configurations/wt150/Configuration.h index 3a0e403c52..d9c4b4a2f6 100644 --- a/Marlin/example_configurations/wt150/Configuration.h +++ b/Marlin/example_configurations/wt150/Configuration.h @@ -1153,10 +1153,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 diff --git a/Marlin/language.h b/Marlin/language.h index 914c0363d0..e0cad44e2b 100644 --- a/Marlin/language.h +++ b/Marlin/language.h @@ -52,6 +52,7 @@ // ca Catalan // cn Chinese // cz Czech +// cz_utf8 Czech (UTF8) // de German // el Greek // el-gr Greek (Greece) @@ -69,7 +70,7 @@ // pl Polish // pt Portuguese // pt-br Portuguese (Brazilian) -// pt-br_utf8 Portuguese (Brazilian UTF8) +// pt-br_utf8 Portuguese (Brazilian) (UTF8) // pt_utf8 Portuguese (UTF8) // ru Russian // tr Turkish @@ -299,7 +300,8 @@ && DISABLED(DISPLAY_CHARSET_ISO10646_GREEK) \ && DISABLED(DISPLAY_CHARSET_ISO10646_CN) \ && DISABLED(DISPLAY_CHARSET_ISO10646_TR) \ - && DISABLED(DISPLAY_CHARSET_ISO10646_PL) + && DISABLED(DISPLAY_CHARSET_ISO10646_PL) \ + && DISABLED(DISPLAY_CHARSET_ISO10646_CZ) #define DISPLAY_CHARSET_ISO10646_1 // use the better font on full graphic displays. #endif diff --git a/Marlin/language_cz.h b/Marlin/language_cz.h index caa6af1ffb..098cbff079 100644 --- a/Marlin/language_cz.h +++ b/Marlin/language_cz.h @@ -40,7 +40,7 @@ #define MSG_BACK _UxGT("Zpet") #define MSG_SD_INSERTED _UxGT("Karta vlozena") #define MSG_SD_REMOVED _UxGT("Karta vyjmuta") -#define MSG_LCD_ENDSTOPS _UxGT("Endstopy") // maximalne 8 znaku +#define MSG_LCD_ENDSTOPS _UxGT("Endstopy") // max 8 znaku #define MSG_MAIN _UxGT("Hlavni nabidka") #define MSG_AUTOSTART _UxGT("Autostart") #define MSG_DISABLE_STEPPERS _UxGT("Uvolnit motory") @@ -130,7 +130,7 @@ #define MSG_UBL_INVALIDATE_CLOSEST _UxGT("Zrusit posledni") #define MSG_UBL_FINE_TUNE_ALL _UxGT("Upravit vsechny") #define MSG_UBL_FINE_TUNE_CLOSEST _UxGT("Upravit posledni") -#define MSG_UBL_STORAGE_MESH_MENU _UxGT("Stockage maille") +#define MSG_UBL_STORAGE_MESH_MENU _UxGT("Uloziste siti") #define MSG_UBL_STORAGE_SLOT _UxGT("Pametovy slot") #define MSG_UBL_LOAD_MESH _UxGT("Nacist sit bodu") #define MSG_UBL_SAVE_MESH _UxGT("Ulozit sit bodu") diff --git a/Marlin/language_cz_utf8.h b/Marlin/language_cz_utf8.h new file mode 100644 index 0000000000..21c4ea1632 --- /dev/null +++ b/Marlin/language_cz_utf8.h @@ -0,0 +1,351 @@ +/** + * 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 . + * + */ + +/** + * Czech + * UTF-8 for Graphical Display + * + * LCD Menu Messages + * See also https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language + * + * Translated by Petr Zahradnik, Computer Laboratory + * Blog and video blog Zahradnik se bavi + * http://www.zahradniksebavi.cz + * + */ +#ifndef LANGUAGE_CZ_UTF_H +#define LANGUAGE_CZ_UTF_H + +#define MAPPER_C3C4C5_CZ +#define DISPLAY_CHARSET_ISO10646_CZ + +#define WELCOME_MSG MACHINE_NAME _UxGT(" připraven.") +#define MSG_BACK _UxGT("Zpět") +#define MSG_SD_INSERTED _UxGT("Karta vložena") +#define MSG_SD_REMOVED _UxGT("Karta vyjmuta") +#define MSG_LCD_ENDSTOPS _UxGT("Endstopy") // max 8 znaku +#define MSG_MAIN _UxGT("Hlavní nabídka") +#define MSG_AUTOSTART _UxGT("Autostart") +#define MSG_DISABLE_STEPPERS _UxGT("Uvolnit motory") +#define MSG_DEBUG_MENU _UxGT("Nabídka ladění") +#define MSG_PROGRESS_BAR_TEST _UxGT("Test uk. průběhu") +#define MSG_AUTO_HOME _UxGT("Domovská pozice") +#define MSG_AUTO_HOME_X _UxGT("Domů osa X") +#define MSG_AUTO_HOME_Y _UxGT("Domů osa Y") +#define MSG_AUTO_HOME_Z _UxGT("Domů osa Z") +#define MSG_LEVEL_BED_HOMING _UxGT("Měření podložky") +#define MSG_LEVEL_BED_WAITING _UxGT("Kliknutím spusťte") +#define MSG_LEVEL_BED_NEXT_POINT _UxGT("Další bod") +#define MSG_LEVEL_BED_DONE _UxGT("Měření hotovo!") +#define MSG_Z_FADE_HEIGHT _UxGT("Výška srovnávání") +#define MSG_SET_HOME_OFFSETS _UxGT("Nastavit ofsety") +#define MSG_HOME_OFFSETS_APPLIED _UxGT("Ofsety nastaveny") +#define MSG_SET_ORIGIN _UxGT("Nastavit počátek") +#define MSG_PREHEAT_1 _UxGT("Zahřát PLA") +#define MSG_PREHEAT_1_N MSG_PREHEAT_1 _UxGT(" ") +#define MSG_PREHEAT_1_ALL MSG_PREHEAT_1 _UxGT(" vše") +#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("Zahřát ABS") +#define MSG_PREHEAT_2_N MSG_PREHEAT_2 _UxGT(" ") +#define MSG_PREHEAT_2_ALL MSG_PREHEAT_2 _UxGT(" vše") +#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("Zchladit") +#define MSG_SWITCH_PS_ON _UxGT("Zapnout napájení") +#define MSG_SWITCH_PS_OFF _UxGT("Vypnout napájení") +#define MSG_EXTRUDE _UxGT("Vytlačit (extr.)") +#define MSG_RETRACT _UxGT("Zatlačit (retr.)") +#define MSG_MOVE_AXIS _UxGT("Posunout osy") +#define MSG_BED_LEVELING _UxGT("Vyrovnat podložku") +#define MSG_LEVEL_BED _UxGT("Vyrovnat podložku") +#define MSG_EDITING_STOPPED _UxGT("Konec úprav sítě") + +#define MSG_UBL_DOING_G29 _UxGT("Provádím G29") +#define MSG_UBL_UNHOMED _UxGT("Přejeďte domů") +#define MSG_UBL_TOOLS _UxGT("UBL nástroje") +#define MSG_UBL_LEVEL_BED _UxGT("Unified Bed Leveling") +#define MSG_UBL_MANUAL_MESH _UxGT("Manuální síť bodů") +#define MSG_UBL_BC_INSERT _UxGT("Vložte kartu, změřte") +#define MSG_UBL_BC_INSERT2 _UxGT("Změřte") +#define MSG_UBL_BC_REMOVE _UxGT("Odstraňte a změřte") +#define MSG_UBL_MOVING_TO_NEXT _UxGT("Přesun na další") +#define MSG_UBL_ACTIVATE_MESH _UxGT("Aktivovat UBL") +#define MSG_UBL_DEACTIVATE_MESH _UxGT("Deaktivovat 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("Upravit vlastní síť") +#define MSG_UBL_FINE_TUNE_MESH _UxGT("Doladit síť bodů") +#define MSG_UBL_DONE_EDITING_MESH _UxGT("Konec úprav sítě") +#define MSG_UBL_BUILD_CUSTOM_MESH _UxGT("Vlastní síť") +#define MSG_UBL_BUILD_MESH_MENU _UxGT("Vytvořit síť") +#define MSG_UBL_BUILD_PLA_MESH _UxGT("Síť bodu PLA") +#define MSG_UBL_BUILD_ABS_MESH _UxGT("Síť bodu ABS") +#define MSG_UBL_BUILD_COLD_MESH _UxGT("Studená síť bodu") +#define MSG_UBL_MESH_HEIGHT_ADJUST _UxGT("Upravit výšku sítě") +#define MSG_UBL_MESH_HEIGHT_AMOUNT _UxGT("Výška") +#define MSG_UBL_VALIDATE_MESH_MENU _UxGT("Zkontrolovat síť") +#define MSG_UBL_VALIDATE_PLA_MESH _UxGT("Kontrola sítě PLA") +#define MSG_UBL_VALIDATE_ABS_MESH _UxGT("Kontrola sítě ABS") +#define MSG_UBL_VALIDATE_CUSTOM_MESH _UxGT("Kontrola vlast. sítě") +#define MSG_UBL_CONTINUE_MESH _UxGT("Pokračovat v síťi") +#define MSG_UBL_MESH_LEVELING _UxGT("Síťové rovnání") +#define MSG_UBL_3POINT_MESH_LEVELING _UxGT("3-bodove rovnání") +#define MSG_UBL_GRID_MESH_LEVELING _UxGT("Mrizkove rovnání") +#define MSG_UBL_MESH_LEVEL _UxGT("Srovnat podložku") +#define MSG_UBL_SIDE_POINTS _UxGT("Postranní body") +#define MSG_UBL_MAP_TYPE _UxGT("Typ sítě bodu") +#define MSG_UBL_OUTPUT_MAP _UxGT("Exportovat síť") +#define MSG_UBL_OUTPUT_MAP_HOST _UxGT("Exportovat do PC") +#define MSG_UBL_OUTPUT_MAP_CSV _UxGT("Exportovat 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("Upravit síť bodů") +#define MSG_UBL_FILLIN_AMOUNT _UxGT("Hustota mřížky") +#define MSG_UBL_MANUAL_FILLIN _UxGT("Ruční hustota") +#define MSG_UBL_SMART_FILLIN _UxGT("Chytrá hustota") +#define MSG_UBL_FILLIN_MESH _UxGT("Zaplnit mřížku") +#define MSG_UBL_INVALIDATE_ALL _UxGT("Zrušit všechno") +#define MSG_UBL_INVALIDATE_CLOSEST _UxGT("Zrušit poslední") +#define MSG_UBL_FINE_TUNE_ALL _UxGT("Upravit všechny") +#define MSG_UBL_FINE_TUNE_CLOSEST _UxGT("Upravit poslední") +#define MSG_UBL_STORAGE_MESH_MENU _UxGT("Uložiště sítí") +#define MSG_UBL_STORAGE_SLOT _UxGT("Paměťový slot") +#define MSG_UBL_LOAD_MESH _UxGT("Načíst síť bodů") +#define MSG_UBL_SAVE_MESH _UxGT("Uložit síť bodů") +#define MSG_UBL_SAVE_ERROR _UxGT("Err: Uložit UBL") +#define MSG_UBL_RESTORE_ERROR _UxGT("Err: Obnovit UBL") +#define MSG_UBL_Z_OFFSET_STOPPED _UxGT("Konec Z-Offsetu") +#define MSG_UBL_STEP_BY_STEP_MENU _UxGT("UBL Postupně") + +#define MSG_USER_MENU _UxGT("Vlastní příkazy") +#define MSG_MOVING _UxGT("Posouvání...") +#define MSG_FREE_XY _UxGT("Uvolnit XY") +#define MSG_MOVE_X _UxGT("Posunout X") +#define MSG_MOVE_Y _UxGT("Posunout Y") +#define MSG_MOVE_Z _UxGT("Posunout Z") +#define MSG_MOVE_E _UxGT("Extrudér") +#define MSG_MOVE_01MM _UxGT("Posunout o 0,1mm") +#define MSG_MOVE_1MM _UxGT("Posunout o 1mm") +#define MSG_MOVE_10MM _UxGT("Posunout o 10mm") +#define MSG_SPEED _UxGT("Rychlost") +#define MSG_BED_Z _UxGT("Výška podl.") +#define MSG_NOZZLE _UxGT("Tryska") +#define MSG_BED _UxGT("Podložka") +#define MSG_FAN_SPEED _UxGT("Rychlost vent.") +#define MSG_FLOW _UxGT("Průtok") +#define MSG_CONTROL _UxGT("Ovládaní") +#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("Vybrat") +#define MSG_ACC _UxGT("Zrychl") +#define MSG_JERK _UxGT("Jerk") +#define MSG_VX_JERK _UxGT("Vx-jerk") +#define MSG_VY_JERK _UxGT("Vy-jerk") +#define MSG_VZ_JERK _UxGT("Vz-jerk") +#define MSG_VE_JERK _UxGT("Ve-jerk") +#define MSG_VELOCITY _UxGT("Rychlost") +#define MSG_VMAX _UxGT("Vmax ") +#define MSG_VMIN _UxGT("Vmin") +#define MSG_VTRAV_MIN _UxGT("VTrav min") +#define MSG_ACCELERATION _UxGT("Akcelerace") +#define MSG_AMAX _UxGT("Amax ") +#define MSG_A_RETRACT _UxGT("A-retrakt") +#define MSG_A_TRAVEL _UxGT("A-přejezd") +#define MSG_STEPS_PER_MM _UxGT("Kroků/mm") +#define MSG_XSTEPS _UxGT("Xkroků/mm") +#define MSG_YSTEPS _UxGT("Ykroků/mm") +#define MSG_ZSTEPS _UxGT("Zkroků/mm") +#define MSG_ESTEPS _UxGT("Ekroků/mm") +#define MSG_E1STEPS _UxGT("E1kroků/mm") +#define MSG_E2STEPS _UxGT("E2kroků/mm") +#define MSG_E3STEPS _UxGT("E3kroků/mm") +#define MSG_E4STEPS _UxGT("E4kroků/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. Prum.") +#define MSG_ADVANCE_K _UxGT("K pro posun") +#define MSG_CONTRAST _UxGT("Kontrast LCD") +#define MSG_STORE_EEPROM _UxGT("Uložit nastavení") +#define MSG_LOAD_EEPROM _UxGT("Načíst nastavení") +#define MSG_RESTORE_FAILSAFE _UxGT("Obnovit výchozí") +#define MSG_INIT_EEPROM _UxGT("Inic. EEPROM") +#define MSG_REFRESH _UxGT("Obnovit") +#define MSG_WATCH _UxGT("Info obrazovka") +#define MSG_PREPARE _UxGT("Připrava tisku") +#define MSG_TUNE _UxGT("Doladění tisku") +#define MSG_PAUSE_PRINT _UxGT("Pozastavit tisk") +#define MSG_RESUME_PRINT _UxGT("Obnovit tisk") +#define MSG_STOP_PRINT _UxGT("Zastavit tisk") +#define MSG_CARD_MENU _UxGT("Tisknout z SD") +#define MSG_NO_CARD _UxGT("Žádná SD karta") +#define MSG_DWELL _UxGT("Uspáno...") +#define MSG_USERWAIT _UxGT("Čekání na uživ...") +#define MSG_PRINT_PAUSED _UxGT("Tisk pozastaven") +#define MSG_RESUMING _UxGT("Obnovování tisku") +#define MSG_PRINT_ABORTED _UxGT("Tisk zrušen") +#define MSG_NO_MOVE _UxGT("Žádný pohyb.") +#define MSG_KILLED _UxGT("PŘERUSENO. ") +#define MSG_STOPPED _UxGT("ZASTAVENO. ") +#define MSG_CONTROL_RETRACT _UxGT("Retrakt mm") +#define MSG_CONTROL_RETRACT_SWAP _UxGT("Výměna Re.mm") +#define MSG_CONTROL_RETRACTF _UxGT("Retraktovat V") +#define MSG_CONTROL_RETRACT_ZLIFT _UxGT("Zvednuti 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("Vyměnit filament") +#define MSG_INIT_SDCARD _UxGT("Načíst SD kartu") +#define MSG_CNG_SDCARD _UxGT("Vyměnit 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 Vysunout") +#define MSG_BLTOUCH_STOW _UxGT("BLTouch Zasunout") +#define MSG_HOME _UxGT("Domů") // Used as MSG_HOME " " MSG_X MSG_Y MSG_Z " " MSG_FIRST +#define MSG_FIRST _UxGT("první") +#define MSG_ZPROBE_ZOFFSET _UxGT("Z ofset") +#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 abort") +#define MSG_HEATING_FAILED_LCD _UxGT("Chyba zahřívání") +#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ÁZÁNO") +#define MSG_HALTED _UxGT("TISK. ZASTAVENA") +#define MSG_PLEASE_RESET _UxGT("Proveďte reset") +#define MSG_SHORT_DAY _UxGT("d") +#define MSG_SHORT_HOUR _UxGT("h") +#define MSG_SHORT_MINUTE _UxGT("m") +#define MSG_HEATING _UxGT("Zahřívání...") +#define MSG_HEATING_COMPLETE _UxGT("Zahřáti hotovo.") +#define MSG_BED_HEATING _UxGT("Zahřívání podl.") +#define MSG_BED_DONE _UxGT("Podložka hotova.") +#define MSG_DELTA_CALIBRATE _UxGT("Delta Kalibrace") +#define MSG_DELTA_CALIBRATE_X _UxGT("Kalibrovat X") +#define MSG_DELTA_CALIBRATE_Y _UxGT("Kalibrovat Y") +#define MSG_DELTA_CALIBRATE_Z _UxGT("Kalibrovat Z") +#define MSG_DELTA_CALIBRATE_CENTER _UxGT("Kalibrovat Střed") +#define MSG_DELTA_AUTO_CALIBRATE _UxGT("Autokalibrace") +#define MSG_DELTA_HEIGHT_CALIBRATE _UxGT("Nast.výšku delty") +#define MSG_INFO_MENU _UxGT("O tiskárně") +#define MSG_INFO_PRINTER_MENU _UxGT("Info o tiskárně") +#define MSG_3POINT_LEVELING _UxGT("3-bodové rovnání") +#define MSG_LINEAR_LEVELING _UxGT("Lineárni rovnání") +#define MSG_BILINEAR_LEVELING _UxGT("Bilineární rovnání") +#define MSG_UBL_LEVELING _UxGT("Unified Bed Leveling") +#define MSG_MESH_LEVELING _UxGT("Mřížkové rovnání") +#define MSG_INFO_STATS_MENU _UxGT("Statistika") +#define MSG_INFO_BOARD_MENU _UxGT("Info o desce") +#define MSG_INFO_THERMISTOR_MENU _UxGT("Termistory") +#define MSG_INFO_EXTRUDERS _UxGT("Extrudéry") +#define MSG_INFO_BAUDRATE _UxGT("Rychlost") +#define MSG_INFO_PROTOCOL _UxGT("Protokol") +#define MSG_CASE_LIGHT _UxGT("Osvětlení") +#define MSG_CASE_LIGHT_BRIGHTNESS _UxGT("Jas světla") + +#if LCD_WIDTH >= 20 + #define MSG_INFO_PRINT_COUNT _UxGT("Počet tisků") + #define MSG_INFO_COMPLETED_PRINTS _UxGT("Dokončeno") + #define MSG_INFO_PRINT_TIME _UxGT("Celkový čas") + #define MSG_INFO_PRINT_LONGEST _UxGT("Nejdelší tisk") + #define MSG_INFO_PRINT_FILAMENT _UxGT("Celkem vytlačeno") +#else + #define MSG_INFO_PRINT_COUNT _UxGT("Tisky") + #define MSG_INFO_COMPLETED_PRINTS _UxGT("Hotovo") + #define MSG_INFO_PRINT_TIME _UxGT("Čas") + #define MSG_INFO_PRINT_LONGEST _UxGT("Nejdelší") + #define MSG_INFO_PRINT_FILAMENT _UxGT("Vytlačeno") +#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("Buzení motorů") +#define MSG_DAC_PERCENT _UxGT("Motor %") +#define MSG_DAC_EEPROM_WRITE _UxGT("Uložit do EEPROM") + +#define MSG_FILAMENT_CHANGE_HEADER _UxGT("PRINT PAUSED") +#define MSG_FILAMENT_CHANGE_OPTION_HEADER _UxGT("RESUME OPTIONS:") +#define MSG_FILAMENT_CHANGE_OPTION_EXTRUDE _UxGT("Ještě vytlačit") +#define MSG_FILAMENT_CHANGE_OPTION_RESUME _UxGT("Obnovit tisk") +#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("Čekejte prosím") + #define MSG_FILAMENT_CHANGE_INIT_2 _UxGT("na zahájení") + #define MSG_FILAMENT_CHANGE_INIT_3 _UxGT("výměny filamentu") + #define MSG_FILAMENT_CHANGE_UNLOAD_1 _UxGT("Čekejte prosím") + #define MSG_FILAMENT_CHANGE_UNLOAD_2 _UxGT("na vysunuti") + #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 stiskněte") + #define MSG_FILAMENT_CHANGE_INSERT_3 _UxGT("tlačítko...") + #define MSG_FILAMENT_CHANGE_HEAT_1 _UxGT("Klikněte pro") + #define MSG_FILAMENT_CHANGE_HEAT_2 _UxGT("nahřátí trysky") + #define MSG_FILAMENT_CHANGE_HEATING_1 _UxGT("Čekejte prosím") + #define MSG_FILAMENT_CHANGE_HEATING_2 _UxGT("na nahřátí tr.") + #define MSG_FILAMENT_CHANGE_LOAD_1 _UxGT("Čekejte prosím") + #define MSG_FILAMENT_CHANGE_LOAD_2 _UxGT("na zavedení") + #define MSG_FILAMENT_CHANGE_LOAD_3 _UxGT("filamentu") + #define MSG_FILAMENT_CHANGE_EXTRUDE_1 _UxGT("Čekejte prosím") + #define MSG_FILAMENT_CHANGE_EXTRUDE_2 _UxGT("na vytlačení") + #define MSG_FILAMENT_CHANGE_EXTRUDE_3 _UxGT("filamentu") + #define MSG_FILAMENT_CHANGE_RESUME_1 _UxGT("Čekejte prosím") + #define MSG_FILAMENT_CHANGE_RESUME_2 _UxGT("na pokračování") + #define MSG_FILAMENT_CHANGE_RESUME_3 _UxGT("tisku") +#else // LCD_HEIGHT < 4 + // Up to 2 lines allowed + #define MSG_FILAMENT_CHANGE_INIT_1 _UxGT("Čekejte...") + #define MSG_FILAMENT_CHANGE_UNLOAD_1 _UxGT("Vysouvání...") + #define MSG_FILAMENT_CHANGE_INSERT_1 _UxGT("Vložte, klikněte") + #define MSG_FILAMENT_CHANGE_HEATING_1 _UxGT("Nahřívání...") + #define MSG_FILAMENT_CHANGE_LOAD_1 _UxGT("Zavádění...") + #define MSG_FILAMENT_CHANGE_EXTRUDE_1 _UxGT("Vytlačování...") + #define MSG_FILAMENT_CHANGE_RESUME_1 _UxGT("Pokračování...") +#endif // LCD_HEIGHT < 4 + +#endif // LANGUAGE_CZ_UTF_H diff --git a/Marlin/language_kana_utf8.h b/Marlin/language_kana_utf8.h index 5a0378bb98..d44a5f85d9 100644 --- a/Marlin/language_kana_utf8.h +++ b/Marlin/language_kana_utf8.h @@ -21,7 +21,8 @@ */ /** - * Japanese (Kana UTF8 version) + * Japanese (Kana) + * UTF-8 for Graphical Display * * LCD Menu Messages * See also https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language diff --git a/Marlin/language_pt-br_utf8.h b/Marlin/language_pt-br_utf8.h index e2d9ced5ee..2062ffb9a5 100644 --- a/Marlin/language_pt-br_utf8.h +++ b/Marlin/language_pt-br_utf8.h @@ -22,6 +22,7 @@ /** * Portuguese (Brazil) + * UTF-8 for Graphical Display * * LCD Menu Messages * See also https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language diff --git a/Marlin/language_pt_utf8.h b/Marlin/language_pt_utf8.h index e939c4d0c1..af9891eb10 100644 --- a/Marlin/language_pt_utf8.h +++ b/Marlin/language_pt_utf8.h @@ -22,6 +22,7 @@ /** * Portuguese + * UTF-8 for Graphical Display * * LCD Menu Messages * See also https://github.com/MarlinFirmware/Marlin/wiki/LCD-Language diff --git a/Marlin/ultralcd_impl_DOGM.h b/Marlin/ultralcd_impl_DOGM.h index 392e812c99..a11c9afeb7 100644 --- a/Marlin/ultralcd_impl_DOGM.h +++ b/Marlin/ultralcd_impl_DOGM.h @@ -97,6 +97,9 @@ #elif ENABLED(DISPLAY_CHARSET_ISO10646_TR) #include "dogm_font_data_ISO10646_1_tr.h" #define FONT_MENU_NAME ISO10646_TR + #elif ENABLED(DISPLAY_CHARSET_ISO10646_CZ) + #include "dogm_font_data_ISO10646_CZ.h" + #define FONT_MENU_NAME ISO10646_CZ #else // fall-back #include "dogm_font_data_ISO10646_1.h" #define FONT_MENU_NAME ISO10646_1_5x7 diff --git a/Marlin/utf_mapper.h b/Marlin/utf_mapper.h index edf2a6ca17..35dac27a13 100644 --- a/Marlin/utf_mapper.h +++ b/Marlin/utf_mapper.h @@ -39,7 +39,7 @@ || ENABLED(DISPLAY_CHARSET_ISO10646_TR) #define MAPPER_ONE_TO_ONE #endif -#else // SIMULATE_ROMFONT +#else // SIMULATE_ROMFONT || !DOGLCD #if DISPLAY_CHARSET_HD44780 == JAPANESE #if ENABLED(MAPPER_C2C3) const PROGMEM uint8_t utf_recode[] = @@ -401,27 +401,28 @@ #elif ENABLED(MAPPER_C3C4C5_PL) - //Ą c4 84 = 80 - //ą c4 85 = 81 - //Ć c4 86 = 82 - //ć c4 87 = 83 - //Ę c4 98 = 84 - //ę c4 99 = 85 - //Ł c5 81 = 86 - //ł c5 82 = 87 - //Ń c5 83 = 88 - //ń c5 84 = 89 - //Ó c3 93 = 8a - //ó c3 b3 = 8b - //Ś c5 9a = 8c - //ś c5 9b = 8d - //Ź c5 b9 = 8e - //ź c5 ba = 8f - //Ż c5 bb = 90 - //ż c5 bc = 91 + /** + * Ą C4 84 = 80 + * ą C4 85 = 81 + * Ć C4 86 = 82 + * ć C4 87 = 83 + * Ę C4 98 = 84 + * ę C4 99 = 85 + * Ł C5 81 = 86 + * ł C5 82 = 87 + * Ń C5 83 = 88 + * ń C5 84 = 89 + * Ó C3 93 = 8A + * ó C3 B3 = 8B + * Ś C5 9A = 8C + * ś C5 9B = 8D + * Ź C5 B9 = 8E + * ź C5 BA = 8F + * Ż C5 BB = 90 + * ż C5 BC = 91 + */ char charset_mapper(const char c) { - static uint8_t utf_hi_char; // UTF-8 high part static bool seen_c3 = false, seen_c4 = false, seen_c5 = false; @@ -464,6 +465,97 @@ return 1; } +#elif ENABLED(MAPPER_C3C4C5_CZ) + + /** + * Á C3 81 = 80 + * É C3 89 = 81 + * Í C3 8D = 82 + * Ó C3 93 = 83 + * Ú C3 9A = 84 + * Ý C3 9D = 85 + * á C3 A1 = 86 + * é C3 A9 = 87 + * í C3 AD = 88 + * ó C3 B3 = 89 + * ú C3 BA = 8A + * ý C3 BD = 8B + * Č C4 8C = 8C + * č C4 8D = 8D + * Ď C4 8E = 8E + * ď C4 8F = 8F + * Ě C4 9A = 90 + * ě C4 9B = 91 + * Ň C5 87 = 92 + * ň C5 88 = 93 + * Ř C5 98 = 94 + * ř C5 99 = 95 + * Š C5 A0 = 96 + * š C5 A1 = 97 + * Ť C5 A4 = 98 + * ť C5 A5 = 99 + * Ů C5 AE = 9A + * ů C5 AF = 9B + * Ž C5 BD = 9C + * ž C5 BE = 9D + */ + + char charset_mapper(const char c) { + static bool seen_c3 = false, + seen_c4 = false, + seen_c5 = false; + uint8_t d = c; + if (d >= 0x80u) { // UTF-8 handling + if (d == 0xC4u) { seen_c4 = true; return 0; } + else if (d == 0xC5u) { seen_c5 = true; return 0; } + else if (d == 0xC3u) { seen_c3 = true; return 0; } + else if (seen_c4) { + switch(d) { + case 0x8Cu ... 0x8Fu: break; // ČčĎď Mapping 1:1 + case 0x9Au ... 0x9Bu: d -= 10; break; // Ěě + default: d = '?'; + } + HARDWARE_CHAR_OUT((char)d) ; + } + else if (seen_c5) { + switch(d) { + case 0x87u ... 0x88u: d += 0x0Bu; break; // Ňň + case 0x98u ... 0x99u: d -= 0x04u; break; // Řř + case 0xA0u ... 0xA1u: d -= 0x0Au; break; // Šš + case 0xA4u ... 0xA5u: d -= 0x0Cu; break; // Ťť + case 0xAEu ... 0xAFu: d -= 0x14u; break; // Ůů + case 0xBDu ... 0xBEu: d -= 0x21u; break; // Žž + default: d = '?'; + } + HARDWARE_CHAR_OUT((char)d) ; + } + else if (seen_c3) { + switch(d) { + case 0x81u: d = 0x80u; break; // Á + case 0x89u: d = 0x81u; break; // É + case 0x8Du: d = 0x82u; break; // Í + case 0x93u: d = 0x83u; break; // Ó + case 0x9Au: d = 0x84u; break; // Ú + case 0x9Du: d = 0x85u; break; // Ý + case 0xA1u: d = 0x86u; break; // á + case 0xA9u: d = 0x87u; break; // é + case 0xADu: d = 0x88u; break; // í + case 0xB3u: d = 0x89u; break; // ó + case 0xBAu: d = 0x8Au; break; // ú + case 0xBDu: d = 0x8Bu; break; // ý + default: d = '?'; + } + HARDWARE_CHAR_OUT((char)d) ; + } + + } + else { + HARDWARE_CHAR_OUT((char) c ); + } + seen_c3 = seen_c4 = seen_c5 = false; + return 1; + } + #else #define MAPPER_NON @@ -476,6 +568,6 @@ return 1; } - #endif // code mappers +#endif // code mappers #endif // UTF_MAPPER_H diff --git a/buildroot/share/fonts/ISO10646_CZ.fon b/buildroot/share/fonts/ISO10646_CZ.fon new file mode 100644 index 0000000000000000000000000000000000000000..5208f92fdbf4db5ea3af4253481597af04dd74d4 GIT binary patch literal 4224 zcmchYaflq%9mn6r^D?nXn3f=iSo@S9M>vl?3CC4}OeKa@VjNx*O*g0A z29d$4EJb9HB8x~_L}U;tp#)ii$Wf#mQYAi&%U{Q z_B+4#-tYb1@BQZGp2PoeW6rs8{kwS4xuJfoCGfkEt9$#8PH%UowtR5oaBTkvHy&y) z9`{*i`O(gi$9?DMFP>QJ96j#uS$w3ke0=%XivQ{2(!%mDkI!toW@qL4z@1m`d5#F2 zi+=sz>+Mn`iCb~c>6x%ViF8v`jl62yZO$>f9d3(Dw@%X$Rkk0xzq`iuV|f_8dEdPU z4(+|`;I_N&yLYxRw|nlE*;^htVSP7S&%rzI^Rtb{^pEHC=Wp{@jPg&;&ddfkS8&W? zzv}hv&i!P@H;;4{R-RaTblN|@ys&s|@#uno_*XtXy3+B7kF+~S7M2!&cE#+=FOh5M zskh~dv9SqvjdK%v{6*(WMxMR8ny?|XmCj`+rvBftd}c9y|H>Ht<88v(pb7US9KlT! zX4wj_g&yvLyW#Dy2@k>t;W3!O6YyF1BJ9K0;9Kx*xC-BgXW=LC0{jYo3nw;PY%#nJ z?u0XN9^L`>!~0q=isOC3-~p(;!sV%9qc2h@FVy!{2Z>sZ{YYAi)}lcgg3!yI0qAWH#`I% zf^FD=Pr>J50bhZy!{5Up{3HA`{0lq}{|5gF{{c6N@O^j|egZGRui&?EVk`9zuY)_`44j8|!2R%k*n*G275Fsl!I$8x@C|qp zo`&zi58*lZDf|L{4c#{CAMSuRz$thu+ynQ)6dr~Pa0zzdGw=oYG917+;VJkoT!SCM zkKyNV9exAHb^ojW;Uv5XPQy8vz`Nlg_z-Nv4txqe4-5E;_#L;sx8}Sq+%&Ck-83EP zu~*+6WK-+bySf(pq(3RuDh5eev`zU$w5Gl!@v)Q`>&=Y5%t~*!jLsaO8& zFQ{%5nPSnft}Rbgwtm=$JnFHgcZ*9(5h!#YRJ$xIeHxn8YpG9 za9U;yUb=anh5YGQs@0gvTvX~c7geUH)Th;Iy)?vU*-eNg)8QwHt?Mj%k%`QrkIklu zX1LTWdP=3TWKp-*mCo~%Yav&fUF9!|+S;1++D=Bf`D--K+j3^I-E|`w!(3ZO=Tq${ zb{2tcB+p5pdRuf7sXJ4u$>yA`8)CFC@guA&1Nfldf7+p z71Sja&P^3uW!zNAsg%w2HrH}$IgpaD9R+1Er&>3hOsa9UQmQz&@g0*{Q52e+`Z_8b z7uHC9U8k~D8BhIsRg>7rZt5w|b@Ni^S^lc{#`kji4IOk^+PYfJ%XNrUp^YsV!7yF zu!`;W``yXONd{E+YS4C&$*T6oYdGexq@qg)X6+T_149Dr6~kuV&+Fn(R-5PMv1#84 z_gccKTK&nT&exPrYo%(fY-Xx^ePwg=t-eZ;!rG Date: Tue, 4 Jul 2017 17:38:45 -0500 Subject: [PATCH 179/180] Fix a bug in mfup --- buildroot/share/git/mfup | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/buildroot/share/git/mfup b/buildroot/share/git/mfup index cb6abda9ae..cd65c46cc2 100755 --- a/buildroot/share/git/mfup +++ b/buildroot/share/git/mfup @@ -28,7 +28,7 @@ echo "Fetching upstream ($ORG/$REPO)..." git fetch upstream echo ; echo "Bringing $TARG up to date..." -if [[ git checkout -q $TARG ]]; then +if [[ ! $(git checkout -q $TARG) ]]; then git reset --hard upstream/$TARG git push -f origin else From 3efe4aeef875bbb92afd5482b46445128442f976 Mon Sep 17 00:00:00 2001 From: LVD-AC Date: Mon, 3 Jul 2017 17:06:23 +0200 Subject: [PATCH 180/180] Add PROBE_MANUALLY support to G33 --- Marlin/Marlin_main.cpp | 87 +++++++++++++++++++++++++----------------- Marlin/SanityCheck.h | 6 ++- Marlin/ultralcd.cpp | 34 ++++++++++------- Marlin/ultralcd.h | 4 ++ 4 files changed, 81 insertions(+), 50 deletions(-) diff --git a/Marlin/Marlin_main.cpp b/Marlin/Marlin_main.cpp index 09a7e3d9d3..6f52f208d7 100644 --- a/Marlin/Marlin_main.cpp +++ b/Marlin/Marlin_main.cpp @@ -5127,6 +5127,10 @@ void home_all_axes() { gcode_G28(true); } #endif // Z_PROBE_SLED +#endif // HAS_BED_PROBE + +#if PROBE_SELECTED + #if ENABLED(DELTA_AUTO_CALIBRATION) /** * G33 - Delta '1-4-7-point' Auto-Calibration @@ -5184,9 +5188,9 @@ void home_all_axes() { gcode_G28(true); } return; } - const int8_t force_iterations = parser.intval('F', 1); - if (!WITHIN(force_iterations, 1, 30)) { - SERIAL_PROTOCOLLNPGM("?(F)orce iteration is implausible (1-30)."); + const int8_t force_iterations = parser.intval('F', 0); + if (!WITHIN(force_iterations, 0, 30)) { + SERIAL_PROTOCOLLNPGM("?(F)orce iteration is implausible (0-30)."); return; } @@ -5221,7 +5225,7 @@ void home_all_axes() { gcode_G28(true); } alpha_old = delta_tower_angle_trim[A_AXIS], beta_old = delta_tower_angle_trim[B_AXIS]; - if (!_1p_calibration) { // test if the outer radius is reachable + if (!_1p_calibration) { // test if the outer radius is reachable const float circles = (_7p_quadruple_circle ? 1.5 : _7p_triple_circle ? 1.0 : _7p_double_circle ? 0.5 : 0), @@ -5273,7 +5277,9 @@ void home_all_axes() { gcode_G28(true); } SERIAL_EOL(); } - home_offset[Z_AXIS] -= probe_pt(dx, dy, stow_after_each, 1, false); // 1st probe to set height + #if DISABLED(PROBE_MANUALLY) + home_offset[Z_AXIS] -= probe_pt(dx, dy, stow_after_each, 1, false); // 1st probe to set height + #endif do { @@ -5286,12 +5292,20 @@ void home_all_axes() { gcode_G28(true); } // Probe the points if (!_7p_half_circle && !_7p_triple_circle) { // probe the center - z_at_pt[0] += probe_pt(dx, dy, stow_after_each, 1, false); + #if ENABLED(PROBE_MANUALLY) + z_at_pt[0] += lcd_probe_pt(0, 0); + #else + z_at_pt[0] += probe_pt(dx, dy, stow_after_each, 1, false); + #endif } if (_7p_calibration) { // probe extra center points for (int8_t axis = _7p_multi_circle ? 11 : 9; axis > 0; axis -= _7p_multi_circle ? 2 : 4) { const float a = RADIANS(180 + 30 * axis), r = delta_calibration_radius * 0.1; - z_at_pt[0] += probe_pt(cos(a) * r + dx, sin(a) * r + dy, stow_after_each, 1, false); + #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); + #endif } z_at_pt[0] /= float(_7p_double_circle ? 7 : probe_points); } @@ -5307,7 +5321,11 @@ void home_all_axes() { gcode_G28(true); } for (float circles = -offset_circles ; circles <= offset_circles; circles++) { const float a = RADIANS(180 + 30 * axis), r = delta_calibration_radius * (1 + circles * (zig_zag ? 0.1 : -0.1)); - z_at_pt[axis] += probe_pt(cos(a) * r + dx, sin(a) * r + dy, stow_after_each, 1, false); + #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); + #endif } zig_zag = !zig_zag; z_at_pt[axis] /= (2 * offset_circles + 1); @@ -5359,9 +5377,13 @@ void home_all_axes() { gcode_G28(true); } #define Z0444(I) ZP(a_factor * 4.0 / 9.0, I) #define Z0888(I) ZP(a_factor * 8.0 / 9.0, I) + #if ENABLED(PROBE_MANUALLY) + test_precision = 0.00; // forced end + #endif + switch (probe_points) { case 1: - test_precision = 0.00; + test_precision = 0.00; // forced end LOOP_XYZ(i) e_delta[i] = Z1000(0); break; @@ -5437,16 +5459,19 @@ void home_all_axes() { gcode_G28(true); } SERIAL_EOL(); } } - if (test_precision != 0.0) { // !forced end + if (verbose_level != 0) { // !dry run if ((zero_std_dev >= test_precision || zero_std_dev <= calibration_precision) && iterations > force_iterations) { // end iterations SERIAL_PROTOCOLPGM("Calibration OK"); SERIAL_PROTOCOL_SP(36); - if (zero_std_dev >= test_precision) - SERIAL_PROTOCOLPGM("rolling back."); - else { - SERIAL_PROTOCOLPGM("std dev:"); - SERIAL_PROTOCOL_F(zero_std_dev, 3); - } + #if DISABLED(PROBE_MANUALLY) + if (zero_std_dev >= test_precision && !_1p_calibration) + SERIAL_PROTOCOLPGM("rolling back."); + else + #endif + { + SERIAL_PROTOCOLPGM("std dev:"); + SERIAL_PROTOCOL_F(zero_std_dev, 3); + } SERIAL_EOL(); LCD_MESSAGEPGM("Calibration OK"); // TODO: Make translatable string } @@ -5480,22 +5505,12 @@ void home_all_axes() { gcode_G28(true); } serialprintPGM(save_message); SERIAL_EOL(); } - else { // forced end - if (verbose_level == 0) { - SERIAL_PROTOCOLPGM("End DRY-RUN"); - SERIAL_PROTOCOL_SP(39); - SERIAL_PROTOCOLPGM("std dev:"); - SERIAL_PROTOCOL_F(zero_std_dev, 3); - SERIAL_EOL(); - } - else { - SERIAL_PROTOCOLLNPGM("Calibration OK"); - LCD_MESSAGEPGM("Calibration OK"); // TODO: Make translatable string - SERIAL_PROTOCOLPAIR(".Height:", DELTA_HEIGHT + home_offset[Z_AXIS]); - SERIAL_EOL(); - serialprintPGM(save_message); - SERIAL_EOL(); - } + else { // dry run + SERIAL_PROTOCOLPGM("End DRY-RUN"); + SERIAL_PROTOCOL_SP(39); + SERIAL_PROTOCOLPGM("std dev:"); + SERIAL_PROTOCOL_F(zero_std_dev, 3); + SERIAL_EOL(); } endstops.enable(true); @@ -5517,7 +5532,7 @@ void home_all_axes() { gcode_G28(true); } #endif // DELTA_AUTO_CALIBRATION -#endif // HAS_BED_PROBE +#endif // PROBE_SELECTED #if ENABLED(G38_PROBE_TARGET) @@ -10493,6 +10508,10 @@ void process_next_command() { #endif // Z_PROBE_SLED + #endif // HAS_BED_PROBE + + #if PROBE_SELECTED + #if ENABLED(DELTA_AUTO_CALIBRATION) case 33: // G33: Delta Auto-Calibration @@ -10501,7 +10520,7 @@ void process_next_command() { #endif // DELTA_AUTO_CALIBRATION - #endif // HAS_BED_PROBE + #endif // PROBE_SELECTED #if ENABLED(G38_PROBE_TARGET) case 38: // G38.2 & G38.3 diff --git a/Marlin/SanityCheck.h b/Marlin/SanityCheck.h index bd33460cb8..df8bdea5f0 100644 --- a/Marlin/SanityCheck.h +++ b/Marlin/SanityCheck.h @@ -480,8 +480,10 @@ static_assert(1 >= 0 #error "You probably want to use Max Endstops for DELTA!" #elif ENABLED(ENABLE_LEVELING_FADE_HEIGHT) && DISABLED(AUTO_BED_LEVELING_BILINEAR) && !UBL_DELTA #error "ENABLE_LEVELING_FADE_HEIGHT on DELTA requires AUTO_BED_LEVELING_BILINEAR or AUTO_BED_LEVELING_UBL." - #elif ENABLED(DELTA_AUTO_CALIBRATION) && !HAS_BED_PROBE - #error "DELTA_AUTO_CALIBRATION requires a probe: FIX_MOUNTED_PROBE, BLTOUCH, SOLENOID_PROBE, Z_PROBE_ALLEN_KEY, Z_PROBE_SLED, or Z Servo." + #elif ENABLED(DELTA_AUTO_CALIBRATION) && !PROBE_SELECTED + #error "DELTA_AUTO_CALIBRATION requires a probe: PROBE_MANUALLY, FIX_MOUNTED_PROBE, BLTOUCH, SOLENOID_PROBE, Z_PROBE_ALLEN_KEY, Z_PROBE_SLED, Z Servo." + #elif ENABLED(DELTA_AUTO_CALIBRATION) && ENABLED(PROBE_MANUALLY) && DISABLED(ULTIPANEL) + #error "DELTA_AUTO_CALIBRATION requires an LCD controller with PROBE_MANUALLY." #elif ABL_GRID #if (GRID_MAX_POINTS_X & 1) == 0 || (GRID_MAX_POINTS_Y & 1) == 0 #error "DELTA requires GRID_MAX_POINTS_X and GRID_MAX_POINTS_Y to be odd numbers." diff --git a/Marlin/ultralcd.cpp b/Marlin/ultralcd.cpp index 7803a72c4a..e2f320ecc9 100644 --- a/Marlin/ultralcd.cpp +++ b/Marlin/ultralcd.cpp @@ -2486,31 +2486,37 @@ void kill_screen(const char* lcd_msg) { lcd_goto_screen(_lcd_calibrate_homing); } - // Move directly to the tower position with uninterpolated moves - // If we used interpolated moves it would cause this to become re-entrant - void _goto_tower_pos(const float &a) { + void _man_probe_pt(const float &lx, const float &ly) { #if HAS_LEVELING reset_bed_level(); // After calibration bed-level data is no longer valid #endif - line_to_z(max(Z_HOMING_HEIGHT, Z_CLEARANCE_BETWEEN_PROBES) + (DELTA_PRINTABLE_RADIUS) / 5); - - current_position[X_AXIS] = a < 0 ? LOGICAL_X_POSITION(X_HOME_POS) : cos(RADIANS(a)) * delta_calibration_radius; - current_position[Y_AXIS] = a < 0 ? LOGICAL_Y_POSITION(Y_HOME_POS) : sin(RADIANS(a)) * delta_calibration_radius; + float z_dest = LOGICAL_Z_POSITION((Z_CLEARANCE_BETWEEN_PROBES) + (DELTA_PRINTABLE_RADIUS) / 5); + line_to_z(z_dest); + current_position[X_AXIS] = LOGICAL_X_POSITION(lx); + current_position[Y_AXIS] = LOGICAL_Y_POSITION(ly); line_to_current_z(); - - line_to_z(4.0); + z_dest = LOGICAL_Z_POSITION(Z_CLEARANCE_BETWEEN_PROBES); + line_to_z(z_dest); lcd_synchronize(); - move_menu_scale = 0.1; lcd_goto_screen(lcd_move_z); } - void _goto_tower_x() { _goto_tower_pos(210); } - void _goto_tower_y() { _goto_tower_pos(330); } - void _goto_tower_z() { _goto_tower_pos(90); } - void _goto_center() { _goto_tower_pos(-1); } + float lcd_probe_pt(const float &lx, const float &ly) { + _man_probe_pt(lx, ly); + KEEPALIVE_STATE(PAUSED_FOR_USER); + wait_for_user = true; + while (wait_for_user) idle(); + KEEPALIVE_STATE(IN_HANDLER); + return current_position[Z_AXIS]; + } + + void _goto_tower_x() { _man_probe_pt(cos(RADIANS(210)) * delta_calibration_radius, sin(RADIANS(210)) * delta_calibration_radius); } + void _goto_tower_y() { _man_probe_pt(cos(RADIANS(330)) * delta_calibration_radius, sin(RADIANS(330)) * delta_calibration_radius); } + 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_calibrate_menu() { START_MENU(); diff --git a/Marlin/ultralcd.h b/Marlin/ultralcd.h index f1087616fa..0a50f173ae 100644 --- a/Marlin/ultralcd.h +++ b/Marlin/ultralcd.h @@ -197,4 +197,8 @@ void lcd_reset_status(); float lcd_z_offset_edit(); #endif +#if ENABLED(DELTA_CALIBRATION_MENU) + float lcd_probe_pt(const float &lx, const float &ly); +#endif + #endif // ULTRALCD_H