Browse Source

Merge branch 'MK3' into MK3_Fix_LCD_stats

DRracer 3 years ago
parent
commit
e491b53f48
100 changed files with 6482 additions and 4450 deletions
  1. 4 0
      .editorconfig
  2. 1 0
      .gitattributes
  3. 3 0
      .github/ISSUE_TEMPLATE/bug_report.md
  4. 2 2
      .gitignore
  5. 3 3
      Firmware/Configuration.h
  6. 23 11
      Firmware/ConfigurationStore.cpp
  7. 1 0
      Firmware/ConfigurationStore.h
  8. 30 7
      Firmware/Configuration_adv.h
  9. 102 15
      Firmware/Dcodes.cpp
  10. 18 4
      Firmware/Dcodes.h
  11. 14 24
      Firmware/Marlin.h
  12. 2 2
      Firmware/MarlinSerial.cpp
  13. 951 695
      Firmware/Marlin_main.cpp
  14. 4 1
      Firmware/Sd2Card.cpp
  15. 1 5
      Firmware/Sd2PinMap.h
  16. 2 2
      Firmware/Timer.h
  17. 1 1
      Firmware/adc.c
  18. 4 4
      Firmware/backlight.cpp
  19. 4 4
      Firmware/bootapp.c
  20. 63 43
      Firmware/cardreader.cpp
  21. 4 4
      Firmware/cardreader.h
  22. 17 7
      Firmware/cmdqueue.cpp
  23. 4 3
      Firmware/cmdqueue.h
  24. 7 2
      Firmware/config.h
  25. 4 0
      Firmware/eeprom.cpp
  26. 31 58
      Firmware/eeprom.h
  27. 11 18
      Firmware/fastio.h
  28. 1 0
      Firmware/first_lay_cal.cpp
  29. 181 125
      Firmware/fsensor.cpp
  30. 15 1
      Firmware/fsensor.h
  31. 183 190
      Firmware/heatbed_pwm.cpp
  32. 0 374
      Firmware/io_atmega2560.h
  33. 9 6
      Firmware/la10compat.cpp
  34. 3 3
      Firmware/language.c
  35. 1 3
      Firmware/language.h
  36. 7 1
      Firmware/lcd.cpp
  37. 4 1
      Firmware/lcd.h
  38. 90 0
      Firmware/macros.h
  39. 8 3
      Firmware/menu.cpp
  40. 2 1
      Firmware/menu.h
  41. 21 12
      Firmware/mesh_bed_calibration.cpp
  42. 50 23
      Firmware/messages.c
  43. 26 0
      Firmware/messages.h
  44. 55 57
      Firmware/mmu.cpp
  45. 21 11
      Firmware/optiboot_w25x20cl.cpp
  46. 1 1
      Firmware/optiboot_w25x20cl.h
  47. 55 28
      Firmware/pat9125.c
  48. 1 0
      Firmware/pat9125.h
  49. 5 0
      Firmware/pins.h
  50. 2 6
      Firmware/pins_Einsy_1_0.h
  51. 0 3
      Firmware/pins_Rambo_1_3.h
  52. 106 64
      Firmware/planner.cpp
  53. 10 7
      Firmware/planner.h
  54. 45 1
      Firmware/sm4.c
  55. 1 0
      Firmware/sm4.h
  56. 11 5
      Firmware/speed_lookuptable.h
  57. 296 192
      Firmware/stepper.cpp
  58. 0 2
      Firmware/stepper.h
  59. 32 29
      Firmware/swi2c.c
  60. 3 2
      Firmware/system_timer.h
  61. 284 128
      Firmware/temperature.cpp
  62. 9 4
      Firmware/temperature.h
  63. 2 0
      Firmware/thermistortables.h
  64. 12 11
      Firmware/timer02.c
  65. 3 0
      Firmware/timer02.h
  66. 46 20
      Firmware/tmc2130.cpp
  67. 12 0
      Firmware/tmc2130.h
  68. 118 0
      Firmware/tone04.c
  69. 25 0
      Firmware/tone04.h
  70. 137 0
      Firmware/twi.c
  71. 63 0
      Firmware/twi.h
  72. 4 3
      Firmware/uart2.c
  73. 746 950
      Firmware/ultralcd.cpp
  74. 10 10
      Firmware/ultralcd.h
  75. 11 4
      Firmware/util.cpp
  76. 4 0
      Firmware/util.h
  77. 10 1
      Firmware/variants/1_75mm_MK2-RAMBo10a-E3Dv6full.h
  78. 8 1
      Firmware/variants/1_75mm_MK2-RAMBo13a-E3Dv6full.h
  79. 12 2
      Firmware/variants/1_75mm_MK25-RAMBo10a-E3Dv6full.h
  80. 12 2
      Firmware/variants/1_75mm_MK25-RAMBo13a-E3Dv6full.h
  81. 12 2
      Firmware/variants/1_75mm_MK25S-RAMBo10a-E3Dv6full.h
  82. 12 2
      Firmware/variants/1_75mm_MK25S-RAMBo13a-E3Dv6full.h
  83. 15 3
      Firmware/variants/1_75mm_MK3-EINSy10a-E3Dv6full.h
  84. 17 3
      Firmware/variants/1_75mm_MK3S-EINSy10a-E3Dv6full.h
  85. 4 4
      Firmware/w25x20cl.c
  86. 633 460
      Firmware/xyzcal.cpp
  87. 0 14
      Firmware/xyzcal.h
  88. 283 65
      PF-build.sh
  89. 224 198
      README.md
  90. 1 1
      lang/lang-add.sh
  91. 2 2
      lang/lang-build.sh
  92. 0 0
      lang/lang-check.py
  93. 1 1
      lang/lang-check.sh
  94. 158 66
      lang/lang_en.txt
  95. 194 73
      lang/lang_en_cz.txt
  96. 197 76
      lang/lang_en_de.txt
  97. 210 89
      lang/lang_en_es.txt
  98. 209 85
      lang/lang_en_fr.txt
  99. 226 104
      lang/lang_en_it.txt
  100. 0 0
      lang/lang_en_pl.txt

+ 4 - 0
.editorconfig

@@ -12,3 +12,7 @@ indent_style                = space
 indent_size                 = 4
 tab_width                   = 4
 max_line_length             = 100
+
+[lang/po/*.po]
+end_of_line                 = crlf
+trim_trailing_whitespace    = false

+ 1 - 0
.gitattributes

@@ -0,0 +1 @@
+lang/po/*.po text eol=crlf

+ 3 - 0
.github/ISSUE_TEMPLATE/bug_report.md

@@ -15,6 +15,9 @@ Please, before you create a new bug report, please make sure you searched in ope
 **MMU Upgrade** - [e.g. MMU2S, MMU2, MMU1]
 **MMU upgrade firmware version [e.g. 1.0.6, 1.0.6-RC2, ...]
 
+**SD card or USB/Octoprint**
+  Please let us know if you print via SD card or USB/Octoprint
+
 **Describe the bug**
   A clear and concise description of what the bug is.
   

+ 2 - 2
.gitignore

@@ -40,8 +40,8 @@ Firmware/Doc
 /lang/*.dat
 /lang/*.tmp
 /lang/*.out
-/lang/not_tran.txt
-/lang/not_used.txt
+/lang/not_tran*.txt
+/lang/not_used*.txt
 /lang/progmem1.chr
 /lang/progmem1.lss
 /lang/progmem1.txt

+ 3 - 3
Firmware/Configuration.h

@@ -16,8 +16,8 @@ extern uint16_t nPrinterType;
 extern PGM_P sPrinterName;
 
 // Firmware version
-#define FW_VERSION "3.9.0-RC1"
-#define FW_COMMIT_NR   3272
+#define FW_VERSION "3.9.3"
+#define FW_COMMIT_NR 3556
 // FW_VERSION_UNKNOWN means this is an unofficial build.
 // The firmware should only be checked into github with this symbol.
 #define FW_DEV_VERSION FW_VERSION_UNKNOWN
@@ -552,7 +552,7 @@ enum CalibrationStatus
 // Try to maintain a minimum distance from the bed even when Z is
 // unknown when doing the following operations
 #define MIN_Z_FOR_LOAD    50
-#define MIN_Z_FOR_UNLOAD  20
+#define MIN_Z_FOR_UNLOAD  50
 #define MIN_Z_FOR_PREHEAT 10
 
 #include "Configuration_adv.h"

+ 23 - 11
Firmware/ConfigurationStore.cpp

@@ -96,7 +96,7 @@ void Config_PrintSettings(uint8_t level)
 		"%SMaximum feedrates - stealth (mm/s):\n%S  M203 X%.2f Y%.2f Z%.2f E%.2f\n"
 		"%SMaximum acceleration - normal (mm/s2):\n%S  M201 X%lu Y%lu Z%lu E%lu\n"
 		"%SMaximum acceleration - stealth (mm/s2):\n%S  M201 X%lu Y%lu Z%lu E%lu\n"
-		"%SAcceleration: S=acceleration, T=retract acceleration\n%S  M204 S%.2f T%.2f\n"
+		"%SAcceleration: P=print, R=retract, T=travel\n%S  M204 P%.2f R%.2f T%.2f\n"
 		"%SAdvanced variables: S=Min feedrate (mm/s), T=Min travel feedrate (mm/s), B=minimum segment time (ms), X=maximum XY jerk (mm/s),  Z=maximum Z jerk (mm/s),  E=maximum E jerk (mm/s)\n%S  M205 S%.2f T%.2f B%.2f X%.2f Y%.2f Z%.2f E%.2f\n"
 		"%SHome offset (mm):\n%S  M206 X%.2f Y%.2f Z%.2f\n"
 		),
@@ -106,7 +106,7 @@ void Config_PrintSettings(uint8_t level)
 		echomagic, echomagic, cs.max_feedrate_silent[X_AXIS], cs.max_feedrate_silent[Y_AXIS], cs.max_feedrate_silent[Z_AXIS], cs.max_feedrate_silent[E_AXIS],
 		echomagic, echomagic, cs.max_acceleration_units_per_sq_second_normal[X_AXIS], cs.max_acceleration_units_per_sq_second_normal[Y_AXIS], cs.max_acceleration_units_per_sq_second_normal[Z_AXIS], cs.max_acceleration_units_per_sq_second_normal[E_AXIS],
 		echomagic, echomagic, cs.max_acceleration_units_per_sq_second_silent[X_AXIS], cs.max_acceleration_units_per_sq_second_silent[Y_AXIS], cs.max_acceleration_units_per_sq_second_silent[Z_AXIS], cs.max_acceleration_units_per_sq_second_silent[E_AXIS],
-		echomagic, echomagic, cs.acceleration, cs.retract_acceleration,
+		echomagic, echomagic, cs.acceleration, cs.retract_acceleration, cs.travel_acceleration,
 		echomagic, echomagic, cs.minimumfeedrate, cs.mintravelfeedrate, cs.minsegmenttime, cs.max_jerk[X_AXIS], cs.max_jerk[Y_AXIS], cs.max_jerk[Z_AXIS], cs.max_jerk[E_AXIS],
 		echomagic, echomagic, cs.add_homing[X_AXIS], cs.add_homing[Y_AXIS], cs.add_homing[Z_AXIS]
 #else //TMC2130
@@ -114,14 +114,14 @@ void Config_PrintSettings(uint8_t level)
 		"%SSteps per unit:\n%S  M92 X%.2f Y%.2f Z%.2f E%.2f\n"
 		"%SMaximum feedrates (mm/s):\n%S  M203 X%.2f Y%.2f Z%.2f E%.2f\n"
 		"%SMaximum acceleration (mm/s2):\n%S  M201 X%lu Y%lu Z%lu E%lu\n"
-		"%SAcceleration: S=acceleration, T=retract acceleration\n%S  M204 S%.2f T%.2f\n"
+		"%SAcceleration: P=print, R=retract, T=travel\n%S  M204 P%.2f R%.2f T%.2f\n"
 		"%SAdvanced variables: S=Min feedrate (mm/s), T=Min travel feedrate (mm/s), B=minimum segment time (ms), X=maximum XY jerk (mm/s),  Z=maximum Z jerk (mm/s),  E=maximum E jerk (mm/s)\n%S  M205 S%.2f T%.2f B%.2f X%.2f Y%.2f Z%.2f E%.2f\n"
 		"%SHome offset (mm):\n%S  M206 X%.2f Y%.2f Z%.2f\n"
 		),
 		echomagic, echomagic, cs.axis_steps_per_unit[X_AXIS], cs.axis_steps_per_unit[Y_AXIS], cs.axis_steps_per_unit[Z_AXIS], cs.axis_steps_per_unit[E_AXIS],
 		echomagic, echomagic, max_feedrate[X_AXIS], max_feedrate[Y_AXIS], max_feedrate[Z_AXIS], max_feedrate[E_AXIS],
 		echomagic, echomagic, max_acceleration_units_per_sq_second[X_AXIS], max_acceleration_units_per_sq_second[Y_AXIS], max_acceleration_units_per_sq_second[Z_AXIS], max_acceleration_units_per_sq_second[E_AXIS],
-		echomagic, echomagic, cs.acceleration, cs.retract_acceleration,
+		echomagic, echomagic, cs.acceleration, cs.retract_acceleration, cs.travel_acceleration,
 		echomagic, echomagic, cs.minimumfeedrate, cs.mintravelfeedrate, cs.minsegmenttime, cs.max_jerk[X_AXIS], cs.max_jerk[Y_AXIS], cs.max_jerk[Z_AXIS], cs.max_jerk[E_AXIS],
 		echomagic, echomagic, cs.add_homing[X_AXIS], cs.add_homing[Y_AXIS], cs.add_homing[Z_AXIS]
 #endif //TMC2130
@@ -184,7 +184,7 @@ static_assert (false, "zprobe_zoffset was not initialized in printers in field t
         "0.0, if this is not acceptable, increment EEPROM_VERSION to force use default_conf");
 #endif
 
-static_assert (sizeof(M500_conf) == 192, "sizeof(M500_conf) has changed, ensure that EEPROM_VERSION has been incremented, "
+static_assert (sizeof(M500_conf) == 196, "sizeof(M500_conf) has changed, ensure that EEPROM_VERSION has been incremented, "
         "or if you added members in the end of struct, ensure that historically uninitialized values will be initialized."
         "If this is caused by change to more then 8bit processor, decide whether make this struct packed to save EEPROM,"
         "leave as it is to keep fast code, or reorder struct members to pack more tightly.");
@@ -232,8 +232,21 @@ static const M500_conf default_conf PROGMEM =
 #else // TMC2130
     {16,16,16,16},
 #endif
+    DEFAULT_TRAVEL_ACCELERATION,
 };
 
+
+static bool is_uninitialized(void* addr, uint8_t len)
+{
+    while(len--)
+    {
+        if(reinterpret_cast<uint8_t*>(addr)[len] != 0xff)
+            return false;
+    }
+    return true;
+}
+
+
 //! @brief Read M500 configuration
 //! @retval true Succeeded. Stored settings retrieved or default settings retrieved in case EEPROM has been erased.
 //! @retval false Failed. Default settings has been retrieved, because of older version or corrupted data.
@@ -257,13 +270,9 @@ bool Config_RetrieveSettings()
         for (uint8_t i = 0; i < (sizeof(cs.max_feedrate_silent)/sizeof(cs.max_feedrate_silent[0])); ++i)
         {
             const uint32_t erased = 0xffffffff;
-            bool initialized = false;
-
-            for(uint8_t j = 0; j < sizeof(float); ++j)
-            {
-                if(0xff != reinterpret_cast<uint8_t*>(&(cs.max_feedrate_silent[i]))[j]) initialized = true;
+            if (is_uninitialized(&(cs.max_feedrate_silent[i]), sizeof(float))) {
+                memcpy_P(&cs.max_feedrate_silent[i],&default_conf.max_feedrate_silent[i], sizeof(cs.max_feedrate_silent[i]));
             }
-            if (!initialized) memcpy_P(&cs.max_feedrate_silent[i],&default_conf.max_feedrate_silent[i], sizeof(cs.max_feedrate_silent[i]));
             if (erased == cs.max_acceleration_units_per_sq_second_silent[i]) {
                 memcpy_P(&cs.max_acceleration_units_per_sq_second_silent[i],&default_conf.max_acceleration_units_per_sq_second_silent[i],sizeof(cs.max_acceleration_units_per_sq_second_silent[i]));
             }
@@ -293,6 +302,9 @@ bool Config_RetrieveSettings()
 		tmc2130_set_res(E_AXIS, cs.axis_ustep_resolution[E_AXIS]);
 #endif //TMC2130
 
+        if(is_uninitialized(&cs.travel_acceleration, sizeof(cs.travel_acceleration)))
+            cs.travel_acceleration = cs.acceleration;
+
 		reset_acceleration_rates();
 
 		// Call updatePID (similar to when we have processed M301)

+ 1 - 0
Firmware/ConfigurationStore.h

@@ -38,6 +38,7 @@ typedef struct
     float max_feedrate_silent[4]; //!< max speeds for silent mode
     unsigned long max_acceleration_units_per_sq_second_silent[4];
     unsigned char axis_ustep_resolution[4];
+    float travel_acceleration; //!< travel acceleration mm/s^2
 } M500_conf;
 
 extern M500_conf cs;

+ 30 - 7
Firmware/Configuration_adv.h

@@ -62,8 +62,19 @@
 // before setting a PWM value. (Does not work with software PWM for fan on Sanguinololu)
 #define FAN_KICKSTART_TIME 800
 
-
-
+/**
+ * Auto-report all at once with M155 S<seconds> C[bitmask] with single timer
+ * 
+ * bit 0 = Auto-report temperatures
+ * bit 1 = Auto-report fans
+ * bit 2 = Auto-report position
+ * bit 3 = free
+ * bit 4 = free
+ * bit 5 = free
+ * bit 6 = free
+ * bit 7 = free
+*/
+#define AUTO_REPORT
 
 //===========================================================================
 //=============================Mechanical Settings===========================
@@ -285,11 +296,14 @@
 #define LIN_ADVANCE
 
 #ifdef LIN_ADVANCE
-  #define LIN_ADVANCE_K 0  // Unit: mm compression per 1mm/s extruder speed
-  //#define LA_NOCOMPAT    // Disable Linear Advance 1.0 compatibility
-  //#define LA_LIVE_K      // Allow adjusting K in the Tune menu
-  //#define LA_DEBUG       // If enabled, this will generate debug information output over USB.
-  //#define LA_DEBUG_LOGIC // @wavexx: setup logic channels for isr debugging
+  #define LA_K_DEF    0        // Default K factor (Unit: mm compression per 1mm/s extruder speed)
+  #define LA_K_MAX    10       // Maximum acceptable K factor (exclusive, see notes in planner.cpp:plan_buffer_line)
+  #define LA_LA10_MIN LA_K_MAX // Lin. Advance 1.0 threshold value (inclusive)
+  //#define LA_FLOWADJ         // Adjust LA along with flow/M221 for uniform width
+  //#define LA_NOCOMPAT        // Disable Linear Advance 1.0 compatibility
+  //#define LA_LIVE_K          // Allow adjusting K in the Tune menu
+  //#define LA_DEBUG           // If enabled, this will generate debug information output over USB.
+  //#define LA_DEBUG_LOGIC     // @wavexx: setup logic channels for isr debugging
 #endif
 
 // Arc interpretation settings:
@@ -373,6 +387,11 @@ const unsigned int dropsegments=5; //everything with less than this number of st
   #endif
 #endif
 
+/**
+ * Include capabilities in M115 output
+ */
+#define EXTENDED_CAPABILITIES_REPORT
+
 //===========================================================================
 //=============================  Define Defines  ============================
 //===========================================================================
@@ -434,6 +453,10 @@ const unsigned int dropsegments=5; //everything with less than this number of st
   #undef BED_MINTEMP
   #undef BED_MAXTEMP
 #endif
+#if TEMP_SENSOR_AMBIENT == 0
+  #undef AMBIENT_MINTEMP
+  #undef AMBIENT_MAXTEMP
+#endif
 
 
 #endif //__CONFIGURATION_ADV_H

+ 102 - 15
Firmware/Dcodes.cpp

@@ -1,5 +1,5 @@
 #include "Dcodes.h"
-//#include "Marlin.h"
+#include "Marlin.h"
 #include "Configuration.h"
 #include "language.h"
 #include "cmdqueue.h"
@@ -204,7 +204,7 @@ extern float axis_steps_per_unit[NUM_AXIS];
     */
 void dcode__1()
 {
-	printf_P(PSTR("D-1 - Endless loop\n"));
+	DBG(_N("D-1 - Endless loop\n"));
 //	cli();
 	while (1);
 }
@@ -226,9 +226,7 @@ void dcode_0()
 	LOG("D0 - Reset\n");
 	if (code_seen('B')) //bootloader
 	{
-		cli();
-		wdt_enable(WDTO_15MS);
-		while(1);
+		softReset();
 	}
 	else //reset
 	{
@@ -252,8 +250,7 @@ void dcode_1()
 	cli();
 	for (int i = 0; i < 8192; i++)
 		eeprom_write_byte((unsigned char*)i, (unsigned char)0xff);
-	wdt_enable(WDTO_15MS);
-	while(1);
+	softReset();
 }
 
     /*!
@@ -383,7 +380,7 @@ void dcode_4()
    */
 void dcode_5()
 {
-	printf_P(PSTR("D5 - Read/Write FLASH\n"));
+	puts_P(PSTR("D5 - Read/Write FLASH"));
 	uint32_t address = 0x0000; //default 0x0000
 	uint16_t count = 0x0400; //default 0x0400 (1kb block)
 	if (code_seen('A')) // Address (0x00000-0x3ffff)
@@ -420,8 +417,7 @@ void dcode_5()
 		boot_dst_addr = (uint32_t)address;
 		boot_src_addr = (uint32_t)(&data);
 		bootapp_print_vars();
-		wdt_enable(WDTO_15MS);
-		while(1);
+		softReset();
 	}
 	while (count)
 	{
@@ -467,8 +463,7 @@ void dcode_7()
 	boot_copy_size = (uint16_t)0xc00;
 	boot_src_addr = (uint32_t)0x0003e400;
 	boot_dst_addr = (uint32_t)0x0003f400;
-	wdt_enable(WDTO_15MS);
-	while(1);
+	softReset();
 */
 }
 
@@ -486,7 +481,7 @@ void dcode_7()
     */
 void dcode_8()
 {
-	printf_P(PSTR("D8 - Read/Write PINDA\n"));
+	puts_P(PSTR("D8 - Read/Write PINDA"));
 	uint8_t cal_status = calibration_status_pinda();
 	float temp_pinda = current_temperature_pinda;
 	float offset_z = temp_compensation_pinda_thermistor_offset(temp_pinda);
@@ -592,7 +587,7 @@ uint16_t dcode_9_ADC_val(uint8_t i)
 
 void dcode_9()
 {
-	printf_P(PSTR("D9 - Read/Write ADC\n"));
+	puts_P(PSTR("D9 - Read/Write ADC"));
 	if ((strchr_pointer[1+1] == '?') || (strchr_pointer[1+1] == 0))
 	{
 		for (uint8_t i = 0; i < ADC_CHAN_CNT; i++)
@@ -635,6 +630,98 @@ void dcode_12()
 
 }
 
+#ifdef HEATBED_ANALYSIS
+    /*!
+    ### D80 - Bed check <a href="https://reprap.org/wiki/G-code#D80:_Bed_check">D80: Bed check</a>
+    This command will log data to SD card file "mesh.txt".
+    #### Usage
+    
+        D80 [ E | F | G | H | I | J ]
+    
+    #### Parameters
+    - `E` - Dimension X (default 40)
+    - `F` - Dimention Y (default 40)
+    - `G` - Points X (default 40)
+    - `H` - Points Y (default 40)
+    - `I` - Offset X (default 74)
+    - `J` - Offset Y (default 34)
+  */
+void dcode_80()
+{
+	float dimension_x = 40;
+	float dimension_y = 40;
+	int points_x = 40;
+	int points_y = 40;
+	float offset_x = 74;
+	float offset_y = 33;
+
+	if (code_seen('E')) dimension_x = code_value();
+	if (code_seen('F')) dimension_y = code_value();
+	if (code_seen('G')) {points_x = code_value(); }
+	if (code_seen('H')) {points_y = code_value(); }
+	if (code_seen('I')) {offset_x = code_value(); }
+	if (code_seen('J')) {offset_y = code_value(); }
+	printf_P(PSTR("DIM X: %f\n"), dimension_x);
+	printf_P(PSTR("DIM Y: %f\n"), dimension_y);
+	printf_P(PSTR("POINTS X: %d\n"), points_x);
+	printf_P(PSTR("POINTS Y: %d\n"), points_y);
+	printf_P(PSTR("OFFSET X: %f\n"), offset_x);
+	printf_P(PSTR("OFFSET Y: %f\n"), offset_y);
+		bed_check(dimension_x,dimension_y,points_x,points_y,offset_x,offset_y);
+}
+
+
+    /*!
+    ### D81 - Bed analysis <a href="https://reprap.org/wiki/G-code#D81:_Bed_analysis">D80: Bed analysis</a>
+    This command will log data to SD card file "wldsd.txt".
+    #### Usage
+    
+        D81 [ E | F | G | H | I | J ]
+    
+    #### Parameters
+    - `E` - Dimension X (default 40)
+    - `F` - Dimention Y (default 40)
+    - `G` - Points X (default 40)
+    - `H` - Points Y (default 40)
+    - `I` - Offset X (default 74)
+    - `J` - Offset Y (default 34)
+  */
+void dcode_81()
+{
+	float dimension_x = 40;
+	float dimension_y = 40;
+	int points_x = 40;
+	int points_y = 40;
+	float offset_x = 74;
+	float offset_y = 33;
+
+	if (code_seen('E')) dimension_x = code_value();
+	if (code_seen('F')) dimension_y = code_value();
+	if (code_seen("G")) { strchr_pointer+=1; points_x = code_value(); }
+	if (code_seen("H")) { strchr_pointer+=1; points_y = code_value(); }
+	if (code_seen("I")) { strchr_pointer+=1; offset_x = code_value(); }
+	if (code_seen("J")) { strchr_pointer+=1; offset_y = code_value(); }
+	
+	bed_analysis(dimension_x,dimension_y,points_x,points_y,offset_x,offset_y);
+	
+}
+
+#endif //HEATBED_ANALYSIS
+
+    /*!
+    ### D106 - Print measured fan speed for different pwm values <a href="https://reprap.org/wiki/G-code#D106:_Print_measured_fan_speed_for_different_pwm_values">D106: Print measured fan speed for different pwm values</a>
+    */
+void dcode_106()
+{
+	for (int i = 255; i > 0; i = i - 5) {
+		fanSpeed = i;
+		//delay_keep_alive(2000);
+		for (int j = 0; j < 100; j++) {
+			delay_keep_alive(100);
+			}
+			printf_P(_N("%d: %d\n"), i, fan_speed[1]);
+	}
+}
 
 #ifdef TMC2130
 #include "planner.h"
@@ -697,7 +784,7 @@ extern void st_synchronize();
 	*/
 void dcode_2130()
 {
-	printf_P(PSTR("D2130 - TMC2130\n"));
+	puts_P(PSTR("D2130 - TMC2130"));
 	uint8_t axis = 0xff;
 	switch (strchr_pointer[1+4])
 	{

+ 18 - 4
Firmware/Dcodes.h

@@ -2,26 +2,40 @@
 #define DCODES_H
 
 extern void dcode__1(); //D-1 - Endless loop (to simulate deadlock)
-
 extern void dcode_0(); //D0 - Reset
 extern void dcode_1(); //D1 - Clear EEPROM
 extern void dcode_2(); //D2 - Read/Write RAM
+
+#if defined DEBUG_DCODE3 || defined DEBUG_DCODES
 extern void dcode_3(); //D3 - Read/Write EEPROM
+#endif //DEBUG_DCODE3
+
 extern void dcode_4(); //D4 - Read/Write PIN
+
+#if defined DEBUG_DCODE5 || defined DEBUG_DCODES
 extern void dcode_5(); //D5 - Read/Write FLASH
+#endif //DEBUG_DCODE5
+
 extern void dcode_6(); //D6 - Read/Write external FLASH
 extern void dcode_7(); //D7 - Read/Write Bootloader
 extern void dcode_8(); //D8 - Read/Write PINDA
 extern void dcode_9(); //D9 - Read/Write ADC (Write=enable simulated, Read=disable simulated)
-
 extern void dcode_10(); //D10 - XYZ calibration = OK
+extern void dcode_12(); //D12 - Log time. Writes the current time in the log file.
+
+#ifdef HEATBED_ANALYSIS
+extern void dcode_80(); //D80 - Bed check. This command will log data to SD card file "mesh.txt".
+extern void dcode_81(); //D81 - Bed analysis. This command will log data to SD card file "wldsd.txt".
+#endif //HEATBED_ANALYSIS
+
+	extern void dcode_106(); //D106 - Print measured fan speed for different pwm values
 
 #ifdef TMC2130
-extern void dcode_2130(); //D2130 - TMC2130
+	extern void dcode_2130(); //D2130 - TMC2130
 #endif //TMC2130
 
 #ifdef PAT9125
-extern void dcode_9125(); //D9125 - PAT9125
+	extern void dcode_9125(); //D9125 - PAT9125
 #endif //PAT9125
 
 

+ 14 - 24
Firmware/Marlin.h

@@ -4,7 +4,7 @@
 #ifndef MARLIN_H
 #define MARLIN_H
 
-#define  FORCE_INLINE __attribute__((always_inline)) inline
+#include "macros.h"
 
 #include <math.h>
 #include <stdio.h>
@@ -116,7 +116,6 @@ void serial_echopair_P(const char *s_P, unsigned long v);
 void serialprintPGM(const char *str);
 
 bool is_buffer_empty();
-void get_command();
 void process_commands();
 void ramming();
 
@@ -238,26 +237,15 @@ void get_coordinates();
 void prepare_move();
 void kill(const char *full_screen_message = NULL, unsigned char id = 0);
 void Stop();
-
 bool IsStopped();
-
-//put an ASCII command at the end of the current buffer.
-void enquecommand(const char *cmd, bool from_progmem = false);
+void finishAndDisableSteppers();
 
 //put an ASCII command at the end of the current buffer, read from flash
 #define enquecommand_P(cmd) enquecommand(cmd, true)
 
-//put an ASCII command at the begin of the current buffer
-void enquecommand_front(const char *cmd, bool from_progmem = false);
-
 //put an ASCII command at the begin of the current buffer, read from flash
 #define enquecommand_front_P(cmd) enquecommand_front(cmd, true)
 
-void repeatcommand_front();
-
-// Remove all lines from the command queue.
-void cmdqueue_reset();
-
 void prepare_arc_move(char isclockwise);
 void clamp_to_software_endstops(float target[3]);
 void refresh_cmd_timeout(void);
@@ -287,11 +275,6 @@ FORCE_INLINE unsigned long millis_nc() {
 void setPwmFrequency(uint8_t pin, int val);
 #endif
 
-#ifndef CRITICAL_SECTION_START
-  #define CRITICAL_SECTION_START  unsigned char _sreg = SREG; cli();
-  #define CRITICAL_SECTION_END    SREG = _sreg;
-#endif //CRITICAL_SECTION_START
-
 extern bool fans_check_enabled;
 extern float homing_feedrate[];
 extern uint8_t axis_relative_modes;
@@ -299,20 +282,21 @@ extern float feedrate;
 extern int feedmultiply;
 extern int extrudemultiply; // Sets extrude multiply factor (in percent) for all extruders
 extern int extruder_multiply[EXTRUDERS]; // sets extrude multiply factor (in percent) for each extruder individually
-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 float extruder_multiplier[EXTRUDERS]; // reciprocal of cross-sectional area of filament (in square millimeters), stored this way to reduce computational burden in planner
 extern float current_position[NUM_AXIS] ;
 extern float destination[NUM_AXIS] ;
 extern float min_pos[3];
 extern float max_pos[3];
 extern bool axis_known_position[3];
 extern int fanSpeed;
+extern uint8_t newFanSpeed;
 extern int8_t lcd_change_fil_state;
 extern float default_retraction;
 
 #ifdef TMC2130
-bool homeaxis(int axis, bool doError = true, uint8_t cnt = 1, uint8_t* pstep = 0);
+void homeaxis(int axis, uint8_t cnt = 1, uint8_t* pstep = 0);
 #else
-bool homeaxis(int axis, bool doError = true, uint8_t cnt = 1);
+void homeaxis(int axis, uint8_t cnt = 1);
 #endif //TMC2130
 
 
@@ -334,7 +318,6 @@ extern unsigned long stoptime;
 extern int bowden_length[4];
 extern bool is_usb_printing;
 extern bool homing_flag;
-extern bool temp_cal_active;
 extern bool loading_flag;
 extern unsigned int usb_printing_counter;
 
@@ -369,7 +352,7 @@ extern bool mesh_bed_run_from_menu;
 
 extern bool sortAlpha;
 
-extern char dir_names[3][9];
+extern char dir_names[][9];
 
 extern int8_t lcd_change_fil_state;
 // save/restore printing
@@ -498,6 +481,9 @@ void force_high_power_mode(bool start_high_power_section);
 
 bool gcode_M45(bool onlyZ, int8_t verbosity_level);
 void gcode_M114();
+#if (defined(FANCHECK) && (((defined(TACH_0) && (TACH_0 >-1)) || (defined(TACH_1) && (TACH_1 > -1)))))
+void gcode_M123();
+#endif //FANCHECK and TACH_0 and TACH_1
 void gcode_M701();
 
 #define UVLO !(PINE & (1<<4))
@@ -513,4 +499,8 @@ void load_filament_final_feed();
 void marlin_wait_for_click();
 void raise_z_above(float target, bool plan=true);
 
+extern "C" void softReset();
+
+extern uint32_t IP_address;
+
 #endif

+ 2 - 2
Firmware/MarlinSerial.cpp

@@ -255,7 +255,7 @@ void MarlinSerial::print(double n, int digits)
 
 void MarlinSerial::println(void)
 {
-  print('\r');
+  // print('\r');
   print('\n');  
 }
 
@@ -359,7 +359,7 @@ void MarlinSerial::printFloat(double number, uint8_t digits)
 
   // Print the decimal point, but only if there are digits beyond
   if (digits > 0)
-    print("."); 
+    print('.'); 
 
   // Extract digits from the remainder one at a time
   while (digits-- > 0)

+ 951 - 695
Firmware/Marlin_main.cpp

@@ -47,7 +47,9 @@
 #include "Configuration.h"
 #include "Marlin.h"
 #include "config.h"
-  
+
+#include "macros.h"
+
 #ifdef ENABLE_AUTO_BED_LEVELING
 #include "vector_3.h"
   #ifdef AUTO_BED_LEVELING_GRID
@@ -88,18 +90,13 @@
 #include "la10compat.h"
 #endif
 
-#ifdef SWSPI
-#include "swspi.h"
-#endif //SWSPI
-
 #include "spi.h"
 
-#ifdef SWI2C
-#include "swi2c.h"
-#endif //SWI2C
-
 #ifdef FILAMENT_SENSOR
 #include "fsensor.h"
+#ifdef IR_SENSOR
+#include "pat9125.h" // for pat9125_probe
+#endif
 #endif //FILAMENT_SENSOR
 
 #ifdef TMC2130
@@ -137,12 +134,6 @@
 #include "sound.h"
 
 #include "cmdqueue.h"
-#include "io_atmega2560.h"
-
-// Macros for bit masks
-#define BIT(b) (1<<(b))
-#define TEST(n,b) (((n)&BIT(b))!=0)
-#define SET_BIT(n,b,value) (n) ^= ((-value)^(n)) & (BIT(b))
 
 //Macro for print fan speed
 #define FAN_PULSE_WIDTH_LIMIT ((fanSpeed > 100) ? 3 : 4) //time in ms
@@ -202,8 +193,6 @@ int bowden_length[4] = {385, 385, 385, 385};
 bool is_usb_printing = false;
 bool homing_flag = false;
 
-bool temp_cal_active = false;
-
 unsigned long kicktime = _millis()+100000;
 
 unsigned int  usb_printing_counter;
@@ -239,7 +228,7 @@ bool fan_state[2];
 int fan_edge_counter[2];
 int fan_speed[2];
 
-char dir_names[3][9];
+char dir_names[MAX_DIR_DEPTH][9];
 
 bool sortAlpha = false;
 
@@ -276,6 +265,7 @@ float extruder_offset[NUM_EXTRUDER_OFFSETS][EXTRUDERS] = {
 
 uint8_t active_extruder = 0;
 int fanSpeed=0;
+uint8_t newFanSpeed = 0;
 
 #ifdef FWRETRACT
   bool retracted[EXTRUDERS]={false
@@ -313,6 +303,7 @@ uint8_t host_keepalive_interval = HOST_KEEPALIVE_INTERVAL;
 
 const char errormagic[] PROGMEM = "Error:";
 const char echomagic[] PROGMEM = "echo:";
+const char G28W0[] PROGMEM = "G28 W0";
 
 bool no_response = false;
 uint8_t important_status;
@@ -330,6 +321,8 @@ uint16_t print_time_remaining_normal = PRINT_TIME_REMAINING_INIT; //estimated re
 uint8_t print_percent_done_silent = PRINT_PERCENT_DONE_INIT;
 uint16_t print_time_remaining_silent = PRINT_TIME_REMAINING_INIT; //estimated remaining print time in minutes
 
+uint32_t IP_address = 0;
+
 //===========================================================================
 //=============================Private Variables=============================
 //===========================================================================
@@ -395,6 +388,59 @@ static int saved_fanSpeed = 0; //!< Print fan speed
 
 static int saved_feedmultiply_mm = 100;
 
+class AutoReportFeatures {
+    union {
+          struct {
+            uint8_t temp : 1; //Temperature flag
+            uint8_t fans : 1; //Fans flag
+            uint8_t pos: 1;   //Position flag
+            uint8_t ar4 : 1;  //Unused
+            uint8_t ar5 : 1;  //Unused
+            uint8_t ar6 : 1;  //Unused
+            uint8_t ar7 : 1;  //Unused
+          } __attribute__((packed)) bits;
+          uint8_t byte;
+        } arFunctionsActive;
+    uint8_t auto_report_period;
+public:
+    LongTimer auto_report_timer;
+    AutoReportFeatures():auto_report_period(0){ 
+#if defined(AUTO_REPORT)
+        arFunctionsActive.byte = 0xff; 
+#else
+        arFunctionsActive.byte = 0;
+#endif //AUTO_REPORT
+    }
+    
+    inline bool Temp()const { return arFunctionsActive.bits.temp != 0; }
+    inline void SetTemp(uint8_t v){ arFunctionsActive.bits.temp = v; }
+
+    inline bool Fans()const { return arFunctionsActive.bits.fans != 0; }
+    inline void SetFans(uint8_t v){ arFunctionsActive.bits.fans = v; }
+
+    inline bool Pos()const { return arFunctionsActive.bits.pos != 0; }
+    inline void SetPos(uint8_t v){ arFunctionsActive.bits.pos = v; }
+    
+    inline void SetMask(uint8_t mask){ arFunctionsActive.byte = mask; }
+    
+    /// sets the autoreporting timer's period
+    /// setting it to zero stops the timer
+    void SetPeriod(uint8_t p){
+        auto_report_period = p;
+        if (auto_report_period != 0){
+          auto_report_timer.start();
+        } else{
+          auto_report_timer.stop();
+        }
+    }
+    
+    inline void TimerStart() { auto_report_timer.start(); }
+    inline bool TimerRunning()const { return auto_report_timer.running(); }
+    inline bool TimerExpired() { return auto_report_timer.expired(auto_report_period * 1000ul); }
+};
+
+AutoReportFeatures autoReportFeatures;
+
 //===========================================================================
 //=============================Routines======================================
 //===========================================================================
@@ -404,9 +450,11 @@ static bool setTargetedHotend(int code, uint8_t &extruder);
 static void print_time_remaining_init();
 static void wait_for_heater(long codenum, uint8_t extruder);
 static void gcode_G28(bool home_x_axis, bool home_y_axis, bool home_z_axis);
+static void gcode_M105(uint8_t extruder);
 static void temp_compensation_start();
 static void temp_compensation_apply();
 
+static bool get_PRUSA_SN(char* SN);
 
 uint16_t gcode_in_progress = 0;
 uint16_t mcode_in_progress = 0;
@@ -631,7 +679,7 @@ void crashdet_cancel()
 		lcd_print_stop();
 	}else if(saved_printing_type == PRINTING_TYPE_USB){
 		SERIAL_ECHOLNRPGM(MSG_OCTOPRINT_CANCEL); //for Octoprint: works the same as clicking "Abort" button in Octoprint GUI
-		SERIAL_PROTOCOLLNRPGM(MSG_OK);
+		cmdqueue_reset();
 	}
 }
 
@@ -650,6 +698,12 @@ void failstats_reset_print()
 #endif
 }
 
+void softReset()
+{
+    cli();
+    wdt_enable(WDTO_15MS);
+    while(1);
+}
 
 
 #ifdef MESH_BED_LEVELING
@@ -708,10 +762,8 @@ static void factory_reset(char level)
             // Force the "Follow calibration flow" message at the next boot up.
             calibration_status_store(CALIBRATION_STATUS_Z_CALIBRATION);
 			eeprom_write_byte((uint8_t*)EEPROM_WIZARD_ACTIVE, 1); //run wizard
-            farm_no = 0;
 			farm_mode = false;
 			eeprom_update_byte((uint8_t*)EEPROM_FARM_MODE, farm_mode);
-            EEPROM_save_B(EEPROM_FARM_NUMBER, &farm_no);
 
             eeprom_update_dword((uint32_t *)EEPROM_TOTALTIME, 0);
             eeprom_update_dword((uint32_t *)EEPROM_FILAMENTUSED, 0);
@@ -764,6 +816,7 @@ static void factory_reset(char level)
 				}
 
 			}
+			softReset();
 
 
 			break;
@@ -866,17 +919,15 @@ static void check_if_fw_is_on_right_printer(){
 #ifdef FILAMENT_SENSOR
   if((PRINTER_TYPE == PRINTER_MK3) || (PRINTER_TYPE == PRINTER_MK3S)){
     #ifdef IR_SENSOR
-    swi2c_init();
-    const uint8_t pat9125_detected = swi2c_readByte_A8(PAT9125_I2C_ADDR,0x00,NULL);
-      if (pat9125_detected){
-        lcd_show_fullscreen_message_and_wait_P(_i("MK3S firmware detected on MK3 printer"));}
+      if (pat9125_probe()){
+        lcd_show_fullscreen_message_and_wait_P(_i("MK3S firmware detected on MK3 printer"));}////c=20 r=3
     #endif //IR_SENSOR
 
     #ifdef PAT9125
       //will return 1 only if IR can detect filament in bondtech extruder so this may fail even when we have IR sensor
-      const uint8_t ir_detected = !(PIN_GET(IR_SENSOR_PIN));
+      const uint8_t ir_detected = !READ(IR_SENSOR_PIN);
       if (ir_detected){
-        lcd_show_fullscreen_message_and_wait_P(_i("MK3 firmware detected on MK3S printer"));}
+        lcd_show_fullscreen_message_and_wait_P(_i("MK3 firmware detected on MK3S printer"));}////c=20 r=3
     #endif //PAT9125
   }
 #endif //FILAMENT_SENSOR
@@ -962,10 +1013,10 @@ uint8_t lang_xflash_enum_codes(uint16_t* codes)
 		w25x20cl_rd_data(addr, (uint8_t*)&header, sizeof(lang_table_header_t));
 		if (header.magic != LANG_MAGIC)
 		{
-			printf_P(_n("NG!\n"));
+			puts_P(_n("NG!"));
 			break;
 		}
-		printf_P(_n("OK\n"));
+		puts_P(_n("OK"));
 		printf_P(_n(" _lt_magic        = 0x%08lx %S\n"), header.magic, (header.magic==LANG_MAGIC)?_n("OK"):_n("NA"));
 		printf_P(_n(" _lt_size         = 0x%04x (%d)\n"), header.size, header.size);
 		printf_P(_n(" _lt_count        = 0x%04x (%d)\n"), header.count, header.count);
@@ -1005,6 +1056,8 @@ static void w25x20cl_err_msg()
 // are initialized by the main() routine provided by the Arduino framework.
 void setup()
 {
+	timer2_init(); // enables functional millis
+
 	mmu_init();
 
 	ultralcd_init();
@@ -1014,11 +1067,19 @@ void setup()
 	lcd_splash();
     Sound_Init();                                // also guarantee "SET_OUTPUT(BEEPER)"
 
+	selectedSerialPort = eeprom_read_byte((uint8_t *)EEPROM_SECOND_SERIAL_ACTIVE);
+	if (selectedSerialPort == 0xFF) selectedSerialPort = 0;
+	eeprom_update_byte((uint8_t *)EEPROM_SECOND_SERIAL_ACTIVE, selectedSerialPort);
+	MYSERIAL.begin(BAUDRATE);
+	fdev_setup_stream(uartout, uart_putchar, NULL, _FDEV_SETUP_WRITE); //setup uart out stream
+	stdout = uartout;
+
 #ifdef W25X20CL
     bool w25x20cl_success = w25x20cl_init();
+	uint8_t optiboot_status = 1;
 	if (w25x20cl_success)
 	{
-	    optiboot_w25x20cl_enter();
+		optiboot_status = optiboot_w25x20cl_enter();
 #if (LANG_MODE != 0) //secondary language support
         update_sec_lang_from_external_flash();
 #endif //(LANG_MODE != 0)
@@ -1036,19 +1097,17 @@ void setup()
 	setup_powerhold();
 
 	farm_mode = eeprom_read_byte((uint8_t*)EEPROM_FARM_MODE); 
-	EEPROM_read_B(EEPROM_FARM_NUMBER, &farm_no);
-	if ((farm_mode == 0xFF && farm_no == 0) || ((uint16_t)farm_no == 0xFFFF)) 
+	if (farm_mode == 0xFF) 
 		farm_mode = false; //if farm_mode has not been stored to eeprom yet and farm number is set to zero or EEPROM is fresh, deactivate farm mode
-	if ((uint16_t)farm_no == 0xFFFF) farm_no = 0;
-	
-	selectedSerialPort = eeprom_read_byte((uint8_t*)EEPROM_SECOND_SERIAL_ACTIVE);
-	if (selectedSerialPort == 0xFF) selectedSerialPort = 0;
 	if (farm_mode)
 	{
 		no_response = true; //we need confirmation by recieving PRUSA thx
 		important_status = 8;
 		prusa_statistics(8);
+#ifdef HAS_SECOND_SERIAL_PORT
 		selectedSerialPort = 1;
+#endif //HAS_SECOND_SERIAL_PORT
+		MYSERIAL.begin(BAUDRATE);
 #ifdef TMC2130
 		//increased extruder current (PFW363)
 		tmc2130_current_h[E_AXIS] = 36;
@@ -1062,14 +1121,30 @@ void setup()
           if(!(eeprom_read_byte((uint8_t*)EEPROM_FAN_CHECK_ENABLED)))
                eeprom_update_byte((unsigned char *)EEPROM_FAN_CHECK_ENABLED,true);
 	}
-	MYSERIAL.begin(BAUDRATE);
-	fdev_setup_stream(uartout, uart_putchar, NULL, _FDEV_SETUP_WRITE); //setup uart out stream
+
+    //saved EEPROM SN is not valid. Try to retrieve it.
+    //SN is valid only if it is NULL terminated. Any other character means either uninitialized or corrupted
+    if (eeprom_read_byte((uint8_t*)EEPROM_PRUSA_SN + 19))
+    {
+        char SN[20];
+        if (get_PRUSA_SN(SN))
+        {
+            eeprom_update_block(SN, (uint8_t*)EEPROM_PRUSA_SN, 20);
+            puts_P(PSTR("SN updated"));
+        }
+        else
+            puts_P(PSTR("SN update failed"));
+    }
+
+
 #ifndef W25X20CL
 	SERIAL_PROTOCOLLNPGM("start");
-#endif //W25X20CL
-	stdout = uartout;
+#else
+	if ((optiboot_status != 0) || (selectedSerialPort != 0))
+		SERIAL_PROTOCOLLNPGM("start");
+#endif
 	SERIAL_ECHO_START;
-	printf_P(PSTR(" " FW_VERSION_FULL "\n"));
+	puts_P(PSTR(" " FW_VERSION_FULL));
 
 	//SERIAL_ECHOPAIR("Active sheet before:", static_cast<unsigned long int>(eeprom_read_byte(&(EEPROM_Sheets_base->active_sheet))));
 
@@ -1159,12 +1234,12 @@ void setup()
 		printf_P(_n("_SEC_LANG_TABLE checksum = %04x\n"), sum);
 		sum = (sum >> 8) | ((sum & 0xff) << 8); //swap bytes
 		if (sum == header.checksum)
-			printf_P(_n("Checksum OK\n"), sum);
+			puts_P(_n("Checksum OK"), sum);
 		else
-			printf_P(_n("Checksum NG\n"), sum);
+			puts_P(_n("Checksum NG"), sum);
 	}
 	else
-		printf_P(_n("lang_get_header failed!\n"));
+		puts_P(_n("lang_get_header failed!"));
 
 #if 0
 		for (uint16_t i = 0; i < 1024*10; i++)
@@ -1244,8 +1319,15 @@ void setup()
 	else
 	{
 	    w25x20cl_err_msg();
-	    printf_P(_n("W25X20CL not responding.\n"));
+	    puts_P(_n("W25X20CL not responding."));
 	}
+#ifdef EXTRUDER_ALTFAN_DETECT
+	SERIAL_ECHORPGM(_n("Extruder fan type: "));
+	if (extruder_altfan_detect())
+		SERIAL_ECHOLNRPGM(PSTR("ALTFAN"));
+	else
+		SERIAL_ECHOLNRPGM(PSTR("NOCTUA"));
+#endif //EXTRUDER_ALTFAN_DETECT
 
 	plan_init();  // Initialize planner;
 
@@ -1332,8 +1414,7 @@ void setup()
     // Initialize current_position accounting for software endstops to
     // avoid unexpected initial shifts on the first move
     clamp_to_software_endstops(current_position);
-    plan_set_position(current_position[X_AXIS], current_position[Y_AXIS],
-                      current_position[Z_AXIS], current_position[E_AXIS]);
+    plan_set_position_curposXYZE();
 
 #ifdef FILAMENT_SENSOR
 	fsensor_init();
@@ -1351,9 +1432,7 @@ void setup()
 #endif
 
 	farm_mode = eeprom_read_byte((uint8_t*)EEPROM_FARM_MODE);
-	EEPROM_read_B(EEPROM_FARM_NUMBER, &farm_no);
-	if ((farm_mode == 0xFF && farm_no == 0) || (farm_no == static_cast<int>(0xFFFF))) farm_mode = false; //if farm_mode has not been stored to eeprom yet and farm number is set to zero or EEPROM is fresh, deactivate farm mode
-	if (farm_no == static_cast<int>(0xFFFF)) farm_no = 0;
+	if (farm_mode == 0xFF) farm_mode = false; //if farm_mode has not been stored to eeprom yet and farm number is set to zero or EEPROM is fresh, deactivate farm mode
 	if (farm_mode)
 	{
 		prusa_statistics(8);
@@ -1453,8 +1532,7 @@ void setup()
 
 	if (eeprom_read_byte((uint8_t*)EEPROM_TEMP_CAL_ACTIVE) == 255) {
 		eeprom_write_byte((uint8_t*)EEPROM_TEMP_CAL_ACTIVE, 0);
-		temp_cal_active = false;
-	} else temp_cal_active = eeprom_read_byte((uint8_t*)EEPROM_TEMP_CAL_ACTIVE);
+	}
 
 	if (eeprom_read_byte((uint8_t*)EEPROM_CALIBRATION_STATUS_PINDA) == 255) {
 		//eeprom_write_byte((uint8_t*)EEPROM_CALIBRATION_STATUS_PINDA, 0);
@@ -1462,7 +1540,6 @@ void setup()
 		int16_t z_shift = 0;
 		for (uint8_t i = 0; i < 5; i++) EEPROM_save_B(EEPROM_PROBE_TEMP_SHIFT + i * 2, &z_shift);
 		eeprom_write_byte((uint8_t*)EEPROM_TEMP_CAL_ACTIVE, 0);
-		temp_cal_active = false;
 	}
 	if (eeprom_read_byte((uint8_t*)EEPROM_UVLO) == 255) {
 		eeprom_write_byte((uint8_t*)EEPROM_UVLO, 0);
@@ -1515,7 +1592,7 @@ void setup()
   }
 
   if (!previous_settings_retrieved) {
-	  lcd_show_fullscreen_message_and_wait_P(_i("Old settings found. Default PID, Esteps etc. will be set.")); //if EEPROM version or printer type was changed, inform user that default setting were loaded////MSG_DEFAULT_SETTINGS_LOADED c=20 r=4
+	  lcd_show_fullscreen_message_and_wait_P(_i("Old settings found. Default PID, Esteps etc. will be set.")); //if EEPROM version or printer type was changed, inform user that default setting were loaded////MSG_DEFAULT_SETTINGS_LOADED c=20 r=5
 	  Config_StoreSettings();
   }
   if (eeprom_read_byte((uint8_t*)EEPROM_WIZARD_ACTIVE) == 1) {
@@ -1535,7 +1612,7 @@ void setup()
 		  lcd_show_fullscreen_message_and_wait_P(_T(MSG_BABYSTEP_Z_NOT_SET));
 		  lcd_update_enable(true);
 	  }
-	  else if (calibration_status() == CALIBRATION_STATUS_CALIBRATED && temp_cal_active == true && calibration_status_pinda() == false) {
+	  else if (calibration_status() == CALIBRATION_STATUS_CALIBRATED && eeprom_read_byte((unsigned char *)EEPROM_TEMP_CAL_ACTIVE) && calibration_status_pinda() == false) {
 		  //lcd_show_fullscreen_message_and_wait_P(_i("Temperature calibration has not been run yet"));////MSG_PINDA_NOT_CALIBRATED c=20 r=4
 		  lcd_update_enable(true);
 	  }
@@ -1712,6 +1789,28 @@ void host_keepalive() {
 #endif //HOST_KEEPALIVE_FEATURE
   if (farm_mode) return;
   long ms = _millis();
+
+#if defined(AUTO_REPORT)
+  {
+    if (autoReportFeatures.TimerExpired())
+    {
+      if(autoReportFeatures.Temp()){
+        gcode_M105(active_extruder);
+      }
+      if(autoReportFeatures.Pos()){
+        gcode_M114();
+      }
+ #if defined(AUTO_REPORT) && (defined(FANCHECK) && (((defined(TACH_0) && (TACH_0 >-1)) || (defined(TACH_1) && (TACH_1 > -1)))))      
+      if(autoReportFeatures.Fans()){
+        gcode_M123();
+      }
+#endif //AUTO_REPORT and (FANCHECK and TACH_0 or TACH_1)
+     autoReportFeatures.TimerStart();
+    }
+  }
+#endif //AUTO_REPORT
+
+
   if (host_keepalive_interval && busy_state != NOT_BUSY) {
     if ((ms - prev_busy_signal_ms) < (long)(1000L * host_keepalive_interval)) return;
      switch (busy_state) {
@@ -1948,7 +2047,7 @@ static void set_bed_level_equation_lsq(double *plane_equation_coefficients)
     // put the bed at 0 so we don't go below it.
     current_position[Z_AXIS] = cs.zprobe_zoffset; // in the lsq we reach here after raising the extruder due to the loop structure
 
-    plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
+    plan_set_position_curposXYZE();
 }
 
 #else // not AUTO_BED_LEVELING_GRID
@@ -1976,7 +2075,7 @@ static void set_bed_level_equation_3pts(float z_at_pt_1, float z_at_pt_2, float
     // put the bed at 0 so we don't go below it.
     current_position[Z_AXIS] = cs.zprobe_zoffset;
 
-    plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
+    plan_set_position_curposXYZE();
 
 }
 
@@ -2008,7 +2107,7 @@ static void run_z_probe() {
 
     current_position[Z_AXIS] = st_get_position_mm(Z_AXIS);
     // make sure the planner knows where we are as it may be a bit different than we last said to move to
-    plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
+    plan_set_position_curposXYZE();
 }
 
 static void do_blocking_move_to(float x, float y, float z) {
@@ -2066,15 +2165,16 @@ static float probe_pt(float x, float y, float z_before) {
 inline void gcode_M900() {
     float newK = code_seen('K') ? code_value_float() : -2;
 #ifdef LA_NOCOMPAT
-    if (newK >= 0 && newK < 10)
+    if (newK >= 0 && newK < LA_K_MAX)
         extruder_advance_K = newK;
     else
         SERIAL_ECHOLNPGM("K out of allowed range!");
 #else
     if (newK == 0)
+    {
         extruder_advance_K = 0;
-    else if (newK == -1)
         la10c_reset();
+    }
     else
     {
         newK = la10c_value(newK);
@@ -2096,7 +2196,7 @@ bool check_commands() {
 	
 		while (buflen)
 		{
-		if ((code_seen("M84")) || (code_seen("M 84"))) end_command_found = true;
+		if ((code_seen_P(PSTR("M84"))) || (code_seen_P(PSTR("M 84")))) end_command_found = true;
 		if (!cmdbuffer_front_already_processed)
 			 cmdqueue_pop_front();
 		cmdbuffer_front_already_processed = false;
@@ -2128,7 +2228,7 @@ void raise_z_above(float target, bool plan)
     if (axis_known_position[Z_AXIS] || z_min_endstop)
     {
         // current position is known or very low, it's safe to raise Z
-        if(plan) plan_buffer_line_curposXYZE(max_feedrate[Z_AXIS], active_extruder);
+        if(plan) plan_buffer_line_curposXYZE(max_feedrate[Z_AXIS]);
         return;
     }
 
@@ -2141,15 +2241,14 @@ void raise_z_above(float target, bool plan)
 #ifdef TMC2130
     tmc2130_home_enter(Z_AXIS_MASK);
 #endif //TMC2130
-    plan_buffer_line_curposXYZE(homing_feedrate[Z_AXIS] / 60, active_extruder);
+    plan_buffer_line_curposXYZE(homing_feedrate[Z_AXIS] / 60);
     st_synchronize();
 #ifdef TMC2130
     if (endstop_z_hit_on_purpose())
     {
         // not necessarily exact, but will avoid further vertical moves
         current_position[Z_AXIS] = max_pos[Z_AXIS];
-        plan_set_position(current_position[X_AXIS], current_position[Y_AXIS],
-                          current_position[Z_AXIS], current_position[E_AXIS]);
+        plan_set_position_curposXYZE();
     }
     tmc2130_home_exit();
 #endif //TMC2130
@@ -2167,22 +2266,22 @@ bool calibrate_z_auto()
 	int axis_up_dir = -home_dir(Z_AXIS);
 	tmc2130_home_enter(Z_AXIS_MASK);
 	current_position[Z_AXIS] = 0;
-	plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
+	plan_set_position_curposXYZE();
 	set_destination_to_current();
 	destination[Z_AXIS] += (1.1 * max_length(Z_AXIS) * axis_up_dir);
 	feedrate = homing_feedrate[Z_AXIS];
-	plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate / 60, active_extruder);
+	plan_buffer_line_destinationXYZE(feedrate / 60);
 	st_synchronize();
 	//	current_position[axis] = 0;
-	//	plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
+	//	plan_set_position_curposXYZE();
 	tmc2130_home_exit();
 	enable_endstops(false);
 	current_position[Z_AXIS] = 0;
-	plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
+	plan_set_position_curposXYZE();
 	set_destination_to_current();
 	destination[Z_AXIS] += 10 * axis_up_dir; //10mm up
 	feedrate = homing_feedrate[Z_AXIS] / 2;
-	plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate / 60, active_extruder);
+	plan_buffer_line_destinationXYZE(feedrate / 60);
 	st_synchronize();
 	enable_endstops(endstops_enabled);
 	if (PRINTER_TYPE == PRINTER_MK3) {
@@ -2191,15 +2290,30 @@ bool calibrate_z_auto()
 	else {
 		current_position[Z_AXIS] = Z_MAX_POS + 9.0;
 	}
-    plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
+	plan_set_position_curposXYZE();
 	return true;
 }
 #endif //TMC2130
 
 #ifdef TMC2130
-bool homeaxis(int axis, bool doError, uint8_t cnt, uint8_t* pstep)
+static void check_Z_crash(void)
+{
+	if (READ(Z_TMC2130_DIAG) != 0) { //Z crash
+		FORCE_HIGH_POWER_END;
+		current_position[Z_AXIS] = 0;
+		plan_set_position_curposXYZE();
+		current_position[Z_AXIS] += MESH_HOME_Z_SEARCH;
+		plan_buffer_line_curposXYZE(max_feedrate[Z_AXIS]);
+		st_synchronize();
+		kill(_T(MSG_BED_LEVELING_FAILED_POINT_LOW));
+	}
+}
+#endif //TMC2130
+
+#ifdef TMC2130
+void homeaxis(int axis, uint8_t cnt, uint8_t* pstep)
 #else
-bool homeaxis(int axis, bool doError, uint8_t cnt)
+void homeaxis(int axis, uint8_t cnt)
 #endif //TMC2130
 {
 	bool endstops_enabled  = enable_endstops(true); //RP: endstops should be allways enabled durring homing
@@ -2219,24 +2333,24 @@ bool homeaxis(int axis, bool doError, uint8_t cnt)
         // and the following movement to endstop has a chance to achieve the required velocity
         // for the stall guard to work.
         current_position[axis] = 0;
-        plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
+        plan_set_position_curposXYZE();
 		set_destination_to_current();
 //        destination[axis] = 11.f;
         destination[axis] = -3.f * axis_home_dir;
-        plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder);
+        plan_buffer_line_destinationXYZE(feedrate/60);
         st_synchronize();
         // Move away from the possible collision with opposite endstop with the collision detection disabled.
         endstops_hit_on_purpose();
         enable_endstops(false);
         current_position[axis] = 0;
-        plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
+        plan_set_position_curposXYZE();
         destination[axis] = 1. * axis_home_dir;
-        plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder);
+        plan_buffer_line_destinationXYZE(feedrate/60);
         st_synchronize();
         // Now continue to move up to the left end stop with the collision detection enabled.
         enable_endstops(true);
         destination[axis] = 1.1 * axis_home_dir * max_length(axis);
-        plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder);
+        plan_buffer_line_destinationXYZE(feedrate/60);
         st_synchronize();
 		for (uint8_t i = 0; i < cnt; i++)
 		{
@@ -2244,9 +2358,9 @@ bool homeaxis(int axis, bool doError, uint8_t cnt)
 			endstops_hit_on_purpose();
 			enable_endstops(false);
 			current_position[axis] = 0;
-			plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
+			plan_set_position_curposXYZE();
 			destination[axis] = -10.f * axis_home_dir;
-			plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder);
+			plan_buffer_line_destinationXYZE(feedrate/60);
 			st_synchronize();
 			endstops_hit_on_purpose();
 			// Now move left up to the collision, this time with a repeatable velocity.
@@ -2257,7 +2371,7 @@ bool homeaxis(int axis, bool doError, uint8_t cnt)
 #else //TMC2130
 			feedrate = homing_feedrate[axis] / 2;
 #endif //TMC2130
-			plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder);
+			plan_buffer_line_destinationXYZE(feedrate/60);
 			st_synchronize();
 #ifdef TMC2130
 			uint16_t mscnt = tmc2130_rd_MSCNT(axis);
@@ -2291,10 +2405,10 @@ bool homeaxis(int axis, bool doError, uint8_t cnt)
         float dist = - axis_home_dir * 0.01f * 64;
 #endif //TMC2130
         current_position[axis] -= dist;
-        plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
+        plan_set_position_curposXYZE();
         current_position[axis] += dist;
         destination[axis] = current_position[axis];
-        plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], 0.5f*feedrate/60, active_extruder);
+        plan_buffer_line_destinationXYZE(0.5f*feedrate/60);
         st_synchronize();
 
    		feedrate = 0.0;
@@ -2306,37 +2420,25 @@ bool homeaxis(int axis, bool doError, uint8_t cnt)
 #endif	
         int axis_home_dir = home_dir(axis);
         current_position[axis] = 0;
-        plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
+        plan_set_position_curposXYZE();
         destination[axis] = 1.5 * max_length(axis) * axis_home_dir;
         feedrate = homing_feedrate[axis];
-        plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder);
+        plan_buffer_line_destinationXYZE(feedrate/60);
         st_synchronize();
 #ifdef TMC2130
-		if (READ(Z_TMC2130_DIAG) != 0) { //Z crash
-			FORCE_HIGH_POWER_END;
-			if (doError) kill(_T(MSG_BED_LEVELING_FAILED_POINT_LOW));
-            current_position[axis] = -5; //assume that nozzle crashed into bed
-            plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
-			return 0; 
-		}
+        check_Z_crash();
 #endif //TMC2130
         current_position[axis] = 0;
-        plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
+        plan_set_position_curposXYZE();
         destination[axis] = -home_retract_mm(axis) * axis_home_dir;
-        plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder);
+        plan_buffer_line_destinationXYZE(feedrate/60);
         st_synchronize();
         destination[axis] = 2*home_retract_mm(axis) * axis_home_dir;
         feedrate = homing_feedrate[axis]/2 ;
-        plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder);
+        plan_buffer_line_destinationXYZE(feedrate/60);
         st_synchronize();
 #ifdef TMC2130
-		if (READ(Z_TMC2130_DIAG) != 0) { //Z crash
-			FORCE_HIGH_POWER_END;
-			if (doError) kill(_T(MSG_BED_LEVELING_FAILED_POINT_LOW));
-            current_position[axis] = -5; //assume that nozzle crashed into bed
-            plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
-			return 0; 
-		}
+        check_Z_crash();
 #endif //TMC2130
         axis_is_at_home(axis);
         destination[axis] = current_position[axis];
@@ -2348,7 +2450,6 @@ bool homeaxis(int axis, bool doError, uint8_t cnt)
 #endif	
     }
     enable_endstops(endstops_enabled);
-    return 1;
 }
 
 /**/
@@ -2357,7 +2458,7 @@ void home_xy()
     set_destination_to_current();
     homeaxis(X_AXIS);
     homeaxis(Y_AXIS);
-    plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
+    plan_set_position_curposXYZE();
     endstops_hit_on_purpose();
 }
 
@@ -2380,7 +2481,7 @@ void refresh_cmd_timeout(void)
       retracted[active_extruder]=true;
       prepare_move();
       current_position[Z_AXIS]-=cs.retract_zlift;
-      plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
+      plan_set_position_curposXYZE();
       prepare_move();
       feedrate = oldFeedrate;
     } else if(!retracting && retracted[active_extruder]) {
@@ -2389,7 +2490,7 @@ void refresh_cmd_timeout(void)
       destination[Z_AXIS]=current_position[Z_AXIS];
       destination[E_AXIS]=current_position[E_AXIS];
       current_position[Z_AXIS]+=cs.retract_zlift;
-      plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
+      plan_set_position_curposXYZE();
       current_position[E_AXIS]-=(swapretract?(retract_length_swap+retract_recover_length_swap):(cs.retract_length+cs.retract_recover_length))*float(extrudemultiply)*0.01f;
       plan_set_e_position(current_position[E_AXIS]);
       float oldFeedrate = feedrate;
@@ -2513,6 +2614,95 @@ void force_high_power_mode(bool start_high_power_section) {
 }
 #endif //TMC2130
 
+void gcode_M105(uint8_t extruder)
+{
+#if defined(TEMP_0_PIN) && TEMP_0_PIN > -1
+    SERIAL_PROTOCOLPGM("T:");
+    SERIAL_PROTOCOL_F(degHotend(extruder),1);
+    SERIAL_PROTOCOLPGM(" /");
+    SERIAL_PROTOCOL_F(degTargetHotend(extruder),1);
+#if defined(TEMP_BED_PIN) && TEMP_BED_PIN > -1
+    SERIAL_PROTOCOLPGM(" B:");
+    SERIAL_PROTOCOL_F(degBed(),1);
+    SERIAL_PROTOCOLPGM(" /");
+    SERIAL_PROTOCOL_F(degTargetBed(),1);
+#endif //TEMP_BED_PIN
+    for (int8_t cur_extruder = 0; cur_extruder < EXTRUDERS; ++cur_extruder) {
+        SERIAL_PROTOCOLPGM(" T");
+        SERIAL_PROTOCOL(cur_extruder);
+        SERIAL_PROTOCOL(':');
+        SERIAL_PROTOCOL_F(degHotend(cur_extruder),1);
+        SERIAL_PROTOCOLPGM(" /");
+        SERIAL_PROTOCOL_F(degTargetHotend(cur_extruder),1);
+    }
+#else
+    SERIAL_ERROR_START;
+    SERIAL_ERRORLNRPGM(_i("No thermistors - no temperature"));////MSG_ERR_NO_THERMISTORS
+#endif
+
+    SERIAL_PROTOCOLPGM(" @:");
+#ifdef EXTRUDER_WATTS
+    SERIAL_PROTOCOL((EXTRUDER_WATTS * getHeaterPower(tmp_extruder))/127);
+    SERIAL_PROTOCOLPGM("W");
+#else
+    SERIAL_PROTOCOL(getHeaterPower(extruder));
+#endif
+
+    SERIAL_PROTOCOLPGM(" B@:");
+#ifdef BED_WATTS
+    SERIAL_PROTOCOL((BED_WATTS * getHeaterPower(-1))/127);
+    SERIAL_PROTOCOLPGM("W");
+#else
+    SERIAL_PROTOCOL(getHeaterPower(-1));
+#endif
+
+#ifdef PINDA_THERMISTOR
+    SERIAL_PROTOCOLPGM(" P:");
+    SERIAL_PROTOCOL_F(current_temperature_pinda,1);
+#endif //PINDA_THERMISTOR
+
+#ifdef AMBIENT_THERMISTOR
+    SERIAL_PROTOCOLPGM(" A:");
+    SERIAL_PROTOCOL_F(current_temperature_ambient,1);
+#endif //AMBIENT_THERMISTOR
+
+
+#ifdef SHOW_TEMP_ADC_VALUES
+    {
+        float raw = 0.0;
+#if defined(TEMP_BED_PIN) && TEMP_BED_PIN > -1
+        SERIAL_PROTOCOLPGM("    ADC B:");
+        SERIAL_PROTOCOL_F(degBed(),1);
+        SERIAL_PROTOCOLPGM("C->");
+        raw = rawBedTemp();
+        SERIAL_PROTOCOL_F(raw/OVERSAMPLENR,5);
+        SERIAL_PROTOCOLPGM(" Rb->");
+        SERIAL_PROTOCOL_F(100 * (1 + (PtA * (raw/OVERSAMPLENR)) + (PtB * sq((raw/OVERSAMPLENR)))), 5);
+        SERIAL_PROTOCOLPGM(" Rxb->");
+        SERIAL_PROTOCOL_F(raw, 5);
+#endif
+        for (int8_t cur_extruder = 0; cur_extruder < EXTRUDERS; ++cur_extruder) {
+            SERIAL_PROTOCOLPGM("  T");
+            SERIAL_PROTOCOL(cur_extruder);
+            SERIAL_PROTOCOLPGM(":");
+            SERIAL_PROTOCOL_F(degHotend(cur_extruder),1);
+            SERIAL_PROTOCOLPGM("C->");
+            raw = rawHotendTemp(cur_extruder);
+            SERIAL_PROTOCOL_F(raw/OVERSAMPLENR,5);
+            SERIAL_PROTOCOLPGM(" Rt");
+            SERIAL_PROTOCOL(cur_extruder);
+            SERIAL_PROTOCOLPGM("->");
+            SERIAL_PROTOCOL_F(100 * (1 + (PtA * (raw/OVERSAMPLENR)) + (PtB * sq((raw/OVERSAMPLENR)))), 5);
+            SERIAL_PROTOCOLPGM(" Rx");
+            SERIAL_PROTOCOL(cur_extruder);
+            SERIAL_PROTOCOLPGM("->");
+            SERIAL_PROTOCOL_F(raw, 5);
+        }
+    }
+#endif
+    SERIAL_PROTOCOLLN();
+}
+
 #ifdef TMC2130
 static void gcode_G28(bool home_x_axis, long home_x_value, bool home_y_axis, long home_y_value, bool home_z_axis, long home_z_value, bool calib, bool without_mbl)
 #else
@@ -2592,7 +2782,7 @@ static void gcode_G28(bool home_x_axis, long home_x_value, bool home_y_axis, lon
 
         int x_axis_home_dir = home_dir(X_AXIS);
 
-        plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
+        plan_set_position_curposXYZE();
         destination[X_AXIS] = 1.5 * max_length(X_AXIS) * x_axis_home_dir;destination[Y_AXIS] = 1.5 * max_length(Y_AXIS) * home_dir(Y_AXIS);
         feedrate = homing_feedrate[X_AXIS];
         if(homing_feedrate[Y_AXIS]<feedrate)
@@ -2602,15 +2792,15 @@ static void gcode_G28(bool home_x_axis, long home_x_value, bool home_y_axis, lon
         } else {
           feedrate *= sqrt(pow(max_length(X_AXIS) / max_length(Y_AXIS), 2) + 1);
         }
-        plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder);
+        plan_buffer_line_destinationXYZE(feedrate/60);
         st_synchronize();
 
         axis_is_at_home(X_AXIS);
         axis_is_at_home(Y_AXIS);
-        plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
+        plan_set_position_curposXYZE();
         destination[X_AXIS] = current_position[X_AXIS];
         destination[Y_AXIS] = current_position[Y_AXIS];
-        plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder);
+        plan_buffer_line_destinationXYZE(feedrate/60);
         feedrate = 0.0;
         st_synchronize();
         endstops_hit_on_purpose();
@@ -2674,14 +2864,14 @@ static void gcode_G28(bool home_x_axis, long home_x_value, bool home_y_axis, lon
               MYSERIAL.println(current_position[X_AXIS]);MYSERIAL.println(current_position[Y_AXIS]);
               MYSERIAL.println(current_position[Z_AXIS]);MYSERIAL.println(current_position[E_AXIS]);
 #endif
-              plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
+              plan_set_position_curposXYZE();
 #ifdef DEBUG_BUILD
               SERIAL_ECHOLNPGM("plan_buffer_line()");
               MYSERIAL.println(destination[X_AXIS]);MYSERIAL.println(destination[Y_AXIS]);
               MYSERIAL.println(destination[Z_AXIS]);MYSERIAL.println(destination[E_AXIS]);
               MYSERIAL.println(feedrate);MYSERIAL.println(active_extruder);
 #endif
-              plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate, active_extruder);
+              plan_buffer_line_destinationXYZE(feedrate);
               st_synchronize();
               current_position[X_AXIS] = destination[X_AXIS];
               current_position[Y_AXIS] = destination[Y_AXIS];
@@ -2700,8 +2890,8 @@ static void gcode_G28(bool home_x_axis, long home_x_value, bool home_y_axis, lon
             feedrate = XY_TRAVEL_SPEED/60;
             current_position[Z_AXIS] = 0;
 
-            plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
-            plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate, active_extruder);
+            plan_set_position_curposXYZE();
+            plan_buffer_line_destinationXYZE(feedrate);
             st_synchronize();
             current_position[X_AXIS] = destination[X_AXIS];
             current_position[Y_AXIS] = destination[Y_AXIS];
@@ -2717,10 +2907,10 @@ static void gcode_G28(bool home_x_axis, long home_x_value, bool home_y_axis, lon
               && (current_position[Y_AXIS]+Y_PROBE_OFFSET_FROM_EXTRUDER <= Y_MAX_POS)) {
 
               current_position[Z_AXIS] = 0;
-              plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
+              plan_set_position_curposXYZE();
               destination[Z_AXIS] = Z_RAISE_BEFORE_HOMING * home_dir(Z_AXIS) * (-1);    // Set destination away from bed
               feedrate = max_feedrate[Z_AXIS];
-              plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate, active_extruder);
+              plan_buffer_line_destinationXYZE(feedrate);
               st_synchronize();
 
               homeaxis(Z_AXIS);
@@ -2747,7 +2937,7 @@ static void gcode_G28(bool home_x_axis, long home_x_value, bool home_y_axis, lon
       // Set the planner and stepper routine positions.
       // At this point the mesh bed leveling and world2machine corrections are disabled and current_position
       // contains the machine coordinates.
-      plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
+      plan_set_position_curposXYZE();
 
       #ifdef ENDSTOPS_ONLY_FOR_HOMING
         enable_endstops(false);
@@ -2854,12 +3044,14 @@ bool gcode_M45(bool onlyZ, int8_t verbosity_level)
 	//set_destination_to_current();
 	int l_feedmultiply = setup_for_endstop_move();
 	lcd_display_message_fullscreen_P(_T(MSG_AUTO_HOME));
+  raise_z_above(MESH_HOME_Z_SEARCH);
+  st_synchronize();
 	home_xy();
 
 	enable_endstops(false);
 	current_position[X_AXIS] += 5;
 	current_position[Y_AXIS] += 5;
-	plan_buffer_line_curposXYZE(homing_feedrate[Z_AXIS] / 40, active_extruder);
+	plan_buffer_line_curposXYZE(homing_feedrate[Z_AXIS] / 40);
 	st_synchronize();
 
 	// Let the user move the Z axes up to the end stoppers.
@@ -2909,7 +3101,7 @@ bool gcode_M45(bool onlyZ, int8_t verbosity_level)
 			
 		bool endstops_enabled  = enable_endstops(false);
         current_position[Z_AXIS] -= 1; //move 1mm down with disabled endstop
-        plan_buffer_line_curposXYZE(homing_feedrate[Z_AXIS] / 40, active_extruder);
+        plan_buffer_line_curposXYZE(homing_feedrate[Z_AXIS] / 40);
         st_synchronize();
 
 		// Move the print head close to the bed.
@@ -2920,7 +3112,7 @@ bool gcode_M45(bool onlyZ, int8_t verbosity_level)
 		tmc2130_home_enter(Z_AXIS_MASK);
 #endif //TMC2130
 
-		plan_buffer_line_curposXYZE(homing_feedrate[Z_AXIS] / 40, active_extruder);
+		plan_buffer_line_curposXYZE(homing_feedrate[Z_AXIS] / 40);
 
 		st_synchronize();
 #ifdef TMC2130
@@ -2961,7 +3153,7 @@ bool gcode_M45(bool onlyZ, int8_t verbosity_level)
 				clean_up_after_endstop_move(l_feedmultiply);
 				// Print head up.
 				current_position[Z_AXIS] = MESH_HOME_Z_SEARCH;
-				plan_buffer_line_curposXYZE(homing_feedrate[Z_AXIS] / 40, active_extruder);
+				plan_buffer_line_curposXYZE(homing_feedrate[Z_AXIS] / 40);
 				st_synchronize();
 //#ifndef NEW_XYZCAL
 				if (result >= 0)
@@ -2981,7 +3173,7 @@ bool gcode_M45(bool onlyZ, int8_t verbosity_level)
 					clean_up_after_endstop_move(l_feedmultiply);
 					// Print head up.
 					current_position[Z_AXIS] = MESH_HOME_Z_SEARCH;
-					plan_buffer_line_curposXYZE(homing_feedrate[Z_AXIS] / 40, active_extruder);
+					plan_buffer_line_curposXYZE(homing_feedrate[Z_AXIS] / 40);
 					st_synchronize();
 					// if (result >= 0) babystep_apply();					
 					#endif //HEATBED_V2
@@ -3043,9 +3235,16 @@ void gcode_M114()
 	SERIAL_PROTOCOLPGM(" E:");
 	SERIAL_PROTOCOL(float(st_get_position(E_AXIS)) / cs.axis_steps_per_unit[E_AXIS]);
 
-	SERIAL_PROTOCOLLN("");
+	SERIAL_PROTOCOLLN();
 }
 
+#if (defined(FANCHECK) && (((defined(TACH_0) && (TACH_0 >-1)) || (defined(TACH_1) && (TACH_1 > -1)))))
+void gcode_M123()
+{
+  printf_P(_N("E0:%d RPM PRN1:%d RPM E0@:%u PRN1@:%d\n"), 60*fan_speed[active_extruder], 60*fan_speed[1], newFanSpeed, fanSpeed);
+}
+#endif //FANCHECK and TACH_0 or TACH_1
+
 //! extracted code to compute z_shift for M600 in case of filament change operation 
 //! requested from fsensors.
 //! The function ensures, that the printhead lifts to at least 25mm above the heat bed
@@ -3094,18 +3293,18 @@ static void gcode_M600(bool automatic, float x_position, float y_position, float
 
     //Retract E
     current_position[E_AXIS] += e_shift;
-    plan_buffer_line_curposXYZE(FILAMENTCHANGE_RFEED, active_extruder);
+    plan_buffer_line_curposXYZE(FILAMENTCHANGE_RFEED);
     st_synchronize();
 
     //Lift Z
     current_position[Z_AXIS] += z_shift;
-    plan_buffer_line_curposXYZE(FILAMENTCHANGE_ZFEED, active_extruder);
+    plan_buffer_line_curposXYZE(FILAMENTCHANGE_ZFEED);
     st_synchronize();
 
     //Move XY to side
     current_position[X_AXIS] = x_position;
     current_position[Y_AXIS] = y_position;
-    plan_buffer_line_curposXYZE(FILAMENTCHANGE_XYFEED, active_extruder);
+    plan_buffer_line_curposXYZE(FILAMENTCHANGE_XYFEED);
     st_synchronize();
 
     //Beep, manage nozzle heater and wait for user to start unload filament
@@ -3127,10 +3326,9 @@ static void gcode_M600(bool automatic, float x_position, float y_position, float
         if (lcd_change_fil_state == 0)
         {
 			lcd_clear();
-			lcd_set_cursor(0, 2);
-			lcd_puts_P(_T(MSG_PLEASE_WAIT));
+			lcd_puts_at_P(0, 2, _T(MSG_PLEASE_WAIT));
 			current_position[X_AXIS] -= 100;
-			plan_buffer_line_curposXYZE(FILAMENTCHANGE_XYFEED, active_extruder);
+			plan_buffer_line_curposXYZE(FILAMENTCHANGE_XYFEED);
 			st_synchronize();
 			lcd_show_fullscreen_message_and_wait_P(_i("Please open idler and remove filament manually."));////MSG_CHECK_IDLER c=20 r=4
         }
@@ -3144,8 +3342,7 @@ static void gcode_M600(bool automatic, float x_position, float y_position, float
             if (saved_printing) {
 
                 lcd_clear();
-                lcd_set_cursor(0, 2);
-                lcd_puts_P(_T(MSG_PLEASE_WAIT));
+                lcd_puts_at_P(0, 2, _T(MSG_PLEASE_WAIT));
 
                 mmu_command(MmuCmd::R0);
                 manage_response(false, false);
@@ -3167,7 +3364,7 @@ static void gcode_M600(bool automatic, float x_position, float y_position, float
     if (!automatic)
     {
         current_position[E_AXIS] += FILAMENTCHANGE_RECFEED;
-        plan_buffer_line_curposXYZE(FILAMENTCHANGE_EXFEED, active_extruder);
+        plan_buffer_line_curposXYZE(FILAMENTCHANGE_EXFEED);
     }
 
     //Move XY back
@@ -3225,12 +3422,12 @@ void gcode_M701()
 
 		lcd_setstatuspgm(_T(MSG_LOADING_FILAMENT));
 		current_position[E_AXIS] += 40;
-		plan_buffer_line_curposXYZE(400 / 60, active_extruder); //fast sequence
+		plan_buffer_line_curposXYZE(400 / 60); //fast sequence
 		st_synchronize();
 
         raise_z_above(MIN_Z_FOR_LOAD, false);
 		current_position[E_AXIS] += 30;
-		plan_buffer_line_curposXYZE(400 / 60, active_extruder); //fast sequence
+		plan_buffer_line_curposXYZE(400 / 60); //fast sequence
 		
 		load_filament_final_feed(); //slow sequence
 		st_synchronize();
@@ -3266,47 +3463,35 @@ void gcode_M701()
  *
  * Typical format of S/N is:CZPX0917X003XC13518
  *
- * Command operates only in farm mode, if not in farm mode, "Not in farm mode." is written to MYSERIAL.
- *
  * Send command ;S to serial port 0 to retrieve serial number stored in 32U2 processor,
- * reply is transmitted to serial port 1 character by character.
+ * reply is stored in *SN.
  * Operation takes typically 23 ms. If the retransmit is not finished until 100 ms,
- * it is interrupted, so less, or no characters are retransmitted, only newline character is send
- * in any case.
+ * it is interrupted, so less, or no characters are retransmitted, the function returns false
+ * The command will fail if the 32U2 processor is unpowered via USB since it is isolated from the rest of the electronics.
+ * In that case the value that is stored in the EEPROM should be used instead.
+ *
+ * @return 1 on success
+ * @return 0 on general failure
  */
-static void gcode_PRUSA_SN()
+static bool get_PRUSA_SN(char* SN)
 {
-    if (farm_mode) {
-        selectedSerialPort = 0;
-        putchar(';');
-        putchar('S');
-        int numbersRead = 0;
-        ShortTimer timeout;
-        timeout.start();
-
-        while (numbersRead < 19) {
-            while (MSerial.available() > 0) {
-                uint8_t serial_char = MSerial.read();
-                selectedSerialPort = 1;
-                putchar(serial_char);
-                numbersRead++;
-                selectedSerialPort = 0;
-            }
-            if (timeout.expired(100u)) break;
-        }
-        selectedSerialPort = 1;
-        putchar('\n');
-#if 0
-        for (int b = 0; b < 3; b++) {
-            _tone(BEEPER, 110);
-            _delay(50);
-            _noTone(BEEPER);
-            _delay(50);
+    uint8_t selectedSerialPort_bak = selectedSerialPort;
+    selectedSerialPort = 0;
+    SERIAL_ECHOLNRPGM(PSTR(";S"));
+    uint8_t numbersRead = 0;
+    ShortTimer timeout;
+    timeout.start();
+
+    while (numbersRead < 19) {
+        if (MSerial.available() > 0) {
+            SN[numbersRead] = MSerial.read();
+            numbersRead++;
         }
-#endif
-    } else {
-        puts_P(_N("Not in farm mode."));
+        if (timeout.expired(100u)) break;
     }
+    SN[numbersRead] = 0;
+    selectedSerialPort = selectedSerialPort_bak;
+    return (numbersRead == 19);
 }
 //! Detection of faulty RAMBo 1.1b boards equipped with bigger capacitors
 //! at the TACH_1 pin, which causes bad detection of print fan speed.
@@ -3396,11 +3581,29 @@ static void gcode_G92()
             current_position[E_AXIS] = values[E_AXIS];
 
         // Set all at once
-        plan_set_position(current_position[X_AXIS], current_position[Y_AXIS],
-                          current_position[Z_AXIS], current_position[E_AXIS]);
+        plan_set_position_curposXYZE();
     }
 }
 
+#ifdef EXTENDED_CAPABILITIES_REPORT
+
+static void cap_line(const char* name, bool ena = false) {
+    printf_P(PSTR("Cap:%S:%c\n"), name, (char)ena + '0');
+}
+
+static void extended_capabilities_report()
+{
+    // AUTOREPORT_TEMP (M155)
+    cap_line(PSTR("AUTOREPORT_TEMP"), ENABLED(AUTO_REPORT));
+#if (defined(FANCHECK) && (((defined(TACH_0) && (TACH_0 >-1)) || (defined(TACH_1) && (TACH_1 > -1)))))
+    // AUTOREPORT_FANS (M123)
+    cap_line(PSTR("AUTOREPORT_FANS"), ENABLED(AUTO_REPORT));
+#endif //FANCHECK and TACH_0 or TACH_1
+    // AUTOREPORT_POSITION (M114)
+    cap_line(PSTR("AUTOREPORT_POSITION"), ENABLED(AUTO_REPORT));
+    //@todo Update RepRap cap
+}
+#endif //EXTENDED_CAPABILITIES_REPORT
 
 #ifdef BACKLASH_X
 extern uint8_t st_backlash_x;
@@ -3488,12 +3691,14 @@ extern uint8_t st_backlash_y;
 //!@n M115 - Capabilities string
 //!@n M117 - display message
 //!@n M119 - Output Endstop status to serial port
+//!@n M123 - Tachometer value
 //!@n M126 - Solenoid Air Valve Open (BariCUDA support by jmil)
 //!@n M127 - Solenoid Air Valve Closed (BariCUDA vent to atmospheric pressure by jmil)
 //!@n M128 - EtoP Open (BariCUDA EtoP = electricity to air pressure transducer by jmil)
 //!@n M129 - EtoP Closed (BariCUDA EtoP = electricity to air pressure transducer by jmil)
 //!@n M140 - Set bed target temp
 //!@n M150 - Set BlinkM Color Output R: Red<0-255> U(!): Green<0-255> B: Blue<0-255> over i2c, G for green does not work.
+//!@n M155 - Automatically send temperatures, fan speeds, position
 //!@n M190 - Sxxx Wait for bed current temp to reach target temp. Waits only when heating
 //!          Rxxx Wait for bed current temp to reach target temp. Waits when heating and cooling
 //!@n M200 D<millimeters>- set filament diameter and set E axis units to cubic millimeters (use S0 to set back to millimeters).
@@ -3531,6 +3736,7 @@ extern uint8_t st_backlash_y;
 //!@n M503 - print the current settings (from memory not from EEPROM)
 //!@n M509 - force language selection on next restart
 //!@n M540 - Use S[0|1] to enable or disable the stop SD card print on endstop hit (requires ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED)
+//!@n M552 - Set IP address
 //!@n M600 - Pause for filament change X[pos] Y[pos] Z[relative lift] E[initial retract] L[later retract distance for removal]
 //!@n M605 - Set dual x-carriage movement mode: S<mode> [ X<duplication x-offset> R<duplication temp offset> ]
 //!@n M860 - Wait for PINDA thermistor to reach target temperature.
@@ -3559,14 +3765,12 @@ There are reasons why some G Codes aren't in numerical order.
 void process_commands()
 {
 #ifdef FANCHECK
-    if(fan_check_error){
-        if(fan_check_error == EFCE_DETECTED){
-            fan_check_error = EFCE_REPORTED;
-            // SERIAL_PROTOCOLLNRPGM(MSG_OCTOPRINT_PAUSED);
-            lcd_pause_print();
-        } // otherwise it has already been reported, so just ignore further processing
-        return; //ignore usb stream. It is reenabled by selecting resume from the lcd.
-    }
+	if(fan_check_error == EFCE_DETECTED){
+		fan_check_error = EFCE_REPORTED;
+		// SERIAL_PROTOCOLLNRPGM(MSG_OCTOPRINT_PAUSED);
+		lcd_pause_print();
+		cmdqueue_serial_disabled = true;
+	}
 #endif
 
 	if (!buflen) return; //empty command
@@ -3616,7 +3820,7 @@ void process_commands()
     - TMC_SET_STEP
     - TMC_SET_CHOP
  */
-  if (code_seen("M117")) { //moved to highest priority place to be able to to print strings which includes "G", "PRUSA" and "^"
+  if (code_seen_P(PSTR("M117"))) { //moved to highest priority place to be able to to print strings which includes "G", "PRUSA" and "^"
 	  starpos = (strchr(strchr_pointer + 5, '*'));
 	  if (starpos != NULL)
 		  *(starpos) = '\0';
@@ -3629,7 +3833,7 @@ void process_commands()
 
     // ### CRASH_DETECTED - TMC2130
     // ---------------------------------
-	  if(code_seen("CRASH_DETECTED"))
+	  if(code_seen_P(PSTR("CRASH_DETECTED")))
 	  {
 		  uint8_t mask = 0;
 		  if (code_seen('X')) mask |= X_AXIS_MASK;
@@ -3639,12 +3843,12 @@ void process_commands()
 
     // ### CRASH_RECOVER - TMC2130
     // ----------------------------------
-	  else if(code_seen("CRASH_RECOVER"))
+	  else if(code_seen_P(PSTR("CRASH_RECOVER")))
 		  crashdet_recover();
 
     // ### CRASH_CANCEL - TMC2130
     // ----------------------------------
-	  else if(code_seen("CRASH_CANCEL"))
+	  else if(code_seen_P(PSTR("CRASH_CANCEL")))
 		  crashdet_cancel();
 	}
 	else if (strncmp_P(CMDBUFFER_CURRENT_STRING, PSTR("TMC_"), 4) == 0)
@@ -3730,7 +3934,7 @@ void process_commands()
 	}
 #endif //BACKLASH_Y
 #endif //TMC2130
-  else if(code_seen("PRUSA")){ 
+  else if(code_seen_P(PSTR("PRUSA"))){ 
     /*!
     ---------------------------------------------------------------------------------
     ### PRUSA - Internal command set <a href="https://reprap.org/wiki/G-code#G98:_Activate_farm_mode">G98: Activate farm mode - Notes</a>
@@ -3763,58 +3967,43 @@ void process_commands()
     */
 
 
-		if (code_seen("Ping")) {  // PRUSA Ping
+		if (code_seen_P(PSTR("Ping"))) {  // PRUSA Ping
 			if (farm_mode) {
 				PingTime = _millis();
-				//MYSERIAL.print(farm_no); MYSERIAL.println(": OK");
 			}	  
 		}
-		else if (code_seen("PRN")) { // PRUSA PRN
+		else if (code_seen_P(PSTR("PRN"))) { // PRUSA PRN
 		  printf_P(_N("%d"), status_number);
 
-        } else if( code_seen("FANPINTST") ){
+        } else if( code_seen_P(PSTR("FANPINTST"))){
             gcode_PRUSA_BadRAMBoFanTest();
-        }else if (code_seen("FAN")) { // PRUSA FAN
+        }else if (code_seen_P(PSTR("FAN"))) { // PRUSA FAN
 			printf_P(_N("E0:%d RPM\nPRN0:%d RPM\n"), 60*fan_speed[0], 60*fan_speed[1]);
-		}else if (code_seen("fn")) { // PRUSA fn
-		  if (farm_mode) {
-			printf_P(_N("%d"), farm_no);
-		  }
-		  else {
-			  puts_P(_N("Not in farm mode."));
-		  }
-		  
 		}
-		else if (code_seen("thx")) // PRUSA thx
+		else if (code_seen_P(PSTR("thx"))) // PRUSA thx
 		{
 			no_response = false;
 		}	
-		else if (code_seen("uvlo")) // PRUSA uvlo
+		else if (code_seen_P(PSTR("uvlo"))) // PRUSA uvlo
 		{
                eeprom_update_byte((uint8_t*)EEPROM_UVLO,0); 
                enquecommand_P(PSTR("M24")); 
 		}	
-		else if (code_seen("MMURES")) // PRUSA MMURES
+		else if (code_seen_P(PSTR("MMURES"))) // PRUSA MMURES
 		{
 			mmu_reset();
 		}
-		else if (code_seen("RESET")) { // PRUSA RESET
-            // careful!
-            if (farm_mode) {
-#if (defined(WATCHDOG) && (MOTHERBOARD == BOARD_EINSY_1_0a))
-                boot_app_magic = BOOT_APP_MAGIC;
-                boot_app_flags = BOOT_APP_FLG_RUN;
-				wdt_enable(WDTO_15MS);
-				cli();
-				while(1);
-#else //WATCHDOG
-                asm volatile("jmp 0x3E000");
-#endif //WATCHDOG
-            }
-            else {
-                MYSERIAL.println("Not in farm mode.");
-            }
-		}else if (code_seen("fv")) { // PRUSA fv
+		else if (code_seen_P(PSTR("RESET"))) { // PRUSA RESET
+#ifdef WATCHDOG
+#if defined(W25X20CL) && defined(BOOTAPP)
+            boot_app_magic = BOOT_APP_MAGIC;
+            boot_app_flags = BOOT_APP_FLG_RUN;
+#endif //defined(W25X20CL) && defined(BOOTAPP)
+            softReset();
+#elif defined(BOOTAPP) //this is a safety precaution. This is because the new bootloader turns off the heaters, but the old one doesn't. The watchdog should be used most of the time.
+            asm volatile("jmp 0x3E000");
+#endif
+		}else if (code_seen_P("fv")) { // PRUSA fv
         // get file version
         #ifdef SDSUPPORT
         card.openFile(strchr_pointer + 3,true);
@@ -3829,38 +4018,43 @@ void process_commands()
 
         #endif // SDSUPPORT
 
-    } else if (code_seen("M28")) { // PRUSA M28
+    } else if (code_seen_P(PSTR("M28"))) { // PRUSA M28
         trace();
         prusa_sd_card_upload = true;
         card.openFile(strchr_pointer+4,false);
 
-	} else if (code_seen("SN")) { // PRUSA SN
-        gcode_PRUSA_SN();
+	} else if (code_seen_P(PSTR("SN"))) { // PRUSA SN
+        char SN[20];
+        eeprom_read_block(SN, (uint8_t*)EEPROM_PRUSA_SN, 20);
+        if (SN[19])
+            puts_P(PSTR("SN invalid"));
+        else
+            puts(SN);
 
-	} else if(code_seen("Fir")){ // PRUSA Fir
+	} else if(code_seen_P(PSTR("Fir"))){ // PRUSA Fir
 
       SERIAL_PROTOCOLLN(FW_VERSION_FULL);
 
-    } else if(code_seen("Rev")){ // PRUSA Rev
+    } else if(code_seen_P(PSTR("Rev"))){ // PRUSA Rev
 
       SERIAL_PROTOCOLLN(FILAMENT_SIZE "-" ELECTRONICS "-" NOZZLE_TYPE );
 
-    } else if(code_seen("Lang")) { // PRUSA Lang
+    } else if(code_seen_P(PSTR("Lang"))) { // PRUSA Lang
 	  lang_reset();
 
-	} else if(code_seen("Lz")) { // PRUSA Lz
+	} else if(code_seen_P(PSTR("Lz"))) { // PRUSA Lz
       eeprom_update_word(reinterpret_cast<uint16_t *>(&(EEPROM_Sheets_base->s[(eeprom_read_byte(&(EEPROM_Sheets_base->active_sheet)))].z_offset)),0);
 
-	} else if(code_seen("Beat")) { // PRUSA Beat
+	} else if(code_seen_P(PSTR("Beat"))) { // PRUSA Beat
         // Kick farm link timer
         kicktime = _millis();
 
-    } else if(code_seen("FR")) { // PRUSA FR
+    } else if(code_seen_P(PSTR("FR"))) { // PRUSA FR
         // Factory full reset
         factory_reset(0);
-    } else if(code_seen("MBL")) { // PRUSA MBL
+    } else if(code_seen_P(PSTR("MBL"))) { // PRUSA MBL
         // Change the MBL status without changing the logical Z position.
-        if(code_seen("V")) {
+        if(code_seen('V')) {
             bool value = code_value_short();
             st_synchronize();
             if(value != mbl.active) {
@@ -3885,14 +4079,14 @@ eeprom_update_byte((uint8_t*)EEPROM_CHECK_MODE,0xFF);
 eeprom_update_byte((uint8_t*)EEPROM_NOZZLE_DIAMETER,0xFF);
 eeprom_update_word((uint16_t*)EEPROM_NOZZLE_DIAMETER_uM,0xFFFF);
 */
-    } else if (code_seen("nozzle")) { // PRUSA nozzle
+    } else if (code_seen_P(PSTR("nozzle"))) { // PRUSA nozzle
           uint16_t nDiameter;
           if(code_seen('D'))
                {
                nDiameter=(uint16_t)(code_value()*1000.0+0.5); // [,um]
                nozzle_diameter_check(nDiameter);
                }
-          else if(code_seen("set") && farm_mode)
+          else if(code_seen_P(PSTR("set")) && farm_mode)
                {
                strchr_pointer++;                  // skip 1st char (~ 's')
                strchr_pointer++;                  // skip 2nd char (~ 'e')
@@ -4274,6 +4468,14 @@ if(eSoundMode!=e_SOUND_MODE_SILENT)
       #endif //FWRETRACT
     
 
+    /*!
+	### G21 - Sets Units to Millimters <a href="https://reprap.org/wiki/G-code#G21:_Set_Units_to_Millimeters">G21: Set Units to Millimeters</a>
+	Units are in millimeters. Prusa doesn't support inches.
+    */
+    case 21: 
+      break; //Doing nothing. This is just to prevent serial UNKOWN warnings.
+    
+
     /*!
     ### G28 - Home all Axes one at a time <a href="https://reprap.org/wiki/G-code#G28:_Move_to_Origin_.28Home.29">G28: Move to Origin (Home)</a>
     Using `G28` without any parameters will perfom homing of all axes AND mesh bed leveling, while `G28 W` will just home all axes (no mesh bed leveling).
@@ -4350,7 +4552,7 @@ if(eSoundMode!=e_SOUND_MODE_SILENT)
             current_position[X_AXIS] = uncorrected_position.x;
             current_position[Y_AXIS] = uncorrected_position.y;
             current_position[Z_AXIS] = uncorrected_position.z;
-            plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
+            plan_set_position_curposXYZE();
             int l_feedmultiply = setup_for_endstop_move();
 
             feedrate = homing_feedrate[Z_AXIS];
@@ -4464,7 +4666,7 @@ if(eSoundMode!=e_SOUND_MODE_SILENT)
 
             apply_rotation_xyz(plan_bed_level_matrix, x_tmp, y_tmp, z_tmp);         //Apply the correction sending the probe offset
             current_position[Z_AXIS] = z_tmp - real_z + current_position[Z_AXIS];   //The difference is added to current position and sent to planner.
-            plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
+            plan_set_position_curposXYZE();
         }
         break;
 #ifndef Z_PROBE_SLED
@@ -4552,11 +4754,15 @@ if(eSoundMode!=e_SOUND_MODE_SILENT)
   /*!
   ### G76 - PINDA probe temperature calibration <a href="https://reprap.org/wiki/G-code#G76:_PINDA_probe_temperature_calibration">G76: PINDA probe temperature calibration</a>
   This G-code is used to calibrate the temperature drift of the PINDA (inductive Sensor).
-  
+
   The PINDAv2 sensor has a built-in thermistor which has the advantage that the calibration can be done once for all materials.
   
   The Original i3 Prusa MK2/s uses PINDAv1 and this calibration improves the temperature drift, but not as good as the PINDAv2.
 
+  superPINDA sensor has internal temperature compensation and no thermistor output. There is no point of doing temperature calibration in such case.
+  If PINDA_THERMISTOR and SUPERPINDA_SUPPORT is defined during compilation, calibration is skipped with serial message "No PINDA thermistor".
+  This can be caused also if PINDA thermistor connection is broken or PINDA temperature is lower than PINDA_MINTEMP.
+
   #### Example
   
   ```
@@ -4571,154 +4777,155 @@ if(eSoundMode!=e_SOUND_MODE_SILENT)
   case 76: 
 	{
 #ifdef PINDA_THERMISTOR
-		if (true)
-		{
+        if (!has_temperature_compensation())
+        {
+            SERIAL_ECHOLNPGM("No PINDA thermistor");
+            break;
+        }
 
-			if (calibration_status() >= CALIBRATION_STATUS_XYZ_CALIBRATION) {
-				//we need to know accurate position of first calibration point
-				//if xyz calibration was not performed yet, interrupt temperature calibration and inform user that xyz cal. is needed
-				lcd_show_fullscreen_message_and_wait_P(_i("Please run XYZ calibration first."));
-				break;
-			}
-			
-			if (!(axis_known_position[X_AXIS] && axis_known_position[Y_AXIS] && axis_known_position[Z_AXIS]))
-			{
-				// We don't know where we are! HOME!
-				// Push the commands to the front of the message queue in the reverse order!
-				// There shall be always enough space reserved for these commands.
-				repeatcommand_front(); // repeat G76 with all its parameters
-				enquecommand_front_P((PSTR("G28 W0")));
-				break;
-			}
-			lcd_show_fullscreen_message_and_wait_P(_i("Stable ambient temperature 21-26C is needed a rigid stand is required."));////MSG_TEMP_CAL_WARNING c=20 r=4
-			bool result = lcd_show_fullscreen_message_yes_no_and_wait_P(_T(MSG_STEEL_SHEET_CHECK), false, false);
-			
-			if (result)
-			{
-				current_position[Z_AXIS] = MESH_HOME_Z_SEARCH;
-				plan_buffer_line_curposXYZE(3000 / 60, active_extruder);
-				current_position[Z_AXIS] = 50;
-				current_position[Y_AXIS] = 180;
-				plan_buffer_line_curposXYZE(3000 / 60, active_extruder);
-				st_synchronize();
-				lcd_show_fullscreen_message_and_wait_P(_T(MSG_REMOVE_STEEL_SHEET));
-				current_position[Y_AXIS] = pgm_read_float(bed_ref_points_4 + 1);
-				current_position[X_AXIS] = pgm_read_float(bed_ref_points_4);
-				plan_buffer_line_curposXYZE(3000 / 60, active_extruder);
-				st_synchronize();
-				gcode_G28(false, false, true);
+        if (calibration_status() >= CALIBRATION_STATUS_XYZ_CALIBRATION) {
+            //we need to know accurate position of first calibration point
+            //if xyz calibration was not performed yet, interrupt temperature calibration and inform user that xyz cal. is needed
+            lcd_show_fullscreen_message_and_wait_P(_i("Please run XYZ calibration first."));
+            break;
+        }
 
-			}
-			if ((current_temperature_pinda > 35) && (farm_mode == false)) {
-				//waiting for PIDNA probe to cool down in case that we are not in farm mode
-				current_position[Z_AXIS] = 100;
-				plan_buffer_line_curposXYZE(3000 / 60, active_extruder);
-				if (lcd_wait_for_pinda(35) == false) { //waiting for PINDA probe to cool, if this takes more then time expected, temp. cal. fails
-					lcd_temp_cal_show_result(false);
-					break;
-				}
-			}
-			lcd_update_enable(true);
-			KEEPALIVE_STATE(NOT_BUSY); //no need to print busy messages as we print current temperatures periodicaly
-			SERIAL_ECHOLNPGM("PINDA probe calibration start");
+        if (!(axis_known_position[X_AXIS] && axis_known_position[Y_AXIS] && axis_known_position[Z_AXIS]))
+        {
+            // We don't know where we are! HOME!
+            // Push the commands to the front of the message queue in the reverse order!
+            // There shall be always enough space reserved for these commands.
+            repeatcommand_front(); // repeat G76 with all its parameters
+            enquecommand_front_P(G28W0);
+            break;
+        }
+        lcd_show_fullscreen_message_and_wait_P(_i("Stable ambient temperature 21-26C is needed a rigid stand is required."));////MSG_TEMP_CAL_WARNING c=20 r=4
+        bool result = lcd_show_fullscreen_message_yes_no_and_wait_P(_T(MSG_STEEL_SHEET_CHECK), false, false);
 
-			float zero_z;
-			int z_shift = 0; //unit: steps
-			float start_temp = 5 * (int)(current_temperature_pinda / 5);
-			if (start_temp < 35) start_temp = 35;
-			if (start_temp < current_temperature_pinda) start_temp += 5;
-			printf_P(_N("start temperature: %.1f\n"), start_temp);
+        if (result)
+        {
+            current_position[Z_AXIS] = MESH_HOME_Z_SEARCH;
+            plan_buffer_line_curposXYZE(3000 / 60);
+            current_position[Z_AXIS] = 50;
+            current_position[Y_AXIS] = 180;
+            plan_buffer_line_curposXYZE(3000 / 60);
+            st_synchronize();
+            lcd_show_fullscreen_message_and_wait_P(_T(MSG_REMOVE_STEEL_SHEET));
+            current_position[Y_AXIS] = pgm_read_float(bed_ref_points_4 + 1);
+            current_position[X_AXIS] = pgm_read_float(bed_ref_points_4);
+            plan_buffer_line_curposXYZE(3000 / 60);
+            st_synchronize();
+            gcode_G28(false, false, true);
+
+        }
+        if ((current_temperature_pinda > 35) && (farm_mode == false)) {
+            //waiting for PIDNA probe to cool down in case that we are not in farm mode
+            current_position[Z_AXIS] = 100;
+            plan_buffer_line_curposXYZE(3000 / 60);
+            if (lcd_wait_for_pinda(35) == false) { //waiting for PINDA probe to cool, if this takes more then time expected, temp. cal. fails
+                lcd_temp_cal_show_result(false);
+                break;
+            }
+        }
+        lcd_update_enable(true);
+        KEEPALIVE_STATE(NOT_BUSY); //no need to print busy messages as we print current temperatures periodicaly
+        SERIAL_ECHOLNPGM("PINDA probe calibration start");
+
+        float zero_z;
+        int z_shift = 0; //unit: steps
+        float start_temp = 5 * (int)(current_temperature_pinda / 5);
+        if (start_temp < 35) start_temp = 35;
+        if (start_temp < current_temperature_pinda) start_temp += 5;
+        printf_P(_N("start temperature: %.1f\n"), start_temp);
 
 //			setTargetHotend(200, 0);
-			setTargetBed(70 + (start_temp - 30));
+        setTargetBed(70 + (start_temp - 30));
 
-			custom_message_type = CustomMsg::TempCal;
-			custom_message_state = 1;
-			lcd_setstatuspgm(_T(MSG_TEMP_CALIBRATION));
-			current_position[Z_AXIS] = MESH_HOME_Z_SEARCH;
-			plan_buffer_line_curposXYZE(3000 / 60, active_extruder);
-			current_position[X_AXIS] = PINDA_PREHEAT_X;
-			current_position[Y_AXIS] = PINDA_PREHEAT_Y;
-			plan_buffer_line_curposXYZE(3000 / 60, active_extruder);
-			current_position[Z_AXIS] = PINDA_PREHEAT_Z;
-			plan_buffer_line_curposXYZE(3000 / 60, active_extruder);
-			st_synchronize();
+        custom_message_type = CustomMsg::TempCal;
+        custom_message_state = 1;
+        lcd_setstatuspgm(_T(MSG_TEMP_CALIBRATION));
+        current_position[Z_AXIS] = MESH_HOME_Z_SEARCH;
+        plan_buffer_line_curposXYZE(3000 / 60);
+        current_position[X_AXIS] = PINDA_PREHEAT_X;
+        current_position[Y_AXIS] = PINDA_PREHEAT_Y;
+        plan_buffer_line_curposXYZE(3000 / 60);
+        current_position[Z_AXIS] = PINDA_PREHEAT_Z;
+        plan_buffer_line_curposXYZE(3000 / 60);
+        st_synchronize();
 
-			while (current_temperature_pinda < start_temp)
-			{
-				delay_keep_alive(1000);
-				serialecho_temperatures();
-			}
+        while (current_temperature_pinda < start_temp)
+        {
+            delay_keep_alive(1000);
+            serialecho_temperatures();
+        }
 
-			eeprom_update_byte((uint8_t*)EEPROM_CALIBRATION_STATUS_PINDA, 0); //invalidate temp. calibration in case that in will be aborted during the calibration process 
+        eeprom_update_byte((uint8_t*)EEPROM_CALIBRATION_STATUS_PINDA, 0); //invalidate temp. calibration in case that in will be aborted during the calibration process
 
-			current_position[Z_AXIS] = MESH_HOME_Z_SEARCH;
-			plan_buffer_line_curposXYZE(3000 / 60, active_extruder);
-			current_position[X_AXIS] = pgm_read_float(bed_ref_points_4);
-			current_position[Y_AXIS] = pgm_read_float(bed_ref_points_4 + 1);
-			plan_buffer_line_curposXYZE(3000 / 60, active_extruder);
-			st_synchronize();
+        current_position[Z_AXIS] = MESH_HOME_Z_SEARCH;
+        plan_buffer_line_curposXYZE(3000 / 60);
+        current_position[X_AXIS] = pgm_read_float(bed_ref_points_4);
+        current_position[Y_AXIS] = pgm_read_float(bed_ref_points_4 + 1);
+        plan_buffer_line_curposXYZE(3000 / 60);
+        st_synchronize();
 
-			bool find_z_result = find_bed_induction_sensor_point_z(-1.f);
-			if (find_z_result == false) {
-				lcd_temp_cal_show_result(find_z_result);
-				break;
-			}
-			zero_z = current_position[Z_AXIS];
+        bool find_z_result = find_bed_induction_sensor_point_z(-1.f);
+        if (find_z_result == false) {
+            lcd_temp_cal_show_result(find_z_result);
+            break;
+        }
+        zero_z = current_position[Z_AXIS];
 
-			printf_P(_N("\nZERO: %.3f\n"), current_position[Z_AXIS]);
+        printf_P(_N("\nZERO: %.3f\n"), current_position[Z_AXIS]);
 
-			int i = -1; for (; i < 5; i++)
-			{
-				float temp = (40 + i * 5);
-				printf_P(_N("\nStep: %d/6 (skipped)\nPINDA temperature: %d Z shift (mm):0\n"), i + 2, (40 + i*5));
-				if (i >= 0) EEPROM_save_B(EEPROM_PROBE_TEMP_SHIFT + i * 2, &z_shift);
-				if (start_temp <= temp) break;
-			}
+        int i = -1; for (; i < 5; i++)
+        {
+            float temp = (40 + i * 5);
+            printf_P(_N("\nStep: %d/6 (skipped)\nPINDA temperature: %d Z shift (mm):0\n"), i + 2, (40 + i*5));
+            if (i >= 0) EEPROM_save_B(EEPROM_PROBE_TEMP_SHIFT + i * 2, &z_shift);
+            if (start_temp <= temp) break;
+        }
 
-			for (i++; i < 5; i++)
-			{
-				float temp = (40 + i * 5);
-				printf_P(_N("\nStep: %d/6\n"), i + 2);
-				custom_message_state = i + 2;
-				setTargetBed(50 + 10 * (temp - 30) / 5);
+        for (i++; i < 5; i++)
+        {
+            float temp = (40 + i * 5);
+            printf_P(_N("\nStep: %d/6\n"), i + 2);
+            custom_message_state = i + 2;
+            setTargetBed(50 + 10 * (temp - 30) / 5);
 //				setTargetHotend(255, 0);
-				current_position[Z_AXIS] = MESH_HOME_Z_SEARCH;
-				plan_buffer_line_curposXYZE(3000 / 60, active_extruder);
-				current_position[X_AXIS] = PINDA_PREHEAT_X;
-				current_position[Y_AXIS] = PINDA_PREHEAT_Y;
-				plan_buffer_line_curposXYZE(3000 / 60, active_extruder);
-				current_position[Z_AXIS] = PINDA_PREHEAT_Z;
-				plan_buffer_line_curposXYZE(3000 / 60, active_extruder);
-				st_synchronize();
-				while (current_temperature_pinda < temp)
-				{
-					delay_keep_alive(1000);
-					serialecho_temperatures();
-				}
-				current_position[Z_AXIS] = MESH_HOME_Z_SEARCH;
-				plan_buffer_line_curposXYZE(3000 / 60, active_extruder);
-				current_position[X_AXIS] = pgm_read_float(bed_ref_points_4);
-				current_position[Y_AXIS] = pgm_read_float(bed_ref_points_4 + 1);
-				plan_buffer_line_curposXYZE(3000 / 60, active_extruder);
-				st_synchronize();
-				find_z_result = find_bed_induction_sensor_point_z(-1.f);
-				if (find_z_result == false) {
-					lcd_temp_cal_show_result(find_z_result);
-					break;
-				}
-				z_shift = (int)((current_position[Z_AXIS] - zero_z)*cs.axis_steps_per_unit[Z_AXIS]);
+            current_position[Z_AXIS] = MESH_HOME_Z_SEARCH;
+            plan_buffer_line_curposXYZE(3000 / 60);
+            current_position[X_AXIS] = PINDA_PREHEAT_X;
+            current_position[Y_AXIS] = PINDA_PREHEAT_Y;
+            plan_buffer_line_curposXYZE(3000 / 60);
+            current_position[Z_AXIS] = PINDA_PREHEAT_Z;
+            plan_buffer_line_curposXYZE(3000 / 60);
+            st_synchronize();
+            while (current_temperature_pinda < temp)
+            {
+                delay_keep_alive(1000);
+                serialecho_temperatures();
+            }
+            current_position[Z_AXIS] = MESH_HOME_Z_SEARCH;
+            plan_buffer_line_curposXYZE(3000 / 60);
+            current_position[X_AXIS] = pgm_read_float(bed_ref_points_4);
+            current_position[Y_AXIS] = pgm_read_float(bed_ref_points_4 + 1);
+            plan_buffer_line_curposXYZE(3000 / 60);
+            st_synchronize();
+            find_z_result = find_bed_induction_sensor_point_z(-1.f);
+            if (find_z_result == false) {
+                lcd_temp_cal_show_result(find_z_result);
+                break;
+            }
+            z_shift = (int)((current_position[Z_AXIS] - zero_z)*cs.axis_steps_per_unit[Z_AXIS]);
 
-				printf_P(_N("\nPINDA temperature: %.1f Z shift (mm): %.3f"), current_temperature_pinda, current_position[Z_AXIS] - zero_z);
+            printf_P(_N("\nPINDA temperature: %.1f Z shift (mm): %.3f"), current_temperature_pinda, current_position[Z_AXIS] - zero_z);
 
-				EEPROM_save_B(EEPROM_PROBE_TEMP_SHIFT + i * 2, &z_shift);
+            EEPROM_save_B(EEPROM_PROBE_TEMP_SHIFT + i * 2, &z_shift);
 
-			}
-			lcd_temp_cal_show_result(true);
+        }
+        lcd_temp_cal_show_result(true);
 
-			break;
-		}
-#endif //PINDA_THERMISTOR
+#else //PINDA_THERMISTOR
 
 		setTargetBed(PINDA_MIN_T);
 		float zero_z;
@@ -4730,7 +4937,7 @@ if(eSoundMode!=e_SOUND_MODE_SILENT)
 			// Push the commands to the front of the message queue in the reverse order!
 			// There shall be always enough space reserved for these commands.
 			repeatcommand_front(); // repeat G76 with all its parameters
-			enquecommand_front_P((PSTR("G28 W0")));
+			enquecommand_front_P(G28W0);
 			break;
 		}
 		puts_P(_N("PINDA probe calibration start"));
@@ -4740,7 +4947,7 @@ if(eSoundMode!=e_SOUND_MODE_SILENT)
 		current_position[X_AXIS] = PINDA_PREHEAT_X;
 		current_position[Y_AXIS] = PINDA_PREHEAT_Y;
 		current_position[Z_AXIS] = PINDA_PREHEAT_Z;
-		plan_buffer_line_curposXYZE(3000 / 60, active_extruder);
+		plan_buffer_line_curposXYZE(3000 / 60);
 		st_synchronize();
 		
 		while (abs(degBed() - PINDA_MIN_T) > 1) {
@@ -4756,11 +4963,11 @@ if(eSoundMode!=e_SOUND_MODE_SILENT)
 		eeprom_update_byte((uint8_t*)EEPROM_CALIBRATION_STATUS_PINDA, 0); //invalidate temp. calibration in case that in will be aborted during the calibration process 
 
 		current_position[Z_AXIS] = 5;
-		plan_buffer_line_curposXYZE(3000 / 60, active_extruder);
+		plan_buffer_line_curposXYZE(3000 / 60);
 
 		current_position[X_AXIS] = BED_X0;
 		current_position[Y_AXIS] = BED_Y0;
-		plan_buffer_line_curposXYZE(3000 / 60, active_extruder);
+		plan_buffer_line_curposXYZE(3000 / 60);
 		st_synchronize();
 		
 		find_bed_induction_sensor_point_z(-1.f);
@@ -4777,7 +4984,7 @@ if(eSoundMode!=e_SOUND_MODE_SILENT)
 			current_position[X_AXIS] = PINDA_PREHEAT_X;
 			current_position[Y_AXIS] = PINDA_PREHEAT_Y;
 			current_position[Z_AXIS] = PINDA_PREHEAT_Z;
-			plan_buffer_line_curposXYZE(3000 / 60, active_extruder);
+			plan_buffer_line_curposXYZE(3000 / 60);
 			st_synchronize();
 			while (degBed() < t_c) {
 				delay_keep_alive(1000);
@@ -4788,10 +4995,10 @@ if(eSoundMode!=e_SOUND_MODE_SILENT)
 				serialecho_temperatures();
 			}
 			current_position[Z_AXIS] = 5;
-			plan_buffer_line_curposXYZE(3000 / 60, active_extruder);
+			plan_buffer_line_curposXYZE(3000 / 60);
 			current_position[X_AXIS] = BED_X0;
 			current_position[Y_AXIS] = BED_Y0;
-			plan_buffer_line_curposXYZE(3000 / 60, active_extruder);
+			plan_buffer_line_curposXYZE(3000 / 60);
 			st_synchronize();
 			find_bed_induction_sensor_point_z(-1.f);
 			z_shift = (int)((current_position[Z_AXIS] - zero_z)*cs.axis_steps_per_unit[Z_AXIS]);
@@ -4814,13 +5021,12 @@ if(eSoundMode!=e_SOUND_MODE_SILENT)
 			disable_e2();
 			setTargetBed(0); //set bed target temperature back to 0
 		lcd_show_fullscreen_message_and_wait_P(_T(MSG_TEMP_CALIBRATION_DONE));
-		temp_cal_active = true;
 		eeprom_update_byte((unsigned char *)EEPROM_TEMP_CAL_ACTIVE, 1);
 		lcd_update_enable(true);
 		lcd_update(2);		
 
 		
-
+#endif //PINDA_THERMISTOR
 	}
 	break;
 
@@ -4862,11 +5068,6 @@ if(eSoundMode!=e_SOUND_MODE_SILENT)
 	case_G80:
 	{
 		mesh_bed_leveling_flag = true;
-#ifndef LA_NOCOMPAT
-        // When printing via USB there's no clear boundary between prints. Abuse MBL to indicate
-        // the beginning of a new print, allowing a new autodetected setting just after G80.
-        la10c_reset();
-#endif
 #ifndef PINDA_THERMISTOR
         static bool run = false; // thermistor-less PINDA temperature compensation is running
 #endif // ndef PINDA_THERMISTOR
@@ -4885,7 +5086,7 @@ if(eSoundMode!=e_SOUND_MODE_SILENT)
 			// Push the commands to the front of the message queue in the reverse order!
 			// There shall be always enough space reserved for these commands.
 			repeatcommand_front(); // repeat G80 with all its parameters
-			enquecommand_front_P((PSTR("G28 W0")));
+			enquecommand_front_P(G28W0);
 			break;
 		} 
 		
@@ -4918,7 +5119,7 @@ if(eSoundMode!=e_SOUND_MODE_SILENT)
 			temp_compensation_start();
 			run = true;
 			repeatcommand_front(); // repeat G80 with all its parameters
-			enquecommand_front_P((PSTR("G28 W0")));
+			enquecommand_front_P(G28W0);
 			break;
 		}
         run = false;
@@ -4939,7 +5140,7 @@ if(eSoundMode!=e_SOUND_MODE_SILENT)
 		// Cycle through all points and probe them
 		// First move up. During this first movement, the babystepping will be reverted.
 		current_position[Z_AXIS] = MESH_HOME_Z_SEARCH;
-		plan_buffer_line_curposXYZE(homing_feedrate[Z_AXIS] / 60, active_extruder);
+		plan_buffer_line_curposXYZE(homing_feedrate[Z_AXIS] / 60);
 		// The move to the first calibration point.
 		current_position[X_AXIS] = BED_X0;
 		current_position[Y_AXIS] = BED_Y0;
@@ -4954,7 +5155,7 @@ if(eSoundMode!=e_SOUND_MODE_SILENT)
 			world2machine_clamp(current_position[X_AXIS], current_position[Y_AXIS]);
 		#endif //SUPPORT_VERBOSITY
 
-		plan_buffer_line_curposXYZE(homing_feedrate[X_AXIS] / 30, active_extruder);
+		plan_buffer_line_curposXYZE(homing_feedrate[X_AXIS] / 30);
 		// Wait until the move is finished.
 		st_synchronize();
 
@@ -4969,7 +5170,6 @@ if(eSoundMode!=e_SOUND_MODE_SILENT)
 		}
 		#endif // SUPPORT_VERBOSITY
 		int l_feedmultiply = setup_for_endstop_move(false); //save feedrate and feedmultiply, sets feedmultiply to 100
-		const char *kill_message = NULL;
 		while (mesh_point != nMeasPoints * nMeasPoints) {
 			// Get coords of a measuring point.
 			uint8_t ix = mesh_point % nMeasPoints; // from 0 to MESH_NUM_X_POINTS - 1
@@ -5006,7 +5206,7 @@ if(eSoundMode!=e_SOUND_MODE_SILENT)
 			if((ix == 0) && (iy == 0)) current_position[Z_AXIS] = MESH_HOME_Z_SEARCH;
 			else current_position[Z_AXIS] += 2.f / nMeasPoints; //use relative movement from Z coordinate where PINDa triggered on previous point. This makes calibration faster.
 			float init_z_bckp = current_position[Z_AXIS];
-			plan_buffer_line_curposXYZE(Z_LIFT_FEEDRATE, active_extruder);
+			plan_buffer_line_curposXYZE(Z_LIFT_FEEDRATE);
 			st_synchronize();
 
 			// Move to XY position of the sensor point.
@@ -5027,7 +5227,7 @@ if(eSoundMode!=e_SOUND_MODE_SILENT)
 			#endif // SUPPORT_VERBOSITY
 
 			//printf_P(PSTR("after clamping: [%f;%f]\n"), current_position[X_AXIS], current_position[Y_AXIS]);
-			plan_buffer_line_curposXYZE(XY_AXIS_FEEDRATE, active_extruder);
+			plan_buffer_line_curposXYZE(XY_AXIS_FEEDRATE);
 			st_synchronize();
 
 			// Go down until endstop is hit
@@ -5039,7 +5239,7 @@ if(eSoundMode!=e_SOUND_MODE_SILENT)
 			if (init_z_bckp - current_position[Z_AXIS] < 0.1f) { //broken cable or initial Z coordinate too low. Go to MESH_HOME_Z_SEARCH and repeat last step (z-probe) again to distinguish between these two cases.
 				//printf_P(PSTR("Another attempt! Current Z position: %f\n"), current_position[Z_AXIS]);
 				current_position[Z_AXIS] = MESH_HOME_Z_SEARCH;
-				plan_buffer_line_curposXYZE(Z_LIFT_FEEDRATE, active_extruder);
+				plan_buffer_line_curposXYZE(Z_LIFT_FEEDRATE);
 				st_synchronize();
 
 				if (!find_bed_induction_sensor_point_z((has_z && mesh_point > 0) ? z0 - Z_CALIBRATION_THRESHOLD : -10.f, nProbeRetry)) { //if we have data from z calibration max allowed difference is 1mm for each point, if we dont have data max difference is 10mm from initial point  
@@ -5047,12 +5247,12 @@ if(eSoundMode!=e_SOUND_MODE_SILENT)
 					break;
 				}
 				if (MESH_HOME_Z_SEARCH - current_position[Z_AXIS] < 0.1f) {
-					printf_P(PSTR("Bed leveling failed. Sensor disconnected or cable broken.\n"));
+					puts_P(PSTR("Bed leveling failed. Sensor disconnected or cable broken."));
 					break;
 				}
 			}
 			if (has_z && fabs(z0 - current_position[Z_AXIS]) > Z_CALIBRATION_THRESHOLD) { //if we have data from z calibration, max. allowed difference is 1mm for each point
-				printf_P(PSTR("Bed leveling failed. Sensor triggered too high.\n"));
+				puts_P(PSTR("Bed leveling failed. Sensor triggered too high."));
 				break;
 			}
 			#ifdef SUPPORT_VERBOSITY
@@ -5094,7 +5294,7 @@ if(eSoundMode!=e_SOUND_MODE_SILENT)
 			MYSERIAL.print(current_position[Z_AXIS], 5);
 		}
 		#endif // SUPPORT_VERBOSITY
-		plan_buffer_line_curposXYZE(Z_LIFT_FEEDRATE, active_extruder);
+		plan_buffer_line_curposXYZE(Z_LIFT_FEEDRATE);
 		st_synchronize();
 		if (mesh_point != nMeasPoints * nMeasPoints) {
                Sound_MakeSound(e_SOUND_TYPE_StandardAlert);
@@ -5111,14 +5311,14 @@ if(eSoundMode!=e_SOUND_MODE_SILENT)
                     // ~ Z-homing (can not be used "G28", because X & Y-homing would have been done before (Z-homing))
                     bState=enable_z_endstop(false);
                     current_position[Z_AXIS] -= 1;
-                    plan_buffer_line_curposXYZE(homing_feedrate[Z_AXIS] / 40, active_extruder);
+                    plan_buffer_line_curposXYZE(homing_feedrate[Z_AXIS] / 40);
                     st_synchronize();
                     enable_z_endstop(true);
 #ifdef TMC2130
                     tmc2130_home_enter(Z_AXIS_MASK);
 #endif // TMC2130
                     current_position[Z_AXIS] = MESH_HOME_Z_SEARCH;
-                    plan_buffer_line_curposXYZE(homing_feedrate[Z_AXIS] / 40, active_extruder);
+                    plan_buffer_line_curposXYZE(homing_feedrate[Z_AXIS] / 40);
                     st_synchronize();
 #ifdef TMC2130
                     tmc2130_home_exit();
@@ -5246,9 +5446,9 @@ if(eSoundMode!=e_SOUND_MODE_SILENT)
 		go_home_with_z_lift();
 //		SERIAL_ECHOLNPGM("Go home finished");
 		//unretract (after PINDA preheat retraction)
-		if (degHotend(active_extruder) > EXTRUDE_MINTEMP && temp_cal_active == true && calibration_status_pinda() == true && target_temperature_bed >= 50) {
+		if ((degHotend(active_extruder) > EXTRUDE_MINTEMP) && eeprom_read_byte((unsigned char *)EEPROM_TEMP_CAL_ACTIVE) && calibration_status_pinda() && (target_temperature_bed >= 50)) {
 			current_position[E_AXIS] += default_retraction;
-			plan_buffer_line_curposXYZE(400, active_extruder);
+			plan_buffer_line_curposXYZE(400);
 		}
 		KEEPALIVE_STATE(NOT_BUSY);
 		// Restore custom message state
@@ -5270,7 +5470,7 @@ if(eSoundMode!=e_SOUND_MODE_SILENT)
             if (mbl.active) {
                 SERIAL_PROTOCOLPGM("Num X,Y: ");
                 SERIAL_PROTOCOL(MESH_NUM_X_POINTS);
-                SERIAL_PROTOCOLPGM(",");
+                SERIAL_PROTOCOL(',');
                 SERIAL_PROTOCOL(MESH_NUM_Y_POINTS);
                 SERIAL_PROTOCOLPGM("\nZ search height: ");
                 SERIAL_PROTOCOL(MESH_HOME_Z_SEARCH);
@@ -5280,7 +5480,7 @@ if(eSoundMode!=e_SOUND_MODE_SILENT)
                         SERIAL_PROTOCOLPGM("  ");
                         SERIAL_PROTOCOL_F(mbl.z_values[y][x], 5);
                     }
-                    SERIAL_PROTOCOLPGM("\n");
+                    SERIAL_PROTOCOLLN();
                 }
             }
             else
@@ -5435,10 +5635,9 @@ if(eSoundMode!=e_SOUND_MODE_SILENT)
 		farm_mode = 1;
 		PingTime = _millis();
 		eeprom_update_byte((unsigned char *)EEPROM_FARM_MODE, farm_mode);
-		EEPROM_save_B(EEPROM_FARM_NUMBER, &farm_no);
-          SilentModeMenu = SILENT_MODE_OFF;
-          eeprom_update_byte((unsigned char *)EEPROM_SILENT, SilentModeMenu);
-          fCheckModeInit();                       // alternatively invoke printer reset
+		SilentModeMenu = SILENT_MODE_OFF;
+		eeprom_update_byte((unsigned char *)EEPROM_SILENT, SilentModeMenu);
+		fCheckModeInit();                       // alternatively invoke printer reset
 		break;
 
     /*! ### G99 - Deactivate farm mode <a href="https://reprap.org/wiki/G-code#G99:_Deactivate_farm_mode">G99: Deactivate farm mode</a>
@@ -5553,10 +5752,16 @@ if(eSoundMode!=e_SOUND_MODE_SILENT)
 
     /*!
 	### M20 - SD Card file list <a href="https://reprap.org/wiki/G-code#M20:_List_SD_card">M20: List SD card</a>
+    #### Usage
+    
+        M20 [ L ]
+    #### Parameters
+    - `L` - Reports ling filenames instead of just short filenames. Requires host software parsing.
     */
     case 20:
+      KEEPALIVE_STATE(NOT_BUSY); // do not send busy messages during listing. Inhibits the output of manage_heater()
       SERIAL_PROTOCOLLNRPGM(_N("Begin file list"));////MSG_BEGIN_FILE_LIST
-      card.ls();
+      card.ls(code_seen('L'));
       SERIAL_PROTOCOLLNRPGM(_N("End file list"));////MSG_END_FILE_LIST
       break;
 
@@ -5634,9 +5839,15 @@ if(eSoundMode!=e_SOUND_MODE_SILENT)
 
     /*!
 	### M27 - Get SD status <a href="https://reprap.org/wiki/G-code#M27:_Report_SD_print_status">M27: Report SD print status</a>
+    #### Usage
+	
+	      M27 [ P ]
+	
+	#### Parameters
+	  - `P` - Show full SFN path instead of LFN only.
     */
     case 27:
-      card.getStatus();
+      card.getStatus(code_seen('P'));
       break;
 
     /*!
@@ -5853,28 +6064,29 @@ if(eSoundMode!=e_SOUND_MODE_SILENT)
     /*!
 	### M46 - Show the assigned IP address <a href="https://reprap.org/wiki/G-code#M46:_Show_the_assigned_IP_address">M46: Show the assigned IP address.</a>
     */
-    /*
-     case 46:
+    case 46:
     {
         // M46: Prusa3D: Show the assigned IP address.
-        uint8_t ip[4];
-        bool hasIP = card.ToshibaFlashAir_GetIP(ip);
-        if (hasIP) {
-            SERIAL_ECHOPGM("Toshiba FlashAir current IP: ");
-            SERIAL_ECHO(int(ip[0]));
-            SERIAL_ECHOPGM(".");
-            SERIAL_ECHO(int(ip[1]));
-            SERIAL_ECHOPGM(".");
-            SERIAL_ECHO(int(ip[2]));
-            SERIAL_ECHOPGM(".");
-            SERIAL_ECHO(int(ip[3]));
-            SERIAL_ECHOLNPGM("");
+        if (card.ToshibaFlashAir_isEnabled()) {
+            uint8_t ip[4];
+            if (card.ToshibaFlashAir_GetIP(ip)) {
+                // SERIAL_PROTOCOLPGM("Toshiba FlashAir current IP: ");
+                SERIAL_PROTOCOL(uint8_t(ip[0]));
+                SERIAL_PROTOCOL('.');
+                SERIAL_PROTOCOL(uint8_t(ip[1]));
+                SERIAL_PROTOCOL('.');
+                SERIAL_PROTOCOL(uint8_t(ip[2]));
+                SERIAL_PROTOCOL('.');
+                SERIAL_PROTOCOL(uint8_t(ip[3]));
+                SERIAL_PROTOCOLLN();
+            } else {
+                SERIAL_PROTOCOLPGM("?Toshiba FlashAir GetIP failed\n");          
+            }
         } else {
-            SERIAL_ECHOLNPGM("Toshiba FlashAir GetIP failed");          
+            SERIAL_PROTOCOLLNPGM("n/a");          
         }
         break;
     }
-    */
 
     /*!
 	### M47 - Show end stops dialog on the display <a href="https://reprap.org/wiki/G-code#M47:_Show_end_stops_dialog_on_the_display">M47: Show end stops dialog on the display</a>
@@ -6273,96 +6485,53 @@ Sigma_Exit:
       uint8_t extruder;
       if(setTargetedHotend(105, extruder)){
         break;
-        }
-      #if defined(TEMP_0_PIN) && TEMP_0_PIN > -1
-        SERIAL_PROTOCOLPGM("ok T:");
-        SERIAL_PROTOCOL_F(degHotend(extruder),1);
-        SERIAL_PROTOCOLPGM(" /");
-        SERIAL_PROTOCOL_F(degTargetHotend(extruder),1);
-        #if defined(TEMP_BED_PIN) && TEMP_BED_PIN > -1
-          SERIAL_PROTOCOLPGM(" B:");
-          SERIAL_PROTOCOL_F(degBed(),1);
-          SERIAL_PROTOCOLPGM(" /");
-          SERIAL_PROTOCOL_F(degTargetBed(),1);
-        #endif //TEMP_BED_PIN
-        for (int8_t cur_extruder = 0; cur_extruder < EXTRUDERS; ++cur_extruder) {
-          SERIAL_PROTOCOLPGM(" T");
-          SERIAL_PROTOCOL(cur_extruder);
-          SERIAL_PROTOCOLPGM(":");
-          SERIAL_PROTOCOL_F(degHotend(cur_extruder),1);
-          SERIAL_PROTOCOLPGM(" /");
-          SERIAL_PROTOCOL_F(degTargetHotend(cur_extruder),1);
-        }
-      #else
-        SERIAL_ERROR_START;
-        SERIAL_ERRORLNRPGM(_i("No thermistors - no temperature"));////MSG_ERR_NO_THERMISTORS
-      #endif
-
-        SERIAL_PROTOCOLPGM(" @:");
-      #ifdef EXTRUDER_WATTS
-        SERIAL_PROTOCOL((EXTRUDER_WATTS * getHeaterPower(tmp_extruder))/127);
-        SERIAL_PROTOCOLPGM("W");
-      #else
-        SERIAL_PROTOCOL(getHeaterPower(extruder));
-      #endif
-
-        SERIAL_PROTOCOLPGM(" B@:");
-      #ifdef BED_WATTS
-        SERIAL_PROTOCOL((BED_WATTS * getHeaterPower(-1))/127);
-        SERIAL_PROTOCOLPGM("W");
-      #else
-        SERIAL_PROTOCOL(getHeaterPower(-1));
-      #endif
-
-#ifdef PINDA_THERMISTOR
-		SERIAL_PROTOCOLPGM(" P:");
-		SERIAL_PROTOCOL_F(current_temperature_pinda,1);
-#endif //PINDA_THERMISTOR
-
-#ifdef AMBIENT_THERMISTOR
-		SERIAL_PROTOCOLPGM(" A:");
-		SERIAL_PROTOCOL_F(current_temperature_ambient,1);
-#endif //AMBIENT_THERMISTOR
-
-
-        #ifdef SHOW_TEMP_ADC_VALUES
-          {float raw = 0.0;
-
-          #if defined(TEMP_BED_PIN) && TEMP_BED_PIN > -1
-            SERIAL_PROTOCOLPGM("    ADC B:");
-            SERIAL_PROTOCOL_F(degBed(),1);
-            SERIAL_PROTOCOLPGM("C->");
-            raw = rawBedTemp();
-            SERIAL_PROTOCOL_F(raw/OVERSAMPLENR,5);
-            SERIAL_PROTOCOLPGM(" Rb->");
-            SERIAL_PROTOCOL_F(100 * (1 + (PtA * (raw/OVERSAMPLENR)) + (PtB * sq((raw/OVERSAMPLENR)))), 5);
-            SERIAL_PROTOCOLPGM(" Rxb->");
-            SERIAL_PROTOCOL_F(raw, 5);
-          #endif
-          for (int8_t cur_extruder = 0; cur_extruder < EXTRUDERS; ++cur_extruder) {
-            SERIAL_PROTOCOLPGM("  T");
-            SERIAL_PROTOCOL(cur_extruder);
-            SERIAL_PROTOCOLPGM(":");
-            SERIAL_PROTOCOL_F(degHotend(cur_extruder),1);
-            SERIAL_PROTOCOLPGM("C->");
-            raw = rawHotendTemp(cur_extruder);
-            SERIAL_PROTOCOL_F(raw/OVERSAMPLENR,5);
-            SERIAL_PROTOCOLPGM(" Rt");
-            SERIAL_PROTOCOL(cur_extruder);
-            SERIAL_PROTOCOLPGM("->");
-            SERIAL_PROTOCOL_F(100 * (1 + (PtA * (raw/OVERSAMPLENR)) + (PtB * sq((raw/OVERSAMPLENR)))), 5);
-            SERIAL_PROTOCOLPGM(" Rx");
-            SERIAL_PROTOCOL(cur_extruder);
-            SERIAL_PROTOCOLPGM("->");
-            SERIAL_PROTOCOL_F(raw, 5);
-          }}
-        #endif
-		SERIAL_PROTOCOLLN("");
-		KEEPALIVE_STATE(NOT_BUSY);
-      return;
+      }
+      
+      SERIAL_PROTOCOLPGM("ok ");
+      gcode_M105(extruder);
+      
+      cmdqueue_pop_front(); //prevent an ok after the command since this command uses an ok at the beginning.
+      
       break;
     }
 
+#if defined(AUTO_REPORT)
+    /*!
+	### M155 - Automatically send status <a href="https://reprap.org/wiki/G-code#M155:_Automatically_send_temperatures">M155: Automatically send temperatures</a>
+	#### Usage
+	
+		M155 [ S ] [ C ]
+	
+	#### Parameters
+	
+	- `S` - Set autoreporting interval in seconds. 0 to disable. Maximum: 255
+	- `C` - Activate auto-report function (bit mask). Default is temperature.
+
+          bit 0 = Auto-report temperatures
+          bit 1 = Auto-report fans
+          bit 2 = Auto-report position
+          bit 3 = free
+          bit 4 = free
+          bit 5 = free
+          bit 6 = free
+          bit 7 = free
+     */
+    //!@todo update RepRap Gcode wiki
+    //!@todo Should be temperature always? Octoprint doesn't switch to M105 if M155 timer is set
+    case 155:
+    {
+        if (code_seen('S')){
+            autoReportFeatures.SetPeriod( code_value_uint8() );
+        }
+        if (code_seen('C')){
+            autoReportFeatures.SetMask(code_value());
+        } else{
+            autoReportFeatures.SetMask(1); //Backwards compability to host systems like Octoprint to send only temp if paramerter `C`isn't used.
+        }
+   }
+    break;
+#endif //AUTO_REPORT
+
     /*!
 	### M109 - Wait for extruder temperature <a href="https://reprap.org/wiki/G-code#M109:_Set_Extruder_Temperature_and_Wait">M109: Set Extruder Temperature and Wait</a>
     #### Usage
@@ -6475,7 +6644,7 @@ Sigma_Exit:
 				  SERIAL_PROTOCOL((int)active_extruder);
 				  SERIAL_PROTOCOLPGM(" B:");
 				  SERIAL_PROTOCOL_F(degBed(), 1);
-				  SERIAL_PROTOCOLLN("");
+				  SERIAL_PROTOCOLLN();
 			  }
 				  codenum = _millis();
 			  
@@ -6745,7 +6914,7 @@ Sigma_Exit:
 		else {
 			SERIAL_ECHO_START;
 			SERIAL_ECHOPAIR("M113 S", (unsigned long)host_keepalive_interval);
-			SERIAL_PROTOCOLLN("");
+			SERIAL_PROTOCOLLN();
 		}
 		break;
 
@@ -6795,6 +6964,9 @@ Sigma_Exit:
           SERIAL_ECHOPGM(STRINGIFY(EXTRUDERS)); 
           SERIAL_ECHOPGM(" UUID:"); 
           SERIAL_ECHOLNPGM(MACHINE_UUID);
+#ifdef EXTENDED_CAPABILITIES_REPORT
+          extended_capabilities_report();
+#endif //EXTENDED_CAPABILITIES_REPORT
       }
       break;
 
@@ -6820,14 +6992,14 @@ Sigma_Exit:
 	### M120 - Enable endstops <a href="https://reprap.org/wiki/G-code#M120:_Enable_endstop_detection">M120: Enable endstop detection</a>
     */
     case 120:
-      enable_endstops(false) ;
+      enable_endstops(true) ;
       break;
 
     /*!
 	### M121 - Disable endstops <a href="https://reprap.org/wiki/G-code#M121:_Disable_endstop_detection">M121: Disable endstop detection</a>
     */
     case 121:
-      enable_endstops(true) ;
+      enable_endstops(false) ;
       break;
 
     /*!
@@ -6836,7 +7008,7 @@ Sigma_Exit:
     */
     case 119:
     SERIAL_PROTOCOLRPGM(_N("Reporting endstop status"));////MSG_M119_REPORT
-    SERIAL_PROTOCOLLN("");
+    SERIAL_PROTOCOLLN();
       #if defined(X_MIN_PIN) && X_MIN_PIN > -1
         SERIAL_PROTOCOLRPGM(_n("x_min: "));////MSG_X_MIN
         if(READ(X_MIN_PIN)^X_MIN_ENDSTOP_INVERTING){
@@ -6844,7 +7016,7 @@ Sigma_Exit:
         }else{
           SERIAL_PROTOCOLRPGM(MSG_ENDSTOP_OPEN);
         }
-        SERIAL_PROTOCOLLN("");
+        SERIAL_PROTOCOLLN();
       #endif
       #if defined(X_MAX_PIN) && X_MAX_PIN > -1
         SERIAL_PROTOCOLRPGM(_n("x_max: "));////MSG_X_MAX
@@ -6853,7 +7025,7 @@ Sigma_Exit:
         }else{
           SERIAL_PROTOCOLRPGM(MSG_ENDSTOP_OPEN);
         }
-        SERIAL_PROTOCOLLN("");
+        SERIAL_PROTOCOLLN();
       #endif
       #if defined(Y_MIN_PIN) && Y_MIN_PIN > -1
         SERIAL_PROTOCOLRPGM(_n("y_min: "));////MSG_Y_MIN
@@ -6862,7 +7034,7 @@ Sigma_Exit:
         }else{
           SERIAL_PROTOCOLRPGM(MSG_ENDSTOP_OPEN);
         }
-        SERIAL_PROTOCOLLN("");
+        SERIAL_PROTOCOLLN();
       #endif
       #if defined(Y_MAX_PIN) && Y_MAX_PIN > -1
         SERIAL_PROTOCOLRPGM(_n("y_max: "));////MSG_Y_MAX
@@ -6871,7 +7043,7 @@ Sigma_Exit:
         }else{
           SERIAL_PROTOCOLRPGM(MSG_ENDSTOP_OPEN);
         }
-        SERIAL_PROTOCOLLN("");
+        SERIAL_PROTOCOLLN();
       #endif
       #if defined(Z_MIN_PIN) && Z_MIN_PIN > -1
         SERIAL_PROTOCOLRPGM(MSG_Z_MIN);
@@ -6880,7 +7052,7 @@ Sigma_Exit:
         }else{
           SERIAL_PROTOCOLRPGM(MSG_ENDSTOP_OPEN);
         }
-        SERIAL_PROTOCOLLN("");
+        SERIAL_PROTOCOLLN();
       #endif
       #if defined(Z_MAX_PIN) && Z_MAX_PIN > -1
         SERIAL_PROTOCOLRPGM(MSG_Z_MAX);
@@ -6889,11 +7061,34 @@ Sigma_Exit:
         }else{
           SERIAL_PROTOCOLRPGM(MSG_ENDSTOP_OPEN);
         }
-        SERIAL_PROTOCOLLN("");
+        SERIAL_PROTOCOLLN();
       #endif
       break;
       //!@todo update for all axes, use for loop
+
+#if (defined(FANCHECK) && (((defined(TACH_0) && (TACH_0 >-1)) || (defined(TACH_1) && (TACH_1 > -1)))))
+    /*!
+	### M123 - Tachometer value <a href="https://www.reprap.org/wiki/G-code#M123:_Tachometer_value_.28RepRap.29">M123: Tachometer value</a>
+  This command is used to report fan speeds and fan pwm values.
+  #### Usage
     
+        M123
+
+    - E0:     - Hotend fan speed in RPM
+    - PRN1:   - Part cooling fans speed in RPM
+    - E0@:    - Hotend fan PWM value
+    - PRN1@:  -Part cooling fan PWM value
+
+  _Example:_
+
+    E0:3240 RPM PRN1:4560 RPM E0@:255 PRN1@:255
+
+    */
+   //!@todo Update RepRap Gcode wiki
+    case 123:
+    gcode_M123();
+    break;
+#endif //FANCHECK and TACH_0 and TACH_1
 
     #ifdef BLINKM
     /*!
@@ -7014,7 +7209,7 @@ Sigma_Exit:
     For each axis individually.
     */
     case 203: // M203 max feedrate mm/sec
-		for (int8_t i = 0; i < NUM_AXIS; i++)
+		for (uint8_t i = 0; i < NUM_AXIS; i++)
 		{
 			if (code_seen(axis_codes[i]))
 			{
@@ -7065,7 +7260,7 @@ Sigma_Exit:
           // Legacy acceleration format. This format is used by the legacy Marlin, MK2 or MK3 firmware,
           // and it is also generated by Slic3r to control acceleration per extrusion type
           // (there is a separate acceleration settings in Slicer for perimeter, first layer etc).
-          cs.acceleration = code_value();
+          cs.acceleration = cs.travel_acceleration = code_value();
           // Interpret the T value as retract acceleration in the old Marlin format.
           if(code_seen('T'))
             cs.retract_acceleration = code_value();
@@ -7075,13 +7270,8 @@ Sigma_Exit:
             cs.acceleration = code_value();
           if(code_seen('R'))
             cs.retract_acceleration = code_value();
-          if(code_seen('T')) {
-            // Interpret the T value as the travel acceleration in the new Marlin format.
-            /*!
-            @todo Prusa3D firmware currently does not support travel acceleration value independent from the extruding acceleration value.
-            */
-            // travel_acceleration = code_value();
-          }
+          if(code_seen('T'))
+            cs.travel_acceleration = code_value();
         }
       }
       break;
@@ -7114,7 +7304,6 @@ Sigma_Exit:
       {
           float e = code_value();
 #ifndef LA_NOCOMPAT
-
           e = la10c_jerk(e);
 #endif
           cs.max_jerk[E_AXIS] = e;
@@ -7136,7 +7325,7 @@ Sigma_Exit:
     - `Z` - Z axis offset
 	*/
     case 206:
-      for(int8_t i=0; i < 3; i++)
+      for(uint8_t i=0; i < 3; i++)
       {
         if(code_seen(axis_codes[i])) cs.add_homing[i] = code_value();
       }
@@ -7294,17 +7483,26 @@ Sigma_Exit:
     */
     case 220: // M220 S<factor in percent>- set speed factor override percentage
     {
-      if (code_seen('B')) //backup current speed factor
-      {
-        saved_feedmultiply_mm = feedmultiply;
-      }
-      if(code_seen('S'))
-      {		
-        feedmultiply = code_value() ;
-      }
-      if (code_seen('R')) { //restore previous feedmultiply
-        feedmultiply = saved_feedmultiply_mm;
-      }
+        bool codesWereSeen = false;
+        if (code_seen('B')) //backup current speed factor
+        {
+            saved_feedmultiply_mm = feedmultiply;
+            codesWereSeen = true;
+        }
+        if (code_seen('S'))
+        {
+            feedmultiply = code_value();
+            codesWereSeen = true;
+        }
+        if (code_seen('R')) //restore previous feedmultiply
+        {
+            feedmultiply = saved_feedmultiply_mm;
+            codesWereSeen = true;
+        }
+        if (!codesWereSeen)
+        {
+            printf_P(PSTR("%i%%\n"), feedmultiply);
+        }
     }
     break;
 
@@ -7320,23 +7518,26 @@ Sigma_Exit:
     */
     case 221: // M221 S<factor in percent>- set extrude factor override percentage
     {
-      if(code_seen('S'))
-      {
-        int tmp_code = code_value();
-        if (code_seen('T'))
+        if (code_seen('S'))
         {
-          uint8_t extruder;
-          if(setTargetedHotend(221, extruder)){
-            break;
-          }
-          extruder_multiply[extruder] = tmp_code;
+            int tmp_code = code_value();
+            if (code_seen('T'))
+            {
+                uint8_t extruder;
+                if (setTargetedHotend(221, extruder))
+                    break;
+                extruder_multiply[extruder] = tmp_code;
+            }
+            else
+            {
+                extrudemultiply = tmp_code ;
+            }
         }
         else
         {
-          extrudemultiply = tmp_code ;
+            printf_P(PSTR("%i%%\n"), extrudemultiply);
         }
-      }
-      calculate_extruder_multipliers();
+        calculate_extruder_multipliers();
     }
     break;
 
@@ -7447,7 +7648,7 @@ Sigma_Exit:
           SERIAL_PROTOCOL(servo_index);
           SERIAL_PROTOCOL(": ");
           SERIAL_PROTOCOL(servos[servo_index].read());
-          SERIAL_PROTOCOLLN("");
+          SERIAL_PROTOCOLLN();
         }
       }
       break;
@@ -7523,7 +7724,7 @@ Sigma_Exit:
         //Kc does not have scaling applied above, or in resetting defaults
         SERIAL_PROTOCOL(Kc);
         #endif
-        SERIAL_PROTOCOLLN("");
+        SERIAL_PROTOCOLLN();
       }
       break;
     #endif //PIDTEMP
@@ -7556,7 +7757,7 @@ Sigma_Exit:
         SERIAL_PROTOCOL(unscalePID_i(cs.bedKi));
         SERIAL_PROTOCOL(" d:");
         SERIAL_PROTOCOL(unscalePID_d(cs.bedKd));
-        SERIAL_PROTOCOLLN("");
+        SERIAL_PROTOCOLLN();
       }
       break;
     #endif //PIDTEMP
@@ -7779,7 +7980,7 @@ Sigma_Exit:
           cs.zprobe_zoffset = -value; // compare w/ line 278 of ConfigurationStore.cpp
           SERIAL_ECHO_START;
           SERIAL_ECHOLNRPGM(CAT4(MSG_ZPROBE_ZOFFSET, " ", MSG_OK,PSTR("")));
-          SERIAL_PROTOCOLLN("");
+          SERIAL_PROTOCOLLN();
         }
         else
         {
@@ -7789,7 +7990,7 @@ Sigma_Exit:
           SERIAL_ECHO(Z_PROBE_OFFSET_RANGE_MIN);
           SERIAL_ECHORPGM(MSG_Z_MAX);
           SERIAL_ECHO(Z_PROBE_OFFSET_RANGE_MAX);
-          SERIAL_PROTOCOLLN("");
+          SERIAL_PROTOCOLLN();
         }
       }
       else
@@ -7797,12 +7998,42 @@ Sigma_Exit:
           SERIAL_ECHO_START;
           SERIAL_ECHOLNRPGM(CAT2(MSG_ZPROBE_ZOFFSET, PSTR(" : ")));
           SERIAL_ECHO(-cs.zprobe_zoffset);
-          SERIAL_PROTOCOLLN("");
+          SERIAL_PROTOCOLLN();
       }
       break;
     }
     #endif // CUSTOM_M_CODE_SET_Z_PROBE_OFFSET
 
+	/*!
+	### M552 - Set IP address <a href="https://reprap.org/wiki/G-code#M552:_Set_IP_address.2C_enable.2Fdisable_network_interface">M552: Set IP address, enable/disable network interface"</a>
+    Sets the printer IP address that is shown in the support menu. Designed to be used with the help of host software.
+    If P is not specified nothing happens.
+    If the structure of the IP address is invalid, 0.0.0.0 is assumed and nothing is shown on the screen in the Support menu.
+    #### Usage
+    
+        M552 [ P<IP_address> ]
+    
+    #### Parameters
+    - `P` - The IP address in xxx.xxx.xxx.xxx format. Eg: P192.168.1.14
+	*/
+    case 552:
+    {
+        if (code_seen('P'))
+        {
+            uint8_t valCnt = 0;
+            IP_address = 0;
+            do
+            {
+                *strchr_pointer = '*';
+                ((uint8_t*)&IP_address)[valCnt] = code_value_short();
+                valCnt++;
+            } while ((valCnt < 4) && code_seen('.'));
+            
+            if (valCnt != 4)
+                IP_address = 0;
+        }
+    } break;
+
     #ifdef FILAMENTCHANGEENABLE
 
     /*!
@@ -7886,7 +8117,7 @@ Sigma_Exit:
           #endif
         }
 
-		if (mmu_enabled && code_seen("AUTO"))
+		if (mmu_enabled && code_seen_P(PSTR("AUTO")))
 			automatic = true;
 
 		gcode_M600(automatic, x_position, y_position, z_shift, e_shift_init, e_shift_late);
@@ -7910,6 +8141,7 @@ Sigma_Exit:
         if (!isPrintPaused)
         {
             st_synchronize();
+            ClearToSend(); //send OK even before the command finishes executing because we want to make sure it is not skipped because of cmdqueue_pop_front();
             cmdqueue_pop_front(); //trick because we want skip this command (M601) after restore
             lcd_pause_print();
         }
@@ -7959,7 +8191,7 @@ Sigma_Exit:
 
 		SERIAL_PROTOCOLPGM("Wait for PINDA target temperature:");
 		SERIAL_PROTOCOL(set_target_pinda);
-		SERIAL_PROTOCOLLN("");
+		SERIAL_PROTOCOLLN();
 
 		codenum = _millis();
 		cancel_heatup = false;
@@ -7974,9 +8206,8 @@ Sigma_Exit:
 			{
 				SERIAL_PROTOCOLPGM("P:");
 				SERIAL_PROTOCOL_F(current_temperature_pinda, 1);
-				SERIAL_PROTOCOLPGM("/");
-				SERIAL_PROTOCOL(set_target_pinda);
-				SERIAL_PROTOCOLLN("");
+				SERIAL_PROTOCOL('/');
+				SERIAL_PROTOCOLLN(set_target_pinda);
 				codenum = _millis();
 			}
 			manage_heater();
@@ -8019,7 +8250,7 @@ Sigma_Exit:
 				SERIAL_PROTOCOL(usteps);
 				SERIAL_PROTOCOLPGM(", ");
 				SERIAL_PROTOCOL(mm * 1000);
-				SERIAL_PROTOCOLLN("");
+				SERIAL_PROTOCOLLN();
 			}
 		}
 		else if (code_seen('!')) { // ! - Set factory default values
@@ -8062,7 +8293,7 @@ Sigma_Exit:
 						SERIAL_PROTOCOL(usteps);
 						SERIAL_PROTOCOLPGM(", ");
 						SERIAL_PROTOCOL(mm * 1000);
-						SERIAL_PROTOCOLLN("");
+						SERIAL_PROTOCOLLN();
 					}
 				}
 			}
@@ -8153,7 +8384,7 @@ Sigma_Exit:
                     if(code_seen('P'))
                          fw_version_check(++strchr_pointer);
                     else if(code_seen('Q'))
-                         SERIAL_PROTOCOLLN(FW_VERSION);
+                         SERIAL_PROTOCOLLNRPGM(FW_VERSION_STR_P());
                     break;
                case ClPrintChecking::_Gcode:      // ~ .5
                     if(code_seen('P'))
@@ -8565,7 +8796,7 @@ Sigma_Exit:
 	break;
 
     /*!
-	### M999 - Restart after being stopped <a href="https://reprap.org/wiki/G-code#M999:_Restart_after_being_stopped_by_error">M999: Restart after being stopped by error</a>
+    ### M999 - Restart after being stopped <a href="https://reprap.org/wiki/G-code#M999:_Restart_after_being_stopped_by_error">M999: Restart after being stopped by error</a>
     @todo Usually doesn't work. Should be fixed or removed. Most of the time, if `Stopped` it set, the print fails and is unrecoverable.
     */
     case 999:
@@ -8597,6 +8828,8 @@ Sigma_Exit:
   */
   else if(code_seen('T'))
   {
+      static const char duplicate_Tcode_ignored[] PROGMEM = "Duplicate T-code ignored.";
+      
       int index;
       bool load_to_nozzle = false;
       for (index = 1; *(strchr_pointer + index) == ' ' || *(strchr_pointer + index) == '\t'; index++);
@@ -8612,7 +8845,7 @@ Sigma_Exit:
 			tmp_extruder = choose_menu_P(_T(MSG_CHOOSE_FILAMENT), _T(MSG_FILAMENT));
 			if ((tmp_extruder == mmu_extruder) && mmu_fil_loaded) //dont execute the same T-code twice in a row
 			{
-				printf_P(PSTR("Duplicate T-code ignored.\n"));
+				puts_P(duplicate_Tcode_ignored);
 			}
 			else
 			{
@@ -8657,7 +8890,7 @@ Sigma_Exit:
           {
               if ((tmp_extruder == mmu_extruder) && mmu_fil_loaded) //dont execute the same T-code twice in a row
               {
-                  printf_P(PSTR("Duplicate T-code ignored.\n"));
+                  puts_P(duplicate_Tcode_ignored);
               }
 			  else
 			  {
@@ -8725,7 +8958,7 @@ Sigma_Exit:
 #else //SNMM
               if (tmp_extruder >= EXTRUDERS) {
                   SERIAL_ECHO_START;
-                  SERIAL_ECHOPGM("T");
+                  SERIAL_ECHO('T');
                   SERIAL_PROTOCOLLN((int)tmp_extruder);
                   SERIAL_ECHOLNRPGM(_n("Invalid extruder"));////MSG_INVALID_EXTRUDER
               }
@@ -8755,7 +8988,7 @@ Sigma_Exit:
                       }
                       // Set the new active extruder and position
                       active_extruder = tmp_extruder;
-                      plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
+                      plan_set_position_curposXYZE();
                       // Move to the old position if 'F' was in the parameters
                       if (make_move && Stopped == false) {
                           prepare_move();
@@ -8899,7 +9132,6 @@ Sigma_Exit:
    */
 	case 5:
 		dcode_5(); break;
-		break;
 #endif //DEBUG_DCODE5
 #ifdef DEBUG_DCODES
 
@@ -8982,28 +9214,7 @@ Sigma_Exit:
     - `J` - Offset Y (default 34)
   */
 	case 80:
-	{
-		float dimension_x = 40;
-		float dimension_y = 40;
-		int points_x = 40;
-		int points_y = 40;
-		float offset_x = 74;
-		float offset_y = 33;
-
-		if (code_seen('E')) dimension_x = code_value();
-		if (code_seen('F')) dimension_y = code_value();
-		if (code_seen('G')) {points_x = code_value(); }
-		if (code_seen('H')) {points_y = code_value(); }
-		if (code_seen('I')) {offset_x = code_value(); }
-		if (code_seen('J')) {offset_y = code_value(); }
-		printf_P(PSTR("DIM X: %f\n"), dimension_x);
-		printf_P(PSTR("DIM Y: %f\n"), dimension_y);
-		printf_P(PSTR("POINTS X: %d\n"), points_x);
-		printf_P(PSTR("POINTS Y: %d\n"), points_y);
-		printf_P(PSTR("OFFSET X: %f\n"), offset_x);
-		printf_P(PSTR("OFFSET Y: %f\n"), offset_y);
- 		bed_check(dimension_x,dimension_y,points_x,points_y,offset_x,offset_y);
-	}break;
+		dcode_80(); break;
 
     /*!
     ### D81 - Bed analysis <a href="https://reprap.org/wiki/G-code#D81:_Bed_analysis">D80: Bed analysis</a>
@@ -9021,24 +9232,7 @@ Sigma_Exit:
     - `J` - Offset Y (default 34)
   */
 	case 81:
-	{
-		float dimension_x = 40;
-		float dimension_y = 40;
-		int points_x = 40;
-		int points_y = 40;
-		float offset_x = 74;
-		float offset_y = 33;
-
-		if (code_seen('E')) dimension_x = code_value();
-		if (code_seen('F')) dimension_y = code_value();
-		if (code_seen("G")) { strchr_pointer+=1; points_x = code_value(); }
-		if (code_seen("H")) { strchr_pointer+=1; points_y = code_value(); }
-		if (code_seen("I")) { strchr_pointer+=1; offset_x = code_value(); }
-		if (code_seen("J")) { strchr_pointer+=1; offset_y = code_value(); }
-		
-		bed_analysis(dimension_x,dimension_y,points_x,points_y,offset_x,offset_y);
-		
-	} break;
+		dcode_81(); break;
 	
 #endif //HEATBED_ANALYSIS
 #ifdef DEBUG_DCODES
@@ -9047,17 +9241,7 @@ Sigma_Exit:
     ### D106 - Print measured fan speed for different pwm values <a href="https://reprap.org/wiki/G-code#D106:_Print_measured_fan_speed_for_different_pwm_values">D106: Print measured fan speed for different pwm values</a>
     */
 	case 106:
-	{
-		for (int i = 255; i > 0; i = i - 5) {
-			fanSpeed = i;
-			//delay_keep_alive(2000);
-			for (int j = 0; j < 100; j++) {
-				delay_keep_alive(100);
-
-			}
-			printf_P(_N("%d: %d\n"), i, fan_speed[1]);
-		}
-	}break;
+		dcode_106(); break;
 
 #ifdef TMC2130
     /*!
@@ -9174,8 +9358,8 @@ void FlushSerialRequestResend()
 // Execution of a command from a SD card will not be confirmed.
 void ClearToSend()
 {
-    previous_millis_cmd = _millis();
-	if ((CMDBUFFER_CURRENT_TYPE == CMDBUFFER_CURRENT_TYPE_USB) || (CMDBUFFER_CURRENT_TYPE == CMDBUFFER_CURRENT_TYPE_USB_WITH_LINENR)) 
+	previous_millis_cmd = _millis();
+	if (buflen && ((CMDBUFFER_CURRENT_TYPE == CMDBUFFER_CURRENT_TYPE_USB) || (CMDBUFFER_CURRENT_TYPE == CMDBUFFER_CURRENT_TYPE_USB_WITH_LINENR)))
 		SERIAL_PROTOCOLLNRPGM(MSG_OK);
 }
 
@@ -9354,13 +9538,13 @@ void prepare_move()
 
   // Do not use feedmultiply for E or Z only moves
   if( (current_position[X_AXIS] == destination [X_AXIS]) && (current_position[Y_AXIS] == destination [Y_AXIS])) {
-      plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder);
+      plan_buffer_line_destinationXYZE(feedrate/60);
   }
   else {
 #ifdef MESH_BED_LEVELING
     mesh_plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate*feedmultiply*(1./(60.f*100.f)), active_extruder);
 #else
-     plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate*feedmultiply*(1./(60.f*100.f)), active_extruder);
+     plan_buffer_line_destinationXYZE(feedrate*feedmultiply*(1./(60.f*100.f)));
 #endif
   }
 
@@ -9494,51 +9678,95 @@ static void handleSafetyTimer()
 }
 #endif //SAFETYTIMER
 
-#define FS_CHECK_COUNT 15
+#ifdef IR_SENSOR_ANALOG
+#define FS_CHECK_COUNT 16
+/// Switching mechanism of the fsensor type.
+/// Called from 2 spots which have a very similar behavior
+/// 1: ClFsensorPCB::_Old -> ClFsensorPCB::_Rev04 and print _i("FS v0.4 or newer")
+/// 2: ClFsensorPCB::_Rev04 -> oFsensorPCB=ClFsensorPCB::_Old and print _i("FS v0.3 or older")
+void manage_inactivity_IR_ANALOG_Check(uint16_t &nFSCheckCount, ClFsensorPCB isVersion, ClFsensorPCB switchTo, const char *statusLineTxt_P) {
+    bool bTemp = (!CHECK_ALL_HEATERS);
+    bTemp = bTemp && (menu_menu == lcd_status_screen);
+    bTemp = bTemp && ((oFsensorPCB == isVersion) || (oFsensorPCB == ClFsensorPCB::_Undef));
+    bTemp = bTemp && fsensor_enabled;
+    if (bTemp) {
+        nFSCheckCount++;
+        if (nFSCheckCount > FS_CHECK_COUNT) {
+            nFSCheckCount = 0; // not necessary
+            oFsensorPCB = switchTo;
+            eeprom_update_byte((uint8_t *)EEPROM_FSENSOR_PCB, (uint8_t)oFsensorPCB);
+            printf_IRSensorAnalogBoardChange();
+            lcd_setstatuspgm(statusLineTxt_P);
+        }
+    } else {
+        nFSCheckCount = 0;
+    }
+}
+#endif
+
 void manage_inactivity(bool ignore_stepper_queue/*=false*/) //default argument set in Marlin.h
 {
 #ifdef FILAMENT_SENSOR
 bool bInhibitFlag;
 #ifdef IR_SENSOR_ANALOG
-static uint8_t nFSCheckCount=0;
+static uint16_t nFSCheckCount=0;
 #endif // IR_SENSOR_ANALOG
 
 	if (mmu_enabled == false)
 	{
 //-//		if (mcode_in_progress != 600) //M600 not in progress
 #ifdef PAT9125
-          bInhibitFlag=(menu_menu==lcd_menu_extruder_info); // Support::ExtruderInfo menu active
+		bInhibitFlag=(menu_menu==lcd_menu_extruder_info); // Support::ExtruderInfo menu active
 #endif // PAT9125
 #ifdef IR_SENSOR
-          bInhibitFlag=(menu_menu==lcd_menu_show_sensors_state); // Support::SensorInfo menu active
+		bInhibitFlag=(menu_menu==lcd_menu_show_sensors_state); // Support::SensorInfo menu active
 #ifdef IR_SENSOR_ANALOG
-          bInhibitFlag=bInhibitFlag||bMenuFSDetect; // Settings::HWsetup::FSdetect menu active
+		bInhibitFlag=bInhibitFlag||bMenuFSDetect; // Settings::HWsetup::FSdetect menu active
 #endif // IR_SENSOR_ANALOG
 #endif // IR_SENSOR
-          if ((mcode_in_progress != 600) && (eFilamentAction != FilamentAction::AutoLoad) && (!bInhibitFlag)) //M600 not in progress, preHeat @ autoLoad menu not active, Support::ExtruderInfo/SensorInfo menu not active
+		if ((mcode_in_progress != 600) && (eFilamentAction != FilamentAction::AutoLoad) && (!bInhibitFlag) && (menu_menu != lcd_move_e)) //M600 not in progress, preHeat @ autoLoad menu not active, Support::ExtruderInfo/SensorInfo menu not active
 		{
 			if (!moves_planned() && !IS_SD_PRINTING && !is_usb_printing && (lcd_commands_type != LcdCommands::Layer1Cal) && ! eeprom_read_byte((uint8_t*)EEPROM_WIZARD_ACTIVE))
 			{
 #ifdef IR_SENSOR_ANALOG
-                    bool bTemp=current_voltage_raw_IR>IRsensor_Hmin_TRESHOLD;
-                    bTemp=bTemp&&current_voltage_raw_IR<IRsensor_Hopen_TRESHOLD;
-                    bTemp=bTemp&&(!CHECK_ALL_HEATERS);
-                    bTemp=bTemp&&(menu_menu==lcd_status_screen);
-                    bTemp=bTemp&&((oFsensorPCB==ClFsensorPCB::_Old)||(oFsensorPCB==ClFsensorPCB::_Undef));
-                    bTemp=bTemp&&fsensor_enabled;
-                    if(bTemp)
-                    {
-                         nFSCheckCount++;
-                         if(nFSCheckCount>FS_CHECK_COUNT)
-                         {
-                              nFSCheckCount=0;    // not necessary
-                              oFsensorPCB=ClFsensorPCB::_Rev03b;
-                              eeprom_update_byte((uint8_t*)EEPROM_FSENSOR_PCB,(uint8_t)oFsensorPCB);
-                              printf_IRSensorAnalogBoardChange(true);
-                              lcd_setstatuspgm(_i("FS rev. 03b or newer"));
-                         }
-                    }
-                    else nFSCheckCount=0;
+				static uint16_t minVolt = Voltage2Raw(6.F), maxVolt = 0;
+				// detect min-max, some long term sliding window for filtration may be added
+				// avoiding floating point operations, thus computing in raw
+				if( current_voltage_raw_IR > maxVolt )maxVolt = current_voltage_raw_IR;
+				if( current_voltage_raw_IR < minVolt )minVolt = current_voltage_raw_IR;
+				
+#if 0 // Start: IR Sensor debug info
+				{ // debug print
+					static uint16_t lastVolt = ~0U;
+					if( current_voltage_raw_IR != lastVolt ){
+						printf_P(PSTR("fs volt=%4.2fV (min=%4.2f max=%4.2f)\n"), Raw2Voltage(current_voltage_raw_IR), Raw2Voltage(minVolt), Raw2Voltage(maxVolt) );
+						lastVolt = current_voltage_raw_IR;
+					}
+				}
+#endif // End: IR Sensor debug info
+				//! The trouble is, I can hold the filament in the hole in such a way, that it creates the exact voltage
+				//! to be detected as the new fsensor
+				//! We can either fake it by extending the detection window to a looooong time
+				//! or do some other countermeasures
+				
+				//! what we want to detect:
+				//! if minvolt gets below ~0.3V, it means there is an old fsensor
+				//! if maxvolt gets above 4.6V, it means we either have an old fsensor or broken cables/fsensor
+				//! So I'm waiting for a situation, when minVolt gets to range <0, 1.5> and maxVolt gets into range <3.0, 5>
+				//! If and only if minVolt is in range <0.3, 1.5> and maxVolt is in range <3.0, 4.6>, I'm considering a situation with the new fsensor
+				if( minVolt >= IRsensor_Ldiode_TRESHOLD && minVolt <= IRsensor_Lmax_TRESHOLD 
+				 && maxVolt >= IRsensor_Hmin_TRESHOLD && maxVolt <= IRsensor_Hopen_TRESHOLD
+				){
+					manage_inactivity_IR_ANALOG_Check(nFSCheckCount, ClFsensorPCB::_Old, ClFsensorPCB::_Rev04, _i("FS v0.4 or newer") ); ////c=18
+				} 
+				//! If and only if minVolt is in range <0.0, 0.3> and maxVolt is in range  <4.6, 5.0V>, I'm considering a situation with the old fsensor
+				//! Note, we are not relying on one voltage here - getting just +5V can mean an old fsensor or a broken new sensor - that's why
+				//! we need to have both voltages detected correctly to allow switching back to the old fsensor.
+				else if( minVolt < IRsensor_Ldiode_TRESHOLD 
+				 && maxVolt > IRsensor_Hopen_TRESHOLD && maxVolt <= IRsensor_VMax_TRESHOLD
+				){
+					manage_inactivity_IR_ANALOG_Check(nFSCheckCount, ClFsensorPCB::_Rev04, oFsensorPCB=ClFsensorPCB::_Old, _i("FS v0.3 or older")); ////c=18
+				}
 #endif // IR_SENSOR_ANALOG
 				if (fsensor_check_autoload())
 				{
@@ -9548,7 +9776,7 @@ static uint8_t nFSCheckCount=0;
 //-//					if (degHotend0() > EXTRUDE_MINTEMP)
 if(0)
 					{
-            Sound_MakeCustom(50,1000,false);
+						Sound_MakeCustom(50,1000,false);
 						loading_flag = true;
 						enquecommand_front_P((PSTR("M701")));
 					}
@@ -9559,20 +9787,17 @@ if(0)
 						show_preheat_nozzle_warning();
 						lcd_update_enable(true);
 */
-                              eFilamentAction=FilamentAction::AutoLoad;
-                              bFilamentFirstRun=false;
-                              if(target_temperature[0]>=EXTRUDE_MINTEMP)
-                              {
-                                   bFilamentPreheatState=true;
-//                                   mFilamentItem(target_temperature[0],target_temperature_bed);
-                                   menu_submenu(mFilamentItemForce);
-                              }
-                              else
-                              {
-                                   menu_submenu(lcd_generic_preheat_menu);
-                                   lcd_timeoutToStatus.start();
-                              }
-                         }
+						eFilamentAction=FilamentAction::AutoLoad;
+						bFilamentFirstRun=false;
+						if(target_temperature[0]>=EXTRUDE_MINTEMP){
+							bFilamentPreheatState=true;
+//							mFilamentItem(target_temperature[0],target_temperature_bed);
+							menu_submenu(mFilamentItemForce);
+						} else {
+							menu_submenu(lcd_generic_preheat_menu);
+							lcd_timeoutToStatus.start();
+						}
+					}
 				}
 			}
 			else
@@ -9746,6 +9971,24 @@ void Stop()
 
 bool IsStopped() { return Stopped; };
 
+void finishAndDisableSteppers()
+{
+  st_synchronize();
+  disable_x();
+  disable_y();
+  disable_z();
+  disable_e0();
+  disable_e1();
+  disable_e2();
+
+#ifndef LA_NOCOMPAT
+  // Steppers are disabled both when a print is stopped and also via M84 (which is additionally
+  // checked-for to indicate a complete file), so abuse this function to reset the LA detection
+  // state for the next print.
+  la10c_reset();
+#endif
+}
+
 #ifdef FAST_PWM_FAN
 void setPwmFrequency(uint8_t pin, int val)
 {
@@ -9837,16 +10080,16 @@ bool setTargetedHotend(int code, uint8_t &extruder)
           SERIAL_ECHORPGM(_n("M104 Invalid extruder "));////MSG_M104_INVALID_EXTRUDER
           break;
         case 105:
-          SERIAL_ECHO(_n("M105 Invalid extruder "));////MSG_M105_INVALID_EXTRUDER
+          SERIAL_ECHORPGM(_n("M105 Invalid extruder "));////MSG_M105_INVALID_EXTRUDER
           break;
         case 109:
-          SERIAL_ECHO(_n("M109 Invalid extruder "));////MSG_M109_INVALID_EXTRUDER
+          SERIAL_ECHORPGM(_n("M109 Invalid extruder "));////MSG_M109_INVALID_EXTRUDER
           break;
         case 218:
-          SERIAL_ECHO(_n("M218 Invalid extruder "));////MSG_M218_INVALID_EXTRUDER
+          SERIAL_ECHORPGM(_n("M218 Invalid extruder "));////MSG_M218_INVALID_EXTRUDER
           break;
         case 221:
-          SERIAL_ECHO(_n("M221 Invalid extruder "));////MSG_M221_INVALID_EXTRUDER
+          SERIAL_ECHORPGM(_n("M221 Invalid extruder "));////MSG_M221_INVALID_EXTRUDER
           break;
       }
       SERIAL_PROTOCOLLN((int)extruder);
@@ -9946,11 +10189,11 @@ static void wait_for_heater(long codenum, uint8_t extruder) {
 				}
 				else
 				{
-					SERIAL_PROTOCOLLN("?");
+					SERIAL_PROTOCOLLN('?');
 				}
 			}
 #else
-				SERIAL_PROTOCOLLN("");
+				SERIAL_PROTOCOLLN();
 #endif
 				codenum = _millis();
 		}
@@ -10077,16 +10320,16 @@ void bed_check(float x_dimension, float y_dimension, int x_points_num, int y_poi
 	card.openFile(filename_wldsd, false);
 
 	/*destination[Z_AXIS] = mesh_home_z_search;
-	//plan_buffer_line_curposXYZE(Z_LIFT_FEEDRATE, active_extruder);
+	//plan_buffer_line_curposXYZE(Z_LIFT_FEEDRATE);
 
-	plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], Z_LIFT_FEEDRATE, active_extruder);
+	plan_buffer_line_destinationXYZE(Z_LIFT_FEEDRATE);
 	for(int8_t i=0; i < NUM_AXIS; i++) {
 		current_position[i] = destination[i];
 	}
 	st_synchronize();
 	*/
 		destination[Z_AXIS] = measure_z_height;
-		plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], Z_LIFT_FEEDRATE, active_extruder);
+		plan_buffer_line_destinationXYZE(Z_LIFT_FEEDRATE);
 		for(int8_t i=0; i < NUM_AXIS; i++) {
 			current_position[i] = destination[i];
 		}
@@ -10111,9 +10354,9 @@ void bed_check(float x_dimension, float y_dimension, int x_points_num, int y_poi
 		if (iy & 1) ix = (x_points_num - 1) - ix; // Zig zag
 		float z0 = 0.f;
 		/*destination[Z_AXIS] = mesh_home_z_search;
-		//plan_buffer_line_curposXYZE(Z_LIFT_FEEDRATE, active_extruder);
+		//plan_buffer_line_curposXYZE(Z_LIFT_FEEDRATE);
 
-		plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], Z_LIFT_FEEDRATE, active_extruder);
+		plan_buffer_line_destinationXYZE(Z_LIFT_FEEDRATE);
 		for(int8_t i=0; i < NUM_AXIS; i++) {
 			current_position[i] = destination[i];
 		}
@@ -10126,8 +10369,8 @@ void bed_check(float x_dimension, float y_dimension, int x_points_num, int y_poi
 		destination[X_AXIS] = ix * (x_dimension / (x_points_num - 1)) + shift_x;
 		destination[Y_AXIS] = iy * (y_dimension / (y_points_num - 1)) + shift_y;
 
-        mesh_plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], XY_AXIS_FEEDRATE/6, active_extruder);
-        set_current_to_destination();
+		mesh_plan_buffer_line_destinationXYZE(XY_AXIS_FEEDRATE/6);
+		set_current_to_destination();
 		st_synchronize();
 
 	//	printf_P(PSTR("X = %f; Y= %f \n"), current_position[X_AXIS], current_position[Y_AXIS]);
@@ -10257,7 +10500,7 @@ void bed_analysis(float x_dimension, float y_dimension, int x_points_num, int y_
 		// There shall be always enough space reserved for these commands.
 		repeatcommand_front(); // repeat G80 with all its parameters
 		
-		enquecommand_front_P((PSTR("G28 W0")));
+		enquecommand_front_P(G28W0);
 		enquecommand_front_P((PSTR("G1 Z5")));
 		return;
 	}
@@ -10480,7 +10723,11 @@ float temp_comp_interpolation(float inp_temperature) {
 		if (i>0) EEPROM_read_B(EEPROM_PROBE_TEMP_SHIFT + (i-1) * 2, &shift[i]); //read shift in steps from EEPROM
 		temp_C[i] = 50 + i * 10; //temperature in C
 #ifdef PINDA_THERMISTOR
-		temp_C[i] = 35 + i * 5; //temperature in C
+		constexpr int start_compensating_temp = 35;
+		temp_C[i] = start_compensating_temp + i * 5; //temperature in degrees C
+#ifdef SUPERPINDA_SUPPORT
+    static_assert(start_compensating_temp >= PINDA_MINTEMP, "Temperature compensation start point is lower than PINDA_MINTEMP.");
+#endif //SUPERPINDA_SUPPORT
 #else
 		temp_C[i] = 50 + i * 10; //temperature in C
 #endif
@@ -10533,7 +10780,7 @@ float temp_comp_interpolation(float inp_temperature) {
 #ifdef PINDA_THERMISTOR
 float temp_compensation_pinda_thermistor_offset(float temperature_pinda)
 {
-	if (!temp_cal_active) return 0;
+	if (!eeprom_read_byte((unsigned char *)EEPROM_TEMP_CAL_ACTIVE)) return 0;
 	if (!calibration_status_pinda()) return 0;
 	return temp_comp_interpolation(temperature_pinda) / cs.axis_steps_per_unit[Z_AXIS];
 }
@@ -10550,12 +10797,12 @@ void long_pause() //long pause print
 	//lift z
 	current_position[Z_AXIS] += Z_PAUSE_LIFT;
 	if (current_position[Z_AXIS] > Z_MAX_POS) current_position[Z_AXIS] = Z_MAX_POS;
-	plan_buffer_line_curposXYZE(15, active_extruder);
+	plan_buffer_line_curposXYZE(15);
 
 	//Move XY to side
 	current_position[X_AXIS] = X_PAUSE_POS;
 	current_position[Y_AXIS] = Y_PAUSE_POS;
-	plan_buffer_line_curposXYZE(50, active_extruder);
+	plan_buffer_line_curposXYZE(50);
 
 	// Turn off the print fan
 	fanSpeed = 0;
@@ -10569,7 +10816,7 @@ void serialecho_temperatures() {
 	SERIAL_PROTOCOL((int)active_extruder);
 	SERIAL_PROTOCOLPGM(" B:");
 	SERIAL_PROTOCOL_F(degBed(), 1);
-	SERIAL_PROTOCOLLN("");
+	SERIAL_PROTOCOLLN();
 }
 
 #ifdef UVLO_SUPPORT
@@ -10665,7 +10912,7 @@ void uvlo_()
 
     // Retract
     current_position[E_AXIS] -= default_retraction;
-    plan_buffer_line_curposXYZE(95, active_extruder);
+    plan_buffer_line_curposXYZE(95);
     st_synchronize();
     disable_e0();
 
@@ -10678,7 +10925,7 @@ void uvlo_()
     current_position[Z_AXIS] += float(1024 - z_microsteps)
                                 / (z_res * cs.axis_steps_per_unit[Z_AXIS])
                                 + UVLO_Z_AXIS_SHIFT;
-    plan_buffer_line_curposXYZE(homing_feedrate[Z_AXIS]/60, active_extruder);
+    plan_buffer_line_curposXYZE(homing_feedrate[Z_AXIS]/60);
     st_synchronize();
     poweroff_z();
 
@@ -10718,6 +10965,10 @@ void uvlo_()
 #endif
 	eeprom_update_word((uint16_t*)(EEPROM_EXTRUDEMULTIPLY), (uint16_t)extrudemultiply);
 
+	eeprom_update_float((float*)(EEPROM_UVLO_ACCELL), cs.acceleration);
+	eeprom_update_float((float*)(EEPROM_UVLO_RETRACT_ACCELL), cs.retract_acceleration);
+	eeprom_update_float((float*)(EEPROM_UVLO_TRAVEL_ACCELL), cs.travel_acceleration);
+
     // Store the saved target
     eeprom_update_float((float*)(EEPROM_UVLO_SAVED_TARGET+0*4), saved_target[X_AXIS]);
     eeprom_update_float((float*)(EEPROM_UVLO_SAVED_TARGET+1*4), saved_target[Y_AXIS]);
@@ -10741,7 +10992,7 @@ void uvlo_()
     // All is set: with all the juice left, try to move extruder away to detach the nozzle completely from the print
     poweron_z();
     current_position[X_AXIS] = (current_position[X_AXIS] < 0.5f * (X_MIN_POS + X_MAX_POS)) ? X_MIN_POS : X_MAX_POS;
-    plan_buffer_line_curposXYZE(500, active_extruder);
+    plan_buffer_line_curposXYZE(500);
     st_synchronize();
 
     wdt_enable(WDTO_1S);
@@ -10792,7 +11043,7 @@ void uvlo_tiny()
         current_position[Z_AXIS] += float(1024 - z_microsteps)
                                     / (z_res * cs.axis_steps_per_unit[Z_AXIS])
                                     + UVLO_TINY_Z_AXIS_SHIFT;
-        plan_buffer_line_curposXYZE(homing_feedrate[Z_AXIS]/60, active_extruder);
+        plan_buffer_line_curposXYZE(homing_feedrate[Z_AXIS]/60);
         st_synchronize();
         poweroff_z();
 
@@ -10886,7 +11137,7 @@ void recover_print(uint8_t automatic) {
 	char cmd[30];
 	lcd_update_enable(true);
 	lcd_update(2);
-  lcd_setstatuspgm(_i("Recovering print    "));////MSG_RECOVERING_PRINT c=20 r=1
+  lcd_setstatuspgm(_i("Recovering print    "));////MSG_RECOVERING_PRINT c=20
 
   // Recover position, temperatures and extrude_multipliers
   bool mbl_was_active = recover_machine_state_after_power_panic();
@@ -10971,7 +11222,7 @@ bool recover_machine_state_after_power_panic()
 
   // 5) Set the physical positions from the logical positions using the world2machine transformation
   // This is only done to inizialize Z/E axes with physical locations, since X/Y are unknown.
-  plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
+  plan_set_position_curposXYZE();
 
   // 6) Power up the Z motors, mark their positions as known.
   axis_known_position[Z_AXIS] = true;
@@ -11062,6 +11313,13 @@ void restore_print_from_eeprom(bool mbl_was_active) {
     sprintf_P(cmd, PSTR("G1 Z%f"), eeprom_read_float((float*)(EEPROM_UVLO_CURRENT_POSITION_Z)));
 	enquecommand(cmd);
 
+    // Restore acceleration settings
+    float acceleration = eeprom_read_float((float*)(EEPROM_UVLO_ACCELL));
+    float retract_acceleration = eeprom_read_float((float*)(EEPROM_UVLO_RETRACT_ACCELL));
+    float travel_acceleration = eeprom_read_float((float*)(EEPROM_UVLO_TRAVEL_ACCELL));
+    sprintf_P(cmd, PSTR("M204 P%f R%f T%f"), acceleration, retract_acceleration, travel_acceleration);
+    enquecommand(cmd);
+
   // Unretract.
     sprintf_P(cmd, PSTR("G1 E%0.3f F2700"), default_retraction);
     enquecommand(cmd);
@@ -11363,7 +11621,6 @@ void restore_print_from_ram_and_continue(float e_move)
 		//not sd printing nor usb printing
 	}
 
-	SERIAL_PROTOCOLLNRPGM(MSG_OK); //dummy response because of octoprint is waiting for this
 	lcd_setstatuspgm(_T(WELCOME_MSG));
     saved_printing_type = PRINTING_TYPE_NONE;
 	saved_printing = false;
@@ -11395,9 +11652,9 @@ void print_mesh_bed_leveling_table()
   for (int8_t y = 0; y < MESH_NUM_Y_POINTS; ++ y)
     for (int8_t x = 0; x < MESH_NUM_Y_POINTS; ++ x) {
       MYSERIAL.print(mbl.z_values[y][x], 3);
-      SERIAL_ECHOPGM(" ");
+      SERIAL_ECHO(' ');
     }
-  SERIAL_ECHOLNPGM("");
+  SERIAL_ECHOLN();
 }
 
 uint16_t print_time_remaining() {
@@ -11445,7 +11702,7 @@ static void print_time_remaining_init()
 void load_filament_final_feed()
 {
 	current_position[E_AXIS]+= FILAMENTCHANGE_FINALFEED;
-	plan_buffer_line_curposXYZE(FILAMENTCHANGE_EFEED_FINAL, active_extruder);
+	plan_buffer_line_curposXYZE(FILAMENTCHANGE_EFEED_FINAL);
 }
 
 //! @brief Wait for user to check the state
@@ -11529,7 +11786,7 @@ void M600_wait_for_user(float HotendTempBckp) {
 				delay_keep_alive(4);
 
 				if (_millis() > waiting_start_time + (unsigned long)M600_TIMEOUT * 1000) {
-					lcd_display_message_fullscreen_P(_i("Press knob to preheat nozzle and continue."));////MSG_PRESS_TO_PREHEAT c=20 r=4
+					lcd_display_message_fullscreen_P(_i("Press the knob to preheat nozzle and continue."));////MSG_PRESS_TO_PREHEAT c=20 r=4
 					wait_for_user_state = 1;
 					setAllTargetHotends(0);
 					st_synchronize();
@@ -11590,7 +11847,7 @@ void M600_load_filament_movements()
 	plan_buffer_line_curposXYZE(50, active_extruder);
 #else
 	current_position[E_AXIS]+= FILAMENTCHANGE_FIRSTFEED ;
-	plan_buffer_line_curposXYZE(FILAMENTCHANGE_EFEED_FIRST, active_extruder); 
+	plan_buffer_line_curposXYZE(FILAMENTCHANGE_EFEED_FIRST);
 #endif                
 	load_filament_final_feed();
 	lcd_loading_filament();
@@ -11697,7 +11954,6 @@ void disable_force_z()
 #endif // TMC2130
 }
 
-
 void enable_force_z()
 {
 if(bEnableForce_z)

+ 4 - 1
Firmware/Sd2Card.cpp

@@ -767,6 +767,9 @@ uint8_t Sd2Card::waitStartBlock(void) {
 
 // Toshiba FlashAir support, copied from 
 // https://flashair-developers.com/en/documents/tutorials/arduino/
+// However, the official website was closed in September 2019.
+// There is an archived website (written in Japanese).
+// https://flashair-developers.github.io/website/docs/tutorials/arduino/2.html
 
 //------------------------------------------------------------------------------
 /** Perform Extention Read. */
@@ -774,7 +777,7 @@ uint8_t Sd2Card::readExt(uint32_t arg, uint8_t* dst, uint16_t count) {
   uint16_t i;
 
   // send command and argument.
-  if (cardCommand(CMD48, arg)) {
+  if (cardCommand(CMD48, arg) && cardCommand(CMD17, arg)) { // CMD48 for W-03, CMD17 for W-04
     error(SD_CARD_ERROR_CMD48);
     goto fail;
   }

+ 1 - 5
Firmware/Sd2PinMap.h

@@ -37,10 +37,6 @@ struct pin_map_t {
 || defined(__AVR_ATmega2560__)
 // Mega
 
-// Two Wire (aka I2C) ports
-uint8_t const SDA_PIN = 20;  // D1
-uint8_t const SCL_PIN = 21;  // D0
-
 #undef MOSI_PIN
 #undef MISO_PIN
 // SPI port
@@ -365,4 +361,4 @@ static inline __attribute__((always_inline))
 #endif  // Sd2PinMap_h
 
 
-#endif
+#endif

+ 2 - 2
Firmware/Timer.h

@@ -20,10 +20,10 @@ public:
     Timer();
     void start();
     void stop(){m_isRunning = false;}
-    bool running(){return m_isRunning;}
+    bool running()const {return m_isRunning;}
     bool expired(T msPeriod);
 protected:
-    T started(){return m_started;}
+    T started()const {return m_started;}
 private:
     bool m_isRunning;
     T m_started;

+ 1 - 1
Firmware/adc.c

@@ -19,7 +19,7 @@ uint16_t adc_sim_mask;
 
 void adc_init(void)
 {
-	printf_P(PSTR("adc_init\n"));
+	puts_P(PSTR("adc_init"));
 	adc_sim_mask = 0x00;
 	ADCSRA |= (1 << ADPS2) | (1 << ADPS1) | (1 << ADPS0);
 	ADMUX |= (1 << REFS0);

+ 4 - 4
Firmware/backlight.cpp

@@ -1,10 +1,10 @@
 //backlight.cpp
 
 #include "backlight.h"
+#include "macros.h"
 #include <avr/eeprom.h>
 #include <Arduino.h>
 #include "eeprom.h"
-#include "Marlin.h"
 #include "pins.h"
 #include "fastio.h"
 #include "Timer.h"
@@ -111,10 +111,10 @@ void backlight_init()
 
 #else //LCD_BL_PIN
 
-void force_bl_on(__attribute__((unused)) bool section_start) {}
+void force_bl_on(bool) {}
 void backlight_update() {}
 void backlight_init() {}
 void backlight_save() {}
-void backlight_wake(__attribute__((unused)) const uint8_t flashNo) {}
+void backlight_wake(const uint8_t) {}
 
-#endif //LCD_BL_PIN
+#endif //LCD_BL_PIN

+ 4 - 4
Firmware/bootapp.c

@@ -9,6 +9,8 @@
 extern FILE _uartout;
 #define uartout (&_uartout)
 
+extern void softReset();
+
 void bootapp_print_vars(void)
 {
 	fprintf_P(uartout, PSTR("boot_src_addr  =0x%08lx\n"), boot_src_addr);
@@ -39,8 +41,7 @@ void bootapp_ram2flash(uint16_t rptr, uint16_t fptr, uint16_t size)
 	boot_src_addr = (uint32_t)rptr;
 	boot_dst_addr = (uint32_t)fptr;
 	bootapp_print_vars();
-	wdt_enable(WDTO_15MS);
-	while(1);
+	softReset();
 }
 
 void bootapp_reboot_user0(uint8_t reserved)
@@ -50,6 +51,5 @@ void bootapp_reboot_user0(uint8_t reserved)
 	boot_app_flags = BOOT_APP_FLG_USER0;
 	boot_reserved = reserved;
 	bootapp_print_vars();
-	wdt_enable(WDTO_15MS);
-	while(1);
+	softReset();
 }

+ 63 - 43
Firmware/cardreader.cpp

@@ -1,4 +1,5 @@
 #include "Marlin.h"
+#include "cmdqueue.h"
 #include "cardreader.h"
 #include "ultralcd.h"
 #include "stepper.h"
@@ -61,9 +62,10 @@ char *createFilename(char *buffer,const dir_t &p) //buffer>12characters
 
 /**
 +* Dive into a folder and recurse depth-first to perform a pre-set operation lsAction:
-+*   LS_Count       - Add +1 to nrFiles for every file within the parent
-+*   LS_GetFilename - Get the filename of the file indexed by nrFiles
-+*   LS_SerialPrint - Print the full path and size of each file to serial output
++*   LS_Count           - Add +1 to nrFiles for every file within the parent
++*   LS_GetFilename     - Get the filename of the file indexed by nrFiles
++*   LS_SerialPrint     - Print the full path and size of each file to serial output
++*   LS_SerialPrint_LFN - Print the full path, long filename and size of each file to serial output
 +*/
 
 void CardReader::lsDive(const char *prepend, SdFile parent, const char * const match/*=NULL*/) {
@@ -89,9 +91,13 @@ void CardReader::lsDive(const char *prepend, SdFile parent, const char * const m
 				// Serial.print(path);
 				// Get a new directory object using the full path
 				// and dive recursively into it.
+				
+				if (lsAction == LS_SerialPrint_LFN)
+					printf_P(PSTR("DIR_ENTER: %s \"%s\"\n"), path, longFilename[0] ? longFilename : lfilename);
+				
 				SdFile dir;
 				if (!dir.open(parent, lfilename, O_READ)) {
-					if (lsAction == LS_SerialPrint) {
+					if (lsAction == LS_SerialPrint || lsAction == LS_SerialPrint_LFN) {
 						//SERIAL_ECHO_START();
 						//SERIAL_ECHOPGM(_i("Cannot open subdir"));////MSG_SD_CANT_OPEN_SUBDIR
 						//SERIAL_ECHOLN(lfilename);
@@ -99,6 +105,9 @@ void CardReader::lsDive(const char *prepend, SdFile parent, const char * const m
 				}
 				lsDive(path, dir);
 				// close() is done automatically by destructor of SdFile
+				
+				if (lsAction == LS_SerialPrint_LFN)
+					puts_P(PSTR("DIR_EXIT"));
 			}
 			else {
 				uint8_t pn0 = p.name[0];
@@ -113,12 +122,18 @@ void CardReader::lsDive(const char *prepend, SdFile parent, const char * const m
 						nrFiles++;
 						break;
 					
+					case LS_SerialPrint_LFN:
 					case LS_SerialPrint:
 						createFilename(filename, p);
 						SERIAL_PROTOCOL(prepend);
 						SERIAL_PROTOCOL(filename);
 						MYSERIAL.write(' ');
+						
+						if (lsAction == LS_SerialPrint_LFN)
+							printf_P(PSTR("\"%s\" "), LONGEST_FILENAME);
+						
 						SERIAL_PROTOCOLLN(p.fileSize);
+						manage_heater();
 						break;
 				
 					case LS_GetFilename:
@@ -159,9 +174,9 @@ void CardReader::lsDive(const char *prepend, SdFile parent, const char * const m
 		} // while readDir
 }
 
-void CardReader::ls() 
+void CardReader::ls(bool printLFN)
 {
-  lsAction=LS_SerialPrint;
+  lsAction = printLFN ? LS_SerialPrint_LFN : LS_SerialPrint;
   //if(lsAction==LS_Count)
   //nrFiles=0;
 
@@ -243,6 +258,8 @@ void CardReader::release()
 {
   sdprinting = false;
   cardOK = false;
+  SERIAL_ECHO_START;
+  SERIAL_ECHOLNRPGM(_n("SD card released"));////MSG_SD_CARD_RELEASED
 }
 
 void CardReader::startFileprint()
@@ -331,7 +348,7 @@ void CardReader::diveSubfolder (const char *fileName, SdFile& dir)
                 {
                     SERIAL_PROTOCOLRPGM(MSG_SD_OPEN_FILE_FAIL);
                     SERIAL_PROTOCOL(subdirname);
-                    SERIAL_PROTOCOLLNPGM(".");
+                    SERIAL_PROTOCOLLN('.');
                     return;
                 }
                 else
@@ -424,13 +441,13 @@ void CardReader::openFile(const char* name,bool read, bool replace_current/*=tru
       SERIAL_PROTOCOLLNRPGM(_N("File selected"));////MSG_SD_FILE_SELECTED
       getfilename(0, fname);
       lcd_setstatus(longFilename[0] ? longFilename : fname);
-      lcd_setstatus("SD-PRINTING         ");
+      lcd_setstatuspgm(PSTR("SD-PRINTING"));
     }
     else
     {
       SERIAL_PROTOCOLRPGM(MSG_SD_OPEN_FILE_FAIL);
       SERIAL_PROTOCOL(fname);
-      SERIAL_PROTOCOLLNPGM(".");
+      SERIAL_PROTOCOLLN('.');
     }
   }
   else 
@@ -439,7 +456,7 @@ void CardReader::openFile(const char* name,bool read, bool replace_current/*=tru
     {
       SERIAL_PROTOCOLRPGM(MSG_SD_OPEN_FILE_FAIL);
       SERIAL_PROTOCOL(fname);
-      SERIAL_PROTOCOLLNPGM(".");
+      SERIAL_PROTOCOLLN('.');
     }
     else
     {
@@ -475,7 +492,7 @@ void CardReader::removeFile(const char* name)
     {
       SERIAL_PROTOCOLPGM("Deletion failed, File: ");
       SERIAL_PROTOCOL(fname);
-      SERIAL_PROTOCOLLNPGM(".");
+      SERIAL_PROTOCOLLN('.');
     }
   
 }
@@ -485,33 +502,38 @@ uint32_t CardReader::getFileSize()
 	return filesize;
 }
 
-void CardReader::getStatus()
+void CardReader::getStatus(bool arg_P)
 {
-  if(sdprinting)
-  {
-      if (isPrintPaused) {
-          SERIAL_PROTOCOLLNPGM("SD print paused");
-      }
-      else if (saved_printing) {
-          SERIAL_PROTOCOLLNPGM("Print saved");
-      }
-      else {
-          SERIAL_PROTOCOL(longFilename);
-          SERIAL_PROTOCOLPGM("\n");
-          SERIAL_PROTOCOLRPGM(_N("SD printing byte "));////MSG_SD_PRINTING_BYTE
-          SERIAL_PROTOCOL(sdpos);
-          SERIAL_PROTOCOLPGM("/");
-          SERIAL_PROTOCOLLN(filesize);
-          uint16_t time = _millis()/60000 - starttime/60000;
-          SERIAL_PROTOCOL(itostr2(time/60));
-          SERIAL_PROTOCOL(':');
-          SERIAL_PROTOCOL(itostr2(time%60));
-          SERIAL_PROTOCOLPGM("\n");
-      }
-  }
-  else {
-    SERIAL_PROTOCOLLNPGM("Not SD printing");
-  }
+    if (isPrintPaused)
+    {
+        if (saved_printing && (saved_printing_type == PRINTING_TYPE_SD))
+            SERIAL_PROTOCOLLNPGM("SD print paused");
+        else
+            SERIAL_PROTOCOLLNPGM("Print saved");
+    }
+    else if (sdprinting)
+    {
+        if (arg_P)
+        {
+            SERIAL_PROTOCOL('/');
+            for (uint8_t i = 0; i < getWorkDirDepth(); i++)
+                printf_P(PSTR("%s/"), dir_names[i]);
+            puts(filename);
+        }
+        else
+            SERIAL_PROTOCOLLN(LONGEST_FILENAME);
+        
+        SERIAL_PROTOCOLRPGM(_N("SD printing byte "));////MSG_SD_PRINTING_BYTE
+        SERIAL_PROTOCOL(sdpos);
+        SERIAL_PROTOCOL('/');
+        SERIAL_PROTOCOLLN(filesize);
+        uint16_t time = ( _millis() - starttime ) / 60000U;
+        SERIAL_PROTOCOL(itostr2(time/60));
+        SERIAL_PROTOCOL(':');
+        SERIAL_PROTOCOLLN(itostr2(time%60));
+    }
+    else
+        SERIAL_PROTOCOLLNPGM("Not SD printing");
 }
 void CardReader::write_command(char *buf)
 {
@@ -545,7 +567,7 @@ void CardReader::write_command_no_newline(char *buf)
   {
     SERIAL_ERROR_START;
     SERIAL_ERRORLNRPGM(MSG_SD_ERR_WRITE_TO_FILE);
-    MYSERIAL.println("An error while writing to the SD Card.");
+    SERIAL_PROTOCOLLNPGM("An error while writing to the SD Card.");
   }
 }
 
@@ -735,7 +757,7 @@ void CardReader::presort() {
 		// Never sort more than the max allowed
 		// If you use folders to organize, 20 may be enough
 		if (fileCnt > SDSORT_LIMIT) {
-			lcd_show_fullscreen_message_and_wait_P(_i("Some files will not be sorted. Max. No. of files in 1 folder for sorting is 100."));////MSG_FILE_CNT c=20 r=4
+			lcd_show_fullscreen_message_and_wait_P(_i("Some files will not be sorted. Max. No. of files in 1 folder for sorting is 100."));////MSG_FILE_CNT c=20 r=6
 			fileCnt = SDSORT_LIMIT;
 		}
 		lcd_clear();
@@ -872,8 +894,7 @@ void CardReader::presort() {
 				for (int column = 0; column < 20; column++) {
 					if (column < (percent / 5))
 					{
-						lcd_set_cursor(column, 2);
-						lcd_print('\x01'); //simple progress bar
+						lcd_putc_at(column, 2, '\x01'); //simple progress bar
 					}
 				}
 				counter++;
@@ -951,8 +972,7 @@ void CardReader::presort() {
 #if !SDSORT_USES_RAM //show progresss bar only if slow sorting method is used
 	for (int column = 0; column <= 19; column++)
 	{
-		lcd_set_cursor(column, 2);
-		lcd_print('\x01'); //simple progress bar
+		lcd_putc_at(column, 2, '\x01'); //simple progress bar
 	}
 	_delay(300);
 	lcd_set_degree();

+ 4 - 4
Firmware/cardreader.h

@@ -3,10 +3,10 @@
 
 #ifdef SDSUPPORT
 
-#define MAX_DIR_DEPTH 10
+#define MAX_DIR_DEPTH 6
 
 #include "SdFile.h"
-enum LsAction {LS_SerialPrint,LS_Count,LS_GetFilename};
+enum LsAction {LS_SerialPrint,LS_SerialPrint_LFN,LS_Count,LS_GetFilename};
 class CardReader
 {
 public:
@@ -26,7 +26,7 @@ public:
   void release();
   void startFileprint();
   uint32_t getFileSize();
-  void getStatus();
+  void getStatus(bool arg_P);
   void printingHasFinished();
 
   void getfilename(uint16_t nr, const char* const match=NULL);
@@ -38,7 +38,7 @@ public:
   uint16_t getWorkDirDepth();
   
 
-  void ls();
+  void ls(bool printLFN);
   void chdir(const char * relpath);
   void updir();
   void setroot();

+ 17 - 7
Firmware/cmdqueue.cpp

@@ -18,6 +18,10 @@ int buflen = 0;
 // Therefore don't remove the command from the queue in the loop() function.
 bool cmdbuffer_front_already_processed = false;
 
+// Used for temporarely preventing accidental adding of Serial commands to the queue.
+// For now only check_file and the fancheck pause use this.
+bool cmdqueue_serial_disabled = false;
+
 int serial_count = 0;  //index of character read from serial line
 boolean comment_mode = false;
 char *strchr_pointer; // just a pointer to find chars in the command string like X, Y, Z, E, etc
@@ -91,14 +95,19 @@ bool cmdqueue_pop_front()
 
 void cmdqueue_reset()
 {
-    bufindr = 0;
-    bufindw = 0;
-    buflen = 0;
+	while (buflen)
+	{
+		// printf_P(PSTR("dumping: \"%s\" of type %hu\n"), cmdbuffer+bufindr+CMDHDRSIZE, CMDBUFFER_CURRENT_TYPE);
+		ClearToSend();
+		cmdqueue_pop_front();
+	}
+	bufindr = 0;
+	bufindw = 0;
 
 	//commands are removed from command queue after process_command() function is finished
 	//reseting command queue and enqueing new commands during some (usually long running) command processing would cause that new commands are immediately removed from queue (or damaged)
 	//this will ensure that all new commands which are enqueued after cmdqueue reset, will be always executed
-    cmdbuffer_front_already_processed = true; 
+	cmdbuffer_front_already_processed = true; 
 }
 
 // How long a string could be pushed to the front of the command queue?
@@ -390,7 +399,7 @@ void get_command()
 	}
 
   // start of serial line processing loop
-  while ((MYSERIAL.available() > 0 && !saved_printing) || (MYSERIAL.available() > 0 && isPrintPaused)) {  //is print is saved (crash detection or filament detection), dont process data from serial line
+  while (((MYSERIAL.available() > 0 && !saved_printing) || (MYSERIAL.available() > 0 && isPrintPaused)) && !cmdqueue_serial_disabled) {  //is print is saved (crash detection or filament detection), dont process data from serial line
 	
     char serial_char = MYSERIAL.read();
 /*    if (selectedSerialPort == 1)
@@ -582,8 +591,6 @@ void get_command()
        ((serial_char == '#' || serial_char == ':') && comment_mode == false) ||
        serial_count >= (MAX_CMD_SIZE - 1) || n==-1)
     {
-      if(card.eof()) break;
-
       if(serial_char=='#')
         stop_buffering=true;
 
@@ -631,6 +638,9 @@ void get_command()
 
       comment_mode = false; //for new command
       serial_count = 0; //clear buffer
+    
+      if(card.eof()) break;
+    
       // The following line will reserve buffer space if available.
       if (! cmdqueue_could_enqueue_back(MAX_CMD_SIZE-1, true))
           return;

+ 4 - 3
Firmware/cmdqueue.h

@@ -35,6 +35,7 @@ extern char cmdbuffer[BUFSIZE * (MAX_CMD_SIZE + 1) + CMDBUFFER_RESERVE_FRONT];
 extern size_t bufindr;
 extern int buflen;
 extern bool cmdbuffer_front_already_processed;
+extern bool cmdqueue_serial_disabled;
 
 // Type of a command, which is to be executed right now.
 #define CMDBUFFER_CURRENT_TYPE   (cmdbuffer[bufindr])
@@ -65,8 +66,8 @@ extern void cmdqueue_dump_to_serial_single_line(int nr, const char *p);
 extern void cmdqueue_dump_to_serial();
 #endif /* CMDBUFFER_DEBUG */
 extern bool cmd_buffer_empty();
-extern void enquecommand(const char *cmd, bool from_progmem);
-extern void enquecommand_front(const char *cmd, bool from_progmem);
+extern void enquecommand(const char *cmd, bool from_progmem = false);
+extern void enquecommand_front(const char *cmd, bool from_progmem = false);
 extern void repeatcommand_front();
 extern bool is_buffer_empty();
 extern void get_command();
@@ -74,7 +75,7 @@ extern uint16_t cmdqueue_calc_sd_length();
 
 // Return True if a character was found
 static inline bool    code_seen(char code) { return (strchr_pointer = strchr(CMDBUFFER_CURRENT_STRING, code)) != NULL; }
-static inline bool    code_seen(const char *code) { return (strchr_pointer = strstr(CMDBUFFER_CURRENT_STRING, code)) != NULL; }
+static inline bool    code_seen_P(const char *code_PROGMEM) { return (strchr_pointer = strstr_P(CMDBUFFER_CURRENT_STRING, code_PROGMEM)) != NULL; }
 static inline float   code_value()      { return strtod(strchr_pointer+1, NULL);}
 static inline long    code_value_long()    { return strtol(strchr_pointer+1, NULL, 10); }
 static inline int16_t code_value_short()   { return int16_t(strtol(strchr_pointer+1, NULL, 10)); };

+ 7 - 2
Firmware/config.h

@@ -23,7 +23,6 @@
 #define ADC_CALLBACK      adc_ready //callback function ()
 
 //SWI2C configuration
-#define SWI2C
 //#define SWI2C_SDA         20 //SDA on P3
 //#define SWI2C_SCL         21 //SCL on P3
 #define SWI2C_A8
@@ -31,7 +30,13 @@
 #define SWI2C_TMO         2048 //2048 cycles timeout
 
 //PAT9125 configuration
-#define PAT9125_SWI2C
+//#define PAT9125_SWSPI // software SPI mode (incomplete)
+#ifdef SWI2C_SCL
+#define PAT9125_SWI2C   // software I2C mode
+#else
+#define PAT9125_I2C     // hardware I2C mode
+#endif
+
 #define PAT9125_I2C_ADDR  0x75  //ID=LO
 //#define PAT9125_I2C_ADDR  0x79  //ID=HI
 //#define PAT9125_I2C_ADDR  0x73  //ID=NC

+ 4 - 0
Firmware/eeprom.cpp

@@ -93,6 +93,10 @@ void eeprom_init()
         eeprom_switch_to_next_sheet();
     }
     check_babystep();
+
+#ifdef PINDA_TEMP_COMP
+if (eeprom_read_byte((uint8_t*)EEPROM_PINDA_TEMP_COMPENSATION) == 0xff) eeprom_update_byte((uint8_t *)EEPROM_PINDA_TEMP_COMPENSATION, 0);
+#endif //PINDA_TEMP_COMP
 }
 
 //! @brief Get default sheet name for index

+ 31 - 58
Firmware/eeprom.h

@@ -81,6 +81,7 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP
 | :--				| :-- 		| :-- 									| :--:			| :--:					| :--												| :--:			| :--:
 | 0x0FFFh 4095		| uchar    	| EEPROM_SILENT 						| 00h 0			| ffh 255				| TMC Stealth mode: __off__ / miniRambo Power mode	| LCD menu		| D3 Ax0fff C1
 | ^ 				| ^ 		| ^										| 01h 1			| ^						| TMC Stealth mode: __on__ / miniRambo Silent mode	| ^				| ^ 
+| ^ 				| ^ 		| ^										| 02h 2			| ^						| miniRambo Auto mode								| ^				| ^ 
 | 0x0FFEh 4094		| uchar    	| EEPROM_LANG 							| 00h 0			| ffh 255		__L__	| English / LANG_ID_PRI								| LCD menu		| D3 Ax0ffe C1 
 | ^ 				| ^ 		| ^										| 01h 1			| ^						| Other language LANG_ID_SEC						| ^ 			| ^
 | 0x0FFCh 4092		| uint16	| EEPROM_BABYSTEP_X						| ???			| ff ffh 65535			| Babystep for X axis _unsued_						| ??? 			| D3 Ax0ffc C2
@@ -97,19 +98,9 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP
 | 0x0FF1h 4081		| uint32	| EEPROM_FILAMENTUSED					| ???			| 00 00 00 00h 0 __S/P__| Filament used in meters							| ??? 			| D3 Ax0ff1 C4
 | 0x0FEDh 4077		| uint32	| EEPROM_TOTALTIME						| ???			| 00 00 00 00h 0 __S/P__| Total print time									| ??? 			| D3 Ax0fed C4
 | 0x0FE5h 4069		| float		| EEPROM_BED_CALIBRATION_CENTER			| ???			| ff ff ff ffh			| ???											 	| ??? 			| D3 Ax0fe5 C8
-| ^					| ^			| ^										| ^				| ^						| ^													| ^ 			| ^
 | 0x0FDDh 4061		| float		| EEPROM_BED_CALIBRATION_VEC_X			| ???			| ff ff ff ffh			| ???											 	| ??? 			| D3 Ax0fdd C8
-| ^					| ^			| ^										| ^				| ^						| ^													| ^ 			| ^	
 | 0x0FD5h 4053		| float		| EEPROM_BED_CALIBRATION_VEC_Y			| ???			| ff ff ff ffh			| ???											 	| ??? 			| D3 Ax0fd5 C8
-| ^					| ^			| ^										| ^				| ^						| ^													| ^ 			| ^
 | 0x0FC5h 4037		| int16		| EEPROM_BED_CALIBRATION_Z_JITTER		| ???			| ff ffh 65535			| ???											 	| ??? 			| D3 Ax0fc5 C16
-| ^					| ^			| ^										| ^				| ^						| ^													| ^ 			| ^	
-| ^					| ^			| ^										| ^				| ^						| ^													| ^ 			| ^
-| ^					| ^			| ^										| ^				| ^						| ^													| ^ 			| ^
-| ^					| ^			| ^										| ^				| ^						| ^													| ^ 			| ^
-| ^					| ^			| ^										| ^				| ^						| ^													| ^ 			| ^
-| ^					| ^			| ^										| ^				| ^						| ^													| ^ 			| ^
-| ^					| ^			| ^										| ^				| ^						| ^													| ^ 			| ^
 | 0x0FC4h 4036		| bool		| EEPROM_FARM_MODE						| 00h 0			| ffh 255 		__P__	| Prusa farm mode: __off__							| G99 			| D3 Ax0fc4 C1
 | ^					| ^			| ^										| 01h 1			| ^						| Prusa farm mode: __on__							| G98			| ^
 | 0x0FC3h 4035		| free		| _EEPROM_FREE_NR1_						| ???			| ffh 255				| _Free EEPROM space_								| _free space_	| D3 Ax0fc3 C1
@@ -128,10 +119,6 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP
 | ^					| ^			| ^										| 01h 1			| ^						| Toshiba Air: __on__								| ^ 			| ^	
 | 0x0FBAh 4026		| uchar		| EEPROM_PRINT_FLAG						| ???			| ???					| _unsued_											| ??? 			| D3 Ax0fba C1
 | 0x0FB0h 4016		| int16		| EEPROM_PROBE_TEMP_SHIFT				| ???			| ???					| ???												| ??? 			| D3 Ax0fb0 C10
-| ^					| ^			| ^										| ^				| ^						| ^													| ^ 			| ^
-| ^					| ^			| ^										| ^				| ^						| ^													| ^ 			| ^
-| ^					| ^			| ^										| ^				| ^						| ^													| ^ 			| ^
-| ^					| ^			| ^										| ^				| ^						| ^													| ^ 			| ^
 | 0x0FAFh 4015		| bool		| EEPROM_TEMP_CAL_ACTIVE				| 00h 0			| 00h 0					| PINDA Temp cal.: __inactive__						| LCD menu		| D3 Ax0faf C1
 | ^					| ^			| ^										| ffh 255		| ^						| PINDA Temp cal.: __active__						| ^ 			| ^
 | 0x0FA7h 4007		| uint32	| EEPROM_BOWDEN_LENGTH					| ???			| ff 00 00 00h			| Bowden length										| ??? 			| D3 Ax0fae C8
@@ -142,16 +129,8 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP
 | ^					| ^			| ^										| 01h 1			| ^						| Power Panic flag: __active__						| ^ 			| ^
 | ^					| ^			| ^										| 02h 2			| ^						| Power Panic flag: __???__							| ^ 			| ^
 | 0x0F9Dh 3997		| float		| EEPROM_UVLO_CURRENT_POSITION			| ???			| ffh 255				| Power Panic position 								| ??? 			| D3 Ax0f9d C8
-| ^					| ^			| ^										| ^				| ^						| ^													| ^ 			| ^
 | 0x0F95h 3989		| char		| EEPROM_FILENAME						| ???			| ffh 255				| Power Panic Filename 								| ??? 			| D3 Ax0f95 C8
-| ^					| ^			| ^										| ^				| ^						| ^													| ^ 			| ^
-| ^					| ^			| ^										| ^				| ^						| ^													| ^ 			| ^
-| ^					| ^			| ^										| ^				| ^						| ^													| ^ 			| ^
-| ^					| ^			| ^										| ^				| ^						| ^													| ^ 			| ^
-| ^					| ^			| ^										| ^				| ^						| ^													| ^ 			| ^
-| ^					| ^			| ^										| ^				| ^						| ^													| ^ 			| ^
-| ^					| ^			| ^										| ^				| ^						| ^													| ^ 			| ^
-| 0x0F91h 39851		| uint32	| EEPROM_FILE_POSITION					| ???			| ff ff ff ffh			| Power Panic File Position							| ??? 			| D3 Ax0f91 C4
+| 0x0F91h 3985		| uint32	| EEPROM_FILE_POSITION					| ???			| ff ff ff ffh			| Power Panic File Position							| ??? 			| D3 Ax0f91 C4
 | 0x0F8Dh 3981		| float		| EEPROM_UVLO_CURRENT_POSITION_Z		| ???			| ff ff ff ffh			| Power Panic Z Position	 						| ^ 			| D3 Ax0f8d C4
 | 0x0F8Ch 3980		| ???		| EEPROM_UVLO_UNUSED_001				| ??? 			| ffh 255				| Power Panic _unused_								| ^ 			| D3 Ax0f8c C1
 | 0x0F8Bh 3979		| uint8		| EEPROM_UVLO_TARGET_BED				| ???			| ffh 255				| Power Panic Bed temperature						| ^ 			| D3 Ax0f8b C1
@@ -160,14 +139,6 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP
 | 0x0F87h 3975		| uint8		| EEPROM_FAN_CHECK_ENABLED				| 00h 0			| ???					| Fan Check __disabled__							| LCD menu		| D3 Ax0f87 C1
 | ^					| ^			| ^										| 01h 1			| ffh 255				| Fan Check __enabled__ 							| ^ 			| ^
 | 0x0F75h 3957		| uint16	| EEPROM_UVLO_MESH_BED_LEVELING			| ???			| ff ffh 65535			| Power Panic Mesh Bed Leveling						| ???			| D3 Ax0f75 C18 
-| ^					| ^			| ^										| ^				| ^						| ^													| ^ 			| ^
-| ^					| ^			| ^										| ^				| ^						| ^													| ^ 			| ^
-| ^					| ^			| ^										| ^				| ^						| ^													| ^ 			| ^
-| ^					| ^			| ^										| ^				| ^						| ^													| ^ 			| ^
-| ^					| ^			| ^										| ^				| ^						| ^													| ^ 			| ^
-| ^					| ^			| ^										| ^				| ^						| ^													| ^ 			| ^
-| ^					| ^			| ^										| ^				| ^						| ^													| ^ 			| ^
-| ^					| ^			| ^										| ^				| ^						| ^													| ^ 			| ^
 | 0x0F73h 3955		| uint16	| EEPROM_UVLO_Z_MICROSTEPS				| ???			| ff ffh 65535			| Power Panic Z microsteps							| ???			| D3 Ax0f73 C2 
 | 0x0F72h 3954		| uint8		| EEPROM_UVLO_E_ABS						| ???			| ffh 255				| Power Panic ??? position							| ???			| D3 Ax0f72 C1
 | 0x0F6Eh 3950		| foat		| EEPROM_UVLO_CURRENT_POSITION_E		| ???			| ff ff ff ffh			| Power Panic E position							| ???			| D3 Ax0f6e C4
@@ -202,7 +173,7 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP
 | 0x0F01h 3841		| uint16	| EEPROM_FERROR_COUNT_TOT				| 0000-fffe		| ff ffh		__S/P__	| Total filament sensor errors 						| ???			| D3 Ax0f01 C2
 | 0x0EFFh 3839		| uint16	| EEPROM_POWER_COUNT_TOT				| 0000-fffe		| ff ffh		__S/P__	| Total power failures		  						| ???			| D3 Ax0eff C2
 | 0x0EFEh 3838		| uint8		| EEPROM_TMC2130_HOME_X_ORIGIN			| ???			| ffh 255				| ???						  						| ???			| D3 Ax0efe C1
-| 0x0EFDh 3837		| uint8		| EEPROM	MC2130_HOME_X_BSTEPS			| ???			| ffh 255			| ???						  						| ???			| D3 Ax0efd C1
+| 0x0EFDh 3837		| uint8		| EEPROM	MC2130_HOME_X_BSTEPS		| ???			| ffh 255		    	| ???						  						| ???			| D3 Ax0efd C1
 | 0x0EFCh 3836		| uint8		| EEPROM_TMC2130_HOME_X_FSTEPS			| ???			| ffh 255				| ???						  						| ???			| D3 Ax0efc C1
 | 0x0EFBh 3835		| uint8		| EEPROM_TMC2130_HOME_Y_ORIGIN			| ???			| ffh 255				| ???						  						| ???			| D3 Ax0efb C1
 | 0x0EFAh 3834		| uint8		| EEPROM_TMC2130_HOME_Y_BSTEPS			| ???			| ffh 255				| ???						  						| ???			| D3 Ax0efa C1
@@ -256,28 +227,6 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP
 | ^					| ^			| ^										| 01h 1			| ^						| MMU2/s cutter: __enabled__						| ^				| ^
 | ^					| ^			| ^										| 02h 2			| ^						| MMU2/s cutter: __always__							| ^				| ^
 | 0x0DAE 3502		| uint16	| EEPROM_UVLO_MESH_BED_LEVELING_FULL	| ???			| ff ffh 65535			| Power panic Mesh bed leveling points 				| ???			| D3 Ax0dae C288
-| ^					| ^			| ^										| ???			| ^						| ^													| ^				| ^
-| ^					| ^			| ^										| ???			| ^						| ^													| ^				| ^
-| ^					| ^			| ^										| ???			| ^						| ^													| ^				| ^
-| ^					| ^			| ^										| ???			| ^						| ^													| ^				| ^
-| ^					| ^			| ^										| ???			| ^						| ^													| ^				| ^
-| ^					| ^			| ^										| ???			| ^						| ^													| ^				| ^
-| ^					| ^			| ^										| ???			| ^						| ^													| ^				| ^
-| ^					| ^			| ^										| ???			| ^						| ^													| ^				| ^
-| ^					| ^			| ^										| ???			| ^						| ^													| ^				| ^
-| ^					| ^			| ^										| ???			| ^						| ^													| ^				| ^
-| ^					| ^			| ^										| ???			| ^						| ^													| ^				| ^
-| ^					| ^			| ^										| ???			| ^						| ^													| ^				| ^
-| ^					| ^			| ^										| ???			| ^						| ^													| ^				| ^
-| ^					| ^			| ^										| ???			| ^						| ^													| ^				| ^
-| ^					| ^			| ^										| ???			| ^						| ^													| ^				| ^
-| ^					| ^			| ^										| ???			| ^						| ^													| ^				| ^
-| ^					| ^			| ^										| ???			| ^						| ^													| ^				| ^
-| ^					| ^			| ^										| ???			| ^						| ^													| ^				| ^
-| ^					| ^			| ^										| ???			| ^						| ^													| ^				| ^
-| ^					| ^			| ^										| ???			| ^						| ^													| ^				| ^
-| ^					| ^			| ^										| ???			| ^						| ^													| ^				| ^
-| ^					| ^			| ^										| ???			| ^						| ^													| ^				| ^
 | 0x0DAD 3501		| uint8		| EEPROM_MBL_TYPE						| ???			| ffh 255				| Mesh bed leveling precision 		_unused atm_	| ???			| D3 Ax0dad C1
 | 0x0DAC 3500		| bool		| EEPROM_MBL_MAGNET_ELIMINATION			| 01h 1			| ffh 255				| Mesh bed leveling does: __ignores__ magnets		| LCD menu		| D3 Ax0dac C1
 | ^					| ^			| ^										| 00h 0			| ^						| Mesh bed leveling does: __NOT ignores__ magnets	| ^				| ^
@@ -293,9 +242,11 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP
 | ^					| ^			| ^										| 00h 0			| ^						| Check mode for nozzle is: __none__				| ^				| ^
 | 0x0DA7 3495		| uint8		| EEPROM_NOZZLE_DIAMETER				| 28h 40		| ffh 255				| Nozzle diameter is: __40 or 0.40mm__				| LCD menu		| D3 Ax0da7 C1
 | ^					| ^			| ^										| 3ch 60		| ^						| Nozzle diameter is: __60 or 0.60mm__				| ^				| ^
+| ^					| ^			| ^										| 3ch 80		| ^						| Nozzle diameter is: __80 or 0.80mm__				| ^				| ^
 | ^					| ^			| ^										| 19h 25		| ^						| Nozzle diameter is: __25 or 0.25mm__				| ^				| ^
 | 0x0DA5 3493		| uint16	| EEPROM_NOZZLE_DIAMETER_uM				| 9001h			| ff ffh 65535			| Nozzle diameter is: __400um__						| LCD menu		| D3 Ax0da5 C2
 | ^					| ^			| ^										| 5802h			| ^						| Nozzle diameter is: __600um__						| ^				| ^
+| ^					| ^			| ^										| 2003h			| ^						| Nozzle diameter is: __800um__						| ^				| ^
 | ^					| ^			| ^										| fa00h			| ^						| Nozzle diameter is: __250um__						| ^				| ^
 | 0x0DA4 3492		| uint8		| EEPROM_CHECK_MODEL					| 01h 1			| ffh 255				| Check mode for printer model is: __warn__			| LCD menu		| D3 Ax0da4 C1
 | ^					| ^			| ^										| 02h 0			| ^						| Check mode for printer model is: __strict__		| ^				| ^
@@ -340,8 +291,9 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP
 | 0x0D9F 3487		| uint8		| ^										| 00h 0			| ffh 255				| 8th sheet - bed temp 								| ^				| D3 Ax0d9f C1	
 | 0x0DA0 3488		| uint8		| ^										| 00h 0			| ffh 255				| 8th sheet - PINDA temp 							| ^				| D3 Ax0da0 C1	
 | 0x0DA1 3489		| uint8		| ???									| 00h 0			| ffh 255				| ???												| ???			| D3 Ax0da1 C1
-| 0x0D48 3400		| uint8		| EEPROM_FSENSOR_PCB					| ???			| ffh 255				| Filament Sensor type old vs new					| ???			| D3 Ax0d48 C1
-| ^					| ^			| ^										| ???			| ^						| Filament Sensor type ???							| ^				| ^
+| 0x0D48 3400		| uint8		| EEPROM_FSENSOR_PCB					| ffh 255		| ffh 255				| Filament Sensor type IR unknown					| LCD Support	| D3 Ax0d48 C1
+| ^					| ^			| ^										| 00h 0			| ^						| Filament Sensor type IR 0.3 or older				| ^				| ^
+| ^					| ^			| ^										| 01h 1			| ^						| Filament Sensor type IR 0.4 or newer				| ^				| ^
 | 0x0D47 3399		| uint8		| EEPROM_FSENSOR_ACTION_NA				| 00h 0			| ffh 255				| Filament Sensor action: __Continue__				| LCD menu		| D3 Ax0d47 C1
 | ^					| ^			| ^										| 01h 1			| ^						| Filament Sensor action: __Pause__					| ^				| ^
 | 0x0D37 3383		| float		| EEPROM_UVLO_SAVED_TARGET				| ???			| ff ff ff ffh			| Power panic saved target all-axis					| ???			| D3 Ax0d37 C16
@@ -357,8 +309,20 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP
 | ^					| ^			| ^										| 00h 0			| ^						| LCD backlight mode: __Dim__						| ^				| ^
 | 0x0D30 3376		| uint16	| EEPROM_BACKLIGHT_TIMEOUT				| 01 00 - ff ff | 0a 00h 65535			| LCD backlight timeout: __10__ seconds				| LCD menu		| D3 Ax0d30 C2
 | 0x0D2C 3372		| float		| EEPROM_UVLO_LA_K						| ???			| ff ff ff ffh			| Power panic saved Linear Advanced K value			| ???			| D3 Ax0d2c C4
+| 0x0D2B 3371		| uint8		| EEPROM_ALTFAN_OVERRIDE				| ffh 255		| ffh 255				| ALTFAN override unknown state						| LCD menu		| D3 Ax0d2b C1
+| ^					| ^			| ^										| 00h 0			| ^						| ALTFAN override deactivated						| ^				| ^
+| ^					| ^			| ^										| 01h 1			| ^						| ALTFAN override activated 						| ^				| ^
+| 0x0D2A 3370		| uint8		| EEPROM_EXPERIMENTAL_VISIBILITY		| ffh 255		| ffh 255				| Experimental menu visibility unknown state		| LCD menu		| D3 Ax0d2a C1
+| ^					| ^			| ^										| 00h 0			| ^						| Experimental menu visibility hidden				| ^				| ^
+| ^					| ^			| ^										| 01h 1			| ^						| Experimental menu visibility visible				| ^				| ^
+| 0x0D29 3369		| uint8		| EEPROM_PINDA_TEMP_COMPENSATION   		| ffh 255		| ffh 255				| PINDA temp compensation unknown state	            | LCD menu		| D3 Ax0d29 C1
+| ^					| ^			| ^										| 00h 0			| ^						| PINDA has no temp compensation PINDA v1/2    		| ^				| ^
+| ^					| ^			| ^										| 01h 1			| ^						| PINDA has temp compensation aka SuperPINDA       	| ^				| ^
+| 0x0D15 3349		| char[20]	| EEPROM_PRUSA_SN						| SN[19] == 0	| ffffffffffffffff...	| PRUSA Serial number string						| PRUSA SN		| D3 Ax0d15 C20
+| 0x0D11 3345		| float		| EEPROM_UVLO_ACCELL                	| ???			| ff ff ff ffh			| Power panic saved normal acceleration     		| ???			| D3 Ax0d11 C4
+| 0x0D0D 3341		| float		| EEPROM_UVLO_RETRACT_ACCELL			| ???			| ff ff ff ffh			| Power panic saved retract acceleration     		| ???			| D3 Ax0d0d C4
+| 0x0D09 3337		| float		| EEPROM_UVLO_TRAVEL_ACCELL				| ???			| ff ff ff ffh			| Power panic saved travel acceleration     		| ???			| D3 Ax0d09 C4
 
-  
 | Address begin		| Bit/Type 	| Name 									| Valid values	| Default/FactoryReset	| Description 										| Gcode/Function| Debug code
 | :--:				| :--: 		| :--: 									| :--:			| :--:					| :--:												| :--:			| :--:
 | 0x0012 18			| uint16	| EEPROM_FIRMWARE_VERSION_END			| ???			| ff ffh 65535			| ???												| ???			| D3 Ax0012 C2
@@ -559,8 +523,17 @@ static Sheets * const EEPROM_Sheets_base = (Sheets*)(EEPROM_SHEETS_BASE);
 
 #define EEPROM_UVLO_LA_K (EEPROM_BACKLIGHT_TIMEOUT-4) // float
 
+#define EEPROM_ALTFAN_OVERRIDE (EEPROM_UVLO_LA_K-1) //uint8
+#define EEPROM_EXPERIMENTAL_VISIBILITY (EEPROM_ALTFAN_OVERRIDE-1) //uint8
+#define EEPROM_PINDA_TEMP_COMPENSATION (EEPROM_EXPERIMENTAL_VISIBILITY-1) //uint8
+#define EEPROM_PRUSA_SN (EEPROM_PINDA_TEMP_COMPENSATION-20) //char[20]
+
+#define EEPROM_UVLO_ACCELL (EEPROM_PRUSA_SN-4) // float
+#define EEPROM_UVLO_RETRACT_ACCELL (EEPROM_UVLO_ACCELL-4) // float
+#define EEPROM_UVLO_TRAVEL_ACCELL (EEPROM_UVLO_RETRACT_ACCELL-4) // float
+
 //This is supposed to point to last item to allow EEPROM overrun check. Please update when adding new items.
-#define EEPROM_LAST_ITEM EEPROM_UVLO_LA_K
+#define EEPROM_LAST_ITEM EEPROM_UVLO_TRAVEL_ACCELL
 // !!!!!
 // !!!!! this is end of EEPROM section ... all updates MUST BE inserted before this mark !!!!!
 // !!!!!

+ 11 - 18
Firmware/fastio.h

@@ -7,15 +7,8 @@
 #define	_FASTIO_ARDUINO_H
 
 #include <avr/io.h>
+#include "macros.h"
 
-/*
-  utility functions
-*/
-
-#ifndef MASK
-/// MASKING- returns \f$2^PIN\f$
-#define MASK(PIN)  (1 << PIN)
-#endif
 
 /*
   magic I/O routines
@@ -23,20 +16,20 @@
 */
 
 /// Read a pin
-#define _READ(IO) ((bool)(DIO ## IO ## _RPORT & MASK(DIO ## IO ## _PIN)))
+#define _READ(IO) ((bool)(DIO ## IO ## _RPORT & _BV(DIO ## IO ## _PIN)))
 /// write to a pin
 // On some boards pins > 0x100 are used. These are not converted to atomic actions. An critical section is needed.
 
-#define _WRITE_NC(IO, v)  do { if (v) {DIO ##  IO ## _WPORT |= MASK(DIO ## IO ## _PIN); } else {DIO ##  IO ## _WPORT &= ~MASK(DIO ## IO ## _PIN); }; } while (0)
+#define _WRITE_NC(IO, v)  do { if (v) {DIO ##  IO ## _WPORT |= _BV(DIO ## IO ## _PIN); } else {DIO ##  IO ## _WPORT &= ~_BV(DIO ## IO ## _PIN); }; } while (0)
 
 #define _WRITE_C(IO, v)   do { if (v) { \
                                          CRITICAL_SECTION_START; \
-                                         {DIO ##  IO ## _WPORT |= MASK(DIO ## IO ## _PIN); }\
+                                         {DIO ##  IO ## _WPORT |= _BV(DIO ## IO ## _PIN); }\
                                          CRITICAL_SECTION_END; \
                                        }\
                                        else {\
                                          CRITICAL_SECTION_START; \
-                                         {DIO ##  IO ## _WPORT &= ~MASK(DIO ## IO ## _PIN); }\
+                                         {DIO ##  IO ## _WPORT &= ~_BV(DIO ## IO ## _PIN); }\
                                          CRITICAL_SECTION_END; \
                                        }\
                                      }\
@@ -45,20 +38,20 @@
 #define _WRITE(IO, v)  do {  if (&(DIO ##  IO ## _RPORT) >= (uint8_t *)0x100) {_WRITE_C(IO, v); } else {_WRITE_NC(IO, v); }; } while (0)
 
 /// toggle a pin
-#define _TOGGLE(IO)  do {DIO ##  IO ## _RPORT = MASK(DIO ## IO ## _PIN); } while (0)
+#define _TOGGLE(IO)  do {DIO ##  IO ## _RPORT = _BV(DIO ## IO ## _PIN); } while (0)
 
 /// set pin as input
-#define	_SET_INPUT(IO) do {DIO ##  IO ## _DDR &= ~MASK(DIO ## IO ## _PIN); } while (0)
+#define	_SET_INPUT(IO) do {DIO ##  IO ## _DDR &= ~_BV(DIO ## IO ## _PIN); } while (0)
 /// set pin as output
-#define	_SET_OUTPUT(IO) do {DIO ##  IO ## _DDR |=  MASK(DIO ## IO ## _PIN); } while (0)
+#define	_SET_OUTPUT(IO) do {DIO ##  IO ## _DDR |=  _BV(DIO ## IO ## _PIN); } while (0)
 
 /// check if pin is an input
-#define	_GET_INPUT(IO)  ((DIO ## IO ## _DDR & MASK(DIO ## IO ## _PIN)) == 0)
+#define	_GET_INPUT(IO)  ((DIO ## IO ## _DDR & _BV(DIO ## IO ## _PIN)) == 0)
 /// check if pin is an output
-#define	_GET_OUTPUT(IO)  ((DIO ## IO ## _DDR & MASK(DIO ## IO ## _PIN)) != 0)
+#define	_GET_OUTPUT(IO)  ((DIO ## IO ## _DDR & _BV(DIO ## IO ## _PIN)) != 0)
 
 /// check if pin is an timer
-#define	_GET_TIMER(IO)  ((DIO ## IO ## _PWM)
+#define	_GET_TIMER(IO)  (DIO ## IO ## _PWM)
 
 //  why double up on these macros? see http://gcc.gnu.org/onlinedocs/cpp/Stringification.html
 

+ 1 - 0
Firmware/first_lay_cal.cpp

@@ -7,6 +7,7 @@
 #include "Configuration_prusa.h"
 #include "language.h"
 #include "Marlin.h"
+#include "cmdqueue.h"
 #include "mmu.h"
 #include <avr/pgmspace.h>
 

+ 181 - 125
Firmware/fsensor.cpp

@@ -6,7 +6,6 @@
 #include <avr/pgmspace.h>
 #include "pat9125.h"
 #include "stepper.h"
-#include "io_atmega2560.h"
 #include "cmdqueue.h"
 #include "ultralcd.h"
 #include "mmu.h"
@@ -130,7 +129,7 @@ unsigned long nIRsensorLastTime;
 
 void fsensor_stop_and_save_print(void)
 {
-    printf_P(PSTR("fsensor_stop_and_save_print\n"));
+    puts_P(PSTR("fsensor_stop_and_save_print"));
     stop_and_save_print_to_ram(0, 0);
     fsensor_watch_runout = false;
 }
@@ -153,7 +152,7 @@ void fsensor_set_axis_steps_per_unit(float u)
 
 void fsensor_restore_print_and_continue(void)
 {
-    printf_P(PSTR("fsensor_restore_print_and_continue\n"));
+    puts_P(PSTR("fsensor_restore_print_and_continue"));
     fsensor_watch_runout = true;
 #ifdef PAT9125
     fsensor_reset_err_cnt();
@@ -165,53 +164,77 @@ void fsensor_restore_print_and_continue(void)
 // allowing new instructions to be inserted in the middle
 void fsensor_checkpoint_print(void)
 {
-    printf_P(PSTR("fsensor_checkpoint_print\n"));
+    puts_P(PSTR("fsensor_checkpoint_print"));
     stop_and_save_print_to_ram(0, 0);
     restore_print_from_ram_and_continue(0);
 }
 
+#ifdef IR_SENSOR_ANALOG
+const char* FsensorIRVersionText()
+{
+	switch(oFsensorPCB)
+	{
+		case ClFsensorPCB::_Old:
+			return _T(MSG_IR_03_OR_OLDER);
+		case ClFsensorPCB::_Rev04:
+			return _T(MSG_IR_04_OR_NEWER);
+		default:
+			return _T(MSG_IR_UNKNOWN);
+	}
+}
+#endif //IR_SENSOR_ANALOG
+
 void fsensor_init(void)
 {
 #ifdef PAT9125
 	uint8_t pat9125 = pat9125_init();
-     printf_P(PSTR("PAT9125_init:%hhu\n"), pat9125);
+	printf_P(PSTR("PAT9125_init:%hhu\n"), pat9125);
 #endif //PAT9125
-	uint8_t fsensor = eeprom_read_byte((uint8_t*)EEPROM_FSENSOR);
+	uint8_t fsensor_enabled = eeprom_read_byte((uint8_t*)EEPROM_FSENSOR);
 	fsensor_autoload_enabled=eeprom_read_byte((uint8_t*)EEPROM_FSENS_AUTOLOAD_ENABLED);
-     fsensor_not_responding = false;
+	fsensor_not_responding = false;
 #ifdef PAT9125
 	uint8_t oq_meassure_enabled = eeprom_read_byte((uint8_t*)EEPROM_FSENS_OQ_MEASS_ENABLED);
 	fsensor_oq_meassure_enabled = (oq_meassure_enabled == 1)?true:false;
-    fsensor_set_axis_steps_per_unit(cs.axis_steps_per_unit[E_AXIS]);
-
-	if (!pat9125)
-	{
-		fsensor = 0; //disable sensor
+	fsensor_set_axis_steps_per_unit(cs.axis_steps_per_unit[E_AXIS]);
+	
+	if (!pat9125){
+		fsensor_enabled = 0; //disable sensor
 		fsensor_not_responding = true;
 	}
 #endif //PAT9125
 #ifdef IR_SENSOR_ANALOG
-     bIRsensorStateFlag=false;
-     oFsensorPCB=(ClFsensorPCB)eeprom_read_byte((uint8_t*)EEPROM_FSENSOR_PCB);
-     oFsensorActionNA=(ClFsensorActionNA)eeprom_read_byte((uint8_t*)EEPROM_FSENSOR_ACTION_NA);
+	bIRsensorStateFlag=false;
+	oFsensorPCB = (ClFsensorPCB)eeprom_read_byte((uint8_t*)EEPROM_FSENSOR_PCB);
+	oFsensorActionNA = (ClFsensorActionNA)eeprom_read_byte((uint8_t*)EEPROM_FSENSOR_ACTION_NA);
+
+	// If the fsensor is not responding even at the start of the printer,
+	// set this flag accordingly to show N/A in Settings->Filament sensor.
+	// This is even valid for both fsensor board revisions (0.3 or older and 0.4).
+	// Must be done after reading what type of fsensor board we have
+	fsensor_not_responding = ! fsensor_IR_check();
 #endif //IR_SENSOR_ANALOG
-	if (fsensor)
+	if (fsensor_enabled){
 		fsensor_enable(false);                  // (in this case) EEPROM update is not necessary
-	else
+	} else {
 		fsensor_disable(false);                 // (in this case) EEPROM update is not necessary
+	}
 	printf_P(PSTR("FSensor %S"), (fsensor_enabled?PSTR("ENABLED"):PSTR("DISABLED")));
 #ifdef IR_SENSOR_ANALOG
-     printf_P(PSTR(" (sensor board revision: %S)\n"),(oFsensorPCB==ClFsensorPCB::_Rev03b)?PSTR("03b or newer"):PSTR("03 or older"));
+	printf_P(PSTR(" (sensor board revision:%S)\n"), FsensorIRVersionText());
 #else //IR_SENSOR_ANALOG
-     printf_P(PSTR("\n"));
+	MYSERIAL.println();
 #endif //IR_SENSOR_ANALOG
-	if (check_for_ir_sensor()) ir_sensor_detected = true;
-
+	if (check_for_ir_sensor()){
+		ir_sensor_detected = true;
+	}
 }
 
 bool fsensor_enable(bool bUpdateEEPROM)
 {
 #ifdef PAT9125
+    (void)bUpdateEEPROM; // silence unused warning in this variant
+
 	if (mmu_enabled == false) { //filament sensor is pat9125, enable only if it is working
 		uint8_t pat9125 = pat9125_init();
 		printf_P(PSTR("PAT9125_init:%hhu\n"), pat9125);
@@ -295,7 +318,7 @@ void fsensor_autoload_check_start(void)
 		printf_P(ERRMSG_PAT9125_NOT_RESP, 3);
 		return;
 	}
-	puts_P(_N("fsensor_autoload_check_start - autoload ENABLED\n"));
+	puts_P(_N("fsensor_autoload_check_start - autoload ENABLED"));
 	fsensor_autoload_y = pat9125_y; //save current y value
 	fsensor_autoload_c = 0; //reset number of changes counter
 	fsensor_autoload_sum = 0;
@@ -313,7 +336,7 @@ void fsensor_autoload_check_stop(void)
 	if (!fsensor_autoload_enabled) return;
 //	puts_P(_N("fsensor_autoload_check_stop 2\n"));
 	if (!fsensor_watch_autoload) return;
-	puts_P(_N("fsensor_autoload_check_stop - autoload DISABLED\n"));
+	puts_P(_N("fsensor_autoload_check_stop - autoload DISABLED"));
 	fsensor_autoload_sum = 0;
 	fsensor_watch_autoload = false;
 	fsensor_watch_runout = true;
@@ -393,7 +416,7 @@ void fsensor_oq_meassure_start(uint8_t skip)
 {
 	if (!fsensor_enabled) return;
 	if (!fsensor_oq_meassure_enabled) return;
-	printf_P(PSTR("fsensor_oq_meassure_start\n"));
+	puts_P(PSTR("fsensor_oq_meassure_start"));
 	fsensor_oq_skipchunk = skip;
 	fsensor_oq_samples = 0;
 	fsensor_oq_st_sum = 0;
@@ -426,7 +449,7 @@ bool fsensor_oq_result(void)
 {
 	if (!fsensor_enabled) return true;
 	if (!fsensor_oq_meassure_enabled) return true;
-	printf_P(_N("fsensor_oq_result\n"));
+	puts_P(_N("fsensor_oq_result"));
 	bool res_er_sum = (fsensor_oq_er_sum <= FSENSOR_OQ_MAX_ES);
 	printf_P(_N(" er_sum = %u %S\n"), fsensor_oq_er_sum, (res_er_sum?_OK:_NG));
 	bool res_er_max = (fsensor_oq_er_max <= FSENSOR_OQ_MAX_EM);
@@ -456,22 +479,8 @@ bool fsensor_oq_result(void)
 }
 #endif //FSENSOR_QUALITY
 
-ISR(FSENSOR_INT_PIN_VECT)
+FORCE_INLINE static void fsensor_isr(int st_cnt)
 {
-	if (mmu_enabled || ir_sensor_detected) return;
-	if (!((fsensor_int_pin_old ^ FSENSOR_INT_PIN_PIN_REG) & FSENSOR_INT_PIN_MASK)) return;
-	fsensor_int_pin_old = FSENSOR_INT_PIN_PIN_REG;
-
-    // prevent isr re-entry
-	static bool _lock = false;
-	if (_lock) return;
-	_lock = true;
-
-    // fetch fsensor_st_cnt atomically
-	int st_cnt = fsensor_st_cnt;
-	fsensor_st_cnt = 0;
-	sei();
-
 	uint8_t old_err_cnt = fsensor_err_cnt;
 	uint8_t pat9125_res = fsensor_oq_meassure?pat9125_update():pat9125_update_y();
 	if (!pat9125_res)
@@ -556,8 +565,28 @@ ISR(FSENSOR_INT_PIN_VECT)
 #endif //DEBUG_FSENSOR_LOG
 
 	pat9125_y = 0;
-	_lock = false;
-	return;
+}
+
+ISR(FSENSOR_INT_PIN_VECT)
+{
+    if (mmu_enabled || ir_sensor_detected) return;
+    if (!((fsensor_int_pin_old ^ FSENSOR_INT_PIN_PIN_REG) & FSENSOR_INT_PIN_MASK)) return;
+    fsensor_int_pin_old = FSENSOR_INT_PIN_PIN_REG;
+
+    // prevent isr re-entry
+    static bool _lock = false;
+    if (!_lock)
+    {
+        // fetch fsensor_st_cnt atomically
+        int st_cnt = fsensor_st_cnt;
+        fsensor_st_cnt = 0;
+
+        _lock = true;
+        sei();
+        fsensor_isr(st_cnt);
+        cli();
+        _lock = false;
+    }
 }
 
 void fsensor_setup_interrupt(void)
@@ -580,9 +609,8 @@ void fsensor_st_block_chunk(int cnt)
 	if (!fsensor_enabled) return;
 	fsensor_st_cnt += cnt;
 
-    // !!! bit toggling (PINxn <- 1) (for PinChangeInterrupt) does not work for some MCU pins
-    if (PIN_GET(FSENSOR_INT_PIN)) {PIN_VAL(FSENSOR_INT_PIN, LOW);}
-    else {PIN_VAL(FSENSOR_INT_PIN, HIGH);}
+	// !!! bit toggling (PINxn <- 1) (for PinChangeInterrupt) does not work for some MCU pins
+	WRITE(FSENSOR_INT_PIN, !READ(FSENSOR_INT_PIN));
 }
 #endif //PAT9125
 
@@ -590,7 +618,7 @@ void fsensor_st_block_chunk(int cnt)
 //! Common code for enqueing M600 and supplemental codes into the command queue.
 //! Used both for the IR sensor and the PAT9125
 void fsensor_enque_M600(){
-	printf_P(PSTR("fsensor_update - M600\n"));
+	puts_P(PSTR("fsensor_update - M600"));
 	eeprom_update_byte((uint8_t*)EEPROM_FERROR_COUNT, eeprom_read_byte((uint8_t*)EEPROM_FERROR_COUNT) + 1);
 	eeprom_update_word((uint16_t*)EEPROM_FERROR_COUNT_TOT, eeprom_read_word((uint16_t*)EEPROM_FERROR_COUNT_TOT) + 1);
 	enquecommand_front_P((PSTR("M600")));
@@ -604,48 +632,47 @@ void fsensor_enque_M600(){
 void fsensor_update(void)
 {
 #ifdef PAT9125
-		if (fsensor_watch_runout && (fsensor_err_cnt > FSENSOR_ERR_MAX))
-		{
-			fsensor_stop_and_save_print();
+    if (fsensor_watch_runout && (fsensor_err_cnt > FSENSOR_ERR_MAX))
+        {
+            fsensor_stop_and_save_print();
             KEEPALIVE_STATE(IN_HANDLER);
 
-			bool autoload_enabled_tmp = fsensor_autoload_enabled;
-			fsensor_autoload_enabled = false;
-			bool oq_meassure_enabled_tmp = fsensor_oq_meassure_enabled;
-			fsensor_oq_meassure_enabled = true;
+            bool autoload_enabled_tmp = fsensor_autoload_enabled;
+            fsensor_autoload_enabled = false;
+            bool oq_meassure_enabled_tmp = fsensor_oq_meassure_enabled;
+            fsensor_oq_meassure_enabled = true;
 
             // move the nozzle away while checking the filament
             current_position[Z_AXIS] += 0.8;
             if(current_position[Z_AXIS] > Z_MAX_POS) current_position[Z_AXIS] = Z_MAX_POS;
-            plan_buffer_line_curposXYZE(max_feedrate[Z_AXIS], active_extruder);
+            plan_buffer_line_curposXYZE(max_feedrate[Z_AXIS]);
             st_synchronize();
 
             // check the filament in isolation
             fsensor_reset_err_cnt();
-			fsensor_oq_meassure_start(0);
+            fsensor_oq_meassure_start(0);
             float e_tmp = current_position[E_AXIS];
             current_position[E_AXIS] -= 3;
-            plan_buffer_line_curposXYZE(250/60, active_extruder);
+            plan_buffer_line_curposXYZE(250/60);
             current_position[E_AXIS] = e_tmp;
-            plan_buffer_line_curposXYZE(200/60, active_extruder);
+            plan_buffer_line_curposXYZE(200/60);
             st_synchronize();
-			fsensor_oq_meassure_stop();
+            fsensor_oq_meassure_stop();
 
-			bool err = false;
-			err |= (fsensor_err_cnt > 0);                   // final error count is non-zero
-			err |= (fsensor_oq_er_sum > FSENSOR_OQ_MAX_ES); // total error count is above limit
-			err |= (fsensor_oq_yd_sum < FSENSOR_OQ_MIN_YD); // total measured distance is below limit
+            bool err = false;
+            err |= (fsensor_err_cnt > 0);                   // final error count is non-zero
+            err |= (fsensor_oq_er_sum > FSENSOR_OQ_MAX_ES); // total error count is above limit
+            err |= (fsensor_oq_yd_sum < FSENSOR_OQ_MIN_YD); // total measured distance is below limit
 
             fsensor_restore_print_and_continue();
             fsensor_autoload_enabled = autoload_enabled_tmp;
             fsensor_oq_meassure_enabled = oq_meassure_enabled_tmp;
-
             unsigned long now = _millis();
             if (!err && (now - fsensor_softfail_last) > FSENSOR_SOFTERR_DELTA)
                 fsensor_softfail_ccnt = 0;
             if (!err && fsensor_softfail_ccnt <= FSENSOR_SOFTERR_CMAX)
             {
-                printf_P(PSTR("fsensor_err_cnt = 0\n"));
+                puts_P(PSTR("fsensor_err_cnt = 0"));
                 ++fsensor_softfail;
                 ++fsensor_softfail_ccnt;
                 fsensor_softfail_last = now;
@@ -656,78 +683,107 @@ void fsensor_update(void)
                 fsensor_softfail_last = 0;
                 fsensor_enque_M600();
             }
-		}
+        }
 #else //PAT9125
-		if (CHECK_FSENSOR && ir_sensor_detected)
+        if (CHECK_FSENSOR && ir_sensor_detected)
         {
-               if(digitalRead(IR_SENSOR_PIN))
-               {                                  // IR_SENSOR_PIN ~ H
+            if(digitalRead(IR_SENSOR_PIN))
+            {                                  // IR_SENSOR_PIN ~ H
 #ifdef IR_SENSOR_ANALOG
-                    if(!bIRsensorStateFlag)
-                    {
-                         bIRsensorStateFlag=true;
-                         nIRsensorLastTime=_millis();
-                    }
-                    else
+                if(!bIRsensorStateFlag)
+                {
+                    bIRsensorStateFlag=true;
+                    nIRsensorLastTime=_millis();
+                }
+                else
+                {
+                    if((_millis()-nIRsensorLastTime)>IR_SENSOR_STEADY)
                     {
-                         if((_millis()-nIRsensorLastTime)>IR_SENSOR_STEADY)
-                         {
-                              uint8_t nMUX1,nMUX2;
-                              uint16_t nADC;
-                              bIRsensorStateFlag=false;
-                              // sequence for direct data reading from AD converter
-                              DISABLE_TEMPERATURE_INTERRUPT();
-                              nMUX1=ADMUX;        // ADMUX saving
-                              nMUX2=ADCSRB;
-                              adc_setmux(VOLT_IR_PIN);
-                              ADCSRA|=(1<<ADSC);  // first conversion after ADMUX change discarded (preventively)
-                              while(ADCSRA&(1<<ADSC))
-                                   ;
-                              ADCSRA|=(1<<ADSC);  // second conversion used
-                              while(ADCSRA&(1<<ADSC))
-                                   ;
-                              nADC=ADC;
-                              ADMUX=nMUX1;        // ADMUX restoring
-                              ADCSRB=nMUX2;
-                              ENABLE_TEMPERATURE_INTERRUPT();
-                              // end of sequence for ...
-                              if((oFsensorPCB==ClFsensorPCB::_Rev03b)&&((nADC*OVERSAMPLENR)>((int)IRsensor_Hopen_TRESHOLD)))
-                              {
-                                   fsensor_disable();
-                                   fsensor_not_responding = true;
-                                   printf_P(PSTR("IR sensor not responding (%d)!\n"),1);
-                                   if((ClFsensorActionNA)eeprom_read_byte((uint8_t*)EEPROM_FSENSOR_ACTION_NA)==ClFsensorActionNA::_Pause)
-                                   if(oFsensorActionNA==ClFsensorActionNA::_Pause)
-                                        lcd_pause_print();
-                              }
-                              else
-                              {
+                        uint8_t nMUX1,nMUX2;
+                        uint16_t nADC;
+                        bIRsensorStateFlag=false;
+                        // sequence for direct data reading from AD converter
+                        DISABLE_TEMPERATURE_INTERRUPT();
+                        nMUX1=ADMUX;        // ADMUX saving
+                        nMUX2=ADCSRB;
+                        adc_setmux(VOLT_IR_PIN);
+                        ADCSRA|=(1<<ADSC);  // first conversion after ADMUX change discarded (preventively)
+                        while(ADCSRA&(1<<ADSC))
+                            ;
+                        ADCSRA|=(1<<ADSC);  // second conversion used
+                        while(ADCSRA&(1<<ADSC))
+                            ;
+                        nADC=ADC;
+                        ADMUX=nMUX1;        // ADMUX restoring
+                        ADCSRB=nMUX2;
+                        ENABLE_TEMPERATURE_INTERRUPT();
+                        // end of sequence for ...
+                        // Detection of correct function of fsensor v04 - it must NOT read >4.6V
+                        // If it does, it means a disconnected cables or faulty board
+                        if( (oFsensorPCB == ClFsensorPCB::_Rev04) && ( (nADC*OVERSAMPLENR) > IRsensor_Hopen_TRESHOLD ) )
+                        {
+                            fsensor_disable();
+                            fsensor_not_responding = true;
+                            printf_P(PSTR("IR sensor not responding (%d)!\n"),1);
+                            if((ClFsensorActionNA)eeprom_read_byte((uint8_t*)EEPROM_FSENSOR_ACTION_NA)==ClFsensorActionNA::_Pause)
+
+                            // if we are printing and FS action is set to "Pause", force pause the print
+                            if(oFsensorActionNA==ClFsensorActionNA::_Pause)
+                                lcd_pause_print();
+                        }
+                        else
+                        {
 #endif //IR_SENSOR_ANALOG
-                                  fsensor_checkpoint_print();
-                                  fsensor_enque_M600();
+                            fsensor_checkpoint_print();
+                            fsensor_enque_M600();
 #ifdef IR_SENSOR_ANALOG
-                              }
-                         }
+                        }
                     }
-               }
-               else
-               {                                  // IR_SENSOR_PIN ~ L
-                    bIRsensorStateFlag=false;
+                }
+                   }
+                   else
+                   {                                  // IR_SENSOR_PIN ~ L
+                        bIRsensorStateFlag=false;
 #endif //IR_SENSOR_ANALOG
-               }
-		}
+            }
+        }
 #endif //PAT9125
 }
 
 #ifdef IR_SENSOR_ANALOG
-bool fsensor_IR_check()
-{
-uint16_t volt_IR_int;
-bool bCheckResult;
-
-volt_IR_int=current_voltage_raw_IR;
-bCheckResult=(volt_IR_int<((int)IRsensor_Lmax_TRESHOLD))||(volt_IR_int>((int)IRsensor_Hmin_TRESHOLD));
-bCheckResult=bCheckResult&&(!((oFsensorPCB==ClFsensorPCB::_Rev03b)&&(volt_IR_int>((int)IRsensor_Hopen_TRESHOLD))));
-return(bCheckResult);
+/// This is called only upon start of the printer or when switching the fsensor ON in the menu
+/// We cannot do temporal window checks here (aka the voltage has been in some range for a period of time)
+bool fsensor_IR_check(){
+    if( IRsensor_Lmax_TRESHOLD <= current_voltage_raw_IR && current_voltage_raw_IR <= IRsensor_Hmin_TRESHOLD ){
+        /// If the voltage is in forbidden range, the fsensor is ok, but the lever is mounted improperly.
+        /// Or the user is so creative so that he can hold a piece of fillament in the hole in such a genius way,
+        /// that the IR fsensor reading is within 1.5 and 3V ... this would have been highly unusual
+        /// and would have been considered more like a sabotage than normal printer operation
+        puts_P(PSTR("fsensor in forbidden range 1.5-3V - check sensor"));
+        return false; 
+    }
+    if( oFsensorPCB == ClFsensorPCB::_Rev04 ){
+        /// newer IR sensor cannot normally produce 4.6-5V, this is considered a failure/bad mount
+        if( IRsensor_Hopen_TRESHOLD <= current_voltage_raw_IR && current_voltage_raw_IR <= IRsensor_VMax_TRESHOLD ){
+            puts_P(PSTR("fsensor v0.4 in fault range 4.6-5V - unconnected"));
+            return false;
+        }
+        /// newer IR sensor cannot normally produce 0-0.3V, this is considered a failure 
+#if 0	//Disabled as it has to be decided if we gonna use this or not.
+        if( IRsensor_Hopen_TRESHOLD <= current_voltage_raw_IR && current_voltage_raw_IR <= IRsensor_VMax_TRESHOLD ){
+            puts_P(PSTR("fsensor v0.4 in fault range 0.0-0.3V - wrong IR sensor"));
+            return false;
+        }
+#endif
+    }
+    /// If IR sensor is "uknown state" and filament is not loaded > 1.5V return false
+#if 0
+    if( (oFsensorPCB == ClFsensorPCB::_Undef) && ( current_voltage_raw_IR > IRsensor_Lmax_TRESHOLD ) ){
+        puts_P(PSTR("Unknown IR sensor version and no filament loaded detected."));
+        return false;
+    }
+#endif
+    // otherwise the IR fsensor is considered working correctly
+    return true;
 }
 #endif //IR_SENSOR_ANALOG

+ 15 - 1
Firmware/fsensor.h

@@ -83,6 +83,7 @@ extern uint8_t fsensor_log;
 //! @}
 #endif //PAT9125
 
+#define VOLT_DIV_REF 5
 
 #ifdef IR_SENSOR_ANALOG
 #define IR_SENSOR_STEADY 10                       // [ms]
@@ -90,7 +91,7 @@ extern uint8_t fsensor_log;
 enum class ClFsensorPCB:uint_least8_t
 {
     _Old=0,
-    _Rev03b=1,
+    _Rev04=1,
     _Undef=EEPROM_EMPTY_VALUE
 };
 
@@ -103,8 +104,21 @@ enum class ClFsensorActionNA:uint_least8_t
 
 extern ClFsensorPCB oFsensorPCB;
 extern ClFsensorActionNA oFsensorActionNA;
+extern const char* FsensorIRVersionText();
 
 extern bool fsensor_IR_check();
+constexpr uint16_t Voltage2Raw(float V){
+	return ( V * 1023 * OVERSAMPLENR / VOLT_DIV_REF ) + 0.5F;
+}
+constexpr float Raw2Voltage(uint16_t raw){
+	return VOLT_DIV_REF*(raw / (1023.F * OVERSAMPLENR) );
+}
+constexpr uint16_t IRsensor_Ldiode_TRESHOLD = Voltage2Raw(0.3F); // ~0.3V, raw value=982
+constexpr uint16_t IRsensor_Lmax_TRESHOLD = Voltage2Raw(1.5F); // ~1.5V (0.3*Vcc), raw value=4910
+constexpr uint16_t IRsensor_Hmin_TRESHOLD = Voltage2Raw(3.0F); // ~3.0V (0.6*Vcc), raw value=9821
+constexpr uint16_t IRsensor_Hopen_TRESHOLD = Voltage2Raw(4.6F); // ~4.6V (N.C. @ Ru~20-50k, Rd'=56k, Ru'=10k), raw value=15059
+constexpr uint16_t IRsensor_VMax_TRESHOLD = Voltage2Raw(5.F); // ~5V, raw value=16368
+
 #endif //IR_SENSOR_ANALOG
 
 #endif //FSENSOR_H

+ 183 - 190
Firmware/heatbed_pwm.cpp

@@ -1,190 +1,183 @@
-#include <avr/io.h>
-#include <avr/interrupt.h>
-#include "io_atmega2560.h"
-
-// All this is about silencing the heat bed, as it behaves like a loudspeaker.
-// Basically, we want the PWM heating switched at 30Hz (or so) which is a well ballanced
-// frequency for both power supply units (i.e. both PSUs are reasonably silent).
-// The only trouble is the rising or falling edge of bed heating - that creates an audible click.
-// This audible click may be suppressed by making the rising or falling edge NOT sharp.
-// Of course, making non-sharp edges in digital technology is not easy, but there is a solution.
-// It is possible to do a fast PWM sequence with duty starting from 0 to 255.
-// Doing this at higher frequency than the bed "loudspeaker" can handle makes the click barely audible.
-// Technically:
-// timer0 is set to fast PWM mode at 62.5kHz (timer0 is linked to the bed heating pin) (zero prescaler)
-// To keep the bed switching at 30Hz - we don't want the PWM running at 62kHz all the time 
-// since it would burn the heatbed's MOSFET:
-// 16MHz/256 levels of PWM duty gives us 62.5kHz
-// 62.5kHz/256 gives ~244Hz, that is still too fast - 244/8 gives ~30Hz, that's what we need
-// So the automaton runs atop of inner 8 (or 16) cycles.
-// The finite automaton is running in the ISR(TIMER0_OVF_vect)
-
-// 2019-08-14 update: the original algorithm worked very well, however there were 2 regressions:
-// 1. 62kHz ISR requires considerable amount of processing power, 
-//    USB transfer speed dropped by 20%, which was most notable when doing short G-code segments.
-// 2. Some users reported TLed PSU started clicking when running at 120V/60Hz. 
-//    This looks like the original algorithm didn't maintain base PWM 30Hz, but only 15Hz
-// To address both issues, there is an improved approach based on the idea of leveraging
-// different CLK prescalers in some automaton states - i.e. when holding LOW or HIGH on the output pin,
-// we don't have to clock 62kHz, but we can increase the CLK prescaler for these states to 8 (or even 64).
-// That shall result in the ISR not being called that much resulting in regained performance
-// Theoretically this is relatively easy, however one must be very carefull handling the AVR's timer
-// control registers correctly, especially setting them in a correct order.
-// Some registers are double buffered, some changes are applied in next cycles etc.
-// The biggest problem was with the CLK prescaler itself - this circuit is shared among almost all timers,
-// we don't want to reset the prescaler counted value when transiting among automaton states.
-// Resetting the prescaler would make the PWM more precise, right now there are temporal segments
-// of variable period ranging from 0 to 7 62kHz ticks - that's logical, the timer must "sync"
-// to the new slower CLK after setting the slower prescaler value.
-// In our application, this isn't any significant problem and may be ignored.
-// Doing changes in timer's registers non-correctly results in artefacts on the output pin
-// - it can toggle unnoticed, which will result in bed clicking again.
-// That's why there are special transition states ZERO_TO_RISE and ONE_TO_FALL, which enable the
-// counter change its operation atomically and without artefacts on the output pin.
-// The resulting signal on the output pin was checked with an osciloscope. 
-// If there are any change requirements in the future, the signal must be checked with an osciloscope again,
-// ad-hoc changes may completely screw things up!
-
-// 2020-01-29 update: we are introducing a new option to the automaton that will allow us to force the output state
-// to either full ON or OFF. This is so that interference during the MBL probing is minimal.
-// To accomplish this goal we use bedPWMDisabled. It is only supposed to be used for brief periods of time as to
-// not make the bed temperature too unstable. Also, careful consideration should be used when using this
-// option as leaving this enabled will also keep the bed output in the state it stopped in.
-
-///! Definition off finite automaton states
-enum class States : uint8_t {
-	ZERO_START = 0,///< entry point of the automaton - reads the soft_pwm_bed value for the next whole PWM cycle
-	ZERO,          ///< steady 0 (OFF), no change for the whole period
-	ZERO_TO_RISE,  ///< metastate allowing the timer change its state atomically without artefacts on the output pin
-	RISE,          ///< 16 fast PWM cycles with increasing duty up to steady ON
-	RISE_TO_ONE,   ///< metastate allowing the timer change its state atomically without artefacts on the output pin
-	ONE,           ///< steady 1 (ON), no change for the whole period 
-	ONE_TO_FALL,   ///< metastate allowing the timer change its state atomically without artefacts on the output pin
-	FALL,          ///< 16 fast PWM cycles with decreasing duty down to steady OFF
-	FALL_TO_ZERO   ///< metastate allowing the timer change its state atomically without artefacts on the output pin
-};
-
-///! Inner states of the finite automaton
-static States state = States::ZERO_START;
-
-bool bedPWMDisabled = 0;
-
-///! Fast PWM counter is used in the RISE and FALL states (62.5kHz)
-static uint8_t slowCounter = 0;
-///! Slow PWM counter is used in the ZERO and ONE states (62.5kHz/8 or 64)
-static uint8_t fastCounter = 0;
-///! PWM counter for the whole cycle - a cache for soft_pwm_bed
-static uint8_t pwm = 0;
-
-///! The slow PWM duty for the next 30Hz cycle
-///! Set in the whole firmware at various places
-extern unsigned char soft_pwm_bed;
-
-/// fastMax - how many fast PWM steps to do in RISE and FALL states
-/// 16 is a good compromise between silenced bed ("smooth" edges)
-/// and not burning the switching MOSFET
-static const uint8_t fastMax = 16;
-
-/// Scaler 16->256 for fast PWM
-static const uint8_t fastShift = 4;
-
-/// Increment slow PWM counter by slowInc every ZERO or ONE state
-/// This allows for fine-tuning the basic PWM switching frequency
-/// A possible further optimization - use a 64 prescaler (instead of 8)
-/// increment slowCounter by 1
-/// but use less bits of soft PWM - something like soft_pwm_bed >> 2
-/// that may further reduce the CPU cycles required by the bed heating automaton
-/// Due to the nature of bed heating the reduced PID precision may not be a major issue, however doing 8x less ISR(timer0_ovf) may significantly improve the performance 
-static const uint8_t slowInc = 1;
-
-ISR(TIMER0_OVF_vect)          // timer compare interrupt service routine
-{
-	switch(state){
-	case States::ZERO_START:
-		if (bedPWMDisabled) return; // stay in the OFF state and do not change the output pin
-		pwm = soft_pwm_bed << 1;// expecting soft_pwm_bed to be 7bit!
-		if( pwm != 0 ){
-			state = States::ZERO;     // do nothing, let it tick once again after the 30Hz period
-		}
-		break;
-	case States::ZERO: // end of state ZERO - we'll either stay in ZERO or change to RISE
-		// In any case update our cache of pwm value for the next whole cycle from soft_pwm_bed
-		slowCounter += slowInc; // this does software timer_clk/256 or less (depends on slowInc)
-		if( slowCounter > pwm ){
-			return;
-		} // otherwise moving towards RISE
-		state = States::ZERO_TO_RISE; // and finalize the change in a transitional state RISE0
-		break;
-	// even though it may look like the ZERO state may be glued together with the ZERO_TO_RISE, don't do it
-	// the timer must tick once more in order to get rid of occasional output pin toggles.
-	case States::ZERO_TO_RISE:  // special state for handling transition between prescalers and switching inverted->non-inverted fast-PWM without toggling the output pin.
-		// It must be done in consequent steps, otherwise the pin will get flipped up and down during one PWM cycle.
-		// Also beware of the correct sequence of the following timer control registers initialization - it really matters!
-		state = States::RISE;     // prepare for standard RISE cycles
-		fastCounter = fastMax - 1;// we'll do 16-1 cycles of RISE
-		TCNT0 = 255;              // force overflow on the next clock cycle
-		TCCR0B = (1 << CS00);     // change prescaler to 1, i.e. 62.5kHz
-		TCCR0A &= ~(1 << COM0B0); // Clear OC0B on Compare Match, set OC0B at BOTTOM (non-inverting mode)
-		break;
-	case States::RISE:
-		OCR0B = (fastMax - fastCounter) << fastShift;
-		if( fastCounter ){
-			--fastCounter;
-		} else { // end of RISE cycles, changing into state ONE
-			state = States::RISE_TO_ONE;
-			OCR0B = 255;          // full duty
-			TCNT0 = 254;          // make the timer overflow in the next cycle
-			// @@TODO these constants are still subject to investigation
-		}
-		break;
-	case States::RISE_TO_ONE:
-		state = States::ONE;
-		OCR0B = 255;              // full duty
-		TCNT0 = 255;              // make the timer overflow in the next cycle
-		TCCR0B = (1 << CS01);     // change prescaler to 8, i.e. 7.8kHz
-		break;
-	case States::ONE:             // state ONE - we'll either stay in ONE or change to FALL
-		OCR0B = 255;
-		if (bedPWMDisabled) return; // stay in the ON state and do not change the output pin
-		slowCounter += slowInc;   // this does software timer_clk/256 or less
-		if( slowCounter < pwm ){
-			return;
-		}
-		if( (soft_pwm_bed << 1) >= (255 - slowInc - 1) ){  //@@TODO simplify & explain
-			// if slowInc==2, soft_pwm == 251 will be the first to do short drops to zero. 252 will keep full heating
-			return;           // want full duty for the next ONE cycle again - so keep on heating and just wait for the next timer ovf
-		}
-		// otherwise moving towards FALL
-		// @@TODO it looks like ONE_TO_FALL isn't necessary, there are no artefacts at all
-		state = States::ONE;//_TO_FALL;
-//		TCCR0B = (1 << CS00);      // change prescaler to 1, i.e. 62.5kHz
-//		break;
-//	case States::ONE_TO_FALL:
-//		OCR0B = 255;              // zero duty
-		state=States::FALL;
-		fastCounter = fastMax - 1;// we'll do 16-1 cycles of RISE
-		TCNT0 = 255;              // force overflow on the next clock cycle
-		TCCR0B = (1 << CS00);     // change prescaler to 1, i.e. 62.5kHz
-		// must switch to inverting mode already here, because it takes a whole PWM cycle and it would make a "1" at the end of this pwm cycle
-		// COM0B1 remains set both in inverting and non-inverting mode
-		TCCR0A |= (1 << COM0B0);  // inverting mode
-		break;
-	case States::FALL:
-		OCR0B = (fastMax - fastCounter) << fastShift; // this is the same as in RISE, because now we are setting the zero part of duty due to inverting mode
-		//TCCR0A |= (1 << COM0B0); // already set in ONE_TO_FALL
-		if( fastCounter ){
-			--fastCounter;
-		} else {   // end of FALL cycles, changing into state ZERO
-			state = States::FALL_TO_ZERO;
-			TCNT0 = 128; //@@TODO again - need to wait long enough to propagate the timer state changes
-			OCR0B = 255;
-		}
-		break;
-	case States::FALL_TO_ZERO:
-		state = States::ZERO_START; // go to read new soft_pwm_bed value for the next cycle
-		TCNT0 = 128;
-		OCR0B = 255;
-		TCCR0B = (1 << CS01); // change prescaler to 8, i.e. 7.8kHz
-		break;		
-    }
-}
+#include <avr/io.h>
+#include <avr/interrupt.h>
+
+// All this is about silencing the heat bed, as it behaves like a loudspeaker.
+// Basically, we want the PWM heating switched at 30Hz (or so) which is a well ballanced
+// frequency for both power supply units (i.e. both PSUs are reasonably silent).
+// The only trouble is the rising or falling edge of bed heating - that creates an audible click.
+// This audible click may be suppressed by making the rising or falling edge NOT sharp.
+// Of course, making non-sharp edges in digital technology is not easy, but there is a solution.
+// It is possible to do a fast PWM sequence with duty starting from 0 to 255.
+// Doing this at higher frequency than the bed "loudspeaker" can handle makes the click barely audible.
+// Technically:
+// timer0 is set to fast PWM mode at 62.5kHz (timer0 is linked to the bed heating pin) (zero prescaler)
+// To keep the bed switching at 30Hz - we don't want the PWM running at 62kHz all the time 
+// since it would burn the heatbed's MOSFET:
+// 16MHz/256 levels of PWM duty gives us 62.5kHz
+// 62.5kHz/256 gives ~244Hz, that is still too fast - 244/8 gives ~30Hz, that's what we need
+// So the automaton runs atop of inner 8 (or 16) cycles.
+// The finite automaton is running in the ISR(TIMER0_OVF_vect)
+
+// 2019-08-14 update: the original algorithm worked very well, however there were 2 regressions:
+// 1. 62kHz ISR requires considerable amount of processing power, 
+//    USB transfer speed dropped by 20%, which was most notable when doing short G-code segments.
+// 2. Some users reported TLed PSU started clicking when running at 120V/60Hz. 
+//    This looks like the original algorithm didn't maintain base PWM 30Hz, but only 15Hz
+// To address both issues, there is an improved approach based on the idea of leveraging
+// different CLK prescalers in some automaton states - i.e. when holding LOW or HIGH on the output pin,
+// we don't have to clock 62kHz, but we can increase the CLK prescaler for these states to 8 (or even 64).
+// That shall result in the ISR not being called that much resulting in regained performance
+// Theoretically this is relatively easy, however one must be very carefull handling the AVR's timer
+// control registers correctly, especially setting them in a correct order.
+// Some registers are double buffered, some changes are applied in next cycles etc.
+// The biggest problem was with the CLK prescaler itself - this circuit is shared among almost all timers,
+// we don't want to reset the prescaler counted value when transiting among automaton states.
+// Resetting the prescaler would make the PWM more precise, right now there are temporal segments
+// of variable period ranging from 0 to 7 62kHz ticks - that's logical, the timer must "sync"
+// to the new slower CLK after setting the slower prescaler value.
+// In our application, this isn't any significant problem and may be ignored.
+// Doing changes in timer's registers non-correctly results in artefacts on the output pin
+// - it can toggle unnoticed, which will result in bed clicking again.
+// That's why there are special transition states ZERO_TO_RISE and ONE_TO_FALL, which enable the
+// counter change its operation atomically and without artefacts on the output pin.
+// The resulting signal on the output pin was checked with an osciloscope. 
+// If there are any change requirements in the future, the signal must be checked with an osciloscope again,
+// ad-hoc changes may completely screw things up!
+
+// 2020-01-29 update: we are introducing a new option to the automaton that will allow us to force the output state
+// to either full ON or OFF. This is so that interference during the MBL probing is minimal.
+// To accomplish this goal we use bedPWMDisabled. It is only supposed to be used for brief periods of time as to
+// not make the bed temperature too unstable. Also, careful consideration should be used when using this
+// option as leaving this enabled will also keep the bed output in the state it stopped in.
+
+///! Definition off finite automaton states
+enum class States : uint8_t {
+	ZERO_START = 0,///< entry point of the automaton - reads the soft_pwm_bed value for the next whole PWM cycle
+	ZERO,          ///< steady 0 (OFF), no change for the whole period
+	ZERO_TO_RISE,  ///< metastate allowing the timer change its state atomically without artefacts on the output pin
+	RISE,          ///< 16 fast PWM cycles with increasing duty up to steady ON
+	RISE_TO_ONE,   ///< metastate allowing the timer change its state atomically without artefacts on the output pin
+	ONE,           ///< steady 1 (ON), no change for the whole period 
+	FALL,          ///< 16 fast PWM cycles with decreasing duty down to steady OFF
+	FALL_TO_ZERO   ///< metastate allowing the timer change its state atomically without artefacts on the output pin
+};
+
+///! Inner states of the finite automaton
+static States state = States::ZERO_START;
+
+bool bedPWMDisabled = 0;
+
+///! Fast PWM counter is used in the RISE and FALL states (62.5kHz)
+static uint8_t slowCounter = 0;
+///! Slow PWM counter is used in the ZERO and ONE states (62.5kHz/8 or 64)
+static uint8_t fastCounter = 0;
+///! PWM counter for the whole cycle - a cache for soft_pwm_bed
+static uint8_t pwm = 0;
+
+///! The slow PWM duty for the next 30Hz cycle
+///! Set in the whole firmware at various places
+extern unsigned char soft_pwm_bed;
+
+/// fastMax - how many fast PWM steps to do in RISE and FALL states
+/// 16 is a good compromise between silenced bed ("smooth" edges)
+/// and not burning the switching MOSFET
+static const uint8_t fastMax = 16;
+
+/// Scaler 16->256 for fast PWM
+static const uint8_t fastShift = 4;
+
+/// Increment slow PWM counter by slowInc every ZERO or ONE state
+/// This allows for fine-tuning the basic PWM switching frequency
+/// A possible further optimization - use a 64 prescaler (instead of 8)
+/// increment slowCounter by 1
+/// but use less bits of soft PWM - something like soft_pwm_bed >> 2
+/// that may further reduce the CPU cycles required by the bed heating automaton
+/// Due to the nature of bed heating the reduced PID precision may not be a major issue, however doing 8x less ISR(timer0_ovf) may significantly improve the performance 
+static const uint8_t slowInc = 1;
+
+ISR(TIMER0_OVF_vect)          // timer compare interrupt service routine
+{
+	switch(state){
+	case States::ZERO_START:
+		if (bedPWMDisabled) return; // stay in the OFF state and do not change the output pin
+		pwm = soft_pwm_bed << 1;// expecting soft_pwm_bed to be 7bit!
+		if( pwm != 0 ){
+			state = States::ZERO;     // do nothing, let it tick once again after the 30Hz period
+		}
+		break;
+	case States::ZERO: // end of state ZERO - we'll either stay in ZERO or change to RISE
+		// In any case update our cache of pwm value for the next whole cycle from soft_pwm_bed
+		slowCounter += slowInc; // this does software timer_clk/256 or less (depends on slowInc)
+		if( slowCounter > pwm ){
+			return;
+		} // otherwise moving towards RISE
+		state = States::ZERO_TO_RISE; // and finalize the change in a transitional state RISE0
+		break;
+	// even though it may look like the ZERO state may be glued together with the ZERO_TO_RISE, don't do it
+	// the timer must tick once more in order to get rid of occasional output pin toggles.
+	case States::ZERO_TO_RISE:  // special state for handling transition between prescalers and switching inverted->non-inverted fast-PWM without toggling the output pin.
+		// It must be done in consequent steps, otherwise the pin will get flipped up and down during one PWM cycle.
+		// Also beware of the correct sequence of the following timer control registers initialization - it really matters!
+		state = States::RISE;     // prepare for standard RISE cycles
+		fastCounter = fastMax - 1;// we'll do 16-1 cycles of RISE
+		TCNT0 = 255;              // force overflow on the next clock cycle
+		TCCR0B = (1 << CS00);     // change prescaler to 1, i.e. 62.5kHz
+		TCCR0A &= ~(1 << COM0B0); // Clear OC0B on Compare Match, set OC0B at BOTTOM (non-inverting mode)
+		break;
+	case States::RISE:
+		OCR0B = (fastMax - fastCounter) << fastShift;
+		if( fastCounter ){
+			--fastCounter;
+		} else { // end of RISE cycles, changing into state ONE
+			state = States::RISE_TO_ONE;
+			OCR0B = 255;          // full duty
+			TCNT0 = 254;          // make the timer overflow in the next cycle
+			// @@TODO these constants are still subject to investigation
+		}
+		break;
+	case States::RISE_TO_ONE:
+		state = States::ONE;
+		OCR0B = 255;              // full duty
+		TCNT0 = 255;              // make the timer overflow in the next cycle
+		TCCR0B = (1 << CS01);     // change prescaler to 8, i.e. 7.8kHz
+		break;
+	case States::ONE:             // state ONE - we'll either stay in ONE or change to FALL
+		OCR0B = 255;
+		if (bedPWMDisabled) return; // stay in the ON state and do not change the output pin
+		slowCounter += slowInc;   // this does software timer_clk/256 or less
+		if( slowCounter < pwm ){
+			return;
+		}
+		if( (soft_pwm_bed << 1) >= (255 - slowInc - 1) ){  //@@TODO simplify & explain
+			// if slowInc==2, soft_pwm == 251 will be the first to do short drops to zero. 252 will keep full heating
+			return;           // want full duty for the next ONE cycle again - so keep on heating and just wait for the next timer ovf
+		}
+		// otherwise moving towards FALL
+		state = States::ONE;//_TO_FALL;
+		state=States::FALL;
+		fastCounter = fastMax - 1;// we'll do 16-1 cycles of RISE
+		TCNT0 = 255;              // force overflow on the next clock cycle
+		TCCR0B = (1 << CS00);     // change prescaler to 1, i.e. 62.5kHz
+		// must switch to inverting mode already here, because it takes a whole PWM cycle and it would make a "1" at the end of this pwm cycle
+		// COM0B1 remains set both in inverting and non-inverting mode
+		TCCR0A |= (1 << COM0B0);  // inverting mode
+		break;
+	case States::FALL:
+		OCR0B = (fastMax - fastCounter) << fastShift; // this is the same as in RISE, because now we are setting the zero part of duty due to inverting mode
+		//TCCR0A |= (1 << COM0B0); // already set in ONE_TO_FALL
+		if( fastCounter ){
+			--fastCounter;
+		} else {   // end of FALL cycles, changing into state ZERO
+			state = States::FALL_TO_ZERO;
+			TCNT0 = 128; //@@TODO again - need to wait long enough to propagate the timer state changes
+			OCR0B = 255;
+		}
+		break;
+	case States::FALL_TO_ZERO:
+		state = States::ZERO_START; // go to read new soft_pwm_bed value for the next cycle
+		TCNT0 = 128;
+		OCR0B = 255;
+		TCCR0B = (1 << CS01); // change prescaler to 8, i.e. 7.8kHz
+		break;		
+    }
+}

+ 0 - 374
Firmware/io_atmega2560.h

@@ -1,374 +0,0 @@
-//io_atmega2560.h
-#ifndef _IO_ATMEGA2560
-#define _IO_ATMEGA2560
-
-
-#define __PIN_P0  PINE
-#define __PIN_P1  PINE
-#define __PIN_P2  PINE
-#define __PIN_P3  PINE
-#define __PIN_P4  PING
-#define __PIN_P5  PINE
-#define __PIN_P6  PINH
-#define __PIN_P7  PINH
-#define __PIN_P8  PINH
-#define __PIN_P9  PINH
-#define __PIN_P10 PINB
-#define __PIN_P11 PINB
-#define __PIN_P12 PINB
-#define __PIN_P13 PINB
-#define __PIN_P14 PINJ
-#define __PIN_P15 PINJ
-#define __PIN_P16 PINH
-#define __PIN_P17 PINH
-#define __PIN_P18 PIND
-#define __PIN_P19 PIND
-#define __PIN_P20 PIND
-#define __PIN_P21 PIND
-#define __PIN_P22 PINA
-#define __PIN_P23 PINA
-#define __PIN_P24 PINA
-#define __PIN_P25 PINA
-#define __PIN_P26 PINA
-#define __PIN_P27 PINA
-#define __PIN_P28 PINA
-#define __PIN_P29 PINA
-#define __PIN_P30 PINC
-#define __PIN_P31 PINC
-#define __PIN_P32 PINC
-#define __PIN_P33 PINC
-#define __PIN_P34 PINC
-#define __PIN_P35 PINC
-#define __PIN_P36 PINC
-#define __PIN_P37 PINC
-#define __PIN_P38 PIND
-#define __PIN_P39 PING
-#define __PIN_P40 PING
-#define __PIN_P41 PING
-#define __PIN_P42 PINL
-#define __PIN_P43 PINL
-#define __PIN_P44 PINL
-#define __PIN_P45 PINL
-#define __PIN_P46 PINL
-#define __PIN_P47 PINL
-#define __PIN_P48 PINL
-#define __PIN_P49 PINL
-#define __PIN_P50 PINB
-#define __PIN_P51 PINB
-#define __PIN_P52 PINB
-#define __PIN_P53 PINB
-#define __PIN_P54 PINF
-#define __PIN_P55 PINF
-#define __PIN_P56 PINF
-#define __PIN_P57 PINF
-#define __PIN_P58 PINF
-#define __PIN_P59 PINF
-#define __PIN_P60 PINF
-#define __PIN_P61 PINF
-#define __PIN_P62 PINK
-#define __PIN_P63 PINK
-#define __PIN_P64 PINK
-#define __PIN_P65 PINK
-#define __PIN_P66 PINK
-#define __PIN_P67 PINK
-#define __PIN_P68 PINK
-#define __PIN_P69 PINK
-#define __PIN_P70 PING
-#define __PIN_P71 PING
-#define __PIN_P72 PINJ
-#define __PIN_P73 PINJ
-#define __PIN_P74 PINJ
-#define __PIN_P75 PINJ
-#define __PIN_P76 PINJ
-#define __PIN_P77 PINJ
-#define __PIN_P78 PINE
-#define __PIN_P79 PINE
-#define __PIN_P80 PINE
-#define __PIN_P81 PIND
-#define __PIN_P82 PIND
-#define __PIN_P83 PIND
-#define __PIN_P84 PINH
-#define __PIN_P85 PINH
-
-#define __PORT_P0  PORTE
-#define __PORT_P1  PORTE
-#define __PORT_P2  PORTE
-#define __PORT_P3  PORTE
-#define __PORT_P4  PORTG
-#define __PORT_P5  PORTE
-#define __PORT_P6  PORTH
-#define __PORT_P7  PORTH
-#define __PORT_P8  PORTH
-#define __PORT_P9  PORTH
-#define __PORT_P10 PORTB
-#define __PORT_P11 PORTB
-#define __PORT_P12 PORTB
-#define __PORT_P13 PORTB
-#define __PORT_P14 PORTJ
-#define __PORT_P15 PORTJ
-#define __PORT_P16 PORTH
-#define __PORT_P17 PORTH
-#define __PORT_P18 PORTD
-#define __PORT_P19 PORTD
-#define __PORT_P20 PORTD
-#define __PORT_P21 PORTD
-#define __PORT_P22 PORTA
-#define __PORT_P23 PORTA
-#define __PORT_P24 PORTA
-#define __PORT_P25 PORTA
-#define __PORT_P26 PORTA
-#define __PORT_P27 PORTA
-#define __PORT_P28 PORTA
-#define __PORT_P29 PORTA
-#define __PORT_P30 PORTC
-#define __PORT_P31 PORTC
-#define __PORT_P32 PORTC
-#define __PORT_P33 PORTC
-#define __PORT_P34 PORTC
-#define __PORT_P35 PORTC
-#define __PORT_P36 PORTC
-#define __PORT_P37 PORTC
-#define __PORT_P38 PORTD
-#define __PORT_P39 PORTG
-#define __PORT_P40 PORTG
-#define __PORT_P41 PORTG
-#define __PORT_P42 PORTL
-#define __PORT_P43 PORTL
-#define __PORT_P44 PORTL
-#define __PORT_P45 PORTL
-#define __PORT_P46 PORTL
-#define __PORT_P47 PORTL
-#define __PORT_P48 PORTL
-#define __PORT_P49 PORTL
-#define __PORT_P50 PORTB
-#define __PORT_P51 PORTB
-#define __PORT_P52 PORTB
-#define __PORT_P53 PORTB
-#define __PORT_P54 PORTF
-#define __PORT_P55 PORTF
-#define __PORT_P56 PORTF
-#define __PORT_P57 PORTF
-#define __PORT_P58 PORTF
-#define __PORT_P59 PORTF
-#define __PORT_P60 PORTF
-#define __PORT_P61 PORTF
-#define __PORT_P62 PORTK
-#define __PORT_P63 PORTK
-#define __PORT_P64 PORTK
-#define __PORT_P65 PORTK
-#define __PORT_P66 PORTK
-#define __PORT_P67 PORTK
-#define __PORT_P68 PORTK
-#define __PORT_P69 PORTK
-#define __PORT_P70 PORTG
-#define __PORT_P71 PORTG
-#define __PORT_P72 PORTJ
-#define __PORT_P73 PORTJ
-#define __PORT_P74 PORTJ
-#define __PORT_P75 PORTJ
-#define __PORT_P76 PORTJ
-#define __PORT_P77 PORTJ
-#define __PORT_P78 PORTE
-#define __PORT_P79 PORTE
-#define __PORT_P80 PORTE
-#define __PORT_P81 PORTD
-#define __PORT_P82 PORTD
-#define __PORT_P83 PORTD
-#define __PORT_P84 PORTH
-#define __PORT_P85 PORTH
-
-#define __DDR_P0  DDRE
-#define __DDR_P1  DDRE
-#define __DDR_P2  DDRE
-#define __DDR_P3  DDRE
-#define __DDR_P4  DDRG
-#define __DDR_P5  DDRE
-#define __DDR_P6  DDRH
-#define __DDR_P7  DDRH
-#define __DDR_P8  DDRH
-#define __DDR_P9  DDRH
-#define __DDR_P10 DDRB
-#define __DDR_P11 DDRB
-#define __DDR_P12 DDRB
-#define __DDR_P13 DDRB
-#define __DDR_P14 DDRJ
-#define __DDR_P15 DDRJ
-#define __DDR_P16 DDRH
-#define __DDR_P17 DDRH
-#define __DDR_P18 DDRD
-#define __DDR_P19 DDRD
-#define __DDR_P20 DDRD
-#define __DDR_P21 DDRD
-#define __DDR_P22 DDRA
-#define __DDR_P23 DDRA
-#define __DDR_P24 DDRA
-#define __DDR_P25 DDRA
-#define __DDR_P26 DDRA
-#define __DDR_P27 DDRA
-#define __DDR_P28 DDRA
-#define __DDR_P29 DDRA
-#define __DDR_P30 DDRC
-#define __DDR_P31 DDRC
-#define __DDR_P32 DDRC
-#define __DDR_P33 DDRC
-#define __DDR_P34 DDRC
-#define __DDR_P35 DDRC
-#define __DDR_P36 DDRC
-#define __DDR_P37 DDRC
-#define __DDR_P38 DDRD
-#define __DDR_P39 DDRG
-#define __DDR_P40 DDRG
-#define __DDR_P41 DDRG
-#define __DDR_P42 DDRL
-#define __DDR_P43 DDRL
-#define __DDR_P44 DDRL
-#define __DDR_P45 DDRL
-#define __DDR_P46 DDRL
-#define __DDR_P47 DDRL
-#define __DDR_P48 DDRL
-#define __DDR_P49 DDRL
-#define __DDR_P50 DDRB
-#define __DDR_P51 DDRB
-#define __DDR_P52 DDRB
-#define __DDR_P53 DDRB
-#define __DDR_P54 DDRF
-#define __DDR_P55 DDRF
-#define __DDR_P56 DDRF
-#define __DDR_P57 DDRF
-#define __DDR_P58 DDRF
-#define __DDR_P59 DDRF
-#define __DDR_P60 DDRF
-#define __DDR_P61 DDRF
-#define __DDR_P62 DDRK
-#define __DDR_P63 DDRK
-#define __DDR_P64 DDRK
-#define __DDR_P65 DDRK
-#define __DDR_P66 DDRK
-#define __DDR_P67 DDRK
-#define __DDR_P68 DDRK
-#define __DDR_P69 DDRK
-#define __DDR_P70 DDRG
-#define __DDR_P71 DDRG
-#define __DDR_P72 DDRJ
-#define __DDR_P73 DDRJ
-#define __DDR_P74 DDRJ
-#define __DDR_P75 DDRJ
-#define __DDR_P76 DDRJ
-#define __DDR_P77 DDRJ
-#define __DDR_P78 DDRE
-#define __DDR_P79 DDRE
-#define __DDR_P80 DDRE
-#define __DDR_P81 DDRD
-#define __DDR_P82 DDRD
-#define __DDR_P83 DDRD
-#define __DDR_P84 DDRH
-#define __DDR_P85 DDRH
-
-#define __BIT_P0  0
-#define __BIT_P1  1
-#define __BIT_P2  4
-#define __BIT_P3  5
-#define __BIT_P4  5
-#define __BIT_P5  3
-#define __BIT_P6  3
-#define __BIT_P7  4
-#define __BIT_P8  5
-#define __BIT_P9  6
-#define __BIT_P10 4
-#define __BIT_P11 5
-#define __BIT_P12 6
-#define __BIT_P13 7
-#define __BIT_P14 1
-#define __BIT_P15 0
-#define __BIT_P16 0
-#define __BIT_P17 1
-#define __BIT_P18 3
-#define __BIT_P19 2
-#define __BIT_P20 1
-#define __BIT_P21 0
-#define __BIT_P22 0
-#define __BIT_P23 1
-#define __BIT_P24 2
-#define __BIT_P25 3
-#define __BIT_P26 4
-#define __BIT_P27 5
-#define __BIT_P28 6
-#define __BIT_P29 7
-#define __BIT_P30 7
-#define __BIT_P31 6
-#define __BIT_P32 5
-#define __BIT_P33 4
-#define __BIT_P34 3
-#define __BIT_P35 2
-#define __BIT_P36 1
-#define __BIT_P37 0
-#define __BIT_P38 7
-#define __BIT_P39 2
-#define __BIT_P40 1
-#define __BIT_P41 0
-#define __BIT_P42 7
-#define __BIT_P43 6
-#define __BIT_P44 5
-#define __BIT_P45 4
-#define __BIT_P46 3
-#define __BIT_P47 2
-#define __BIT_P48 1
-#define __BIT_P49 0
-#define __BIT_P50 3
-#define __BIT_P51 2
-#define __BIT_P52 1
-#define __BIT_P53 0
-#define __BIT_P54 0
-#define __BIT_P55 1
-#define __BIT_P56 2
-#define __BIT_P57 3
-#define __BIT_P58 4
-#define __BIT_P59 5
-#define __BIT_P60 6
-#define __BIT_P61 7
-#define __BIT_P62 0
-#define __BIT_P63 1
-#define __BIT_P64 2
-#define __BIT_P65 3
-#define __BIT_P66 4
-#define __BIT_P67 5
-#define __BIT_P68 6
-#define __BIT_P69 7
-#define __BIT_P70 4
-#define __BIT_P71 3
-#define __BIT_P72 2
-#define __BIT_P73 3
-#define __BIT_P74 7
-#define __BIT_P75 4
-#define __BIT_P76 5
-#define __BIT_P77 6
-#define __BIT_P78 2
-#define __BIT_P79 6
-#define __BIT_P80 7
-#define __BIT_P81 4
-#define __BIT_P82 5
-#define __BIT_P83 6
-#define __BIT_P84 2
-#define __BIT_P85 7
-
-#define __BIT(pin) __BIT_P##pin
-#define __MSK(pin) (1 << __BIT(pin))
-
-#define __PIN(pin) __PIN_P##pin
-#define __PORT(pin) __PORT_P##pin
-#define __DDR(pin) __DDR_P##pin
-
-#define PIN(pin) __PIN(pin)
-#define PORT(pin) __PORT(pin)
-#define DDR(pin) __DDR(pin)
-
-#define PIN_INP(pin) DDR(pin) &= ~__MSK(pin)
-#define PIN_OUT(pin) DDR(pin) |= __MSK(pin)
-#define PIN_CLR(pin) PORT(pin) &= ~__MSK(pin)
-#define PIN_SET(pin) PORT(pin) |= __MSK(pin)
-#define PIN_VAL(pin, val) if (val) PIN_SET(pin); else PIN_CLR(pin);
-#define PIN_GET(pin) (PIN(pin) & __MSK(pin))
-#define PIN_INQ(pin) (PORT(pin) & __MSK(pin))
-
-
-#endif //_IO_ATMEGA2560

+ 9 - 6
Firmware/la10compat.cpp

@@ -1,5 +1,6 @@
 #include "la10compat.h"
 #include "Marlin.h"
+#include <float.h>
 
 
 static LA10C_MODE la10c_mode = LA10C_UNKNOWN; // Current LA compatibility mode
@@ -37,8 +38,10 @@ void la10c_mode_change(LA10C_MODE mode)
 // Approximate a LA10 value to a LA15 equivalent.
 static float la10c_convert(float k)
 {
-    float new_K = k * 0.004 - 0.06;
-    return (new_K < 0? 0: new_K);
+    float new_K = k * 0.002 - 0.01;
+    return new_K < 0? 0:
+           new_K > (LA_K_MAX - FLT_EPSILON)? (LA_K_MAX - FLT_EPSILON):
+           new_K;
 }
 
 
@@ -52,11 +55,11 @@ float la10c_value(float k)
         else if(k < 0)
             return -1;
 
-        la10c_mode_change(k < 10? LA10C_LA15: LA10C_LA10);
+        la10c_mode_change(k < LA_LA10_MIN? LA10C_LA15: LA10C_LA10);
     }
 
     if(la10c_mode == LA10C_LA15)
-        return (k >= 0 && k < 10? k: -1);
+        return (k >= 0 && k < LA_K_MAX? k: -1);
     else
         return (k >= 0? la10c_convert(k): -1);
 }
@@ -75,10 +78,10 @@ float la10c_jerk(float j)
         return j;
 
     // bring low E-jerk values into equivalent LA 1.5 values by
-    // flattening the response in the (1-4.5) range using a piecewise
+    // flattening the response in the (0.3-4.5) range using a piecewise
     // function. Is it truly worth to preserve the difference between
     // 1.5/2.5 E-jerk for LA1.0? Probably not, but we try nonetheless.
-    j = j < 1.0? j * 3.625:
+    j = j < 0.3? j * 11.5:
         j < 4.5? j * 0.25 + 3.375:
         j;
 

+ 3 - 3
Firmware/language.c

@@ -17,10 +17,10 @@ uint8_t lang_selected = 0;
 
 #if (LANG_MODE == 0) //primary language only
 
-uint8_t lang_select(__attribute__((unused)) uint8_t lang) { return 0; }
+uint8_t lang_select(_UNUSED uint8_t lang) { return 0; }
 uint8_t lang_get_count() { return 1; }
-uint16_t lang_get_code(__attribute__((unused)) uint8_t lang) { return LANG_CODE_EN; }
-const char* lang_get_name_by_code(__attribute__((unused)) uint16_t code) { return _n("English"); }
+uint16_t lang_get_code(_UNUSED uint8_t lang) { return LANG_CODE_EN; }
+const char* lang_get_name_by_code(_UNUSED uint16_t code) { return _n("English"); }
 void lang_reset(void) { }
 uint8_t lang_is_selected(void) { return 1; }
 

+ 1 - 3
Firmware/language.h

@@ -5,6 +5,7 @@
 
 
 #include "config.h"
+#include "macros.h"
 #include <inttypes.h>
 #ifdef DEBUG_SEC_LANG
     #include <stdio.h>
@@ -22,9 +23,6 @@
 
 #define MSG_FW_VERSION                   "Firmware"
 
-#define STRINGIFY_(n) #n
-#define STRINGIFY(n) STRINGIFY_(n)
-
 #if (LANG_MODE == 0) //primary language only
 #define PROGMEM_I2 __attribute__((section(".progmem0")))
 #define PROGMEM_I1 __attribute__((section(".progmem1")))

+ 7 - 1
Firmware/lcd.cpp

@@ -486,11 +486,17 @@ void lcd_escape_write(uint8_t chr)
 #endif //VT100
 
 
-int lcd_putc(int c)
+int lcd_putc(char c)
 {
 	return fputc(c, lcdout);
 }
 
+int lcd_putc_at(uint8_t c, uint8_t r, char ch)
+{
+	lcd_set_cursor(c, r);
+	return fputc(ch, lcdout);
+}
+
 int lcd_puts_P(const char* str)
 {
 	return fputs_P(str, lcdout);

+ 4 - 1
Firmware/lcd.h

@@ -40,7 +40,10 @@ extern void lcd_set_cursor(uint8_t col, uint8_t row);
 extern void lcd_createChar_P(uint8_t, const uint8_t*);
 
 
-extern int lcd_putc(int c);
+// char c is non-standard, however it saves 1B on stack
+extern int lcd_putc(char c);
+extern int lcd_putc_at(uint8_t c, uint8_t r, char ch);
+
 extern int lcd_puts_P(const char* str);
 extern int lcd_puts_at_P(uint8_t c, uint8_t r, const char* str);
 extern int lcd_printf_P(const char* format, ...);

+ 90 - 0
Firmware/macros.h

@@ -0,0 +1,90 @@
+#ifndef MACROS_H
+#define MACROS_H
+
+#include <avr/interrupt.h> //for cli() and sei()
+
+#define  FORCE_INLINE __attribute__((always_inline)) inline
+#define _UNUSED __attribute__((unused))
+
+#ifndef CRITICAL_SECTION_START
+  #define CRITICAL_SECTION_START  unsigned char _sreg = SREG; cli();
+  #define CRITICAL_SECTION_END    SREG = _sreg;
+#endif //CRITICAL_SECTION_START
+
+// Macros to make a string from a macro
+#define STRINGIFY_(M) #M
+#define STRINGIFY(M) STRINGIFY_(M)
+
+// Macros for bit masks
+#undef _BV
+#define _BV(n) (1<<(n))
+#define TEST(n,b) (!!((n)&_BV(b)))
+#define SET_BIT_TO(N,B,TF) do{ if (TF) SBI(N,B); else CBI(N,B); }while(0)
+
+#ifndef SBI
+  #define SBI(A,B) (A |= (1 << (B)))
+#endif
+
+#ifndef CBI
+  #define CBI(A,B) (A &= ~(1 << (B)))
+#endif
+
+#define TBI(N,B) (N ^= _BV(B))
+
+
+// Macros to chain up to 12 conditions
+#define _DO_1(W,C,A)       (_##W##_1(A))
+#define _DO_2(W,C,A,B)     (_##W##_1(A) C _##W##_1(B))
+#define _DO_3(W,C,A,V...)  (_##W##_1(A) C _DO_2(W,C,V))
+#define _DO_4(W,C,A,V...)  (_##W##_1(A) C _DO_3(W,C,V))
+#define _DO_5(W,C,A,V...)  (_##W##_1(A) C _DO_4(W,C,V))
+#define _DO_6(W,C,A,V...)  (_##W##_1(A) C _DO_5(W,C,V))
+#define _DO_7(W,C,A,V...)  (_##W##_1(A) C _DO_6(W,C,V))
+#define _DO_8(W,C,A,V...)  (_##W##_1(A) C _DO_7(W,C,V))
+#define _DO_9(W,C,A,V...)  (_##W##_1(A) C _DO_8(W,C,V))
+#define _DO_10(W,C,A,V...) (_##W##_1(A) C _DO_9(W,C,V))
+#define _DO_11(W,C,A,V...) (_##W##_1(A) C _DO_10(W,C,V))
+#define _DO_12(W,C,A,V...) (_##W##_1(A) C _DO_11(W,C,V))
+#define __DO_N(W,C,N,V...) _DO_##N(W,C,V)
+#define _DO_N(W,C,N,V...)  __DO_N(W,C,N,V)
+#define DO(W,C,V...)       _DO_N(W,C,NUM_ARGS(V),V)
+
+// Macros to support option testing
+#define _CAT(a,V...) a##V
+#define CAT(a,V...) _CAT(a,V)
+
+#define _ISENA_     ~,1
+#define _ISENA_1    ~,1
+#define _ISENA_0x1  ~,1
+#define _ISENA_true ~,1
+#define _ISENA(V...)        IS_PROBE(V)
+
+#define _ENA_1(O)           _ISENA(CAT(_IS,CAT(ENA_, O)))
+#define _DIS_1(O)           NOT(_ENA_1(O))
+#define ENABLED(V...)       DO(ENA,&&,V)
+#define DISABLED(V...)      DO(DIS,&&,V)
+
+#define TERN(O,A,B)         _TERN(_ENA_1(O),B,A)    // OPTION converted to '0' or '1'
+#define TERN0(O,A)          _TERN(_ENA_1(O),0,A)    // OPTION converted to A or '0'
+#define TERN1(O,A)          _TERN(_ENA_1(O),1,A)    // OPTION converted to A or '1'
+#define TERN_(O,A)          _TERN(_ENA_1(O),,A)     // OPTION converted to A or '<nul>'
+#define _TERN(E,V...)       __TERN(_CAT(T_,E),V)    // Prepend 'T_' to get 'T_0' or 'T_1'
+#define __TERN(T,V...)      ___TERN(_CAT(_NO,T),V)  // Prepend '_NO' to get '_NOT_0' or '_NOT_1'
+#define ___TERN(P,V...)     THIRD(P,V)              // If first argument has a comma, A. Else B.
+
+
+// Use NUM_ARGS(__VA_ARGS__) to get the number of variadic arguments
+#define _NUM_ARGS(_,Z,Y,X,W,V,U,T,S,R,Q,P,O,N,M,L,K,J,I,H,G,F,E,D,C,B,A,OUT,...) OUT
+#define NUM_ARGS(V...) _NUM_ARGS(0,V,26,25,24,23,22,21,20,19,18,17,16,15,14,13,12,11,10,9,8,7,6,5,4,3,2,1,0)
+
+//
+// Primitives supporting precompiler REPEAT
+//
+#define FIRST(a,...)     a
+#define SECOND(a,b,...)  b
+#define THIRD(a,b,c,...) c
+
+#define IS_PROBE(V...) SECOND(V, 0)     // Get the second item passed, or 0
+#define NOT(x) IS_PROBE(_CAT(_NOT_, x)) // NOT('0') gets '1'. Anything else gets '0'.
+
+#endif //MACROS_H

+ 8 - 3
Firmware/menu.cpp

@@ -8,6 +8,7 @@
 #include "lcd.h"
 #include "Configuration.h"
 #include "Marlin.h"
+#include "cmdqueue.h"
 #include "ultralcd.h"
 #include "language.h"
 #include "static_assert.h"
@@ -48,6 +49,7 @@ void menu_goto(menu_func_t menu, const uint32_t encoder, const bool feedback, bo
 	{
 		menu_menu = menu;
 		lcd_encoder = encoder;
+		menu_top = 0; //reset menu view. Needed if menu_back() is called from deep inside a menu, such as Support
 		asm("sei");
 		if (reset_menu_state)
 		{
@@ -250,8 +252,7 @@ static void menu_draw_item_puts_P(char type_char, const char* str, char num)
     lcd_set_cursor(0, menu_row);
     lcd_printf_P(PSTR("%c%-.16S "), menu_selection_mark(), str);
     lcd_putc(num);
-    lcd_set_cursor(19, menu_row);
-    lcd_putc(type_char);
+    lcd_putc_at(19, menu_row, type_char);
 }
 
 /*
@@ -310,7 +311,7 @@ uint8_t menu_item_submenu_E(const Sheet &sheet, menu_func_t submenu)
     return 0;
 }
 
-uint8_t menu_item_function_E(const Sheet &sheet, menu_func_t func)
+uint8_t __attribute__((noinline)) menu_item_function_E(const Sheet &sheet, menu_func_t func)
 {
     if (menu_item == menu_line)
     {
@@ -344,6 +345,10 @@ uint8_t menu_item_back_P(const char* str)
 	return 0;
 }
 
+bool __attribute__((noinline)) menu_item_leave(){
+    return ((menu_item == menu_line) && menu_clicked && (lcd_encoder == menu_item)) || menu_leaving;
+}
+
 uint8_t menu_item_function_P(const char* str, menu_func_t func)
 {
 	if (menu_item == menu_line)

+ 2 - 1
Firmware/menu.h

@@ -112,7 +112,8 @@ extern uint8_t menu_item_function_E(const Sheet &sheet, menu_func_t func);
 extern uint8_t menu_item_back_P(const char* str);
 
 // leaving menu - this condition must be immediately before MENU_ITEM_BACK_P
-#define ON_MENU_LEAVE(func) do { if (((menu_item == menu_line) && menu_clicked && (lcd_encoder == menu_item)) || menu_leaving){ func } } while (0)
+#define ON_MENU_LEAVE(func) do { if (menu_item_leave()){ func } } while (0)
+extern bool menu_item_leave();
 
 #define MENU_ITEM_FUNCTION_P(str, func) do { if (menu_item_function_P(str, func)) return; } while (0)
 extern uint8_t menu_item_function_P(const char* str, menu_func_t func);

+ 21 - 12
Firmware/mesh_bed_calibration.cpp

@@ -12,6 +12,8 @@
 #include "tmc2130.h"
 #endif //TMC2130
 
+#define DBG(args...) printf_P(args)
+
 uint8_t world2machine_correction_mode;
 float   world2machine_rotation_and_skew[2][2];
 float   world2machine_rotation_and_skew_inv[2][2];
@@ -369,7 +371,9 @@ BedSkewOffsetDetectionResultType calculate_machine_skew_and_offset_LS(
     BedSkewOffsetDetectionResultType result = BED_SKEW_OFFSET_DETECTION_PERFECT;
     {
         angleDiff = fabs(a2 - a1);
-		eeprom_update_float((float*)(EEPROM_XYZ_CAL_SKEW), angleDiff); //storing xyz cal. skew to be able to show in support menu later 
+        /// XY skew and Y-bed skew
+        DBG(_n("Measured skews: %f %f\n"), degrees(a2 - a1), degrees(a2));
+        eeprom_update_float((float *)(EEPROM_XYZ_CAL_SKEW), angleDiff); //storing xyz cal. skew to be able to show in support menu later
         if (angleDiff > bed_skew_angle_mild)
             result = (angleDiff > bed_skew_angle_extreme) ?
                 BED_SKEW_OFFSET_DETECTION_SKEW_EXTREME :
@@ -920,7 +924,7 @@ static inline void go_xy(float x, float y, float fr)
 
 static inline void go_to_current(float fr)
 {
-    plan_buffer_line_curposXYZE(fr, active_extruder);
+    plan_buffer_line_curposXYZE(fr);
     st_synchronize();
 }
 
@@ -929,7 +933,7 @@ static inline void update_current_position_xyz()
       current_position[X_AXIS] = st_get_position_mm(X_AXIS);
       current_position[Y_AXIS] = st_get_position_mm(Y_AXIS);
       current_position[Z_AXIS] = st_get_position_mm(Z_AXIS);
-      plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
+      plan_set_position_curposXYZE();
 }
 
 static inline void update_current_position_z()
@@ -1380,7 +1384,7 @@ inline bool find_bed_induction_sensor_point_xy(int verbosity_level)
 
 		//        go_xyz(current_position[X_AXIS], current_position[Y_AXIS], MESH_HOME_Z_SEARCH, homing_feedrate[Z_AXIS]/60);
 		go_xyz(x0, y0, current_position[Z_AXIS], feedrate);
-		// Continously lower the Z axis.
+		// Continuously lower the Z axis.
 		endstops_hit_on_purpose();
 		enable_z_endstop(true);
 		while (current_position[Z_AXIS] > -10.f) {
@@ -2271,7 +2275,7 @@ BedSkewOffsetDetectionResultType find_bed_offset_and_skew(int8_t verbosity_level
 		/*}
 		else {
 			// if first iteration failed, count corrected point coordinates as initial
-			// Use the coorrected coordinate, which is a result of find_bed_offset_and_skew().
+			// Use the corrected coordinate, which is a result of find_bed_offset_and_skew().
 			
 			current_position[X_AXIS] = vec_x[0] * pgm_read_float(bed_ref_points_4 + k * 2) + vec_y[0] * pgm_read_float(bed_ref_points_4 + k * 2 + 1) + cntr[0];
 			current_position[Y_AXIS] = vec_x[1] * pgm_read_float(bed_ref_points_4 + k * 2) + vec_y[1] * pgm_read_float(bed_ref_points_4 + k * 2 + 1) + cntr[1];
@@ -2375,8 +2379,9 @@ BedSkewOffsetDetectionResultType find_bed_offset_and_skew(int8_t verbosity_level
 				delay_keep_alive(3000);
 			}
 			#endif // SUPPORT_VERBOSITY
-		}
-		delay_keep_alive(0); //manage_heater, reset watchdog, manage inactivity
+        }
+        DBG(_n("All 4 calibration points found.\n"));
+        delay_keep_alive(0); //manage_heater, reset watchdog, manage inactivity
 		
 		#ifdef SUPPORT_VERBOSITY
 		if (verbosity_level >= 20) {
@@ -2386,7 +2391,7 @@ BedSkewOffsetDetectionResultType find_bed_offset_and_skew(int8_t verbosity_level
 				// Don't let the manage_inactivity() function remove power from the motors.
 				refresh_cmd_timeout();
 				// Go to the measurement point.
-				// Use the coorrected coordinate, which is a result of find_bed_offset_and_skew().
+				// Use the corrected coordinate, which is a result of find_bed_offset_and_skew().
 				current_position[X_AXIS] = pts[mesh_point * 2];
 				current_position[Y_AXIS] = pts[mesh_point * 2 + 1];
 				go_to_current(homing_feedrate[X_AXIS] / 60);
@@ -2406,6 +2411,7 @@ BedSkewOffsetDetectionResultType find_bed_offset_and_skew(int8_t verbosity_level
 		delay_keep_alive(0); //manage_heater, reset watchdog, manage inactivity
 		
 		if (result >= 0) {
+            DBG(_n("Calibration success.\n"));
 			world2machine_update(vec_x, vec_y, cntr);
 #if 1
 			// Fearlessly store the calibration values into the eeprom.
@@ -2450,7 +2456,7 @@ BedSkewOffsetDetectionResultType find_bed_offset_and_skew(int8_t verbosity_level
 					// Don't let the manage_inactivity() function remove power from the motors.
 					refresh_cmd_timeout();
 					// Go to the measurement point.
-					// Use the coorrected coordinate, which is a result of find_bed_offset_and_skew().
+					// Use the corrected coordinate, which is a result of find_bed_offset_and_skew().
 					uint8_t ix = mesh_point % MESH_MEAS_NUM_X_POINTS; // from 0 to MESH_NUM_X_POINTS - 1
 					uint8_t iy = mesh_point / MESH_MEAS_NUM_X_POINTS;
 					if (iy & 1) ix = (MESH_MEAS_NUM_X_POINTS - 1) - ix;
@@ -2462,9 +2468,12 @@ BedSkewOffsetDetectionResultType find_bed_offset_and_skew(int8_t verbosity_level
 			}
 			#endif // SUPPORT_VERBOSITY
 			return result;
-		}		
-		if (result == BED_SKEW_OFFSET_DETECTION_FITTING_FAILED && too_far_mask == 2) return result; //if fitting failed and front center point is out of reach, terminate calibration and inform user
-		iteration++;
+		}
+        if (result == BED_SKEW_OFFSET_DETECTION_FITTING_FAILED && too_far_mask == 2){
+            DBG(_n("Fitting failed => calibration failed.\n"));
+            return result; //if fitting failed and front center point is out of reach, terminate calibration and inform user
+        }
+        iteration++;
 	}
 	return result;    
 }

+ 50 - 23
Firmware/messages.c

@@ -14,19 +14,26 @@ const char MSG_BABYSTEP_Z_NOT_SET[] PROGMEM_I1 = ISTR("Distance between tip of t
 const char MSG_BED[] PROGMEM_I1 = ISTR("Bed"); ////
 const char MSG_BED_DONE[] PROGMEM_I1 = ISTR("Bed done"); ////
 const char MSG_BED_HEATING[] PROGMEM_I1 = ISTR("Bed Heating"); ////
-const char MSG_BED_LEVELING_FAILED_POINT_LOW[] PROGMEM_I1 = ISTR("Bed leveling failed. Sensor didnt trigger. Debris on nozzle? Waiting for reset."); ////c=20 r=4
+const char MSG_BED_LEVELING_FAILED_POINT_LOW[] PROGMEM_I1 = ISTR("Bed leveling failed. Sensor didnt trigger. Debris on nozzle? Waiting for reset."); ////c=20 r=5
 const char MSG_BED_SKEW_OFFSET_DETECTION_FITTING_FAILED[] PROGMEM_I1 = ISTR("XYZ calibration failed. Please consult the manual."); ////c=20 r=8
+const char MSG_BELT_STATUS[] PROGMEM_I1 = ISTR("Belt Status");////c=18
 const char MSG_CALIBRATE_Z_AUTO[] PROGMEM_I1 = ISTR("Calibrating Z"); ////c=20 r=2
 const char MSG_CARD_MENU[] PROGMEM_I1 = ISTR("Print from SD"); ////
+const char MSG_CHECKING_X[] PROGMEM_I1 = ISTR("Checking X axis"); ////c=20
+const char MSG_CHECKING_Y[] PROGMEM_I1 = ISTR("Checking Y axis"); ////c=20
 const char MSG_CONFIRM_NOZZLE_CLEAN[] PROGMEM_I1 = ISTR("Please clean the nozzle for calibration. Click when done."); ////c=20 r=8
 const char MSG_COOLDOWN[] PROGMEM_I1 = ISTR("Cooldown"); ////
+const char MSG_CRASH[] PROGMEM_I1 = ISTR("Crash"); ////c=7
 const char MSG_CRASH_DETECTED[] PROGMEM_I1 = ISTR("Crash detected."); ////c=20 r=1
-const char MSG_CRASHDETECT[] PROGMEM_I1 = ISTR("Crash det."); ////
+const char MSG_CRASHDETECT[] PROGMEM_I1 = ISTR("Crash det."); ////c=13
 const char MSG_ERROR[] PROGMEM_I1 = ISTR("ERROR:"); ////
-const char MSG_EXTRUDER[] PROGMEM_I1 = ISTR("Extruder"); ////c=17 r=1
+const char MSG_EXTRUDER[] PROGMEM_I1 = ISTR("Extruder"); ////c=17
+const char MSG_FANS_CHECK[] PROGMEM_I1 = ISTR("Fans check"); ////c=13
+const char MSG_FIL_RUNOUTS[] PROGMEM_I1 = ISTR("Fil. runouts"); ////c=14
 const char MSG_FILAMENT[] PROGMEM_I1 = ISTR("Filament"); ////c=17 r=1
 const char MSG_FAN_SPEED[] PROGMEM_I1 = ISTR("Fan speed"); ////c=14
 const char MSG_FILAMENT_CLEAN[] PROGMEM_I1 = ISTR("Filament extruding & with correct color?"); ////c=20 r=2
+const char MSG_FILAMENT_LOADED[] PROGMEM_I1 = ISTR("Is filament loaded?"); ////c=20 r=2
 const char MSG_FILAMENT_LOADING_T0[] PROGMEM_I1 = ISTR("Insert filament into extruder 1. Click when done."); ////c=20 r=4
 const char MSG_FILAMENT_LOADING_T1[] PROGMEM_I1 = ISTR("Insert filament into extruder 2. Click when done."); ////c=20 r=4
 const char MSG_FILAMENT_LOADING_T2[] PROGMEM_I1 = ISTR("Insert filament into extruder 3. Click when done."); ////c=20 r=4
@@ -34,40 +41,48 @@ const char MSG_FILAMENT_LOADING_T3[] PROGMEM_I1 = ISTR("Insert filament into ext
 const char MSG_FILAMENTCHANGE[] PROGMEM_I1 = ISTR("Change filament"); ////
 const char MSG_FIND_BED_OFFSET_AND_SKEW_LINE1[] PROGMEM_I1 = ISTR("Searching bed calibration point"); ////c=60
 const char MSG_FIND_BED_OFFSET_AND_SKEW_LINE2[] PROGMEM_I1 = ISTR(" of 4"); ////c=14
-const char MSG_FINISHING_MOVEMENTS[] PROGMEM_I1 = ISTR("Finishing movements"); ////c=20 r=1
+const char MSG_FINISHING_MOVEMENTS[] PROGMEM_I1 = ISTR("Finishing movements"); ////c=20
 const char MSG_FOLLOW_CALIBRATION_FLOW[] PROGMEM_I1 = ISTR("Printer has not been calibrated yet. Please follow the manual, chapter First steps, section Calibration flow."); ////c=20 r=8
-const char MSG_FOLLOW_Z_CALIBRATION_FLOW[] PROGMEM_I1 = ISTR("There is still a need to make Z calibration. Please follow the manual, chapter First steps, section Calibration flow."); ////c=20 r=8
-const char MSG_FSENSOR_AUTOLOAD[] PROGMEM_I1 = ISTR("F. autoload"); ////c=17 r=1
+const char MSG_FOLLOW_Z_CALIBRATION_FLOW[] PROGMEM_I1 = ISTR("There is still a need to make Z calibration. Please follow the manual, chapter First steps, section Calibration flow."); ////c=20 r=9
+const char MSG_FSENSOR_AUTOLOAD[] PROGMEM_I1 = ISTR("F. autoload"); ////c=13
 const char MSG_FSENSOR[] PROGMEM_I1 = ISTR("Fil. sensor"); ////
 const char MSG_HEATING[] PROGMEM_I1 = ISTR("Heating"); ////
 const char MSG_HEATING_COMPLETE[] PROGMEM_I1 = ISTR("Heating done."); ////c=20
 const char MSG_HOMEYZ[] PROGMEM_I1 = ISTR("Calibrate Z"); ////
 const char MSG_CHOOSE_EXTRUDER[] PROGMEM_I1 = ISTR("Choose extruder:"); ////c=20 r=1
 const char MSG_CHOOSE_FILAMENT[] PROGMEM_I1 = ISTR("Choose filament:"); ////c=20 r=1
+const char MSG_LAST_PRINT[] PROGMEM_I1 = ISTR("Last print"); ////c=18
+const char MSG_LAST_PRINT_FAILURES[] PROGMEM_I1 = ISTR("Last print failures"); ////c=20
 const char MSG_LOAD_FILAMENT[] PROGMEM_I1 = ISTR("Load filament"); //// Number 1 to 5 is added behind text e.g. "Load filament 1" c=16
 const char MSG_LOADING_FILAMENT[] PROGMEM_I1 = ISTR("Loading filament"); ////c=20
 const char MSG_EJECT_FILAMENT[] PROGMEM_I1 = ISTR("Eject filament"); //// Number 1 to 5 is added behind text e.g. "Eject filament 1" c=16
 const char MSG_CUT_FILAMENT[] PROGMEM_I1 = ISTR("Cut filament"); //// Number 1 to 5 is added behind text e.g. "Cut filament 1" c=16
-const char MSG_M117_V2_CALIBRATION[] PROGMEM_I1 = ISTR("M117 First layer cal."); ////c=25 r=1
+const char MSG_M117_V2_CALIBRATION[] PROGMEM_I1 = ISTR("M117 First layer cal."); ////c=25
 const char MSG_MAIN[] PROGMEM_I1 = ISTR("Main"); ////
 const char MSG_BACK[] PROGMEM_I1 = ISTR("Back"); ////
 const char MSG_SHEET[] PROGMEM_I1 = ISTR("Sheet"); ////c=10
+const char MSG_STEEL_SHEETS[] PROGMEM_I1 = ISTR("Steel sheets"); ////c=18
 const char MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE1[] PROGMEM_I1 = ISTR("Measuring reference height of calibration point"); ////c=60
 const char MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE2[] PROGMEM_I1 = ISTR(" of 9"); ////c=14
 const char MSG_MENU_CALIBRATION[] PROGMEM_I1 = ISTR("Calibration"); ////
+const char MSG_MMU_FAILS[] PROGMEM_I1 = ISTR("MMU fails"); ////c=14
+const char MSG_MMU_LOAD_FAILS[] PROGMEM_I1 = ISTR("MMU load fails"); ////c=14
 const char MSG_NO[] PROGMEM_I1 = ISTR("No"); ////
 const char MSG_NOZZLE[] PROGMEM_I1 = ISTR("Nozzle"); ////
-const char MSG_PAPER[] PROGMEM_I1 = ISTR("Place a sheet of paper under the nozzle during the calibration of first 4 points. If the nozzle catches the paper, power off the printer immediately."); ////c=20 r=8
+const char MSG_PAPER[] PROGMEM_I1 = ISTR("Place a sheet of paper under the nozzle during the calibration of first 4 points. If the nozzle catches the paper, power off the printer immediately."); ////c=20 r=10
 const char MSG_PLACE_STEEL_SHEET[] PROGMEM_I1 = ISTR("Please place steel sheet on heatbed."); ////c=20 r=4
 const char MSG_PLEASE_WAIT[] PROGMEM_I1 = ISTR("Please wait"); ////c=20
+const char MSG_POWER_FAILURES[] PROGMEM_I1 = ISTR("Power failures"); ////c=14
 const char MSG_PREHEAT_NOZZLE[] PROGMEM_I1 = ISTR("Preheat the nozzle!"); ////c=20
 const char MSG_PRESS_TO_UNLOAD[] PROGMEM_I1 = ISTR("Please press the knob to unload filament"); ////c=20 r=4
 const char MSG_PRINT_ABORTED[] PROGMEM_I1 = ISTR("Print aborted"); ////c=20
 const char MSG_PULL_OUT_FILAMENT[] PROGMEM_I1 = ISTR("Please pull out filament immediately"); ////c=20 r=4
 const char MSG_RECOVER_PRINT[] PROGMEM_I1 = ISTR("Blackout occurred. Recover print?"); ////c=20 r=2
 const char MSG_REFRESH[] PROGMEM_I1 = ISTR("\xF8" "Refresh"); ////
-const char MSG_RESUMING_PRINT[] PROGMEM_I1 = ISTR("Resuming print"); ////
 const char MSG_REMOVE_STEEL_SHEET[] PROGMEM_I1 = ISTR("Please remove steel sheet from heatbed."); ////c=20 r=4
+const char MSG_RESET[] PROGMEM_I1 = ISTR("Reset"); ////c=14
+const char MSG_RESUME_PRINT[] PROGMEM_I1 = ISTR("Resume print"); ////c=18
+const char MSG_RESUMING_PRINT[] PROGMEM_I1 = ISTR("Resuming print"); ////
 const char MSG_SELFTEST_COOLING_FAN[] PROGMEM_I1 = ISTR("Front print fan?"); ////c=20
 const char MSG_SELFTEST_EXTRUDER_FAN[] PROGMEM_I1 = ISTR("Left hotend fan?"); ////c=20
 const char MSG_SELFTEST_FAILED[] PROGMEM_I1 = ISTR("Selftest failed  "); ////c=20
@@ -80,7 +95,9 @@ const char MSG_SELFTEST_MOTOR[] PROGMEM_I1 = ISTR("Motor"); ////
 const char MSG_SELFTEST_FILAMENT_SENSOR[] PROGMEM_I1 = ISTR("Filament sensor"); ////c=17
 const char MSG_SELFTEST_WIRINGERROR[] PROGMEM_I1 = ISTR("Wiring error"); ////
 const char MSG_SETTINGS[] PROGMEM_I1 = ISTR("Settings"); ////
-const char MSG_HW_SETUP[] PROGMEM_I1 = ISTR("HW Setup"); ////
+const char MSG_TOTAL[] PROGMEM_I1 = ISTR("Total"); ////c=6
+const char MSG_TOTAL_FAILURES[] PROGMEM_I1 = ISTR("Total failures"); ////c=20
+const char MSG_HW_SETUP[] PROGMEM_I1 = ISTR("HW Setup"); ////c=18
 const char MSG_MODE[] PROGMEM_I1 = ISTR("Mode"); ////
 const char MSG_HIGH_POWER[] PROGMEM_I1 = ISTR("High power"); ////
 const char MSG_AUTO_POWER[] PROGMEM_I1 = ISTR("Auto power"); ////
@@ -90,7 +107,7 @@ const char MSG_STEALTH[] PROGMEM_I1 = ISTR("Stealth"); ////
 const char MSG_STEEL_SHEET_CHECK[] PROGMEM_I1 = ISTR("Is steel sheet on heatbed?"); ////c=20 r=2
 const char MSG_STOP_PRINT[] PROGMEM_I1 = ISTR("Stop print"); ////
 const char MSG_STOPPED[] PROGMEM_I1 = ISTR("STOPPED. "); ////
-const char MSG_TEMP_CALIBRATION[] PROGMEM_I1 = ISTR("Temp. cal."); ////c=12 r=1
+const char MSG_TEMP_CALIBRATION[] PROGMEM_I1 = ISTR("Temp. cal."); ////c=14
 const char MSG_TEMP_CALIBRATION_DONE[] PROGMEM_I1 = ISTR("Temperature calibration is finished and active. Temp. calibration can be disabled in menu Settings->Temp. cal."); ////c=20 r=12
 const char MSG_UNLOAD_FILAMENT[] PROGMEM_I1 = ISTR("Unload filament"); ////c=17
 const char MSG_UNLOADING_FILAMENT[] PROGMEM_I1 = ISTR("Unloading filament"); ////c=20 r=1
@@ -100,19 +117,21 @@ const char MSG_WIZARD_DONE[] PROGMEM_I1 = ISTR("All is done. Happy printing!");
 const char MSG_WIZARD_HEATING[] PROGMEM_I1 = ISTR("Preheating nozzle. Please wait."); ////c=20 r=3
 const char MSG_WIZARD_QUIT[] PROGMEM_I1 = ISTR("You can always resume the Wizard from Calibration -> Wizard."); ////c=20 r=8
 const char MSG_YES[] PROGMEM_I1 = ISTR("Yes"); ////
-const char MSG_V2_CALIBRATION[] PROGMEM_I1 = ISTR("First layer cal."); ////c=17 r=1
+const char MSG_V2_CALIBRATION[] PROGMEM_I1 = ISTR("First layer cal."); ////c=18
 const char WELCOME_MSG[] PROGMEM_I1 = ISTR(CUSTOM_MENDEL_NAME " OK."); ////c=20
 const char MSG_OFF[] PROGMEM_I1 = ISTR("Off"); ////
 const char MSG_ON[] PROGMEM_I1 = ISTR("On"); ////
 const char MSG_NA[] PROGMEM_I1 = ISTR("N/A"); ////
 const char MSG_AUTO_DEPLETE[] PROGMEM_I1 = ISTR("SpoolJoin"); ////
-const char MSG_CUTTER[] PROGMEM_I1 = ISTR("Cutter"); ////
+const char MSG_CUTTER[] PROGMEM_I1 = ISTR("Cutter"); ////c=9
 const char MSG_NONE[] PROGMEM_I1 = ISTR("None"); ////
 const char MSG_WARN[] PROGMEM_I1 = ISTR("Warn"); ////
 const char MSG_STRICT[] PROGMEM_I1 = ISTR("Strict"); ////
 const char MSG_MODEL[] PROGMEM_I1 = ISTR("Model"); ////
 const char MSG_FIRMWARE[] PROGMEM_I1 = ISTR("Firmware"); ////
 const char MSG_GCODE[] PROGMEM_I1 = ISTR("Gcode"); ////
+const char MSG_GCODE_DIFF_PRINTER_CONTINUE[] PROGMEM_I1 = ISTR("G-code sliced for a different printer type. Continue?"); ////c=20 r=5
+const char MSG_GCODE_DIFF_PRINTER_CANCELLED[] PROGMEM_I1 =ISTR("G-code sliced for a different printer type. Please re-slice the model again. Print cancelled."); ////c=20 r=6
 const char MSG_NOZZLE_DIAMETER[] PROGMEM_I1 = ISTR("Nozzle d."); ////
 const char MSG_MMU_MODE[] PROGMEM_I1 = ISTR("MMU Mode"); ////
 const char MSG_SD_CARD[] PROGMEM_I1 = ISTR("SD card"); ////
@@ -126,18 +145,25 @@ const char MSG_SOUND_LOUD[] PROGMEM_I1 = ISTR("Loud"); ////
 const char MSG_SOUND_ONCE[] PROGMEM_I1 = ISTR("Once"); ////
 const char MSG_SOUND_BLIND[] PROGMEM_I1 = ISTR("Assist"); ////
 const char MSG_MESH[] PROGMEM_I1 = ISTR("Mesh"); ////
+const char MSG_MESH_BED_LEVELING[] PROGMEM_I1 = ISTR("Mesh Bed Leveling"); ////c=18
 const char MSG_Z_PROBE_NR[] PROGMEM_I1 = ISTR("Z-probe nr."); ////
 const char MSG_MAGNETS_COMP[] PROGMEM_I1 = ISTR("Magnets comp."); ////
-const char MSG_FS_ACTION[] PROGMEM_I1 = ISTR("FS Action"); ////
-const char MSG_FS_CONTINUE[] PROGMEM_I1 = ISTR("Cont."); ////
-const char MSG_FS_PAUSE[] PROGMEM_I1 = ISTR("Pause"); ////
-const char MSG_BRIGHTNESS[] PROGMEM_I1 = ISTR("Brightness"); ////
-const char MSG_BL_HIGH[] PROGMEM_I1 = ISTR("Level Bright"); ////
-const char MSG_BL_LOW[] PROGMEM_I1 = ISTR("Level Dimmed"); ////
-const char MSG_TIMEOUT[] PROGMEM_I1 = ISTR("Timeout"); ////
-const char MSG_BRIGHT[] PROGMEM_I1 = ISTR("Bright"); ////
-const char MSG_DIM[] PROGMEM_I1 = ISTR("Dim"); ////
-const char MSG_AUTO[] PROGMEM_I1 = ISTR("Auto"); ////
+const char MSG_FS_ACTION[] PROGMEM_I1 = ISTR("FS Action"); ////c=10
+const char MSG_FS_CONTINUE[] PROGMEM_I1 = ISTR("Cont."); ////c=5
+const char MSG_FS_PAUSE[] PROGMEM_I1 = ISTR("Pause"); ////c=5
+const char MSG_BRIGHTNESS[] PROGMEM_I1 = ISTR("Brightness"); ////c=18
+const char MSG_BL_HIGH[] PROGMEM_I1 = ISTR("Level Bright"); ////c=12
+const char MSG_BL_LOW[] PROGMEM_I1 = ISTR("Level Dimmed"); ////c=12
+const char MSG_TIMEOUT[] PROGMEM_I1 = ISTR("Timeout"); ////c=12
+const char MSG_BRIGHT[] PROGMEM_I1 = ISTR("Bright"); ////c=6
+const char MSG_DIM[] PROGMEM_I1 = ISTR("Dim"); ////c=6
+const char MSG_AUTO[] PROGMEM_I1 = ISTR("Auto"); ////c=6
+#ifdef IR_SENSOR_ANALOG
+// Beware - the space at the beginning is necessary since it is reused in LCD menu items which are to be with a space
+const char MSG_IR_04_OR_NEWER[] PROGMEM_I1 = ISTR(" 0.4 or newer");////c=18
+const char MSG_IR_03_OR_OLDER[] PROGMEM_I1 = ISTR(" 0.3 or older");////c=18
+const char MSG_IR_UNKNOWN[] PROGMEM_I1 = ISTR("unknown state");////c=18
+#endif
 
 //not internationalized messages
 const char MSG_SD_WORKDIR_FAIL[] PROGMEM_N1 = "workDir open failed"; ////
@@ -170,3 +196,4 @@ const char MSG_FANCHECK_PRINT[] PROGMEM_N1 = "Err: PRINT FAN ERROR"; ////c=20
 const char MSG_M112_KILL[] PROGMEM_N1 = "M112 called. Emergency Stop."; ////c=20
 const char MSG_ADVANCE_K[] PROGMEM_N1 = "Advance K:"; ////c=13
 const char MSG_POWERPANIC_DETECTED[] PROGMEM_N1 = "POWER PANIC DETECTED"; ////c=20
+const char MSG_LCD_STATUS_CHANGED[] PROGMEM_N1 = "LCD status changed";

+ 26 - 0
Firmware/messages.h

@@ -17,17 +17,24 @@ extern const char MSG_BED_DONE[];
 extern const char MSG_BED_HEATING[];
 extern const char MSG_BED_LEVELING_FAILED_POINT_LOW[];
 extern const char MSG_BED_SKEW_OFFSET_DETECTION_FITTING_FAILED[];
+extern const char MSG_BELT_STATUS[];
 extern const char MSG_CALIBRATE_Z_AUTO[];
 extern const char MSG_CARD_MENU[];
+extern const char MSG_CHECKING_X[];
+extern const char MSG_CHECKING_Y[];
 extern const char MSG_CONFIRM_NOZZLE_CLEAN[];
 extern const char MSG_COOLDOWN[];
+extern const char MSG_CRASH[];
 extern const char MSG_CRASH_DETECTED[];
 extern const char MSG_CRASHDETECT[];
 extern const char MSG_ERROR[];
 extern const char MSG_EXTRUDER[];
+extern const char MSG_FANS_CHECK[];
+extern const char MSG_FIL_RUNOUTS[];
 extern const char MSG_FILAMENT[];
 extern const char MSG_FAN_SPEED[];
 extern const char MSG_FILAMENT_CLEAN[];
+extern const char MSG_FILAMENT_LOADED[];
 extern const char MSG_FILAMENT_LOADING_T0[];
 extern const char MSG_FILAMENT_LOADING_T1[];
 extern const char MSG_FILAMENT_LOADING_T2[];
@@ -45,20 +52,26 @@ extern const char MSG_HEATING_COMPLETE[];
 extern const char MSG_HOMEYZ[];
 extern const char MSG_CHOOSE_EXTRUDER[];
 extern const char MSG_CHOOSE_FILAMENT[];
+extern const char MSG_LAST_PRINT[];
+extern const char MSG_LAST_PRINT_FAILURES[];
 extern const char MSG_LOAD_FILAMENT[];
 extern const char MSG_LOADING_FILAMENT[];
 extern const char MSG_M117_V2_CALIBRATION[];
 extern const char MSG_MAIN[];
 extern const char MSG_BACK[];
 extern const char MSG_SHEET[];
+extern const char MSG_STEEL_SHEETS[];
 extern const char MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE1[];
 extern const char MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE2[];
 extern const char MSG_MENU_CALIBRATION[];
+extern const char MSG_MMU_FAILS[];
+extern const char MSG_MMU_LOAD_FAILS[];
 extern const char MSG_NO[];
 extern const char MSG_NOZZLE[];
 extern const char MSG_PAPER[];
 extern const char MSG_PLACE_STEEL_SHEET[];
 extern const char MSG_PLEASE_WAIT[];
+extern const char MSG_POWER_FAILURES[];
 extern const char MSG_PREHEAT_NOZZLE[];
 extern const char MSG_PRESS_TO_UNLOAD[];
 extern const char MSG_PRINT_ABORTED[];
@@ -66,6 +79,8 @@ extern const char MSG_PULL_OUT_FILAMENT[];
 extern const char MSG_RECOVER_PRINT[];
 extern const char MSG_REFRESH[];
 extern const char MSG_REMOVE_STEEL_SHEET[];
+extern const char MSG_RESET[];
+extern const char MSG_RESUME_PRINT[];
 extern const char MSG_RESUMING_PRINT[];
 extern const char MSG_SD_WORKDIR_FAIL[];
 extern const char MSG_SELFTEST_COOLING_FAN[];
@@ -80,6 +95,8 @@ extern const char MSG_SELFTEST_MOTOR[];
 extern const char MSG_SELFTEST_FILAMENT_SENSOR[];
 extern const char MSG_SELFTEST_WIRINGERROR[];
 extern const char MSG_SETTINGS[];
+extern const char MSG_TOTAL[];
+extern const char MSG_TOTAL_FAILURES[];
 extern const char MSG_HW_SETUP[];
 extern const char MSG_MODE[];
 extern const char MSG_HIGH_POWER[];
@@ -113,6 +130,8 @@ extern const char MSG_STRICT[];
 extern const char MSG_MODEL[];
 extern const char MSG_FIRMWARE[];
 extern const char MSG_GCODE[];
+extern const char MSG_GCODE_DIFF_PRINTER_CONTINUE[];
+extern const char MSG_GCODE_DIFF_PRINTER_CANCELLED[];
 extern const char MSG_NOZZLE_DIAMETER[];
 extern const char MSG_MMU_MODE[];
 extern const char MSG_SD_CARD[];
@@ -126,6 +145,7 @@ extern const char MSG_SOUND_LOUD[];
 extern const char MSG_SOUND_ONCE[];
 extern const char MSG_SOUND_BLIND[];
 extern const char MSG_MESH[];
+extern const char MSG_MESH_BED_LEVELING[];
 extern const char MSG_Z_PROBE_NR[];
 extern const char MSG_MAGNETS_COMP[];
 extern const char MSG_FS_ACTION[];
@@ -138,6 +158,11 @@ extern const char MSG_TIMEOUT[];
 extern const char MSG_BRIGHT[];
 extern const char MSG_DIM[];
 extern const char MSG_AUTO[];
+#ifdef IR_SENSOR_ANALOG
+extern const char MSG_IR_04_OR_NEWER[];
+extern const char MSG_IR_03_OR_OLDER[];
+extern const char MSG_IR_UNKNOWN[];
+#endif
 
 //not internationalized messages
 extern const char MSG_BROWNOUT_RESET[];
@@ -171,6 +196,7 @@ extern const char MSG_FANCHECK_PRINT[];
 extern const char MSG_M112_KILL[];
 extern const char MSG_ADVANCE_K[];
 extern const char MSG_POWERPANIC_DETECTED[];
+extern const char MSG_LCD_STATUS_CHANGED[];
 
 #if defined(__cplusplus)
 }

+ 55 - 57
Firmware/mmu.cpp

@@ -9,12 +9,14 @@
 #include "Configuration_prusa.h"
 #include "fsensor.h"
 #include "cardreader.h"
+#include "cmdqueue.h"
 #include "ultralcd.h"
 #include "sound.h"
 #include "printers.h"
 #include <avr/pgmspace.h>
-#include "io_atmega2560.h"
 #include "AutoDeplete.h"
+#include "fastio.h"
+#include "pins.h"
 //-//
 #include "util.h"
 
@@ -28,9 +30,6 @@
 #define MMU_P0_TIMEOUT 3000ul //timeout for P0 command: 3seconds
 #define MMU_MAX_RESEND_ATTEMPTS 2
 
-#ifdef MMU_HWRESET
-#define MMU_RST_PIN 76
-#endif //MMU_HWRESET
 
 namespace
 {
@@ -156,8 +155,8 @@ void mmu_init(void)
 	_delay_ms(10);                             //wait 10ms for sure
 	mmu_reset();                               //reset mmu (HW or SW), do not wait for response
 	mmu_state = S::Init;
-	PIN_INP(IR_SENSOR_PIN); //input mode
-	PIN_SET(IR_SENSOR_PIN); //pullup
+	SET_INPUT(IR_SENSOR_PIN); //input mode
+	WRITE(IR_SENSOR_PIN, 1); //pullup
 }
 
 //if IR_SENSOR defined, always returns true
@@ -170,7 +169,7 @@ bool check_for_ir_sensor()
 
 	bool detected = false;
 	//if IR_SENSOR_PIN input is low and pat9125sensor is not present we detected idler sensor
-	if ((PIN_GET(IR_SENSOR_PIN) == 0) 
+	if ((READ(IR_SENSOR_PIN) == 0) 
 #ifdef PAT9125
 		&& fsensor_not_responding
 #endif //PAT9125
@@ -363,7 +362,7 @@ void mmu_loop(void)
 	case S::GetFinda: //response to command P0
         if (mmu_idl_sens)
         {
-            if (PIN_GET(IR_SENSOR_PIN) == 0 && mmu_loading_flag)
+            if (READ(IR_SENSOR_PIN) == 0 && mmu_loading_flag)
             {
 #ifdef MMU_DEBUG
                 printf_P(PSTR("MMU <= 'A'\n"));
@@ -406,7 +405,7 @@ void mmu_loop(void)
 	case S::WaitCmd: //response to mmu commands
         if (mmu_idl_sens)
         {
-            if (PIN_GET(IR_SENSOR_PIN) == 0 && mmu_loading_flag)
+            if (READ(IR_SENSOR_PIN) == 0 && mmu_loading_flag)
             {
                 DEBUG_PRINTF_P(PSTR("MMU <= 'A'\n"));
                 mmu_puts_P(PSTR("A\n")); //send 'abort' request
@@ -540,7 +539,7 @@ void mmu_command(MmuCmd cmd)
 void mmu_load_step(bool synchronize)
 {
 		current_position[E_AXIS] = current_position[E_AXIS] + MMU_LOAD_FEEDRATE * 0.1;
-		plan_buffer_line_curposXYZE(MMU_LOAD_FEEDRATE, active_extruder);
+		plan_buffer_line_curposXYZE(MMU_LOAD_FEEDRATE);
 		if (synchronize) st_synchronize();
 }
 
@@ -568,11 +567,11 @@ bool can_extrude()
 static void get_response_print_info(uint8_t move) {
 	printf_P(PSTR("mmu_get_response - begin move: "), move);
 	switch (move) {
-		case MMU_LOAD_MOVE: printf_P(PSTR("load\n")); break;
-		case MMU_UNLOAD_MOVE: printf_P(PSTR("unload\n")); break;
-		case MMU_TCODE_MOVE: printf_P(PSTR("T-code\n")); break;
-		case MMU_NO_MOVE: printf_P(PSTR("no move\n")); break;
-		default: printf_P(PSTR("error: unknown move\n")); break;
+		case MMU_LOAD_MOVE: puts_P(PSTR("load")); break;
+		case MMU_UNLOAD_MOVE: puts_P(PSTR("unload")); break;
+		case MMU_TCODE_MOVE: puts_P(PSTR("T-code")); break;
+		case MMU_NO_MOVE: puts_P(PSTR("no move")); break;
+		default: puts_P(PSTR("error: unknown move")); break;
 	}
 }
 
@@ -596,40 +595,40 @@ bool mmu_get_response(uint8_t move)
 			    mmu_loading_flag = true;
 				if (can_extrude()) mmu_load_step();
 				//don't rely on "ok" signal from mmu unit; if filament detected by idler sensor during loading stop loading movements to prevent infinite loading
-				if (PIN_GET(IR_SENSOR_PIN) == 0) move = MMU_NO_MOVE;
+				if (READ(IR_SENSOR_PIN) == 0) move = MMU_NO_MOVE;
 				break;
 			case MMU_UNLOAD_MOVE:
-				if (PIN_GET(IR_SENSOR_PIN) == 0) //filament is still detected by idler sensor, printer helps with unlading 
+				if (READ(IR_SENSOR_PIN) == 0) //filament is still detected by idler sensor, printer helps with unlading 
 				{
 				    if (can_extrude())
 				    {
-                        printf_P(PSTR("Unload 1\n"));
+                        puts_P(PSTR("Unload 1"));
                         current_position[E_AXIS] = current_position[E_AXIS] - MMU_LOAD_FEEDRATE * MMU_LOAD_TIME_MS*0.001;
-                        plan_buffer_line_curposXYZE(MMU_LOAD_FEEDRATE, active_extruder);
+                        plan_buffer_line_curposXYZE(MMU_LOAD_FEEDRATE);
                         st_synchronize();
 				    }
 				}
 				else //filament was unloaded from idler, no additional movements needed 
 				{ 
-					printf_P(PSTR("Unloading finished 1\n"));
+					puts_P(PSTR("Unloading finished 1"));
 					disable_e0(); //turn off E-stepper to prevent overheating and alow filament pull-out if necessary
 					move = MMU_NO_MOVE;
 				}
 				break;
 			case MMU_TCODE_MOVE: //first do unload and then continue with infinite loading movements
-				if (PIN_GET(IR_SENSOR_PIN) == 0) //filament detected by idler sensor, we must unload first 
+				if (READ(IR_SENSOR_PIN) == 0) //filament detected by idler sensor, we must unload first 
 				{
                     if (can_extrude())
                     {
-                        printf_P(PSTR("Unload 2\n"));
+                        puts_P(PSTR("Unload 2"));
                         current_position[E_AXIS] = current_position[E_AXIS] - MMU_LOAD_FEEDRATE * MMU_LOAD_TIME_MS*0.001;
-                        plan_buffer_line_curposXYZE(MMU_LOAD_FEEDRATE, active_extruder);
+                        plan_buffer_line_curposXYZE(MMU_LOAD_FEEDRATE);
                         st_synchronize();
                     }
 				}
 				else //delay to allow mmu unit to pull out filament from bondtech gears and then start with infinite loading 
 				{ 
-					printf_P(PSTR("Unloading finished 2\n"));
+					puts_P(PSTR("Unloading finished 2"));
 					disable_e0(); //turn off E-stepper to prevent overheating and alow filament pull-out if necessary
 					delay_keep_alive(MMU_LOAD_TIME_MS);
 					move = MMU_LOAD_MOVE;
@@ -690,7 +689,7 @@ void manage_response(bool move_axes, bool turn_off_nozzle, uint8_t move)
 				  }
 				  st_synchronize();
 				  mmu_print_saved = true;
-				  printf_P(PSTR("MMU not responding\n"));
+				  puts_P(PSTR("MMU not responding"));
 				  KEEPALIVE_STATE(PAUSED_FOR_USER);
 				  hotend_temp_bckp = degTargetHotend(active_extruder);
 				  if (move_axes) {
@@ -701,13 +700,13 @@ void manage_response(bool move_axes, bool turn_off_nozzle, uint8_t move)
 					  //lift z
 					  current_position[Z_AXIS] += Z_PAUSE_LIFT;
 					  if (current_position[Z_AXIS] > Z_MAX_POS) current_position[Z_AXIS] = Z_MAX_POS;
-					  plan_buffer_line_curposXYZE(15, active_extruder);
+					  plan_buffer_line_curposXYZE(15);
 					  st_synchronize();
 					  					  
 					  //Move XY to side
 					  current_position[X_AXIS] = X_PAUSE_POS;
 					  current_position[Y_AXIS] = Y_PAUSE_POS;
-					  plan_buffer_line_curposXYZE(50, active_extruder);
+					  plan_buffer_line_curposXYZE(50);
 					  st_synchronize();
 				  }
 				  if (turn_off_nozzle) {
@@ -747,7 +746,7 @@ void manage_response(bool move_axes, bool turn_off_nozzle, uint8_t move)
 			  }
 		  }
 		  else if (mmu_print_saved) {
-			  printf_P(PSTR("MMU starts responding\n"));
+			  puts_P(PSTR("MMU starts responding"));
 			  KEEPALIVE_STATE(IN_HANDLER);
 			  mmu_loading_flag = false;
 			  if (turn_off_nozzle) 
@@ -758,17 +757,17 @@ void manage_response(bool move_axes, bool turn_off_nozzle, uint8_t move)
 					lcd_display_message_fullscreen_P(_i("MMU OK. Resuming temperature..."));
 					delay_keep_alive(3000);
 				}
-                mmu_wait_for_heater_blocking();
+				mmu_wait_for_heater_blocking();
 			  }			  
 			  if (move_axes) {
 				  lcd_clear();
 				  lcd_display_message_fullscreen_P(_i("MMU OK. Resuming position..."));
 				  current_position[X_AXIS] = x_position_bckp;
 				  current_position[Y_AXIS] = y_position_bckp;
-				  plan_buffer_line_curposXYZE(50, active_extruder);
+				  plan_buffer_line_curposXYZE(50);
 				  st_synchronize();
 				  current_position[Z_AXIS] = z_position_bckp;
-				  plan_buffer_line_curposXYZE(15, active_extruder);
+				  plan_buffer_line_curposXYZE(15);
 				  st_synchronize();
 			  }
 			  else {
@@ -807,19 +806,19 @@ void mmu_load_to_nozzle()
 		current_position[E_AXIS] += 7.2f;
 	}
     float feedrate = 562;
-	plan_buffer_line_curposXYZE(feedrate / 60, active_extruder);
+	plan_buffer_line_curposXYZE(feedrate / 60);
     st_synchronize();
 	current_position[E_AXIS] += 14.4f;
 	feedrate = 871;
-	plan_buffer_line_curposXYZE(feedrate / 60, active_extruder);
+	plan_buffer_line_curposXYZE(feedrate / 60);
     st_synchronize();
 	current_position[E_AXIS] += 36.0f;
 	feedrate = 1393;
-	plan_buffer_line_curposXYZE(feedrate / 60, active_extruder);
+	plan_buffer_line_curposXYZE(feedrate / 60);
     st_synchronize();
 	current_position[E_AXIS] += 14.4f;
 	feedrate = 871;
-	plan_buffer_line_curposXYZE(feedrate / 60, active_extruder);
+	plan_buffer_line_curposXYZE(feedrate / 60);
     st_synchronize();
 	if (!saved_e_relative_mode) axis_relative_modes &= ~E_AXIS_MASK;
 }
@@ -830,7 +829,7 @@ void mmu_M600_wait_and_beep() {
 		KEEPALIVE_STATE(PAUSED_FOR_USER);
 
 		int counterBeep = 0;
-		lcd_display_message_fullscreen_P(_i("Remove old filament and press the knob to start loading new filament."));
+		lcd_display_message_fullscreen_P(_i("Remove old filament and press the knob to start loading new filament.")); ////MSG_REMOVE_OLD_FILAMENT c=20 r=5
 		bool bFirst=true;
 
 		while (!lcd_clicked()){
@@ -879,8 +878,8 @@ void mmu_M600_load_filament(bool automatic, float nozzle_temp)
     }
     lcd_update_enable(false);
     lcd_clear();
-    lcd_set_cursor(0, 1); lcd_puts_P(_T(MSG_LOADING_FILAMENT));
-    lcd_print(" ");
+    lcd_puts_at_P(0, 1, _T(MSG_LOADING_FILAMENT));
+    lcd_print(' ');
     lcd_print(tmp_extruder + 1);
     snmm_filaments_used |= (1 << tmp_extruder); //for stop print
 
@@ -992,10 +991,10 @@ void extr_adj(uint8_t extruder) //loading filament for SNMM
 	
 	lcd_update_enable(false);
 	lcd_clear();
-	lcd_set_cursor(0, 1); lcd_puts_P(_T(MSG_LOADING_FILAMENT));
+	lcd_puts_at_P(0, 1, _T(MSG_LOADING_FILAMENT));
 	//if(strlen(_T(MSG_LOADING_FILAMENT))>18) lcd.setCursor(0, 1);
 	//else lcd.print(" ");
-	lcd_print(" ");
+	lcd_print(' ');
 	lcd_print(extruder + 1);
 
 	// get response
@@ -1035,7 +1034,7 @@ void extr_adj(uint8_t extruder) //loading filament for SNMM
 	lcd_clear();
 	lcd_set_cursor(0, 0); lcd_puts_P(_T(MSG_LOADING_FILAMENT));
 	if(strlen(_T(MSG_LOADING_FILAMENT))>18) lcd_set_cursor(0, 1);
-	else lcd_print(" ");
+	else lcd_print(' ');
 	lcd_print(mmu_extruder + 1);
 	lcd_set_cursor(0, 2); lcd_puts_P(_T(MSG_PLEASE_WAIT));
 	st_synchronize();
@@ -1072,7 +1071,7 @@ void mmu_filament_ramming()
     for(uint8_t i = 0; i < (sizeof(ramming_sequence)/sizeof(E_step));++i)
     {
         current_position[E_AXIS] += pgm_read_float(&(ramming_sequence[i].extrude));
-        plan_buffer_line_curposXYZE(pgm_read_float(&(ramming_sequence[i].feed_rate)), active_extruder);
+        plan_buffer_line_curposXYZE(pgm_read_float(&(ramming_sequence[i].feed_rate)));
         st_synchronize();
     }
 }
@@ -1082,9 +1081,9 @@ void mmu_filament_ramming()
 void extr_unload_view()
 {
     lcd_clear();
-    lcd_set_cursor(0, 1); lcd_puts_P(_T(MSG_UNLOADING_FILAMENT));
-    lcd_print(" ");
-    if (mmu_extruder == MMU_FILAMENT_UNKNOWN) lcd_print(" ");
+    lcd_puts_at_P(0, 1, _T(MSG_UNLOADING_FILAMENT));
+    lcd_print(' ');
+    if (mmu_extruder == MMU_FILAMENT_UNKNOWN) lcd_print(' ');
     else lcd_print(mmu_extruder + 1);
 }
 
@@ -1116,7 +1115,7 @@ void extr_unload()
 		lcd_display_message_fullscreen_P(PSTR(""));
 		max_feedrate[E_AXIS] = 50;
 		lcd_set_cursor(0, 0); lcd_puts_P(_T(MSG_UNLOADING_FILAMENT));
-		lcd_print(" ");
+		lcd_print(' ');
 		lcd_print(mmu_extruder + 1);
 		lcd_set_cursor(0, 2); lcd_puts_P(_T(MSG_PLEASE_WAIT));
 		if (current_position[Z_AXIS] < 15) {
@@ -1350,9 +1349,8 @@ void lcd_mmu_load_to_nozzle(uint8_t filament_nr)
         tmp_extruder = filament_nr;
         lcd_update_enable(false);
         lcd_clear();
-        lcd_set_cursor(0, 1);
-        lcd_puts_P(_T(MSG_LOADING_FILAMENT));
-        lcd_print(" ");
+        lcd_puts_at_P(0, 1, _T(MSG_LOADING_FILAMENT));
+        lcd_print(' ');
         lcd_print(tmp_extruder + 1);
         mmu_command(MmuCmd::T0 + tmp_extruder);
         manage_response(true, true, MMU_TCODE_MOVE);
@@ -1385,8 +1383,8 @@ void mmu_cut_filament(uint8_t filament_nr)
     {
         LcdUpdateDisabler disableLcdUpdate;
         lcd_clear();
-        lcd_set_cursor(0, 1); lcd_puts_P(_i("Cutting filament")); //// c=18 r=1
-        lcd_print(" ");
+        lcd_puts_at_P(0, 1, _i("Cutting filament")); //// c=18
+        lcd_print(' ');
         lcd_print(filament_nr + 1);
         mmu_filament_ramming();
         mmu_command(MmuCmd::K0 + filament_nr);
@@ -1413,7 +1411,7 @@ bFilamentAction=false;                            // NOT in "mmu_fil_eject_menu(
 			{
 			    LcdUpdateDisabler disableLcdUpdate;
                 lcd_clear();
-                lcd_set_cursor(0, 1); lcd_puts_P(_i("Ejecting filament"));
+                lcd_puts_at_P(0, 1, _i("Ejecting filament"));
                 mmu_filament_ramming();
                 mmu_command(MmuCmd::E0 + filament);
                 manage_response(false, false, MMU_UNLOAD_MOVE);
@@ -1446,9 +1444,9 @@ bFilamentAction=false;                            // NOT in "mmu_fil_eject_menu(
 static bool can_load()
 {
     current_position[E_AXIS] += 60;
-    plan_buffer_line_curposXYZE(MMU_LOAD_FEEDRATE, active_extruder);
+    plan_buffer_line_curposXYZE(MMU_LOAD_FEEDRATE);
     current_position[E_AXIS] -= 52;
-    plan_buffer_line_curposXYZE(MMU_LOAD_FEEDRATE, active_extruder);
+    plan_buffer_line_curposXYZE(MMU_LOAD_FEEDRATE);
     st_synchronize();
 
     uint_least8_t filament_detected_count = 0;
@@ -1458,9 +1456,9 @@ static bool can_load()
     for(uint_least8_t i = 0; i < steps; ++i)
     {
         current_position[E_AXIS] -= e_increment;
-        plan_buffer_line_curposXYZE(MMU_LOAD_FEEDRATE, active_extruder);
+        plan_buffer_line_curposXYZE(MMU_LOAD_FEEDRATE);
         st_synchronize();
-        if(0 == PIN_GET(IR_SENSOR_PIN))
+        if(0 == READ(IR_SENSOR_PIN))
         {
             ++filament_detected_count;
             DEBUG_PUTCHAR('O');
@@ -1491,7 +1489,7 @@ static bool load_more()
 {
     for (uint8_t i = 0; i < MMU_IDLER_SENSOR_ATTEMPTS_NR; i++)
     {
-        if (PIN_GET(IR_SENSOR_PIN) == 0) return true;
+        if (READ(IR_SENSOR_PIN) == 0) return true;
         DEBUG_PRINTF_P(PSTR("Additional load attempt nr. %d\n"), i);
         mmu_command(MmuCmd::C0);
         manage_response(true, true, MMU_LOAD_MOVE);

+ 21 - 11
Firmware/optiboot_w25x20cl.cpp

@@ -99,9 +99,11 @@ struct block_t;
 extern struct block_t *block_buffer;
 
 //! @brief Enter an STK500 compatible Optiboot boot loader waiting for flashing the languages to an external flash memory.
-void optiboot_w25x20cl_enter()
+//! @return 1 if "start\n" was not sent. Optiboot was skipped
+//! @return 0 if "start\n" was sent. Optiboot ran normally. No need to send "start\n" in setup()
+uint8_t optiboot_w25x20cl_enter()
 {
-  if (boot_app_flags & BOOT_APP_FLG_USER0) return;
+  if (boot_app_flags & BOOT_APP_FLG_USER0) return 1;
   uint8_t ch;
   uint8_t rampz = 0;
   register uint16_t address = 0;
@@ -120,38 +122,46 @@ void optiboot_w25x20cl_enter()
     unsigned long  boot_timer = 0;
     const char    *ptr = entry_magic_send;
     const char    *end = strlen_P(entry_magic_send) + ptr;
-    // Initialize the serial line.
-    UCSR0A |= (1 << U2X0);
-    UBRR0L = (((float)(F_CPU))/(((float)(115200))*8.0)-1.0+0.5);
-    UCSR0B = (1 << RXEN0) | (1 << TXEN0);
+    const uint8_t selectedSerialPort_bak = selectedSerialPort;
     // Flush the serial line.
     while (RECV_READY) {
       watchdogReset();
       // Dummy register read (discard)
       (void)(*(char *)UDR0);
     }
+    selectedSerialPort = 0; //switch to Serial0
+    MYSERIAL.flush(); //clear RX buffer
+    int SerialHead = rx_buffer.head;
     // Send the initial magic string.
     while (ptr != end)
       putch(pgm_read_byte(ptr ++));
     watchdogReset();
-    // Wait for one second until a magic string (constant entry_magic) is received
+    // Wait for two seconds until a magic string (constant entry_magic) is received
     // from the serial line.
     ptr = entry_magic_receive;
     end = strlen_P(entry_magic_receive) + ptr;
     while (ptr != end) {
-      while (! RECV_READY) {
+      while (rx_buffer.head == SerialHead) {
         watchdogReset();
         delayMicroseconds(1);
         if (++ boot_timer > boot_timeout)
+        {
           // Timeout expired, continue with the application.
-          return;
+          selectedSerialPort = selectedSerialPort_bak; //revert Serial setting
+          return 0;
+        }
       }
-      ch = UDR0;
+      ch = rx_buffer.buffer[SerialHead];
+      SerialHead = (unsigned int)(SerialHead + 1) % RX_BUFFER_SIZE;
       if (pgm_read_byte(ptr ++) != ch)
+      {
           // Magic was not received correctly, continue with the application
-          return;
+          selectedSerialPort = selectedSerialPort_bak; //revert Serial setting
+          return 0;
+      }
       watchdogReset();
     }
+    cbi(UCSR0B, RXCIE0); //disable the MarlinSerial0 interrupt
     // Send the cfm magic string.
     ptr = entry_magic_cfm;
     while (ptr != end)

+ 1 - 1
Firmware/optiboot_w25x20cl.h

@@ -1,6 +1,6 @@
 #ifndef OPTIBOOT_W25X20CL_H
 #define OPTIBOOT_W25X20CL_H
 
-extern void optiboot_w25x20cl_enter();
+extern uint8_t optiboot_w25x20cl_enter();
 
 #endif /* OPTIBOOT_W25X20CL_H */

+ 55 - 28
Firmware/pat9125.c

@@ -26,12 +26,15 @@
 #define PAT9125_BANK_SELECTION	0x7f
 
 
-#ifdef PAT9125_SWSPI
+#if defined(PAT9125_SWSPI)
 #include "swspi.h"
-#endif //PAT9125_SWSPI
-#ifdef PAT9125_SWI2C
+#elif defined(PAT9125_SWI2C)
 #include "swi2c.h"
-#endif //PAT9125_SWI2C
+#elif defined(PAT9125_I2C)
+#include "twi.h"
+#else
+#error unknown PAT9125 communication method
+#endif
 
 
 uint8_t pat9125_PID1 = 0;
@@ -103,14 +106,31 @@ extern FILE _uartout;
 #define uartout (&_uartout)
 
 
+uint8_t pat9125_probe()
+{
+#if defined(PAT9125_SWSPI)
+    swspi_init();
+  #error not implemented
+#elif defined(PAT9125_SWI2C)
+    swi2c_init();
+    return swi2c_readByte_A8(PAT9125_I2C_ADDR,0x00,NULL);
+#elif defined(PAT9125_I2C)
+    twi_init();
+  #ifdef IR_SENSOR
+    // NOTE: this is called from the MK3S variant, so it should be kept minimal
+    uint8_t data;
+    return (twi_r8(PAT9125_I2C_ADDR,PAT9125_PID1,&data) == 0);
+  #else
+    return (pat9125_rd_reg(PAT9125_PID1) != 0);
+  #endif
+#endif
+}
+
 uint8_t pat9125_init(void)
 {
-#ifdef PAT9125_SWSPI
-	swspi_init();
-#endif //PAT9125_SWSPI
-#ifdef PAT9125_SWI2C
-	swi2c_init();
-#endif //PAT9125_SWI2C
+    if (!pat9125_probe())
+        return 0;
+
 	// Verify that the sensor responds with its correct product ID.
 	pat9125_PID1 = pat9125_rd_reg(PAT9125_PID1);
 	pat9125_PID2 = pat9125_rd_reg(PAT9125_PID2);
@@ -234,39 +254,46 @@ uint8_t pat9125_update_bs(void)
 uint8_t pat9125_rd_reg(uint8_t addr)
 {
 	uint8_t data = 0;
-#ifdef PAT9125_SWSPI
+#if defined(PAT9125_SWSPI)
 	swspi_start();
 	swspi_tx(addr & 0x7f);
 	data = swspi_rx();
 	swspi_stop();
-#endif //PAT9125_SWSPI
-#ifdef PAT9125_SWI2C
+#elif defined(PAT9125_SWI2C)
 	if (!swi2c_readByte_A8(PAT9125_I2C_ADDR, addr, &data)) //NO ACK error
-	{
-		pat9125_PID1 = 0xff;
-		pat9125_PID2 = 0xff;
-		return 0;
-	}
-#endif //PAT9125_SWI2C
+        goto error;
+#elif defined(PAT9125_I2C)
+	if (twi_r8(PAT9125_I2C_ADDR,addr,&data))
+        goto error;
+#endif
 	return data;
+
+ error:
+    pat9125_PID1 = 0xff;
+    pat9125_PID2 = 0xff;
+    return 0;
 }
 
 void pat9125_wr_reg(uint8_t addr, uint8_t data)
 {
-#ifdef PAT9125_SWSPI
+#if defined(PAT9125_SWSPI)
 	swspi_start();
 	swspi_tx(addr | 0x80);
 	swspi_tx(data);
 	swspi_stop();
-#endif //PAT9125_SWSPI
-#ifdef PAT9125_SWI2C
+#elif defined(PAT9125_SWI2C)
 	if (!swi2c_writeByte_A8(PAT9125_I2C_ADDR, addr, &data)) //NO ACK error
-	{
-		pat9125_PID1 = 0xff;
-		pat9125_PID2 = 0xff;
-		return;
-	}
-#endif //PAT9125_SWI2C
+        goto error;
+#elif defined(PAT9125_I2C)
+	if (twi_w8(PAT9125_I2C_ADDR,addr,data))
+        goto error;
+#endif
+    return;
+
+ error:
+    pat9125_PID1 = 0xff;
+    pat9125_PID2 = 0xff;
+    return;
 }
 
 uint8_t pat9125_wr_reg_verify(uint8_t addr, uint8_t data)

+ 1 - 0
Firmware/pat9125.h

@@ -18,6 +18,7 @@ extern int16_t pat9125_y;
 extern uint8_t pat9125_b;
 extern uint8_t pat9125_s;
 
+extern uint8_t pat9125_probe(void);     // Return non-zero if PAT9125 can be trivially detected
 extern uint8_t pat9125_init(void);
 extern uint8_t pat9125_update(void);    // update all sensor data
 extern uint8_t pat9125_update_y(void);  // update _y only

+ 5 - 0
Firmware/pins.h

@@ -25,6 +25,11 @@
 #error Unknown MOTHERBOARD value in configuration.h
 #endif
 
+#if !defined(SDA_PIN) && (defined(__AVR_ATmega1280__) || defined(__AVR_ATmega2560__))
+#define SDA_PIN 20
+#define SCL_PIN 21
+#endif
+
 //List of pins which to ignore when asked to change by gcode, 0 and 1 are RX and TX, do not mess with those!
 #define _E0_PINS E0_STEP_PIN, E0_DIR_PIN, E0_ENABLE_PIN, HEATER_0_PIN,
 #if EXTRUDERS > 1

+ 2 - 6
Firmware/pins_Einsy_1_0.h

@@ -18,12 +18,6 @@
 #define W25X20CL                 // external 256kB flash
 #define BOOTAPP                  // bootloader support
 
-
-#define SWI2C_SDA      20 //SDA on P3
-#define SWI2C_SCL      21 //SCL on P3
-
-
-
 #define X_TMC2130_CS           41
 #define X_TMC2130_DIAG         64 // !!! changed from 40 (EINY03)
 #define X_STEP_PIN             37
@@ -121,6 +115,8 @@
 
 #define IR_SENSOR_PIN 62 //idler sensor @PK0 (digital pin 62/A8)
 
+#define MMU_RST_PIN 76
+
 // Support for an 8 bit logic analyzer, for example the Saleae.
 // Channels 0-2 are fast, they could generate 2.667Mhz waveform with a software loop.
 #define LOGIC_ANALYZER_CH0		X_MIN_PIN		// PB6

+ 0 - 3
Firmware/pins_Rambo_1_3.h

@@ -11,9 +11,6 @@
 
 #define PINDA_THERMISTOR
 
-#define SWI2C_SDA      20 //SDA on P3
-#define SWI2C_SCL      21 //SCL on P3
-
 #ifdef MICROMETER_LOGGING
 #define D_DATACLOCK		24	//Y_MAX (green)
 #define D_DATA			30	//X_MAX (blue)

+ 106 - 64
Firmware/planner.cpp

@@ -126,7 +126,7 @@ float extrude_min_temp=EXTRUDE_MINTEMP;
 #endif
 
 #ifdef LIN_ADVANCE
-float extruder_advance_K = LIN_ADVANCE_K;
+float extruder_advance_K = LA_K_DEF;
 float position_float[NUM_AXIS];
 #endif
 
@@ -226,11 +226,23 @@ void calculate_trapezoid_for_block(block_t *block, float entry_speed, float exit
   // Size of Plateau of Nominal Rate.
   uint32_t plateau_steps     = 0;
 
+#ifdef LIN_ADVANCE
+  uint16_t final_adv_steps = 0;
+  uint16_t max_adv_steps = 0;
+  if (block->use_advance_lead) {
+      final_adv_steps = final_rate * block->adv_comp;
+  }
+#endif
+
   // 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 acceleration and start braking
   // in order to reach the final_rate exactly at the end of this block.
   if (accel_decel_steps < block->step_event_count.wide) {
     plateau_steps = block->step_event_count.wide - accel_decel_steps;
+#ifdef LIN_ADVANCE
+    if (block->use_advance_lead)
+        max_adv_steps = block->nominal_rate * block->adv_comp;
+#endif
   } else {
     uint32_t acceleration_x4  = acceleration << 2;
     // Avoid negative numbers
@@ -263,14 +275,20 @@ void calculate_trapezoid_for_block(block_t *block, float entry_speed, float exit
             decelerate_steps = block->step_event_count.wide;
         accelerate_steps = block->step_event_count.wide - decelerate_steps;
     }
-  }
 
 #ifdef LIN_ADVANCE
-  uint16_t final_adv_steps = 0;
-  if (block->use_advance_lead) {
-      final_adv_steps = exit_speed * block->adv_comp;
-  }
+    if (block->use_advance_lead) {
+        if(!accelerate_steps || !decelerate_steps) {
+            // accelerate_steps=0: deceleration-only ramp, max_rate is effectively unused
+            // decelerate_steps=0: acceleration-only ramp, max_rate _is_ final_rate
+            max_adv_steps = final_adv_steps;
+        } else {
+            float max_rate = sqrt(acceleration_x2 * accelerate_steps + initial_rate_sqr);
+            max_adv_steps = max_rate * block->adv_comp;
+        }
+    }
 #endif
+  }
 
   CRITICAL_SECTION_START;  // Fill variables used by the stepper in a critical section
   // This block locks the interrupts globally for 4.38 us,
@@ -284,6 +302,7 @@ void calculate_trapezoid_for_block(block_t *block, float entry_speed, float exit
     block->final_rate = final_rate;
 #ifdef LIN_ADVANCE
     block->final_adv_steps = final_adv_steps;
+    block->max_adv_steps = max_adv_steps;
 #endif
   }
   CRITICAL_SECTION_END;
@@ -671,8 +690,16 @@ void planner_abort_hard()
     waiting_inside_plan_buffer_line_print_aborted = true;
 }
 
-void plan_buffer_line_curposXYZE(float feed_rate, uint8_t extruder) { 
-	plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], feed_rate, extruder );
+void plan_buffer_line_curposXYZE(float feed_rate) {
+    plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], feed_rate, active_extruder );
+}
+
+void plan_buffer_line_destinationXYZE(float feed_rate) {
+    plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feed_rate, active_extruder);
+}
+
+void plan_set_position_curposXYZE(){
+    plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
 }
 
 float junction_deviation = 0.1;
@@ -1055,26 +1082,35 @@ Having the real displacement of the head, we can calculate the total movement le
   }
   else
   {
-    block->acceleration_st = ceil(cs.acceleration * steps_per_mm); // convert to: acceleration steps/sec^2
+    float acceleration = (block->steps_e.wide == 0? cs.travel_acceleration: cs.acceleration);
+    block->acceleration_st = ceil(acceleration * steps_per_mm); // convert to: acceleration steps/sec^2
 
     #ifdef LIN_ADVANCE
     /**
      * Use LIN_ADVANCE within this block if all these are true:
      *
-     * block->steps_e           : This is a print move, because we checked for X, Y, Z steps before.
      * extruder_advance_K       : There is an advance factor set.
-     * delta_mm[E_AXIS] > 0     : Extruder is running forward (e.g., for "Wipe while retracting" (Slic3r) or "Combing" (Cura) moves)
+     * delta_mm[E_AXIS] >= 0    : Extruding or traveling, but _not_ retracting.
      * |delta_mm[Z_AXIS]| < 0.5 : Z is only moved for leveling (_not_ for priming)
      */
-    block->use_advance_lead = block->steps_e.wide
-                              && extruder_advance_K
-                              && delta_mm[E_AXIS] > 0
+    block->use_advance_lead = extruder_advance_K > 0
+                              && delta_mm[E_AXIS] >= 0
                               && abs(delta_mm[Z_AXIS]) < 0.5;
     if (block->use_advance_lead) {
-        e_D_ratio = (e - position_float[E_AXIS]) /
-                    sqrt(sq(x - position_float[X_AXIS])
-                         + sq(y - position_float[Y_AXIS])
-                         + sq(z - position_float[Z_AXIS]));
+#ifdef LA_FLOWADJ
+        // M221/FLOW should change uniformly the extrusion thickness
+        float delta_e = (e - position_float[E_AXIS]) / extruder_multiplier[extruder];
+#else
+        // M221/FLOW only adjusts for an incorrect source diameter
+        float delta_e = (e - position_float[E_AXIS]);
+#endif
+        float delta_D = sqrt(sq(x - position_float[X_AXIS])
+                             + sq(y - position_float[Y_AXIS])
+                             + sq(z - position_float[Z_AXIS]));
+
+        // all extrusion moves with LA require a compression which is proportional to the
+        // extrusion_length to distance ratio (e/D)
+        e_D_ratio = delta_e / delta_D;
 
         // Check for unusual high e_D ratio to detect if a retract move was combined with the last
         // print move due to min. steps per segment. Never execute this with advance! This assumes
@@ -1082,10 +1118,10 @@ Having the real displacement of the head, we can calculate the total movement le
         // 100mm wide lines using 3mm filament or 35mm wide lines using 1.75mm filament.
         if (e_D_ratio > 3.0)
             block->use_advance_lead = false;
-        else {
-            const uint32_t max_accel_steps_per_s2 = cs.max_jerk[E_AXIS] / (extruder_advance_K * e_D_ratio) * steps_per_mm;
-            if (block->acceleration_st > max_accel_steps_per_s2) {
-                block->acceleration_st = max_accel_steps_per_s2;
+        else if (e_D_ratio > 0) {
+            const float max_accel_per_s2 = cs.max_jerk[E_AXIS] / (extruder_advance_K * e_D_ratio);
+            if (cs.acceleration > max_accel_per_s2) {
+                block->acceleration_st = ceil(max_accel_per_s2 * steps_per_mm);
                 #ifdef LA_DEBUG
                 SERIAL_ECHOLNPGM("LA: Block acceleration limited due to max E-jerk");
                 #endif
@@ -1124,48 +1160,7 @@ Having the real displacement of the head, we can calculate the total movement le
     block->acceleration_st = (block->acceleration_st + (bresenham_oversample >> 1)) / bresenham_oversample;
 #endif
 
-  block->acceleration_rate = (long)((float)block->acceleration_st * (16777216.0 / (F_CPU / 8.0)));
-
-#ifdef LIN_ADVANCE
-  if (block->use_advance_lead) {
-      // the nominal speed doesn't change past this point: calculate the compression ratio for the
-      // segment and the required advance steps
-      block->adv_comp = extruder_advance_K * e_D_ratio * cs.axis_steps_per_unit[E_AXIS];
-      block->max_adv_steps = block->nominal_speed * block->adv_comp;
-
-      // to save more space we avoid another copy of calc_timer and go through slow division, but we
-      // still need to replicate the *exact* same step grouping policy (see below)
-      float advance_speed = (extruder_advance_K * e_D_ratio * block->acceleration * cs.axis_steps_per_unit[E_AXIS]);
-      if (advance_speed > MAX_STEP_FREQUENCY) advance_speed = MAX_STEP_FREQUENCY;
-      float advance_rate = (F_CPU / 8.0) / advance_speed;
-      if (advance_speed > 20000) {
-          block->advance_rate = advance_rate * 4;
-          block->advance_step_loops = 4;
-      }
-      else if (advance_speed > 10000) {
-          block->advance_rate = advance_rate * 2;
-          block->advance_step_loops = 2;
-      }
-      else
-      {
-          // never overflow the internal accumulator with very low rates
-          if (advance_rate < UINT16_MAX)
-              block->advance_rate = advance_rate;
-          else
-              block->advance_rate = UINT16_MAX;
-          block->advance_step_loops = 1;
-      }
-
-      #ifdef LA_DEBUG
-      if (block->advance_step_loops > 2)
-          // @wavexx: we should really check for the difference between step_loops and
-          //          advance_step_loops instead. A difference of more than 1 will lead
-          //          to uneven speed and *should* be adjusted here by furthermore
-          //          reducing the speed.
-          SERIAL_ECHOLNPGM("LA: More than 2 steps per eISR loop executed.");
-      #endif
-  }
-#endif
+  block->acceleration_rate = ((float)block->acceleration_st * (16777216.0 / (F_CPU / 8.0)));
 
   // Start with a safe speed.
   // Safe speed is the speed, from which the machine may halt to stop immediately.
@@ -1292,6 +1287,53 @@ Having the real displacement of the head, we can calculate the total movement le
 
   // Precalculate the division, so when all the trapezoids in the planner queue get recalculated, the division is not repeated.
   block->speed_factor = block->nominal_rate / block->nominal_speed;
+
+#ifdef LIN_ADVANCE
+  if (block->use_advance_lead) {
+      // calculate the compression ratio for the segment (the required advance steps are computed
+      // during trapezoid planning)
+      float adv_comp = extruder_advance_K * e_D_ratio * cs.axis_steps_per_unit[E_AXIS]; // (step/(mm/s))
+      block->adv_comp = adv_comp / block->speed_factor; // step/(step/min)
+
+      float advance_speed;
+      if (e_D_ratio > 0)
+          advance_speed = (extruder_advance_K * e_D_ratio * block->acceleration * cs.axis_steps_per_unit[E_AXIS]);
+      else
+          advance_speed = cs.max_jerk[E_AXIS] * cs.axis_steps_per_unit[E_AXIS];
+
+      // to save more space we avoid another copy of calc_timer and go through slow division, but we
+      // still need to replicate the *exact* same step grouping policy (see below)
+      if (advance_speed > MAX_STEP_FREQUENCY) advance_speed = MAX_STEP_FREQUENCY;
+      float advance_rate = (F_CPU / 8.0) / advance_speed;
+      if (advance_speed > 20000) {
+          block->advance_rate = advance_rate * 4;
+          block->advance_step_loops = 4;
+      }
+      else if (advance_speed > 10000) {
+          block->advance_rate = advance_rate * 2;
+          block->advance_step_loops = 2;
+      }
+      else
+      {
+          // never overflow the internal accumulator with very low rates
+          if (advance_rate < UINT16_MAX)
+              block->advance_rate = advance_rate;
+          else
+              block->advance_rate = UINT16_MAX;
+          block->advance_step_loops = 1;
+      }
+
+      #ifdef LA_DEBUG
+      if (block->advance_step_loops > 2)
+          // @wavexx: we should really check for the difference between step_loops and
+          //          advance_step_loops instead. A difference of more than 1 will lead
+          //          to uneven speed and *should* be adjusted here by furthermore
+          //          reducing the speed.
+          SERIAL_ECHOLNPGM("LA: More than 2 steps per eISR loop executed.");
+      #endif
+  }
+#endif
+
   calculate_trapezoid_for_block(block, block->entry_speed, safe_speed);
 
   if (block->step_event_count.wide <= 32767)

+ 10 - 7
Firmware/planner.h

@@ -73,12 +73,12 @@ typedef struct {
   // steps_x.y,z, step_event_count, acceleration_rate, direction_bits and active_extruder are set by plan_buffer_line().
   dda_isteps_t steps_x, steps_y, steps_z, steps_e;  // Step count along each axis
   dda_usteps_t step_event_count;            // The number of step events required to complete this block
-  long acceleration_rate;                   // The acceleration rate used for acceleration calculation
+  uint32_t acceleration_rate;               // The acceleration rate used for acceleration calculation
   unsigned char direction_bits;             // The direction bit set for this block (refers to *_DIRECTION_BIT in config.h)
   unsigned char active_extruder;            // Selects the active extruder
   // accelerate_until and decelerate_after are set by calculate_trapezoid_for_block() and they need to be synchronized with the stepper interrupt controller.
-  long accelerate_until;                    // The index of the step event on which to stop acceleration
-  long decelerate_after;                    // The index of the step event on which to start decelerating
+  uint32_t accelerate_until;                // The index of the step event on which to stop acceleration
+  uint32_t decelerate_after;                // The index of the step event on which to start decelerating
 
   // Fields used by the motion planner to manage acceleration
 //  float speed_x, speed_y, speed_z, speed_e;        // Nominal mm/sec for each axis
@@ -100,13 +100,12 @@ typedef struct {
 
   // Settings for the trapezoid generator (runs inside an interrupt handler).
   // Changing the following values in the planner needs to be synchronized with the interrupt handler by disabling the interrupts.
-  //FIXME nominal_rate, initial_rate and final_rate are limited to uint16_t by MultiU24X24toH16 in the stepper interrupt anyway!
   unsigned long nominal_rate;                        // The nominal step rate for this block in step_events/sec 
   unsigned long initial_rate;                        // The jerk-adjusted step rate at start of block  
   unsigned long final_rate;                          // The minimal rate at exit
   unsigned long acceleration_st;                     // acceleration steps/sec^2
-  //FIXME does it have to be unsigned long? Probably uint8_t would be just fine.
-  unsigned long fan_speed;
+  //FIXME does it have to be int? Probably uint8_t would be just fine. Need to change in other places as well
+  int fan_speed;
   volatile char busy;
 
 
@@ -154,7 +153,11 @@ vector_3 plan_get_position();
 /// plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[3], ...
 /// saves almost 5KB.
 /// The performance penalty is negligible, since these planned lines are usually maintenance moves with the extruder.
-void plan_buffer_line_curposXYZE(float feed_rate, uint8_t extruder);
+void plan_buffer_line_curposXYZE(float feed_rate);
+
+void plan_buffer_line_destinationXYZE(float feed_rate);
+
+void plan_set_position_curposXYZE();
 
 void plan_buffer_line(float x, float y, float z, const float &e, float feed_rate, uint8_t extruder, const float* gcode_target = NULL);
 //void plan_buffer_line(const float &x, const float &y, const float &z, const float &e, float feed_rate, const uint8_t &extruder);

+ 45 - 1
Firmware/sm4.c

@@ -129,11 +129,15 @@ void sm4_set_dir_bits(uint8_t dir_bits)
 void sm4_do_step(uint8_t axes_mask)
 {
 #if ((MOTHERBOARD == BOARD_RAMBO_MINI_1_0) || (MOTHERBOARD == BOARD_RAMBO_MINI_1_3) || (MOTHERBOARD == BOARD_EINSY_1_0a))
+#ifdef TMC2130_DEDGE_STEPPING
+	PINC = (axes_mask & 0x0f); // toggle step signals by mask
+#else
     register uint8_t portC = PORTC & 0xf0;
 	PORTC = portC | (axes_mask & 0x0f); //set step signals by mask
 	asm("nop");
 	PORTC = portC; //set step signals to zero
 	asm("nop");
+#endif
 #endif //((MOTHERBOARD == BOARD_RAMBO_MINI_1_0) || (MOTHERBOARD == BOARD_RAMBO_MINI_1_3) || (MOTHERBOARD == BOARD_EINSY_1_0a))
 }
 
@@ -173,7 +177,7 @@ uint16_t sm4_line_xyze_ui(uint16_t dx, uint16_t dy, uint16_t dz, uint16_t de)
 		}
 		if (ce <= de)
 		{
-			sm |= 4;
+			sm |= 8;
 			ce += dd;
 			e++;
 		}
@@ -191,5 +195,45 @@ uint16_t sm4_line_xyze_ui(uint16_t dx, uint16_t dy, uint16_t dz, uint16_t de)
 	return nd;
 }
 
+uint16_t sm4_line_xyz_ui(uint16_t dx, uint16_t dy, uint16_t dz){
+	uint16_t dd = (uint16_t)(sqrt((float)(((uint32_t)dx)*dx + ((uint32_t)dy*dy) + ((uint32_t)dz*dz))) + 0.5);
+	uint16_t nd = dd;
+	uint16_t cx = dd;
+	uint16_t cy = dd;
+	uint16_t cz = dd;
+	uint16_t x = 0;
+	uint16_t y = 0;
+	uint16_t z = 0;
+	while (nd){
+		if (sm4_stop_cb && (*sm4_stop_cb)()) break;
+		uint8_t sm = 0; //step mask
+		if (cx <= dx){
+			sm |= 1;
+			cx += dd;
+			x++;
+		}
+		if (cy <= dy){
+			sm |= 2;
+			cy += dd;
+			y++;
+		}
+		if (cz <= dz){
+			sm |= 4;
+			cz += dd;
+			z++;
+		}
+		cx -= dx;
+		cy -= dy;
+		cz -= dz;
+		sm4_do_step(sm);
+		uint16_t delay = SM4_DEFDELAY;
+		if (sm4_calc_delay_cb) delay = (*sm4_calc_delay_cb)(nd, dd);
+		if (delay) delayMicroseconds(delay);
+		nd--;
+	}
+	if (sm4_update_pos_cb)
+		(*sm4_update_pos_cb)(x, y, z, 0);
+	return nd;
+}
 
 #endif //NEW_XYZCAL

+ 1 - 0
Firmware/sm4.h

@@ -48,6 +48,7 @@ extern void sm4_do_step(uint8_t axes_mask);
 
 // xyze linear-interpolated relative move, returns remaining diagonal steps (>0 means stoped)
 extern uint16_t sm4_line_xyze_ui(uint16_t dx, uint16_t dy, uint16_t dz, uint16_t de);
+extern uint16_t sm4_line_xyz_ui(uint16_t dx, uint16_t dy, uint16_t dz);
 
 
 #if defined(__cplusplus)

+ 11 - 5
Firmware/speed_lookuptable.h

@@ -80,15 +80,21 @@ asm volatile ( \
 
 #else //_NO_ASM
 
-// NOTE: currently not implemented
-void MultiU16X8toH16(unsigned short& intRes, unsigned char& charIn1, unsigned short& intIn2);
-void MultiU24X24toH16(uint16_t& intRes, int32_t& longIn1, long& longIn2);
+static inline void MultiU16X8toH16(uint16_t& intRes, uint8_t& charIn1, uint16_t& intIn2)
+{
+    intRes = ((uint32_t)charIn1 * (uint32_t)intIn2) >> 16;
+}
+
+static inline void MultiU24X24toH16(uint16_t& intRes, uint32_t& longIn1, uint32_t& longIn2)
+{
+    intRes = ((uint64_t)longIn1 * (uint64_t)longIn2) >> 24;
+}
 
 #endif //_NO_ASM
 
 
 FORCE_INLINE unsigned short calc_timer(uint16_t step_rate, uint8_t& step_loops) {
-  unsigned short timer;
+  uint16_t timer;
   if(step_rate > MAX_STEP_FREQUENCY) step_rate = MAX_STEP_FREQUENCY;
 
   if(step_rate > 20000) { // If steprate > 20kHz >> step 4 times
@@ -108,7 +114,7 @@ FORCE_INLINE unsigned short calc_timer(uint16_t step_rate, uint8_t& step_loops)
   if(step_rate >= (8*256)){ // higher step rate
     unsigned short table_address = (unsigned short)&speed_lookuptable_fast[(unsigned char)(step_rate>>8)][0];
     unsigned char tmp_step_rate = (step_rate & 0x00ff);
-    unsigned short gain = (unsigned short)pgm_read_word_near(table_address+2);
+    uint16_t gain = (uint16_t)pgm_read_word_near(table_address+2);
     MultiU16X8toH16(timer, tmp_step_rate, gain);
     timer = (unsigned short)pgm_read_word_near(table_address) - timer;
   }

+ 296 - 192
Firmware/stepper.cpp

@@ -48,6 +48,62 @@ int fsensor_counter; //counter for e-steps
 uint16_t SP_min = 0x21FF;
 #endif //DEBUG_STACK_MONITOR
 
+
+/*
+ * Stepping macros
+ */
+#define _STEP_PIN_X_AXIS X_STEP_PIN
+#define _STEP_PIN_Y_AXIS Y_STEP_PIN
+#define _STEP_PIN_Z_AXIS Z_STEP_PIN
+#define _STEP_PIN_E_AXIS E0_STEP_PIN
+
+#ifdef DEBUG_XSTEP_DUP_PIN
+#define _STEP_PIN_X_DUP_AXIS DEBUG_XSTEP_DUP_PIN
+#endif
+#ifdef DEBUG_YSTEP_DUP_PIN
+#define _STEP_PIN_Y_DUP_AXIS DEBUG_YSTEP_DUP_PIN
+#endif
+#ifdef Y_DUAL_STEPPER_DRIVERS
+#error Y_DUAL_STEPPER_DRIVERS not fully implemented
+#define _STEP_PIN_Y2_AXIS Y2_STEP_PIN
+#endif
+#ifdef Z_DUAL_STEPPER_DRIVERS
+#error Z_DUAL_STEPPER_DRIVERS not fully implemented
+#define _STEP_PIN_Z2_AXIS Z2_STEP_PIN
+#endif
+
+#ifdef TMC2130
+#define STEPPER_MINIMUM_PULSE TMC2130_MINIMUM_PULSE
+#define STEPPER_SET_DIR_DELAY TMC2130_SET_DIR_DELAY
+#define STEPPER_MINIMUM_DELAY TMC2130_MINIMUM_DELAY
+#else
+#define STEPPER_MINIMUM_PULSE 2
+#define STEPPER_SET_DIR_DELAY 100
+#define STEPPER_MINIMUM_DELAY delayMicroseconds(STEPPER_MINIMUM_PULSE)
+#endif
+
+#ifdef TMC2130_DEDGE_STEPPING
+static_assert(TMC2130_MINIMUM_DELAY 1, // this will fail to compile when non-empty
+              "DEDGE implies/requires an empty TMC2130_MINIMUM_DELAY");
+#define STEP_NC_HI(axis) TOGGLE(_STEP_PIN_##axis)
+#define STEP_NC_LO(axis) //NOP
+#else
+
+#define _STEP_HI_X_AXIS  !INVERT_X_STEP_PIN
+#define _STEP_LO_X_AXIS  INVERT_X_STEP_PIN
+#define _STEP_HI_Y_AXIS  !INVERT_Y_STEP_PIN
+#define _STEP_LO_Y_AXIS  INVERT_Y_STEP_PIN
+#define _STEP_HI_Z_AXIS  !INVERT_Z_STEP_PIN
+#define _STEP_LO_Z_AXIS  INVERT_Z_STEP_PIN
+#define _STEP_HI_E_AXIS  !INVERT_E_STEP_PIN
+#define _STEP_LO_E_AXIS  INVERT_E_STEP_PIN
+
+#define STEP_NC_HI(axis) WRITE_NC(_STEP_PIN_##axis, _STEP_HI_##axis)
+#define STEP_NC_LO(axis) WRITE_NC(_STEP_PIN_##axis, _STEP_LO_##axis)
+
+#endif //TMC2130_DEDGE_STEPPING
+
+
 //===========================================================================
 //=============================public variables  ============================
 //===========================================================================
@@ -71,8 +127,7 @@ static dda_isteps_t
                counter_z,
                counter_e;
 volatile dda_usteps_t step_events_completed; // The number of step events executed in the current block
-static int32_t  acceleration_time, deceleration_time;
-//static unsigned long accelerate_until, decelerate_after, acceleration_rate, initial_rate, final_rate, nominal_rate;
+static uint32_t  acceleration_time, deceleration_time;
 static uint16_t acc_step_rate; // needed for deccelaration start point
 static uint8_t  step_loops;
 static uint16_t OCR1A_nominal;
@@ -117,24 +172,23 @@ volatile signed char count_direction[NUM_AXIS] = { 1, 1, 1, 1};
   void advance_isr();
 
   static const uint16_t ADV_NEVER      = 0xFFFF;
-  static const uint8_t  ADV_INIT       = 0b01;
-  static const uint8_t  ADV_DECELERATE = 0b10;
+  static const uint8_t  ADV_INIT       = 0b01; // initialize LA
+  static const uint8_t  ADV_ACC_VARY   = 0b10; // varying acceleration phase
 
   static uint16_t nextMainISR;
   static uint16_t nextAdvanceISR;
 
   static uint16_t main_Rate;
   static uint16_t eISR_Rate;
-  static uint16_t eISR_Err;
+  static uint32_t eISR_Err;
 
   static uint16_t current_adv_steps;
-  static uint16_t final_adv_steps;
-  static uint16_t max_adv_steps;
-  static uint32_t LA_decelerate_after;
+  static uint16_t target_adv_steps;
 
-  static int8_t e_steps;
-  static uint8_t e_step_loops;
-  static int8_t LA_phase;
+  static int8_t e_steps;        // scheduled e-steps during each isr loop
+  static uint8_t e_step_loops;  // e-steps to execute at most in each isr loop
+  static uint8_t e_extruding;   // current move is an extrusion move
+  static int8_t LA_phase;       // LA compensation phase
 
   #define _NEXT_ISR(T)    main_Rate = nextMainISR = T
 #else
@@ -235,7 +289,7 @@ void invert_z_endstop(bool endstop_invert)
 //  The trapezoid is the shape the speed curve over time. It starts at block->initial_rate, accelerates
 //  first block->accelerate_until step_events_completed, then keeps going at constant speed until
 //  step_events_completed reaches block->decelerate_after after which it decelerates until the trapezoid generator is reset.
-//  The slope of acceleration is calculated with the leib ramp alghorithm.
+//  The slope of acceleration is calculated using v = u + at where t is the accumulated timer values of the steps so far.
 
 // "The Stepper Driver Interrupt" - This timer interrupt is the workhorse.
 // It pops blocks from the block_buffer and executes them by pulsing the stepper pins appropriately.
@@ -298,13 +352,13 @@ FORCE_INLINE void stepper_next_block()
 				WRITE_NC(X_DIR_PIN, INVERT_X_DIR);
 			else
 				WRITE_NC(X_DIR_PIN, !INVERT_X_DIR);
-			_delay_us(100);
+			delayMicroseconds(STEPPER_SET_DIR_DELAY);
 			for (uint8_t i = 0; i < st_backlash_x; i++)
 			{
-				WRITE_NC(X_STEP_PIN, !INVERT_X_STEP_PIN);
-				_delay_us(100);
-				WRITE_NC(X_STEP_PIN, INVERT_X_STEP_PIN);
-				_delay_us(900);
+				STEP_NC_HI(X_AXIS);
+				STEPPER_MINIMUM_DELAY;
+				STEP_NC_LO(X_AXIS);
+				_delay_us(900); // hard-coded jerk! *bad*
 			}
 		}
 		last_dir_bits &= ~1;
@@ -321,13 +375,13 @@ FORCE_INLINE void stepper_next_block()
 				WRITE_NC(Y_DIR_PIN, INVERT_Y_DIR);
 			else
 				WRITE_NC(Y_DIR_PIN, !INVERT_Y_DIR);
-			_delay_us(100);
+			delayMicroseconds(STEPPER_SET_DIR_DELAY);
 			for (uint8_t i = 0; i < st_backlash_y; i++)
 			{
-				WRITE_NC(Y_STEP_PIN, !INVERT_Y_STEP_PIN);
-				_delay_us(100);
-				WRITE_NC(Y_STEP_PIN, INVERT_Y_STEP_PIN);
-				_delay_us(900);
+				STEP_NC_HI(Y_AXIS);
+				STEPPER_MINIMUM_DELAY;
+				STEP_NC_LO(Y_AXIS);
+				_delay_us(900); // hard-coded jerk! *bad*
 			}
 		}
 		last_dir_bits &= ~2;
@@ -349,15 +403,9 @@ FORCE_INLINE void stepper_next_block()
 
 #ifdef LIN_ADVANCE
     if (current_block->use_advance_lead) {
-        LA_decelerate_after = current_block->decelerate_after;
-        final_adv_steps = current_block->final_adv_steps;
-        max_adv_steps = current_block->max_adv_steps;
-        e_step_loops = current_block->advance_step_loops;
-    } else {
-        e_steps = 0;
-        e_step_loops = 1;
-        current_adv_steps = 0;
+        target_adv_steps = current_block->max_adv_steps;
     }
+    e_steps = 0;
     nextAdvanceISR = ADV_NEVER;
     LA_phase = -1;
 #endif
@@ -371,11 +419,17 @@ FORCE_INLINE void stepper_next_block()
       counter_y.lo = counter_x.lo;
       counter_z.lo = counter_x.lo;
       counter_e.lo = counter_x.lo;
+#ifdef LIN_ADVANCE
+      e_extruding = current_block->steps_e.lo != 0;
+#endif
     } else {
       counter_x.wide = -(current_block->step_event_count.wide >> 1);
       counter_y.wide = counter_x.wide;
       counter_z.wide = counter_x.wide;
       counter_e.wide = counter_x.wide;
+#ifdef LIN_ADVANCE
+      e_extruding = current_block->steps_e.wide != 0;
+#endif
     }
     step_events_completed.wide = 0;
     // Set directions.
@@ -605,44 +659,44 @@ FORCE_INLINE void stepper_tick_lowres()
     // Step in X axis
     counter_x.lo += current_block->steps_x.lo;
     if (counter_x.lo > 0) {
-      WRITE_NC(X_STEP_PIN, !INVERT_X_STEP_PIN);
+      STEP_NC_HI(X_AXIS);
 #ifdef DEBUG_XSTEP_DUP_PIN
-      WRITE_NC(DEBUG_XSTEP_DUP_PIN,!INVERT_X_STEP_PIN);
+      STEP_NC_HI(X_DUP_AXIS);
 #endif //DEBUG_XSTEP_DUP_PIN
       counter_x.lo -= current_block->step_event_count.lo;
       count_position[X_AXIS]+=count_direction[X_AXIS];
-      WRITE_NC(X_STEP_PIN, INVERT_X_STEP_PIN);
+      STEP_NC_LO(X_AXIS);
 #ifdef DEBUG_XSTEP_DUP_PIN
-      WRITE_NC(DEBUG_XSTEP_DUP_PIN,INVERT_X_STEP_PIN);
+      STEP_NC_LO(X_DUP_AXIS);
 #endif //DEBUG_XSTEP_DUP_PIN
     }
     // Step in Y axis
     counter_y.lo += current_block->steps_y.lo;
     if (counter_y.lo > 0) {
-      WRITE_NC(Y_STEP_PIN, !INVERT_Y_STEP_PIN);
+      STEP_NC_HI(Y_AXIS);
 #ifdef DEBUG_YSTEP_DUP_PIN
-      WRITE_NC(DEBUG_YSTEP_DUP_PIN,!INVERT_Y_STEP_PIN);
+      STEP_NC_HI(Y_DUP_AXIS);
 #endif //DEBUG_YSTEP_DUP_PIN
       counter_y.lo -= current_block->step_event_count.lo;
       count_position[Y_AXIS]+=count_direction[Y_AXIS];
-      WRITE_NC(Y_STEP_PIN, INVERT_Y_STEP_PIN);
+      STEP_NC_LO(Y_AXIS);
 #ifdef DEBUG_YSTEP_DUP_PIN
-      WRITE_NC(DEBUG_YSTEP_DUP_PIN,INVERT_Y_STEP_PIN);
+      STEP_NC_LO(Y_DUP_AXIS);
 #endif //DEBUG_YSTEP_DUP_PIN    
     }
     // Step in Z axis
     counter_z.lo += current_block->steps_z.lo;
     if (counter_z.lo > 0) {
-      WRITE_NC(Z_STEP_PIN, !INVERT_Z_STEP_PIN);
+      STEP_NC_HI(Z_AXIS);
       counter_z.lo -= current_block->step_event_count.lo;
       count_position[Z_AXIS]+=count_direction[Z_AXIS];
-      WRITE_NC(Z_STEP_PIN, INVERT_Z_STEP_PIN);
+      STEP_NC_LO(Z_AXIS);
     }
     // Step in E axis
     counter_e.lo += current_block->steps_e.lo;
     if (counter_e.lo > 0) {
 #ifndef LIN_ADVANCE
-      WRITE(E0_STEP_PIN, !INVERT_E_STEP_PIN);
+      STEP_NC_HI(E_AXIS);
 #endif /* LIN_ADVANCE */
       counter_e.lo -= current_block->step_event_count.lo;
       count_position[E_AXIS] += count_direction[E_AXIS];
@@ -652,7 +706,7 @@ FORCE_INLINE void stepper_tick_lowres()
 	#ifdef FILAMENT_SENSOR
 	  fsensor_counter += count_direction[E_AXIS];
 	#endif //FILAMENT_SENSOR
-      WRITE(E0_STEP_PIN, INVERT_E_STEP_PIN);
+      STEP_NC_LO(E_AXIS);
 #endif
     }
     if(++ step_events_completed.lo >= current_block->step_event_count.lo)
@@ -667,44 +721,44 @@ FORCE_INLINE void stepper_tick_highres()
     // Step in X axis
     counter_x.wide += current_block->steps_x.wide;
     if (counter_x.wide > 0) {
-      WRITE_NC(X_STEP_PIN, !INVERT_X_STEP_PIN);
+      STEP_NC_HI(X_AXIS);
 #ifdef DEBUG_XSTEP_DUP_PIN
-      WRITE_NC(DEBUG_XSTEP_DUP_PIN,!INVERT_X_STEP_PIN);
+      STEP_NC_HI(X_DUP_AXIS);
 #endif //DEBUG_XSTEP_DUP_PIN
       counter_x.wide -= current_block->step_event_count.wide;
       count_position[X_AXIS]+=count_direction[X_AXIS];   
-      WRITE_NC(X_STEP_PIN, INVERT_X_STEP_PIN);
+      STEP_NC_LO(X_AXIS);
 #ifdef DEBUG_XSTEP_DUP_PIN
-      WRITE_NC(DEBUG_XSTEP_DUP_PIN,INVERT_X_STEP_PIN);
+      STEP_NC_LO(X_DUP_AXIS);
 #endif //DEBUG_XSTEP_DUP_PIN
     }
     // Step in Y axis
     counter_y.wide += current_block->steps_y.wide;
     if (counter_y.wide > 0) {
-      WRITE_NC(Y_STEP_PIN, !INVERT_Y_STEP_PIN);
+      STEP_NC_HI(Y_AXIS);
 #ifdef DEBUG_YSTEP_DUP_PIN
-      WRITE_NC(DEBUG_YSTEP_DUP_PIN,!INVERT_Y_STEP_PIN);
+      STEP_NC_HI(Y_DUP_AXIS);
 #endif //DEBUG_YSTEP_DUP_PIN
       counter_y.wide -= current_block->step_event_count.wide;
       count_position[Y_AXIS]+=count_direction[Y_AXIS];
-      WRITE_NC(Y_STEP_PIN, INVERT_Y_STEP_PIN);
+      STEP_NC_LO(Y_AXIS);
 #ifdef DEBUG_YSTEP_DUP_PIN
-      WRITE_NC(DEBUG_YSTEP_DUP_PIN,INVERT_Y_STEP_PIN);
+      STEP_NC_LO(Y_DUP_AXIS);
 #endif //DEBUG_YSTEP_DUP_PIN    
     }
     // Step in Z axis
     counter_z.wide += current_block->steps_z.wide;
     if (counter_z.wide > 0) {
-      WRITE_NC(Z_STEP_PIN, !INVERT_Z_STEP_PIN);
+      STEP_NC_HI(Z_AXIS);
       counter_z.wide -= current_block->step_event_count.wide;
       count_position[Z_AXIS]+=count_direction[Z_AXIS];
-      WRITE_NC(Z_STEP_PIN, INVERT_Z_STEP_PIN);
+      STEP_NC_LO(Z_AXIS);
     }
     // Step in E axis
     counter_e.wide += current_block->steps_e.wide;
     if (counter_e.wide > 0) {
 #ifndef LIN_ADVANCE
-      WRITE(E0_STEP_PIN, !INVERT_E_STEP_PIN);
+      STEP_NC_HI(E_AXIS);
 #endif /* LIN_ADVANCE */
       counter_e.wide -= current_block->step_event_count.wide;
       count_position[E_AXIS]+=count_direction[E_AXIS];
@@ -714,7 +768,7 @@ FORCE_INLINE void stepper_tick_highres()
     #ifdef FILAMENT_SENSOR
       fsensor_counter += count_direction[E_AXIS];
     #endif //FILAMENT_SENSOR
-      WRITE(E0_STEP_PIN, INVERT_E_STEP_PIN);
+      STEP_NC_LO(E_AXIS);
 #endif
     }
     if(++ step_events_completed.wide >= current_block->step_event_count.wide)
@@ -734,38 +788,30 @@ FORCE_INLINE uint16_t fastdiv(uint16_t q, uint8_t d)
 
 FORCE_INLINE void advance_spread(uint16_t timer)
 {
-    if(eISR_Err > timer)
+    eISR_Err += timer;
+
+    uint8_t ticks = 0;
+    while(eISR_Err >= current_block->advance_rate)
+    {
+        ++ticks;
+        eISR_Err -= current_block->advance_rate;
+    }
+    if(!ticks)
     {
-        // advance-step skipped
-        eISR_Err -= timer;
         eISR_Rate = timer;
         nextAdvanceISR = timer;
         return;
     }
 
-    // at least one step
-    uint8_t ticks = 1;
-    uint32_t block = current_block->advance_rate;
-    uint16_t max_t = timer - eISR_Err;
-    while (block < max_t)
-    {
-        ++ticks;
-        block += current_block->advance_rate;
-    }
-    if (block > timer)
-        eISR_Err += block - timer;
-    else
-        eISR_Err -= timer - block;
-
-    if (ticks <= 4)
-        eISR_Rate = fastdiv(timer, ticks);
+    if (ticks <= 3)
+        eISR_Rate = fastdiv(timer, ticks + 1);
     else
     {
         // >4 ticks are still possible on slow moves
-        eISR_Rate = timer / ticks;
+        eISR_Rate = timer / (ticks + 1);
     }
 
-    nextAdvanceISR = eISR_Rate / 2;
+    nextAdvanceISR = eISR_Rate;
 }
 #endif
 
@@ -797,7 +843,7 @@ FORCE_INLINE void isr() {
     // 25.12us for acceleration / deceleration.
     {
       //WRITE_NC(LOGIC_ANALYZER_CH1, true);
-      if (step_events_completed.wide <= (unsigned long int)current_block->accelerate_until) {
+      if (step_events_completed.wide <= current_block->accelerate_until) {
         // v = t * a   ->   acc_step_rate = acceleration_time * current_block->acceleration_rate
         MultiU24X24toH16(acc_step_rate, acceleration_time, current_block->acceleration_rate);
         acc_step_rate += uint16_t(current_block->initial_rate);
@@ -810,28 +856,42 @@ FORCE_INLINE void isr() {
         acceleration_time += timer;
 #ifdef LIN_ADVANCE
         if (current_block->use_advance_lead) {
-            if (step_events_completed.wide <= (unsigned long int)step_loops)
-                la_state = ADV_INIT;
+            if (step_events_completed.wide <= (unsigned long int)step_loops) {
+                la_state = ADV_INIT | ADV_ACC_VARY;
+                if (e_extruding && current_adv_steps > target_adv_steps)
+                    target_adv_steps = current_adv_steps;
+            }
         }
 #endif
       }
-      else if (step_events_completed.wide > (unsigned long int)current_block->decelerate_after) {
+      else if (step_events_completed.wide > current_block->decelerate_after) {
         uint16_t step_rate;
         MultiU24X24toH16(step_rate, deceleration_time, current_block->acceleration_rate);
-        step_rate = acc_step_rate - step_rate; // Decelerate from aceleration end point.
-        if ((step_rate & 0x8000) || step_rate < uint16_t(current_block->final_rate)) {
-          // Result is negative or too small.
-          step_rate = uint16_t(current_block->final_rate);
+
+        if (step_rate > acc_step_rate) { // Check step_rate stays positive
+            step_rate = uint16_t(current_block->final_rate);
+        }
+        else {
+            step_rate = acc_step_rate - step_rate; // Decelerate from acceleration end point.
+
+            // lower limit
+            if (step_rate < current_block->final_rate)
+                step_rate = uint16_t(current_block->final_rate);
         }
+
         // Step_rate to timer interval.
         uint16_t timer = calc_timer(step_rate, step_loops);
         _NEXT_ISR(timer);
         deceleration_time += timer;
+
 #ifdef LIN_ADVANCE
         if (current_block->use_advance_lead) {
-            la_state = ADV_DECELERATE;
-            if (step_events_completed.wide <= (unsigned long int)current_block->decelerate_after + step_loops)
-                la_state |= ADV_INIT;
+            if (step_events_completed.wide <= current_block->decelerate_after + step_loops) {
+                target_adv_steps = current_block->final_adv_steps;
+                la_state = ADV_INIT | ADV_ACC_VARY;
+                if (e_extruding && current_adv_steps < target_adv_steps)
+                    target_adv_steps = current_adv_steps;
+            }
         }
 #endif
       }
@@ -841,6 +901,17 @@ FORCE_INLINE void isr() {
           // the initial interrupt blocking.
           OCR1A_nominal = calc_timer(uint16_t(current_block->nominal_rate), step_loops);
           step_loops_nominal = step_loops;
+
+#ifdef LIN_ADVANCE
+          if(current_block->use_advance_lead) {
+              // Due to E-jerk, there can be discontinuities in pressure state where an
+              // acceleration or deceleration can be skipped or joined with the previous block.
+              // If LA was not previously active, re-check the pressure level
+              la_state = ADV_INIT;
+              if (e_extruding)
+                  target_adv_steps = current_adv_steps;
+          }
+#endif
         }
         _NEXT_ISR(OCR1A_nominal);
       }
@@ -849,16 +920,38 @@ FORCE_INLINE void isr() {
 
 #ifdef LIN_ADVANCE
     // avoid multiple instances or function calls to advance_spread
-    if (la_state & ADV_INIT) eISR_Err = current_block->advance_rate / 4;
+    if (la_state & ADV_INIT) {
+        LA_phase = -1;
+
+        if (current_adv_steps == target_adv_steps) {
+            // nothing to be done in this phase, cancel any pending eisr
+            la_state = 0;
+            nextAdvanceISR = ADV_NEVER;
+        }
+        else {
+            // reset error and iterations per loop for this phase
+            eISR_Err = current_block->advance_rate;
+            e_step_loops = current_block->advance_step_loops;
+
+            if ((la_state & ADV_ACC_VARY) && e_extruding && (current_adv_steps > target_adv_steps)) {
+                // LA could reverse the direction of extrusion in this phase
+                eISR_Err += current_block->advance_rate;
+                LA_phase = 0;
+            }
+        }
+    }
     if (la_state & ADV_INIT || nextAdvanceISR != ADV_NEVER) {
+        // update timers & phase for the next iteration
         advance_spread(main_Rate);
-        if (la_state & ADV_DECELERATE) {
+        if (LA_phase >= 0) {
             if (step_loops == e_step_loops)
-                LA_phase = (eISR_Rate > main_Rate);
+                LA_phase = (current_block->advance_rate < main_Rate);
             else {
                 // avoid overflow through division. warning: we need to _guarantee_ step_loops
                 // and e_step_loops are <= 4 due to fastdiv's limit
-                LA_phase = (fastdiv(eISR_Rate, step_loops) > fastdiv(main_Rate, e_step_loops));
+                auto adv_rate_n = fastdiv(current_block->advance_rate, step_loops);
+                auto main_rate_n = fastdiv(main_Rate, e_step_loops);
+                LA_phase = (adv_rate_n < main_rate_n);
             }
         }
     }
@@ -898,28 +991,36 @@ FORCE_INLINE void isr() {
 // Timer interrupt for E. e_steps is set in the main routine.
 
 FORCE_INLINE void advance_isr() {
-    if (step_events_completed.wide > LA_decelerate_after && current_adv_steps > final_adv_steps) {
+    if (current_adv_steps > target_adv_steps) {
         // decompression
+        if (e_step_loops != 1) {
+            uint16_t d_steps = current_adv_steps - target_adv_steps;
+            if (d_steps < e_step_loops)
+                e_step_loops = d_steps;
+        }
         e_steps -= e_step_loops;
         if (e_steps) WRITE_NC(E0_DIR_PIN, e_steps < 0? INVERT_E0_DIR: !INVERT_E0_DIR);
-        if(current_adv_steps > e_step_loops)
-            current_adv_steps -= e_step_loops;
-        else
-            current_adv_steps = 0;
-        nextAdvanceISR = eISR_Rate;
+        current_adv_steps -= e_step_loops;
     }
-    else if (step_events_completed.wide < LA_decelerate_after && current_adv_steps < max_adv_steps) {
+    else if (current_adv_steps < target_adv_steps) {
         // compression
+        if (e_step_loops != 1) {
+            uint16_t d_steps = target_adv_steps - current_adv_steps;
+            if (d_steps < e_step_loops)
+                e_step_loops = d_steps;
+        }
         e_steps += e_step_loops;
         if (e_steps) WRITE_NC(E0_DIR_PIN, e_steps < 0? INVERT_E0_DIR: !INVERT_E0_DIR);
         current_adv_steps += e_step_loops;
-        nextAdvanceISR = eISR_Rate;
     }
-    else {
+
+    if (current_adv_steps == target_adv_steps) {
         // advance steps completed
         nextAdvanceISR = ADV_NEVER;
-        LA_phase = -1;
-        e_step_loops = 1;
+    }
+    else {
+        // schedule another tick
+        nextAdvanceISR = eISR_Rate;
     }
 }
 
@@ -969,9 +1070,9 @@ FORCE_INLINE void advance_isr_scheduler() {
         bool rev = (e_steps < 0);
         do
         {
-            WRITE_NC(E0_STEP_PIN, !INVERT_E_STEP_PIN);
+            STEP_NC_HI(E_AXIS);
             e_steps += (rev? 1: -1);
-            WRITE_NC(E0_STEP_PIN, INVERT_E_STEP_PIN);
+            STEP_NC_LO(E_AXIS);
 #if defined(FILAMENT_SENSOR) && defined(PAT9125)
             fsensor_counter += (rev? -1: 1);
 #endif
@@ -989,7 +1090,7 @@ FORCE_INLINE void advance_isr_scheduler() {
 
     // Schedule the next closest tick, ignoring advance if scheduled too
     // soon in order to avoid skewing the regular stepper acceleration
-    if (nextAdvanceISR != ADV_NEVER && (nextAdvanceISR + TCNT1 + 40) < nextMainISR)
+    if (nextAdvanceISR != ADV_NEVER && (nextAdvanceISR + 40) < nextMainISR)
         OCR1A = nextAdvanceISR;
     else
         OCR1A = nextMainISR;
@@ -1233,9 +1334,6 @@ void st_init()
   nextMainISR = 0;
   nextAdvanceISR = ADV_NEVER;
   main_Rate = ADV_NEVER;
-  e_steps = 0;
-  e_step_loops = 1;
-  LA_phase = -1;
   current_adv_steps = 0;
 #endif
 
@@ -1331,17 +1429,6 @@ float st_get_position_mm(uint8_t axis)
 }
 
 
-void finishAndDisableSteppers()
-{
-  st_synchronize();
-  disable_x();
-  disable_y();
-  disable_z();
-  disable_e0();
-  disable_e1();
-  disable_e2();
-}
-
 void quickStop()
 {
   DISABLE_STEPPER_DRIVER_INTERRUPT();
@@ -1358,89 +1445,106 @@ void quickStop()
 #ifdef BABYSTEPPING
 void babystep(const uint8_t axis,const bool direction)
 {
-  //MUST ONLY BE CALLED BY A ISR, it depends on that no other ISR interrupts this
-    //store initial pin states
-  switch(axis)
-  {
-  case X_AXIS:
-  {
-    enable_x();   
-    uint8_t old_x_dir_pin= READ(X_DIR_PIN);  //if dualzstepper, both point to same direction.
-   
-    //setup new step
-    WRITE(X_DIR_PIN,(INVERT_X_DIR)^direction);
-    
-    //perform step 
-    WRITE(X_STEP_PIN, !INVERT_X_STEP_PIN); 
+    // MUST ONLY BE CALLED BY A ISR as stepper pins are manipulated directly.
+    // note: when switching direction no delay is inserted at the end when the
+    //       original is restored. We assume enough time passes as the function
+    //       returns and the stepper is manipulated again (to avoid dead times)
+    switch(axis)
+    {
+    case X_AXIS:
+    {
+        enable_x();
+        uint8_t old_x_dir_pin = READ(X_DIR_PIN);  //if dualzstepper, both point to same direction.
+        uint8_t new_x_dir_pin = (INVERT_X_DIR)^direction;
+
+        //setup new step
+        if (new_x_dir_pin != old_x_dir_pin) {
+            WRITE_NC(X_DIR_PIN, new_x_dir_pin);
+            delayMicroseconds(STEPPER_SET_DIR_DELAY);
+        }
+
+        //perform step
+        STEP_NC_HI(X_AXIS);
 #ifdef DEBUG_XSTEP_DUP_PIN
-    WRITE(DEBUG_XSTEP_DUP_PIN,!INVERT_X_STEP_PIN);
-#endif //DEBUG_XSTEP_DUP_PIN
-    delayMicroseconds(1);
-    WRITE(X_STEP_PIN, INVERT_X_STEP_PIN);
+        STEP_NC_HI(X_DUP_AXIS);
+#endif
+        STEPPER_MINIMUM_DELAY;
+        STEP_NC_LO(X_AXIS);
 #ifdef DEBUG_XSTEP_DUP_PIN
-    WRITE(DEBUG_XSTEP_DUP_PIN,INVERT_X_STEP_PIN);
-#endif //DEBUG_XSTEP_DUP_PIN
+        STEP_NC_LO(X_DUP_AXIS);
+#endif
 
-    //get old pin state back.
-    WRITE(X_DIR_PIN,old_x_dir_pin);
-  }
-  break;
-  case Y_AXIS:
-  {
-    enable_y();   
-    uint8_t old_y_dir_pin= READ(Y_DIR_PIN);  //if dualzstepper, both point to same direction.
-   
-    //setup new step
-    WRITE(Y_DIR_PIN,(INVERT_Y_DIR)^direction);
-    
-    //perform step 
-    WRITE(Y_STEP_PIN, !INVERT_Y_STEP_PIN); 
+        //get old pin state back.
+        WRITE_NC(X_DIR_PIN, old_x_dir_pin);
+    }
+    break;
+
+    case Y_AXIS:
+    {
+        enable_y();
+        uint8_t old_y_dir_pin = READ(Y_DIR_PIN);  //if dualzstepper, both point to same direction.
+        uint8_t new_y_dir_pin = (INVERT_Y_DIR)^direction;
+
+        //setup new step
+        if (new_y_dir_pin != old_y_dir_pin) {
+            WRITE_NC(Y_DIR_PIN, new_y_dir_pin);
+            delayMicroseconds(STEPPER_SET_DIR_DELAY);
+        }
+
+        //perform step
+        STEP_NC_HI(Y_AXIS);
 #ifdef DEBUG_YSTEP_DUP_PIN
-    WRITE(DEBUG_YSTEP_DUP_PIN,!INVERT_Y_STEP_PIN);
-#endif //DEBUG_YSTEP_DUP_PIN
-    delayMicroseconds(1);
-    WRITE(Y_STEP_PIN, INVERT_Y_STEP_PIN);
+        STEP_NC_HI(Y_DUP_AXIS);
+#endif
+        STEPPER_MINIMUM_DELAY;
+        STEP_NC_LO(Y_AXIS);
 #ifdef DEBUG_YSTEP_DUP_PIN
-    WRITE(DEBUG_YSTEP_DUP_PIN,INVERT_Y_STEP_PIN);
-#endif //DEBUG_YSTEP_DUP_PIN
+        STEP_NC_LO(Y_DUP_AXIS);
+#endif
 
-    //get old pin state back.
-    WRITE(Y_DIR_PIN,old_y_dir_pin);
+        //get old pin state back.
+        WRITE_NC(Y_DIR_PIN, old_y_dir_pin);
+    }
+    break;
 
-  }
-  break;
- 
-  case Z_AXIS:
-  {
-    enable_z();
-    uint8_t old_z_dir_pin= READ(Z_DIR_PIN);  //if dualzstepper, both point to same direction.
-    //setup new step
-    WRITE(Z_DIR_PIN,(INVERT_Z_DIR)^direction^BABYSTEP_INVERT_Z);
-    #ifdef Z_DUAL_STEPPER_DRIVERS
-      WRITE(Z2_DIR_PIN,(INVERT_Z_DIR)^direction^BABYSTEP_INVERT_Z);
-    #endif
-    //perform step 
-    WRITE(Z_STEP_PIN, !INVERT_Z_STEP_PIN); 
-    #ifdef Z_DUAL_STEPPER_DRIVERS
-      WRITE(Z2_STEP_PIN, !INVERT_Z_STEP_PIN);
-    #endif
-    delayMicroseconds(1);
-    WRITE(Z_STEP_PIN, INVERT_Z_STEP_PIN);
-    #ifdef Z_DUAL_STEPPER_DRIVERS
-      WRITE(Z2_STEP_PIN, INVERT_Z_STEP_PIN);
-    #endif
+    case Z_AXIS:
+    {
+        enable_z();
+        uint8_t old_z_dir_pin = READ(Z_DIR_PIN);  //if dualzstepper, both point to same direction.
+        uint8_t new_z_dir_pin = (INVERT_Z_DIR)^direction^BABYSTEP_INVERT_Z;
+
+        //setup new step
+        if (new_z_dir_pin != old_z_dir_pin) {
+            WRITE_NC(Z_DIR_PIN, new_z_dir_pin);
+#ifdef Z_DUAL_STEPPER_DRIVERS
+            WRITE_NC(Z2_DIR_PIN, new_z_dir_pin);
+#endif
+            delayMicroseconds(STEPPER_SET_DIR_DELAY);
+        }
 
-    //get old pin state back.
-    WRITE(Z_DIR_PIN,old_z_dir_pin);
-    #ifdef Z_DUAL_STEPPER_DRIVERS
-      WRITE(Z2_DIR_PIN,old_z_dir_pin);
-    #endif
+        //perform step
+        STEP_NC_HI(Z_AXIS);
+#ifdef Z_DUAL_STEPPER_DRIVERS
+        STEP_NC_HI(Z2_AXIS);
+#endif
+        STEPPER_MINIMUM_DELAY;
+        STEP_NC_LO(Z_AXIS);
+#ifdef Z_DUAL_STEPPER_DRIVERS
+        STEP_NC_LO(Z2_AXIS);
+#endif
 
-  }
-  break;
- 
-  default:    break;
-  }
+        //get old pin state back.
+        if (new_z_dir_pin != old_z_dir_pin) {
+            WRITE_NC(Z_DIR_PIN, old_z_dir_pin);
+#ifdef Z_DUAL_STEPPER_DRIVERS
+            WRITE_NC(Z2_DIR_PIN, old_z_dir_pin);
+#endif
+        }
+    }
+    break;
+
+    default: break;
+    }
 }
 #endif //BABYSTEPPING
 

+ 0 - 2
Firmware/stepper.h

@@ -69,8 +69,6 @@ void invert_z_endstop(bool endstop_invert);
 
 void checkStepperErrors(); //Print errors detected by the stepper
 
-void finishAndDisableSteppers();
-
 extern block_t *current_block;  // A pointer to the block currently being traced
 extern bool x_min_endstop;
 extern bool x_max_endstop;

+ 32 - 29
Firmware/swi2c.c

@@ -3,10 +3,12 @@
 #include <avr/io.h>
 #include <util/delay.h>
 #include <avr/pgmspace.h>
+#include "stdbool.h"
 #include "Configuration_prusa.h"
 #include "pins.h"
-#include "io_atmega2560.h"
+#include "fastio.h"
 
+#ifdef SWI2C_SCL
 
 #define SWI2C_RMSK   0x01 //read mask (bit0 = 1)
 #define SWI2C_WMSK   0x00 //write mask (bit0 = 0)
@@ -21,75 +23,75 @@ void __delay(void)
 
 void swi2c_init(void)
 {
-	PIN_OUT(SWI2C_SDA);
-	PIN_OUT(SWI2C_SCL);
-	PIN_SET(SWI2C_SDA);
-	PIN_SET(SWI2C_SCL);
+	WRITE(SWI2C_SDA, 1);
+	WRITE(SWI2C_SCL, 1);
+	SET_OUTPUT(SWI2C_SDA);
+	SET_OUTPUT(SWI2C_SCL);
 	uint8_t i; for (i = 0; i < 100; i++)
 		__delay();
 }
 
 void swi2c_start(void)
 {
-	PIN_CLR(SWI2C_SDA);
+	WRITE(SWI2C_SDA, 0);
 	__delay();
-	PIN_CLR(SWI2C_SCL);
+	WRITE(SWI2C_SCL, 0);
 	__delay();
 }
 
 void swi2c_stop(void)
 {
-	PIN_SET(SWI2C_SCL);
+	WRITE(SWI2C_SCL, 1);
 	__delay();
-	PIN_SET(SWI2C_SDA);
+	WRITE(SWI2C_SDA, 1);
 	__delay();
 }
 
 void swi2c_ack(void)
 {
-	PIN_CLR(SWI2C_SDA);
+	WRITE(SWI2C_SDA, 0);
 	__delay();
-	PIN_SET(SWI2C_SCL);
+	WRITE(SWI2C_SCL, 1);
 	__delay();
-	PIN_CLR(SWI2C_SCL);
+	WRITE(SWI2C_SCL, 0);
 	__delay();
 }
 
 uint8_t swi2c_wait_ack()
 {
-	PIN_INP(SWI2C_SDA);
+	SET_INPUT(SWI2C_SDA);
 	__delay();
-//	PIN_SET(SWI2C_SDA);
+//	WRITE(SWI2C_SDA, 1);
 	__delay();
-	PIN_SET(SWI2C_SCL);
+	WRITE(SWI2C_SCL, 1);
 //	__delay();
 	uint8_t ack = 0;
 	uint16_t ackto = SWI2C_TMO;
-	while (!(ack = (PIN_GET(SWI2C_SDA)?0:1)) && ackto--) __delay();
-	PIN_CLR(SWI2C_SCL);
+	while (!(ack = (!READ(SWI2C_SDA))) && ackto--) __delay();
+	WRITE(SWI2C_SCL, 0);
 	__delay();
-	PIN_OUT(SWI2C_SDA);
+	SET_OUTPUT(SWI2C_SDA);
 	__delay();
-	PIN_CLR(SWI2C_SDA);
+	WRITE(SWI2C_SDA, 0);
 	__delay();
 	return ack;
 }
 
 uint8_t swi2c_read(void)
 {
-	PIN_SET(SWI2C_SDA);
+	WRITE(SWI2C_SDA, 1);
 	__delay();
-	PIN_INP(SWI2C_SDA);
+	SET_INPUT(SWI2C_SDA);
 	uint8_t data = 0;
 	int8_t bit; for (bit = 7; bit >= 0; bit--)
 	{
-		PIN_SET(SWI2C_SCL);
+		WRITE(SWI2C_SCL, 1);
 		__delay();
-		data |= (PIN_GET(SWI2C_SDA)?1:0) << bit;
-		PIN_CLR(SWI2C_SCL);
+		data |= (READ(SWI2C_SDA)) << bit;
+		WRITE(SWI2C_SCL, 0);
 		__delay();
 	}
-	PIN_OUT(SWI2C_SDA);
+	SET_OUTPUT(SWI2C_SDA);
 	return data;
 }
 
@@ -97,12 +99,11 @@ void swi2c_write(uint8_t data)
 {
 	int8_t bit; for (bit = 7; bit >= 0; bit--)
 	{
-		if (data & (1 << bit)) PIN_SET(SWI2C_SDA);
-		else PIN_CLR(SWI2C_SDA);
+		WRITE(SWI2C_SDA, data & _BV(bit));
 		__delay();
-		PIN_SET(SWI2C_SCL);
+		WRITE(SWI2C_SCL, 1);
 		__delay();
-		PIN_CLR(SWI2C_SCL);
+		WRITE(SWI2C_SCL, 0);
 		__delay();
 	}
 }
@@ -187,3 +188,5 @@ uint8_t swi2c_writeByte_A16(uint8_t dev_addr, unsigned short addr, uint8_t* pbyt
 }
 
 #endif //SWI2C_A16
+
+#endif //SWI2C_SCL

+ 3 - 2
Firmware/system_timer.h

@@ -8,11 +8,12 @@
 
 #ifdef SYSTEM_TIMER_2
 #include "timer02.h"
+#include "tone04.h"
 #define _millis millis2
 #define _micros micros2
 #define _delay delay2
-#define _tone tone
-#define _noTone noTone
+#define _tone tone4
+#define _noTone noTone4
 
 #define timer02_set_pwm0(pwm0)
 

+ 284 - 128
Firmware/temperature.cpp

@@ -30,6 +30,7 @@
 
 
 #include "Marlin.h"
+#include "cmdqueue.h"
 #include "ultralcd.h"
 #include "sound.h"
 #include "temperature.h"
@@ -74,7 +75,7 @@ int current_voltage_raw_bed = 0;
 #endif
 
 #ifdef IR_SENSOR_ANALOG
-int current_voltage_raw_IR = 0;
+uint16_t current_voltage_raw_IR = 0;
 #endif //IR_SENSOR_ANALOG
 
 int current_temperature_bed_raw = 0;
@@ -143,14 +144,22 @@ static volatile bool temp_meas_ready = false;
 #ifdef FAN_SOFT_PWM
   static unsigned char soft_pwm_fan;
 #endif
-#if (defined(EXTRUDER_0_AUTO_FAN_PIN) && EXTRUDER_0_AUTO_FAN_PIN > -1) || \
-    (defined(EXTRUDER_1_AUTO_FAN_PIN) && EXTRUDER_1_AUTO_FAN_PIN > -1) || \
-    (defined(EXTRUDER_2_AUTO_FAN_PIN) && EXTRUDER_2_AUTO_FAN_PIN > -1)
+
+uint8_t fanSpeedBckp = 255;
+
+#if (defined(EXTRUDER_0_AUTO_FAN_PIN) && EXTRUDER_0_AUTO_FAN_PIN > -1)
   unsigned long extruder_autofan_last_check = _millis();
-  uint8_t fanSpeedBckp = 255;
+  
   bool fan_measuring = false;
-
-#endif  
+  uint8_t fanState = 0;
+#ifdef EXTRUDER_ALTFAN_DETECT
+  struct
+  {
+    uint8_t isAltfan : 1;
+    uint8_t altfanOverride : 1;
+  } altfanStatus;
+#endif //EXTRUDER_ALTFAN_DETECT
+#endif
 
 
 #if EXTRUDERS > 3
@@ -176,6 +185,12 @@ static int bed_minttemp_raw = HEATER_BED_RAW_LO_TEMP;
 #ifdef BED_MAXTEMP
 static int bed_maxttemp_raw = HEATER_BED_RAW_HI_TEMP;
 #endif
+#ifdef AMBIENT_MINTEMP
+static int ambient_minttemp_raw = AMBIENT_RAW_LO_TEMP;
+#endif
+#ifdef AMBIENT_MAXTEMP
+static int ambient_maxttemp_raw = AMBIENT_RAW_HI_TEMP;
+#endif
 
 static void *heater_ttbl_map[EXTRUDERS] = ARRAY_BY_EXTRUDERS( (void *)HEATER_0_TEMPTABLE, (void *)HEATER_1_TEMPTABLE, (void *)HEATER_2_TEMPTABLE );
 static uint8_t heater_ttbllen_map[EXTRUDERS] = ARRAY_BY_EXTRUDERS( HEATER_0_TEMPTABLE_LEN, HEATER_1_TEMPTABLE_LEN, HEATER_2_TEMPTABLE_LEN );
@@ -210,6 +225,56 @@ static void temp_runaway_check(int _heater_id, float _target_temperature, float
 static void temp_runaway_stop(bool isPreheat, bool isBed);
 #endif
 
+#ifdef EXTRUDER_ALTFAN_DETECT
+ISR(INT6_vect) {
+	fan_edge_counter[0]++;
+}
+
+bool extruder_altfan_detect()
+{
+	setExtruderAutoFanState(3);
+
+	SET_INPUT(TACH_0);
+
+	uint8_t overrideVal = eeprom_read_byte((uint8_t *)EEPROM_ALTFAN_OVERRIDE);
+	if (overrideVal == EEPROM_EMPTY_VALUE)
+	{
+		overrideVal = (calibration_status() == CALIBRATION_STATUS_CALIBRATED) ? 1 : 0;
+		eeprom_update_byte((uint8_t *)EEPROM_ALTFAN_OVERRIDE, overrideVal);
+	}
+	altfanStatus.altfanOverride = overrideVal;
+
+	CRITICAL_SECTION_START;
+	EICRB &= ~(1 << ISC61);
+	EICRB |= (1 << ISC60);
+	EIMSK |= (1 << INT6);
+	fan_edge_counter[0] = 0;
+	CRITICAL_SECTION_END;
+	extruder_autofan_last_check = _millis();
+
+	_delay(1000);
+
+	EIMSK &= ~(1 << INT6);
+
+	countFanSpeed();
+	altfanStatus.isAltfan = fan_speed[0] > 100;
+	setExtruderAutoFanState(1);
+	return altfanStatus.isAltfan;
+}
+
+void altfanOverride_toggle()
+{
+    altfanStatus.altfanOverride = !altfanStatus.altfanOverride;
+    eeprom_update_byte((uint8_t *)EEPROM_ALTFAN_OVERRIDE, altfanStatus.altfanOverride);
+}
+
+bool altfanOverride_get()
+{
+    return altfanStatus.altfanOverride;
+}
+
+#endif //EXTRUDER_ALTFAN_DETECT
+
 // return "false", if all extruder-heaters are 'off' (ie. "true", if any heater is 'on')
 bool checkAllHotends(void)
 {
@@ -239,9 +304,7 @@ bool checkAllHotends(void)
   const uint8_t safety_check_cycles_count = (extruder < 0) ? 45 : 10; //10 cycles / 20s delay for extruder and 45 cycles / 90s for heatbed
   float temp_ambient;
 
-#if (defined(EXTRUDER_0_AUTO_FAN_PIN) && EXTRUDER_0_AUTO_FAN_PIN > -1) || \
-    (defined(EXTRUDER_1_AUTO_FAN_PIN) && EXTRUDER_1_AUTO_FAN_PIN > -1) || \
-    (defined(EXTRUDER_2_AUTO_FAN_PIN) && EXTRUDER_2_AUTO_FAN_PIN > -1)
+#if (defined(EXTRUDER_0_AUTO_FAN_PIN) && EXTRUDER_0_AUTO_FAN_PIN > -1)
   unsigned long extruder_autofan_last_check = _millis();
 #endif
 
@@ -289,9 +352,7 @@ bool checkAllHotends(void)
       max=max(max,input);
       min=min(min,input);
 
-      #if (defined(EXTRUDER_0_AUTO_FAN_PIN) && EXTRUDER_0_AUTO_FAN_PIN > -1) || \
-          (defined(EXTRUDER_1_AUTO_FAN_PIN) && EXTRUDER_1_AUTO_FAN_PIN > -1) || \
-          (defined(EXTRUDER_2_AUTO_FAN_PIN) && EXTRUDER_2_AUTO_FAN_PIN > -1)
+      #if (defined(EXTRUDER_0_AUTO_FAN_PIN) && EXTRUDER_0_AUTO_FAN_PIN > -1)
       if(_millis() - extruder_autofan_last_check > 2500) {
         checkExtruderAutoFans();
         extruder_autofan_last_check = _millis();
@@ -447,29 +508,31 @@ int getHeaterPower(int heater) {
   return soft_pwm[heater];
 }
 
-#if (defined(EXTRUDER_0_AUTO_FAN_PIN) && EXTRUDER_0_AUTO_FAN_PIN > -1) || \
-    (defined(EXTRUDER_1_AUTO_FAN_PIN) && EXTRUDER_1_AUTO_FAN_PIN > -1) || \
-    (defined(EXTRUDER_2_AUTO_FAN_PIN) && EXTRUDER_2_AUTO_FAN_PIN > -1)
+#if (defined(EXTRUDER_0_AUTO_FAN_PIN) && EXTRUDER_0_AUTO_FAN_PIN > -1)
 
   #if defined(FAN_PIN) && FAN_PIN > -1
     #if EXTRUDER_0_AUTO_FAN_PIN == FAN_PIN 
        #error "You cannot set EXTRUDER_0_AUTO_FAN_PIN equal to FAN_PIN"
     #endif
-    #if EXTRUDER_1_AUTO_FAN_PIN == FAN_PIN 
-       #error "You cannot set EXTRUDER_1_AUTO_FAN_PIN equal to FAN_PIN"
-    #endif
-    #if EXTRUDER_2_AUTO_FAN_PIN == FAN_PIN 
-       #error "You cannot set EXTRUDER_2_AUTO_FAN_PIN equal to FAN_PIN"
-    #endif
-  #endif 
+  #endif
 
-void setExtruderAutoFanState(int pin, bool state)
+void setExtruderAutoFanState(uint8_t state)
 {
-  unsigned char newFanSpeed = (state != 0) ? EXTRUDER_AUTO_FAN_SPEED : 0;
-  // this idiom allows both digital and PWM fan outputs (see M42 handling).
-  pinMode(pin, OUTPUT);
-  digitalWrite(pin, newFanSpeed);
-  //analogWrite(pin, newFanSpeed);
+	//If bit 1 is set (0x02), then the extruder fan speed won't be adjusted according to temperature. Useful for forcing
+	//the fan to either On or Off during certain tests/errors.
+
+	fanState = state;
+	newFanSpeed = 0;
+	if (fanState & 0x01)
+	{
+#ifdef EXTRUDER_ALTFAN_DETECT
+		if (altfanStatus.isAltfan && !altfanStatus.altfanOverride) newFanSpeed = EXTRUDER_ALTFAN_SPEED_SILENT;
+		else newFanSpeed = EXTRUDER_AUTO_FAN_SPEED;
+#else //EXTRUDER_ALTFAN_DETECT
+		newFanSpeed = EXTRUDER_AUTO_FAN_SPEED;
+#endif //EXTRUDER_ALTFAN_DETECT
+	}
+	timer4_set_fan0(newFanSpeed);
 }
 
 #if (defined(FANCHECK) && (((defined(TACH_0) && (TACH_0 >-1)) || (defined(TACH_1) && (TACH_1 > -1)))))
@@ -503,7 +566,7 @@ void checkFanSpeed()
 	  fans_check_enabled = (eeprom_read_byte((uint8_t*)EEPROM_FAN_CHECK_ENABLED) > 0);
 	static unsigned char fan_speed_errors[2] = { 0,0 };
 #if (defined(FANCHECK) && defined(TACH_0) && (TACH_0 >-1))
-	if ((fan_speed[0] == 0) && (current_temperature[0] > EXTRUDER_AUTO_FAN_TEMPERATURE)){ fan_speed_errors[0]++;}
+	if ((fan_speed[0] < 20) && (current_temperature[0] > EXTRUDER_AUTO_FAN_TEMPERATURE)){ fan_speed_errors[0]++;}
 	else{
     fan_speed_errors[0] = 0;
     host_keepalive();
@@ -570,54 +633,20 @@ void fanSpeedError(unsigned char _fan) {
 		fanSpeedErrorBeep(PSTR("Print fan speed is lower than expected"), MSG_FANCHECK_PRINT);
 		break;
 	}
-    // SERIAL_PROTOCOLLNRPGM(MSG_OK); //This ok messes things up with octoprint.
 }
 #endif //(defined(TACH_0) && TACH_0 >-1) || (defined(TACH_1) && TACH_1 > -1)
 
 
 void checkExtruderAutoFans()
 {
-  uint8_t fanState = 0;
-
-  // which fan pins need to be turned on?      
-  #if defined(EXTRUDER_0_AUTO_FAN_PIN) && EXTRUDER_0_AUTO_FAN_PIN > -1
-  if (current_temperature[0] > EXTRUDER_AUTO_FAN_TEMPERATURE)
-	  fanState |= 1;
-  #endif
-  #if defined(EXTRUDER_1_AUTO_FAN_PIN) && EXTRUDER_1_AUTO_FAN_PIN > -1
-    if (current_temperature[1] > EXTRUDER_AUTO_FAN_TEMPERATURE) 
-    {
-      if (EXTRUDER_1_AUTO_FAN_PIN == EXTRUDER_0_AUTO_FAN_PIN) 
-        fanState |= 1;
-      else
-        fanState |= 2;
-    }
-  #endif
-  #if defined(EXTRUDER_2_AUTO_FAN_PIN) && EXTRUDER_2_AUTO_FAN_PIN > -1
-    if (current_temperature[2] > EXTRUDER_AUTO_FAN_TEMPERATURE) 
-    {
-      if (EXTRUDER_2_AUTO_FAN_PIN == EXTRUDER_0_AUTO_FAN_PIN) 
-        fanState |= 1;
-      else if (EXTRUDER_2_AUTO_FAN_PIN == EXTRUDER_1_AUTO_FAN_PIN) 
-        fanState |= 2;
-      else
-        fanState |= 4;
-    }
-  #endif
-  
-  // update extruder auto fan states
-  #if defined(EXTRUDER_0_AUTO_FAN_PIN) && EXTRUDER_0_AUTO_FAN_PIN > -1
-    setExtruderAutoFanState(EXTRUDER_0_AUTO_FAN_PIN, (fanState & 1) != 0);
-  #endif 
-  #if defined(EXTRUDER_1_AUTO_FAN_PIN) && EXTRUDER_1_AUTO_FAN_PIN > -1
-    if (EXTRUDER_1_AUTO_FAN_PIN != EXTRUDER_0_AUTO_FAN_PIN) 
-      setExtruderAutoFanState(EXTRUDER_1_AUTO_FAN_PIN, (fanState & 2) != 0);
-  #endif 
-  #if defined(EXTRUDER_2_AUTO_FAN_PIN) && EXTRUDER_2_AUTO_FAN_PIN > -1
-    if (EXTRUDER_2_AUTO_FAN_PIN != EXTRUDER_0_AUTO_FAN_PIN 
-        && EXTRUDER_2_AUTO_FAN_PIN != EXTRUDER_1_AUTO_FAN_PIN)
-      setExtruderAutoFanState(EXTRUDER_2_AUTO_FAN_PIN, (fanState & 4) != 0);
-  #endif 
+#if defined(EXTRUDER_0_AUTO_FAN_PIN) && EXTRUDER_0_AUTO_FAN_PIN > -1
+	if (!(fanState & 0x02))
+	{
+		fanState &= ~1;
+		fanState |= current_temperature[0] > EXTRUDER_AUTO_FAN_TEMPERATURE;
+	}
+	setExtruderAutoFanState(fanState);
+#endif 
 }
 
 #endif // any extruder auto fan pins set
@@ -641,6 +670,7 @@ void manage_heater()
     return; 
 // more precisely - this condition partially stabilizes time interval for regulation values evaluation (@ ~ 230ms)
 
+  // ADC values need to be converted before checking: converted values are later used in MINTEMP
   updateTemperaturesFromRawValues();
 
   check_max_temp();
@@ -737,9 +767,7 @@ void manage_heater()
 #define FAN_CHECK_DURATION 100 //100ms
 
 #ifndef DEBUG_DISABLE_FANCHECK
-  #if (defined(EXTRUDER_0_AUTO_FAN_PIN) && EXTRUDER_0_AUTO_FAN_PIN > -1) || \
-      (defined(EXTRUDER_1_AUTO_FAN_PIN) && EXTRUDER_1_AUTO_FAN_PIN > -1) || \
-      (defined(EXTRUDER_2_AUTO_FAN_PIN) && EXTRUDER_2_AUTO_FAN_PIN > -1)
+  #if (defined(EXTRUDER_0_AUTO_FAN_PIN) && EXTRUDER_0_AUTO_FAN_PIN > -1)
 
 #ifdef FAN_SOFT_PWM
 #ifdef FANCHECK
@@ -1096,9 +1124,14 @@ void tp_init()
 
   adc_init();
 
-  timer0_init();
+  timer0_init(); //enables the heatbed timer.
+
+  // timer2 already enabled earlier in the code
+  // now enable the COMPB temperature interrupt
   OCR2B = 128;
-  TIMSK2 |= (1<<OCIE2B);  
+  TIMSK2 |= (1<<OCIE2B);
+  
+  timer4_init(); //for tone and Extruder fan PWM
   
   // Wait for temperature measurement to settle
   _delay(250);
@@ -1167,7 +1200,6 @@ void tp_init()
 #endif //MAXTEMP 2
 
 #ifdef BED_MINTEMP
-  /* No bed MINTEMP error implemented?!? */
   while(analog2tempBed(bed_minttemp_raw) < BED_MINTEMP) {
 #if HEATER_BED_RAW_LO_TEMP < HEATER_BED_RAW_HI_TEMP
     bed_minttemp_raw += OVERSAMPLENR;
@@ -1175,7 +1207,6 @@ void tp_init()
     bed_minttemp_raw -= OVERSAMPLENR;
 #endif
   }
-  
 #endif //BED_MINTEMP
 #ifdef BED_MAXTEMP
   while(analog2tempBed(bed_maxttemp_raw) > BED_MAXTEMP) {
@@ -1186,6 +1217,25 @@ void tp_init()
 #endif
   }
 #endif //BED_MAXTEMP
+
+#ifdef AMBIENT_MINTEMP
+  while(analog2tempAmbient(ambient_minttemp_raw) < AMBIENT_MINTEMP) {
+#if HEATER_AMBIENT_RAW_LO_TEMP < HEATER_AMBIENT_RAW_HI_TEMP
+    ambient_minttemp_raw += OVERSAMPLENR;
+#else
+    ambient_minttemp_raw -= OVERSAMPLENR;
+#endif
+  }
+#endif //AMBIENT_MINTEMP
+#ifdef AMBIENT_MAXTEMP
+  while(analog2tempAmbient(ambient_maxttemp_raw) > AMBIENT_MAXTEMP) {
+#if HEATER_AMBIENT_RAW_LO_TEMP < HEATER_AMBIENT_RAW_HI_TEMP
+    ambient_maxttemp_raw -= OVERSAMPLENR;
+#else
+    ambient_maxttemp_raw += OVERSAMPLENR;
+#endif
+  }
+#endif //AMBIENT_MAXTEMP
 }
 
 #if (defined (TEMP_RUNAWAY_BED_HYSTERESIS) && TEMP_RUNAWAY_BED_TIMEOUT > 0) || (defined (TEMP_RUNAWAY_EXTRUDER_HYSTERESIS) && TEMP_RUNAWAY_EXTRUDER_TIMEOUT > 0)
@@ -1357,9 +1407,11 @@ void temp_runaway_stop(bool isPreheat, bool isBed)
 		isBed ? LCD_ALERTMESSAGEPGM("BED PREHEAT ERROR") : LCD_ALERTMESSAGEPGM("PREHEAT ERROR");
 		SERIAL_ERROR_START;
 		isBed ? SERIAL_ERRORLNPGM(" THERMAL RUNAWAY ( PREHEAT HEATBED)") : SERIAL_ERRORLNPGM(" THERMAL RUNAWAY ( PREHEAT HOTEND)");
-		SET_OUTPUT(EXTRUDER_0_AUTO_FAN_PIN);
+#ifdef EXTRUDER_ALTFAN_DETECT
+		altfanStatus.altfanOverride = 1; //full speed
+#endif //EXTRUDER_ALTFAN_DETECT
+		setExtruderAutoFanState(3);
 		SET_OUTPUT(FAN_PIN);
-		WRITE(EXTRUDER_0_AUTO_FAN_PIN, 1);
 #ifdef FAN_SOFT_PWM
 		fanSpeedSoftPwm = 255;
 #else //FAN_SOFT_PWM
@@ -1427,26 +1479,55 @@ enum { LCDALERT_NONE = 0, LCDALERT_HEATERMINTEMP, LCDALERT_BEDMINTEMP, LCDALERT_
 //! to prevent flicker and improve speed
 uint8_t last_alert_sent_to_lcd = LCDALERT_NONE;
 
+
+//! update the current temperature error message
+//! @param type short error abbreviation (PROGMEM)
+//! @param func optional lcd update function (lcd_setalertstatus when first setting the error)
+void temp_update_messagepgm(const char* PROGMEM type, void (*func)(const char*) = lcd_updatestatus)
+{
+    char msg[LCD_WIDTH];
+    strcpy_P(msg, PSTR("Err: "));
+    strcat_P(msg, type);
+    (*func)(msg);
+}
+
+//! signal a temperature error on both the lcd and serial
+//! @param type short error abbreviation (PROGMEM)
+//! @param e optional extruder index for hotend errors
+void temp_error_messagepgm(const char* PROGMEM type, uint8_t e = EXTRUDERS)
+{
+    temp_update_messagepgm(type, lcd_setalertstatus);
+
+    SERIAL_ERROR_START;
+
+    if(e != EXTRUDERS) {
+        SERIAL_ERROR((int)e);
+        SERIAL_ERRORPGM(": ");
+    }
+
+    SERIAL_ERRORPGM("Heaters switched off. ");
+    SERIAL_ERRORRPGM(type);
+    SERIAL_ERRORLNPGM(" triggered!");
+}
+
+
 void max_temp_error(uint8_t e) {
   disable_heater();
   if(IsStopped() == false) {
-    SERIAL_ERROR_START;
-    SERIAL_ERRORLN((int)e);
-    SERIAL_ERRORLNPGM(": Extruder switched off. MAXTEMP triggered !");
-    LCD_ALERTMESSAGEPGM("Err: MAXTEMP");
+    temp_error_messagepgm(PSTR("MAXTEMP"), e);
   }
   #ifndef BOGUS_TEMPERATURE_FAILSAFE_OVERRIDE
   Stop();
-    
-
-    
   #endif
-    SET_OUTPUT(EXTRUDER_0_AUTO_FAN_PIN);
+
     SET_OUTPUT(FAN_PIN);
     SET_OUTPUT(BEEPER);
     WRITE(FAN_PIN, 1);
-    WRITE(EXTRUDER_0_AUTO_FAN_PIN, 1);
     WRITE(BEEPER, 1);
+#ifdef EXTRUDER_ALTFAN_DETECT
+    altfanStatus.altfanOverride = 1; //full speed
+#endif //EXTRUDER_ALTFAN_DETECT
+    setExtruderAutoFanState(3);
     // fanSpeed will consumed by the check_axes_activity() routine.
     fanSpeed=255;
 	if (farm_mode) { prusa_statistics(93); }
@@ -1456,18 +1537,15 @@ void min_temp_error(uint8_t e) {
 #ifdef DEBUG_DISABLE_MINTEMP
 	return;
 #endif
-//if (current_temperature_ambient < MINTEMP_MINAMBIENT) return;
   disable_heater();
-	static const char err[] PROGMEM = "Err: MINTEMP";
+//if (current_temperature_ambient < MINTEMP_MINAMBIENT) return;
+	static const char err[] PROGMEM = "MINTEMP";
   if(IsStopped() == false) {
-    SERIAL_ERROR_START;
-    SERIAL_ERRORLN((int)e);
-    SERIAL_ERRORLNPGM(": Extruder switched off. MINTEMP triggered !");
-    lcd_setalertstatuspgm(err);
+    temp_error_messagepgm(err, e);
     last_alert_sent_to_lcd = LCDALERT_HEATERMINTEMP;
   } else if( last_alert_sent_to_lcd != LCDALERT_HEATERMINTEMP ){ // only update, if the lcd message is to be changed (i.e. not the same as last time)
 	// we are already stopped due to some error, only update the status message without flickering
-	lcd_updatestatuspgm(err);
+    temp_update_messagepgm(err);
 	last_alert_sent_to_lcd = LCDALERT_HEATERMINTEMP;
   }
   #ifndef BOGUS_TEMPERATURE_FAILSAFE_OVERRIDE
@@ -1482,37 +1560,27 @@ void min_temp_error(uint8_t e) {
 }
 
 void bed_max_temp_error(void) {
-#if HEATER_BED_PIN > -1
-  //WRITE(HEATER_BED_PIN, 0);
-#endif
+  disable_heater();
   if(IsStopped() == false) {
-    SERIAL_ERROR_START;
-    SERIAL_ERRORLNPGM("Temperature heated bed switched off. MAXTEMP triggered !");
-    LCD_ALERTMESSAGEPGM("Err: MAXTEMP BED");
+    temp_error_messagepgm(PSTR("MAXTEMP BED"));
   }
   #ifndef BOGUS_TEMPERATURE_FAILSAFE_OVERRIDE
   Stop();
   #endif
-
 }
 
 void bed_min_temp_error(void) {
 #ifdef DEBUG_DISABLE_MINTEMP
 	return;
 #endif
-//if (current_temperature_ambient < MINTEMP_MINAMBIENT) return;
-#if HEATER_BED_PIN > -1
-    //WRITE(HEATER_BED_PIN, 0);
-#endif
-	static const char err[] PROGMEM = "Err: MINTEMP BED";
+    disable_heater();
+    static const char err[] PROGMEM = "MINTEMP BED";
     if(IsStopped() == false) {
-        SERIAL_ERROR_START;
-        SERIAL_ERRORLNPGM("Temperature heated bed switched off. MINTEMP triggered !");
-		lcd_setalertstatuspgm(err);
+        temp_error_messagepgm(err);
 		last_alert_sent_to_lcd = LCDALERT_BEDMINTEMP;
 	} else if( last_alert_sent_to_lcd != LCDALERT_BEDMINTEMP ){ // only update, if the lcd message is to be changed (i.e. not the same as last time)
 		// we are already stopped due to some error, only update the status message without flickering
-		lcd_updatestatuspgm(err);
+        temp_update_messagepgm(err);
 		last_alert_sent_to_lcd = LCDALERT_BEDMINTEMP;
     }
 #ifndef BOGUS_TEMPERATURE_FAILSAFE_OVERRIDE
@@ -1520,6 +1588,33 @@ void bed_min_temp_error(void) {
 #endif
 }
 
+
+#ifdef AMBIENT_THERMISTOR
+void ambient_max_temp_error(void) {
+    disable_heater();
+    if(IsStopped() == false) {
+        temp_error_messagepgm(PSTR("MAXTEMP AMB"));
+    }
+#ifndef BOGUS_TEMPERATURE_FAILSAFE_OVERRIDE
+    Stop();
+#endif
+}
+
+void ambient_min_temp_error(void) {
+#ifdef DEBUG_DISABLE_MINTEMP
+	return;
+#endif
+    disable_heater();
+    if(IsStopped() == false) {
+        temp_error_messagepgm(PSTR("MINTEMP AMB"));
+    }
+#ifndef BOGUS_TEMPERATURE_FAILSAFE_OVERRIDE
+    Stop();
+#endif
+}
+#endif
+
+
 #ifdef HEATER_0_USES_MAX6675
 #define MAX6675_HEAT_INTERVAL 250
 long max6675_previous_millis = MAX6675_HEAT_INTERVAL;
@@ -1604,18 +1699,8 @@ void adc_ready(void) //callback from adc when sampling finished
 
 } // extern "C"
 
-// Timer2 (originaly timer0) is shared with millies
-#ifdef SYSTEM_TIMER_2
-ISR(TIMER2_COMPB_vect)
-#else //SYSTEM_TIMER_2
-ISR(TIMER0_COMPB_vect)
-#endif //SYSTEM_TIMER_2
+FORCE_INLINE static void temperature_isr()
 {
-	static bool _lock = false;
-	if (_lock) return;
-	_lock = true;
-	asm("sei");
-
 	if (!temp_meas_ready) adc_cycle();
 	lcd_buttons_update();
 
@@ -1981,8 +2066,24 @@ ISR(TIMER0_COMPB_vect)
 #if (defined(FANCHECK) && defined(TACH_0) && (TACH_0 > -1))
   check_fans();
 #endif //(defined(TACH_0))
+}
 
-	_lock = false;
+// Timer2 (originaly timer0) is shared with millies
+#ifdef SYSTEM_TIMER_2
+ISR(TIMER2_COMPB_vect)
+#else //SYSTEM_TIMER_2
+ISR(TIMER0_COMPB_vect)
+#endif //SYSTEM_TIMER_2
+{
+    static bool _lock = false;
+    if (!_lock)
+    {
+        _lock = true;
+        sei();
+        temperature_isr();
+        cli();
+        _lock = false;
+    }
 }
 
 void check_max_temp()
@@ -2002,11 +2103,19 @@ void check_max_temp()
 #else
     if (current_temperature_bed_raw >= bed_maxttemp_raw) {
 #endif
-       target_temperature_bed = 0;
        bed_max_temp_error();
     }
 #endif
-
+//ambient
+#if defined(AMBIENT_MAXTEMP) && (TEMP_SENSOR_AMBIENT != 0)
+#if AMBIENT_RAW_LO_TEMP > AMBIENT_RAW_HI_TEMP
+    if (current_temperature_raw_ambient <= ambient_maxttemp_raw) {
+#else
+    if (current_temperature_raw_ambient >= ambient_maxttemp_raw) {
+#endif
+       ambient_max_temp_error();
+    }
+#endif
 }
 //! number of repeating the same state with consecutive step() calls
 //! used to slow down text switching
@@ -2101,12 +2210,32 @@ void check_min_temp_bed()
 	}
 }
 
+#ifdef AMBIENT_MINTEMP
+void check_min_temp_ambient()
+{
+#if AMBIENT_RAW_LO_TEMP > AMBIENT_RAW_HI_TEMP
+	if (current_temperature_raw_ambient >= ambient_minttemp_raw) {
+#else
+	if (current_temperature_raw_ambient <= ambient_minttemp_raw) {
+#endif
+		ambient_min_temp_error();
+	}
+}
+#endif
+
 void check_min_temp()
 {
 static bool bCheckingOnHeater=false;              // state variable, which allows to short no-checking delay (is set, when temperature is (first time) over heaterMintemp)
 static bool bCheckingOnBed=false;                 // state variable, which allows to short no-checking delay (is set, when temperature is (first time) over bedMintemp)
 #ifdef AMBIENT_THERMISTOR
-if(current_temperature_raw_ambient>(OVERSAMPLENR*MINTEMP_MINAMBIENT_RAW)) // thermistor is NTC type, so operator is ">" ;-)
+#ifdef AMBIENT_MINTEMP
+check_min_temp_ambient();
+#endif
+#if AMBIENT_RAW_LO_TEMP > AMBIENT_RAW_HI_TEMP
+if(current_temperature_raw_ambient>(OVERSAMPLENR*MINTEMP_MINAMBIENT_RAW)) // thermistor is NTC type
+#else
+if(current_temperature_raw_ambient=<(OVERSAMPLENR*MINTEMP_MINAMBIENT_RAW))
+#endif
      {                                            // ambient temperature is low
 #endif //AMBIENT_THERMISTOR
 // *** 'common' part of code for MK2.5 & MK3
@@ -2194,4 +2323,31 @@ float unscalePID_d(float d)
 
 #endif //PIDTEMP
 
+#ifdef PINDA_THERMISTOR
+//! @brief PINDA thermistor detected
+//!
+//! @retval true firmware should do temperature compensation and allow calibration
+//! @retval false PINDA thermistor is not detected, disable temperature compensation and calibration
+//! @retval true/false when forced via LCD menu Settings->HW Setup->SuperPINDA
+//!
+bool has_temperature_compensation()
+{
+#ifdef SUPERPINDA_SUPPORT
+#ifdef PINDA_TEMP_COMP
+   	uint8_t pinda_temp_compensation = eeprom_read_byte((uint8_t*)EEPROM_PINDA_TEMP_COMPENSATION);
+    if (pinda_temp_compensation == EEPROM_EMPTY_VALUE) //Unkown PINDA temp compenstation, so check it.
+      {
+#endif //PINDA_TEMP_COMP
+        return (current_temperature_pinda >= PINDA_MINTEMP) ? true : false;
+#ifdef PINDA_TEMP_COMP
+      }
+    else if (pinda_temp_compensation == 0) return true; //Overwritten via LCD menu SuperPINDA [No]
+    else return false; //Overwritten via LCD menu SuperPINDA [YES]
+#endif //PINDA_TEMP_COMP
+#else
+    return true;
+#endif
+}
+#endif //PINDA_THERMISTOR
+
 

+ 9 - 4
Firmware/temperature.h

@@ -63,6 +63,7 @@ extern float current_temperature_bed;
 #ifdef PINDA_THERMISTOR
 extern uint16_t current_temperature_raw_pinda;
 extern float current_temperature_pinda;
+bool has_temperature_compensation();
 #endif
 
 #ifdef AMBIENT_THERMISTOR
@@ -79,7 +80,7 @@ extern int current_voltage_raw_bed;
 #endif
 
 #ifdef IR_SENSOR_ANALOG
-extern int current_voltage_raw_IR;
+extern uint16_t current_voltage_raw_IR;
 #endif //IR_SENSOR_ANALOG
 
 #if defined(CONTROLLERFAN_PIN) && CONTROLLERFAN_PIN > -1
@@ -245,7 +246,7 @@ FORCE_INLINE void autotempShutdown(){
 
 void PID_autotune(float temp, int extruder, int ncycles);
 
-void setExtruderAutoFanState(int pin, bool state);
+void setExtruderAutoFanState(uint8_t state);
 void checkExtruderAutoFans();
 
 
@@ -270,10 +271,14 @@ void check_fans();
 void check_min_temp();
 void check_max_temp();
 
-
-#endif
+#ifdef EXTRUDER_ALTFAN_DETECT
+  extern bool extruder_altfan_detect();
+  extern void altfanOverride_toggle();
+  extern bool altfanOverride_get();
+#endif //EXTRUDER_ALTFAN_DETECT
 
 extern unsigned long extruder_autofan_last_check;
 extern uint8_t fanSpeedBckp;
 extern bool fan_measuring;
 
+#endif

+ 2 - 0
Firmware/thermistortables.h

@@ -1213,6 +1213,8 @@ const short temptable_1047[][2] PROGMEM = {
 #endif
 
 #if (THERMISTORAMBIENT == 2000) //100k thermistor NTCG104LH104JT1
+# define AMBIENT_RAW_HI_TEMP 0
+# define AMBIENT_RAW_LO_TEMP 16383
 const short temptable_2000[][2] PROGMEM = {
 // Source: https://product.tdk.com/info/en/catalog/datasheets/503021/tpd_ntc-thermistor_ntcg_en.pdf
 // Calculated using 4.7kohm pullup, voltage divider math, and manufacturer provided temp/resistance

+ 12 - 11
Firmware/timer02.c

@@ -9,16 +9,11 @@
 
 #include <avr/io.h>
 #include <avr/interrupt.h>
-#include "io_atmega2560.h"
-
-#define BEEPER              84
+#include "macros.h"
 
 void timer0_init(void)
 {
-	//save sreg
-	uint8_t _sreg = SREG;
-	//disable interrupts for sure
-	cli();
+	CRITICAL_SECTION_START;
 
 	TCNT0  = 0;
 	// Fast PWM duty (0-255). 
@@ -28,7 +23,14 @@ void timer0_init(void)
 	TCCR0A = (1 << WGM01) | (1 << WGM00) | (1 << COM0B1) | (1 << COM0B0);  
 	TCCR0B = (1 << CS01);    // CLK/8 prescaling
 	TIMSK0 |= (1 << TOIE0);  // enable timer overflow interrupt
-	
+
+	CRITICAL_SECTION_END;
+}
+
+void timer2_init(void)
+{
+	CRITICAL_SECTION_START;
+
 	// Everything, that used to be on timer0 was moved to timer2 (delay, beeping, millis etc.)
 	//setup timer2
 	TCCR2A = 0x00; //COM_A-B=00, WGM_0-1=00
@@ -39,9 +41,8 @@ void timer0_init(void)
 	TIMSK2 &= ~(1<<OCIE2B);
 	//set timer2 OCR registers (OCRB interrupt generated 0.5ms after OVF interrupt)
 	OCR2A = 0;
-	OCR2B = 128;
-	//restore sreg (enable interrupts)
-	SREG = _sreg;
+
+	CRITICAL_SECTION_END;
 }
 
 

+ 3 - 0
Firmware/timer02.h

@@ -14,6 +14,9 @@ extern "C" {
 ///! Initializes TIMER0 for fast PWM mode-driven bed heating
 extern void timer0_init(void);
 
+///! Initializes TIMER2 for time keeping and temperature interrupt
+extern void timer2_init(void);
+
 ///! Reimplemented original millis() using timer2
 extern unsigned long millis2(void);
 

+ 46 - 20
Firmware/tmc2130.cpp

@@ -428,6 +428,11 @@ void tmc2130_check_overtemp()
 void tmc2130_setup_chopper(uint8_t axis, uint8_t mres, uint8_t current_h, uint8_t current_r)
 {
 	uint8_t intpol = (mres != 0); // intpol to 256 only if microsteps aren't 256
+#ifdef TMC2130_DEDGE_STEPPING
+	uint8_t dedge = 1;
+#else
+	uint8_t dedge = 0;
+#endif
 	uint8_t toff = tmc2130_chopper_config[axis].toff; // toff = 3 (fchop = 27.778kHz)
 	uint8_t hstrt = tmc2130_chopper_config[axis].hstr; //initial 4, modified to 5
 	uint8_t hend = tmc2130_chopper_config[axis].hend; //original value = 1
@@ -437,6 +442,9 @@ void tmc2130_setup_chopper(uint8_t axis, uint8_t mres, uint8_t current_h, uint8_
 	uint8_t tbl = tmc2130_chopper_config[axis].tbl; //blanking time, original value = 2
 	if (axis == E_AXIS)
 	{
+#if defined(TMC2130_INTPOL_E) && (TMC2130_INTPOL_E == 0)
+        intpol = 0;
+#endif
 #ifdef TMC2130_CNSTOFF_E
 		// fd = 0 (slow decay only)
 		hstrt = 0; //fd0..2
@@ -447,16 +455,26 @@ void tmc2130_setup_chopper(uint8_t axis, uint8_t mres, uint8_t current_h, uint8_
 //		toff = TMC2130_TOFF_E; // toff = 3-5
 //		rndtf = 1;
 	}
+#if defined(TMC2130_INTPOL_XY) && (TMC2130_INTPOL_XY == 0)
+    else if (axis == X_AXIS || axis == Y_AXIS) {
+        intpol = 0;
+    }
+#endif
+#if defined(TMC2130_INTPOL_Z) && (TMC2130_INTPOL_Z == 0)
+    else if (axis == Z_AXIS) {
+        intpol = 0;
+    }
+#endif
 //	DBG(_n("tmc2130_setup_chopper(axis=%hhd, mres=%hhd, curh=%hhd, curr=%hhd\n"), axis, mres, current_h, current_r);
 //	DBG(_n(" toff=%hhd, hstr=%hhd, hend=%hhd, tbl=%hhd\n"), toff, hstrt, hend, tbl);
 	if (current_r <= 31)
 	{
-		tmc2130_wr_CHOPCONF(axis, toff, hstrt, hend, fd3, 0, rndtf, chm, tbl, 1, 0, 0, 0, mres, intpol, 0, 0);
+		tmc2130_wr_CHOPCONF(axis, toff, hstrt, hend, fd3, 0, rndtf, chm, tbl, 1, 0, 0, 0, mres, intpol, dedge, 0);
 		tmc2130_wr(axis, TMC2130_REG_IHOLD_IRUN, 0x000f0000 | ((current_r & 0x1f) << 8) | (current_h & 0x1f));
 	}
 	else
 	{
-		tmc2130_wr_CHOPCONF(axis, toff, hstrt, hend, fd3, 0, rndtf, chm, tbl, 0, 0, 0, 0, mres, intpol, 0, 0);
+		tmc2130_wr_CHOPCONF(axis, toff, hstrt, hend, fd3, 0, rndtf, chm, tbl, 0, 0, 0, 0, mres, intpol, dedge, 0);
 		tmc2130_wr(axis, TMC2130_REG_IHOLD_IRUN, 0x000f0000 | (((current_r >> 1) & 0x1f) << 8) | ((current_h >> 1) & 0x1f));
 	}
 }
@@ -678,25 +696,32 @@ static uint8_t tmc2130_rx(uint8_t axis, uint8_t addr, uint32_t* rval)
 #define _GET_PWR_Z      (READ(Z_ENABLE_PIN) == Z_ENABLE_ON)
 #define _GET_PWR_E      (READ(E0_ENABLE_PIN) == E_ENABLE_ON)
 
-#define _SET_PWR_X(ena) { WRITE(X_ENABLE_PIN, ena?X_ENABLE_ON:!X_ENABLE_ON); asm("nop"); }
-#define _SET_PWR_Y(ena) { WRITE(Y_ENABLE_PIN, ena?Y_ENABLE_ON:!Y_ENABLE_ON); asm("nop"); }
-#define _SET_PWR_Z(ena) { WRITE(Z_ENABLE_PIN, ena?Z_ENABLE_ON:!Z_ENABLE_ON); asm("nop"); }
-#define _SET_PWR_E(ena) { WRITE(E0_ENABLE_PIN, ena?E_ENABLE_ON:!E_ENABLE_ON); asm("nop"); }
+#define _SET_PWR_X(ena) WRITE(X_ENABLE_PIN, ena?X_ENABLE_ON:!X_ENABLE_ON)
+#define _SET_PWR_Y(ena) WRITE(Y_ENABLE_PIN, ena?Y_ENABLE_ON:!Y_ENABLE_ON)
+#define _SET_PWR_Z(ena) WRITE(Z_ENABLE_PIN, ena?Z_ENABLE_ON:!Z_ENABLE_ON)
+#define _SET_PWR_E(ena) WRITE(E0_ENABLE_PIN, ena?E_ENABLE_ON:!E_ENABLE_ON)
 
 #define _GET_DIR_X      (READ(X_DIR_PIN) == INVERT_X_DIR)
 #define _GET_DIR_Y      (READ(Y_DIR_PIN) == INVERT_Y_DIR)
 #define _GET_DIR_Z      (READ(Z_DIR_PIN) == INVERT_Z_DIR)
 #define _GET_DIR_E      (READ(E0_DIR_PIN) == INVERT_E0_DIR)
 
-#define _SET_DIR_X(dir) { WRITE(X_DIR_PIN, dir?INVERT_X_DIR:!INVERT_X_DIR); asm("nop"); }
-#define _SET_DIR_Y(dir) { WRITE(Y_DIR_PIN, dir?INVERT_Y_DIR:!INVERT_Y_DIR); asm("nop"); }
-#define _SET_DIR_Z(dir) { WRITE(Z_DIR_PIN, dir?INVERT_Z_DIR:!INVERT_Z_DIR); asm("nop"); }
-#define _SET_DIR_E(dir) { WRITE(E0_DIR_PIN, dir?INVERT_E0_DIR:!INVERT_E0_DIR); asm("nop"); }
+#define _SET_DIR_X(dir) WRITE(X_DIR_PIN, dir?INVERT_X_DIR:!INVERT_X_DIR)
+#define _SET_DIR_Y(dir) WRITE(Y_DIR_PIN, dir?INVERT_Y_DIR:!INVERT_Y_DIR)
+#define _SET_DIR_Z(dir) WRITE(Z_DIR_PIN, dir?INVERT_Z_DIR:!INVERT_Z_DIR)
+#define _SET_DIR_E(dir) WRITE(E0_DIR_PIN, dir?INVERT_E0_DIR:!INVERT_E0_DIR)
 
-#define _DO_STEP_X      { WRITE(X_STEP_PIN, !INVERT_X_STEP_PIN); asm("nop"); WRITE(X_STEP_PIN, INVERT_X_STEP_PIN); asm("nop"); }
-#define _DO_STEP_Y      { WRITE(Y_STEP_PIN, !INVERT_Y_STEP_PIN); asm("nop"); WRITE(Y_STEP_PIN, INVERT_Y_STEP_PIN); asm("nop"); }
-#define _DO_STEP_Z      { WRITE(Z_STEP_PIN, !INVERT_Z_STEP_PIN); asm("nop"); WRITE(Z_STEP_PIN, INVERT_Z_STEP_PIN); asm("nop"); }
-#define _DO_STEP_E      { WRITE(E0_STEP_PIN, !INVERT_E_STEP_PIN); asm("nop"); WRITE(E0_STEP_PIN, INVERT_E_STEP_PIN); asm("nop"); }
+#ifdef TMC2130_DEDGE_STEPPING
+#define _DO_STEP_X      TOGGLE(X_STEP_PIN)
+#define _DO_STEP_Y      TOGGLE(Y_STEP_PIN)
+#define _DO_STEP_Z      TOGGLE(Z_STEP_PIN)
+#define _DO_STEP_E      TOGGLE(E0_STEP_PIN)
+#else
+#define _DO_STEP_X      { WRITE(X_STEP_PIN, !INVERT_X_STEP_PIN); TMC2130_MINIMUM_DELAY; WRITE(X_STEP_PIN, INVERT_X_STEP_PIN); }
+#define _DO_STEP_Y      { WRITE(Y_STEP_PIN, !INVERT_Y_STEP_PIN); TMC2130_MINIMUM_DELAY; WRITE(Y_STEP_PIN, INVERT_Y_STEP_PIN); }
+#define _DO_STEP_Z      { WRITE(Z_STEP_PIN, !INVERT_Z_STEP_PIN); TMC2130_MINIMUM_DELAY; WRITE(Z_STEP_PIN, INVERT_Z_STEP_PIN); }
+#define _DO_STEP_E      { WRITE(E0_STEP_PIN, !INVERT_E_STEP_PIN); TMC2130_MINIMUM_DELAY; WRITE(E0_STEP_PIN, INVERT_E_STEP_PIN); }
+#endif
 
 
 uint16_t tmc2130_get_res(uint8_t axis)
@@ -737,6 +762,7 @@ void tmc2130_set_pwr(uint8_t axis, uint8_t pwr)
 	case Z_AXIS: _SET_PWR_Z(pwr); break;
 	case E_AXIS: _SET_PWR_E(pwr); break;
 	}
+    delayMicroseconds(TMC2130_SET_PWR_DELAY);
 }
 
 uint8_t tmc2130_get_inv(uint8_t axis)
@@ -773,6 +799,7 @@ void tmc2130_set_dir(uint8_t axis, uint8_t dir)
 	case Z_AXIS: _SET_DIR_Z(dir); break;
 	case E_AXIS: _SET_DIR_E(dir); break;
 	}
+    delayMicroseconds(TMC2130_SET_DIR_DELAY);
 }
 
 void tmc2130_do_step(uint8_t axis)
@@ -788,8 +815,8 @@ void tmc2130_do_step(uint8_t axis)
 
 void tmc2130_do_steps(uint8_t axis, uint16_t steps, uint8_t dir, uint16_t delay_us)
 {
-	tmc2130_set_dir(axis, dir);
-	delayMicroseconds(100);
+    if (tmc2130_get_dir(axis) != dir)
+        tmc2130_set_dir(axis, dir);
 	while (steps--)
 	{
 		tmc2130_do_step(axis);
@@ -820,7 +847,6 @@ void tmc2130_goto_step(uint8_t axis, uint8_t step, uint8_t dir, uint16_t delay_u
 		cnt = steps;
 	}
 	tmc2130_set_dir(axis, dir);
-	delayMicroseconds(100);
 	mscnt = tmc2130_rd_MSCNT(axis);
 	while ((cnt--) && ((mscnt >> shift) != step))
 	{
@@ -994,13 +1020,13 @@ bool tmc2130_home_calibrate(uint8_t axis)
 	uint8_t step[16];
 	uint8_t cnt[16];
 	uint8_t val[16];
-	homeaxis(axis, true, 16, step);
+	homeaxis(axis, 16, step);
 	bubblesort_uint8(step, 16, 0);
-	printf_P(PSTR("sorted samples:\n"));
+	puts_P(PSTR("sorted samples:"));
 	for (uint8_t i = 0; i < 16; i++)
 		printf_P(PSTR(" i=%2d step=%2d\n"), i, step[i]);
 	uint8_t cl = clusterize_uint8(step, 16, cnt, val, 1);
-	printf_P(PSTR("clusters:\n"));
+	puts_P(PSTR("clusters:"));
 	for (uint8_t i = 0; i < cl; i++)
 		printf_P(PSTR(" i=%2d cnt=%2d val=%2d\n"), i, cnt[i], val[i]);
 	bubblesort_uint8(cnt, cl, val);

+ 12 - 0
Firmware/tmc2130.h

@@ -29,6 +29,18 @@ extern uint8_t tmc2130_sg_homing_axes_mask;
 #define TMC2130_WAVE_FAC1000_MAX 200
 #define TMC2130_WAVE_FAC1000_STP   1
 
+#define TMC2130_MINIMUM_PULSE 0   // minimum pulse width in uS
+#define TMC2130_SET_DIR_DELAY 20  // minimum delay after setting direction in uS
+#define TMC2130_SET_PWR_DELAY 0   // minimum delay after changing pwr mode in uS
+
+#ifdef TMC2130_DEDGE_STEPPING
+#define TMC2130_MINIMUM_DELAY //NOP
+#elif TMC2130_MINIMUM_PULSE == 0
+#define TMC2130_MINIMUM_DELAY asm("nop")
+#else
+#define TMC2130_MINIMUM_DELAY delayMicroseconds(TMC2130_MINIMUM_PULSE)
+#endif
+
 extern uint8_t tmc2130_home_enabled;
 extern uint8_t tmc2130_home_origin[2];
 extern uint8_t tmc2130_home_bsteps[2];

+ 118 - 0
Firmware/tone04.c

@@ -0,0 +1,118 @@
+//tone04.c
+// use atmega timer4 as main tone timer instead of timer2
+// timer2 is used for System timer.
+
+#include "system_timer.h"
+#include "Configuration_prusa.h"
+
+#ifdef SYSTEM_TIMER_2
+
+#include "pins.h"
+#include "fastio.h"
+#include "macros.h"
+
+void timer4_init(void)
+{
+	CRITICAL_SECTION_START;
+	
+	SET_OUTPUT(BEEPER);
+	WRITE(BEEPER, LOW);
+	
+	SET_OUTPUT(EXTRUDER_0_AUTO_FAN_PIN);
+	
+	// Set timer mode 9 (PWM,Phase and Frequency Correct)
+	// Prescaler is CLK/1024
+	// Output compare is disabled on all timer pins
+	// Input capture is disabled
+	// All interrupts are disabled
+	TCCR4A = (1 << WGM40);
+	TCCR4B = (1 << WGM43) | (1 << CS42) | (1 << CS40);
+	OCR4A = 255;
+	OCR4B = 255;
+	OCR4C = 255;
+	TIMSK4 = 0;
+	
+	CRITICAL_SECTION_END;
+}
+
+#ifdef EXTRUDER_0_AUTO_FAN_PIN
+void timer4_set_fan0(uint8_t duty)
+{
+	if (duty == 0 || duty == 255)
+	{
+		// We use digital logic if the duty cycle is 0% or 100%
+		TCCR4A &= ~(1 << COM4C1);
+		OCR4C = 0;
+		WRITE(EXTRUDER_0_AUTO_FAN_PIN, duty);
+	}
+	else
+	{
+		// Use the timer for fan speed. Enable the timer compare output and set the duty cycle.
+		// This function also handles the impossible scenario of a fan speed change during a Tone.
+		// Better be safe than sorry.
+		CRITICAL_SECTION_START;
+		// Enable the PWM output on the fan pin.
+		TCCR4A |= (1 << COM4C1);
+		OCR4C = (((uint32_t)duty) * ((uint32_t)((TIMSK4 & (1 << OCIE4A))?OCR4A:255))) / ((uint32_t)255);
+		CRITICAL_SECTION_END;
+	}
+}
+#endif //EXTRUDER_0_AUTO_FAN_PIN
+
+// Because of the timer mode change, we need two interrupts. We could also try to assume that the frequency is x2
+// and use a TOGGLE(), but this seems to work well enough so I left it as it is now.
+ISR(TIMER4_COMPA_vect)
+{
+	WRITE(BEEPER, 1);
+}
+
+ISR(TIMER4_OVF_vect)
+{
+	WRITE(BEEPER, 0);
+}
+
+void tone4(_UNUSED uint8_t _pin, uint16_t frequency)
+{
+	//this ocr and prescalarbits calculation is taken from the Arduino core and simplified for one type of timer only
+	uint8_t prescalarbits = 0b001;
+	uint32_t ocr = F_CPU / frequency / 2 - 1;
+	
+	if (ocr > 0xffff)
+	{
+		ocr = F_CPU / frequency / 2 / 64 - 1;
+		prescalarbits = 0b011;
+	}
+	
+	CRITICAL_SECTION_START;
+	// Set calcualted prescaler
+	TCCR4B = (TCCR4B & 0b11111000) | prescalarbits;
+#ifdef EXTRUDER_0_AUTO_FAN_PIN
+	// Scale the fan PWM duty cycle so that it remains constant, but at the tone frequency
+	OCR4C = (((uint32_t)OCR4C) * ocr) / (uint32_t)((TIMSK4 & (1 << OCIE4A))?OCR4A:255);
+#endif //EXTRUDER_0_AUTO_FAN_PIN
+	// Set calcualted ocr
+	OCR4A = ocr;
+	// Enable Output compare A interrupt and timer overflow interrupt
+	TIMSK4 |= (1 << OCIE4A) | (1 << TOIE4);
+	CRITICAL_SECTION_END;
+}
+
+void noTone4(_UNUSED uint8_t _pin)
+{
+	CRITICAL_SECTION_START;
+	// Revert prescaler to CLK/1024
+	TCCR4B = (TCCR4B & 0b11111000) | (1 << CS42) | (1 << CS40);
+#ifdef EXTRUDER_0_AUTO_FAN_PIN
+	// Scale the fan OCR back to the original value.
+	OCR4C = (((uint32_t)OCR4C) * (uint32_t)255) / (uint32_t)((TIMSK4 & (1 << OCIE4A))?OCR4A:255);
+#endif //EXTRUDER_0_AUTO_FAN_PIN
+	OCR4A = 255;
+	// Disable Output compare A interrupt and timer overflow interrupt
+	TIMSK4 &= ~((1 << OCIE4A) | (1 << TOIE4));
+	CRITICAL_SECTION_END;
+	// Turn beeper off if it was on when noTone was called
+	WRITE(BEEPER, 0);
+}
+
+
+#endif //SYSTEM_TIMER_2

+ 25 - 0
Firmware/tone04.h

@@ -0,0 +1,25 @@
+//tone04.h
+// use atmega timer4 as main tone timer instead of timer2
+// timer2 is used for System timer.
+#ifndef TIMER04_H
+#define TIMER04_H
+
+#include <inttypes.h>
+
+#if defined(__cplusplus)
+extern "C" {
+#endif //defined(__cplusplus)
+
+extern void timer4_init(void);
+
+extern void timer4_set_fan0(uint8_t duty);
+
+extern void tone4(uint8_t _pin, uint16_t frequency);
+
+extern void noTone4(uint8_t _pin);
+
+#if defined(__cplusplus)
+}
+#endif //defined(__cplusplus)
+
+#endif //TIMER02_H

+ 137 - 0
Firmware/twi.c

@@ -0,0 +1,137 @@
+/*
+  twi.c - Stripped-down TWI/I2C library
+  Copyright (c) 2006 Nicholas Zambetti.  All right reserved.
+
+  This library is free software; you can redistribute it and/or
+  modify it under the terms of the GNU Lesser General Public
+  License as published by the Free Software Foundation; either
+  version 2.1 of the License, or (at your option) any later version.
+
+  This library 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
+  Lesser General Public License for more details.
+
+  You should have received a copy of the GNU Lesser General Public
+  License along with this library; if not, write to the Free Software
+  Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA  02110-1301  USA
+
+  Modified 2012 by Todd Krein (todd@krein.org) to implement repeated starts
+*/
+
+
+#include <math.h>
+#include "config.h"
+#include "fastio.h"
+#include "twi.h"
+
+
+void twi_init(void)
+{
+  // activate internal pullups for twi.
+  WRITE(SDA_PIN, 1);
+  WRITE(SCL_PIN, 1);
+
+  // initialize twi prescaler and bit rate
+  TWSR &= ~(_BV(TWPS0) | _BV(TWPS1));
+  TWBR = ((F_CPU / TWI_FREQ) - 16) / 2;
+
+  /* twi bit rate formula from atmega128 manual pg 204
+  SCL Frequency = CPU Clock Frequency / (16 + (2 * TWBR))
+  note: TWBR should be 10 or higher for master mode
+  It is 72 for a 16mhz Wiring board with 100kHz TWI */
+}
+
+void twi_disable(void)
+{
+  // deactivate internal pullups for twi.
+  WRITE(SDA_PIN, 0);
+  WRITE(SCL_PIN, 0);
+}
+
+
+static void twi_stop()
+{
+  TWCR = _BV(TWEN) | _BV(TWINT) | _BV(TWSTO);
+}
+
+
+static uint8_t twi_wait(uint8_t status)
+{
+  while(!(TWCR & _BV(TWINT)));
+  if(TW_STATUS != status)
+  {
+      twi_stop();
+      return 1;
+  }
+  return 0;
+}
+
+
+static uint8_t twi_start(uint8_t address, uint8_t reg)
+{
+  // send start condition
+  TWCR = _BV(TWEN) | _BV(TWINT) | _BV(TWSTA);
+  if(twi_wait(TW_START))
+      return 1;
+
+  // send address
+  TWDR = TW_WRITE | (address << 1);
+  TWCR = _BV(TWEN) | _BV(TWINT);
+  if(twi_wait(TW_MT_SLA_ACK))
+      return 2;
+
+  // send register
+  TWDR = reg;
+  TWCR = _BV(TWEN) | _BV(TWINT);
+  if(twi_wait(TW_MT_DATA_ACK))
+      return 3;
+
+  return 0;
+}
+
+
+uint8_t twi_r8(uint8_t address, uint8_t reg, uint8_t* data)
+{
+  if(twi_start(address, reg))
+      return 1;
+
+  // repeat start
+  TWCR = _BV(TWEN) | _BV(TWINT) | _BV(TWSTA);
+  if(twi_wait(TW_REP_START))
+      return 2;
+
+  // start receiving
+  TWDR = TW_READ | (address << 1);
+  TWCR = _BV(TWEN) | _BV(TWINT);
+  if(twi_wait(TW_MR_SLA_ACK))
+      return 3;
+
+  // receive data
+  TWCR = _BV(TWEN) | _BV(TWINT);
+  if(twi_wait(TW_MR_DATA_NACK))
+      return 4;
+
+  *data = TWDR;
+
+  // send stop
+  twi_stop();
+  return 0;
+}
+
+
+uint8_t twi_w8(uint8_t address, uint8_t reg, uint8_t data)
+{
+  if(twi_start(address, reg))
+      return 1;
+
+  // send data
+  TWDR = data;
+  TWCR = _BV(TWEN) | _BV(TWINT);
+  if(twi_wait(TW_MT_DATA_ACK))
+      return 2;
+
+  // send stop
+  twi_stop();
+  return 0;
+}

+ 63 - 0
Firmware/twi.h

@@ -0,0 +1,63 @@
+/*
+  twi.h - Stripped-down TWI/I2C library
+  Copyright (c) 2006 Nicholas Zambetti.  All right reserved.
+
+  This library is free software; you can redistribute it and/or
+  modify it under the terms of the GNU Lesser General Public
+  License as published by the Free Software Foundation; either
+  version 2.1 of the License, or (at your option) any later version.
+
+  This library 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
+  Lesser General Public License for more details.
+
+  You should have received a copy of the GNU Lesser General Public
+  License along with this library; if not, write to the Free Software
+  Foundation, Inc., 51 Franklin St, Fifth Floor, Boston, MA  02110-1301  USA
+*/
+
+#pragma once
+
+#include <inttypes.h>
+#include <compat/twi.h>
+
+#ifndef TWI_FREQ
+#define TWI_FREQ 400000L
+#endif
+
+/*
+ * Function twi_init
+ * Desc     readys twi pins and sets twi bitrate
+ * Input    none
+ * Output   none
+ */
+void twi_init(void);
+
+/*
+ * Function twi_disable
+ * Desc     disables twi pins
+ * Input    none
+ * Output   none
+ */
+void twi_disable(void);
+
+/*
+ * Function twi_r8
+ * Desc     read a single byte from a device
+ * Input    address: 7bit i2c device address
+ *          reg: register address
+ *          data: pointer to byte for result
+ * Output   0 on success
+ */
+uint8_t twi_r8(uint8_t address, uint8_t reg, uint8_t* data);
+
+/*
+ * Function twi_w8
+ * Desc     write a single byte from a device
+ * Input    address: 7bit i2c device address
+ *          reg: register address
+ *          data: byte to write
+ * Output   0 on success
+ */
+uint8_t twi_w8(uint8_t address, uint8_t reg, uint8_t data);

+ 4 - 3
Firmware/uart2.c

@@ -4,6 +4,7 @@
 #include <avr/interrupt.h>
 #include <avr/pgmspace.h>
 #include "rbuf.h"
+#include "macros.h"
 
 #define UART2_BAUD 115200
 #define UART_BAUD_SELECT(baudRate,xtalCpu) (((float)(xtalCpu))/(((float)(baudRate))*8.0)-1.0+0.5)
@@ -16,7 +17,7 @@ uint8_t uart2_ibuf[14] = {0, 0};
 FILE _uart2io = {0};
 
 
-int uart2_putchar(char c, FILE *stream __attribute__((unused)))
+int uart2_putchar(char c, _UNUSED FILE *stream)
 {
 	while (!uart2_txready);
 	UDR2 = c; // transmit byte
@@ -25,7 +26,7 @@ int uart2_putchar(char c, FILE *stream __attribute__((unused)))
 	return 0;
 }
 
-int uart2_getchar(FILE *stream __attribute__((unused)))
+int uart2_getchar(_UNUSED FILE *stream)
 {
 	if (rbuf_empty(uart2_ibuf)) return -1;
 	return rbuf_get(uart2_ibuf);
@@ -78,7 +79,7 @@ ISR(USART2_RX_vect)
 	if (rbuf_put(uart2_ibuf, UDR2) < 0) // put received byte to buffer
 	{ //rx buffer full
 		//uart2_rx_clr(); //for sure, clear input buffer
-		printf_P(PSTR("USART2 rx Full!!!\n"));
+		puts_P(PSTR("USART2 rx Full!!!"));
 	}
 }
 

+ 746 - 950
Firmware/ultralcd.cpp

@@ -44,13 +44,16 @@
 #include "mmu.h"
 
 #include "static_assert.h"
-#include "io_atmega2560.h"
 #include "first_lay_cal.h"
 
 #include "fsensor.h"
 #include "adc.h"
 #include "config.h"
 
+#ifndef LA_NOCOMPAT
+#include "la10compat.h"
+#endif
+
 
 int scrollstuff = 0;
 char longFilenameOLD[LONG_FILENAME_LENGTH];
@@ -86,7 +89,6 @@ unsigned int custom_message_state = 0;
 
 bool isPrintPaused = false;
 uint8_t farm_mode = 0;
-int farm_no = 0;
 int farm_timer = 8;
 uint8_t farm_status = 0;
 bool printer_connected = true;
@@ -134,7 +136,6 @@ static void prusa_stat_farm_number();
 static void prusa_stat_diameter();
 static void prusa_stat_temperatures();
 static void prusa_stat_printinfo();
-static void lcd_farm_no();
 static void lcd_menu_xyz_y_min();
 static void lcd_menu_xyz_skew();
 static void lcd_menu_xyz_offset();
@@ -168,10 +169,10 @@ static void reset_crash_det(unsigned char axis);
 static bool lcd_selfcheck_axis_sg(unsigned char axis);
 static bool lcd_selfcheck_axis(int _axis, int _travel);
 #else
-static bool lcd_selfcheck_endstops();
 static bool lcd_selfcheck_axis(int _axis, int _travel);
 static bool lcd_selfcheck_pulleys(int axis);
 #endif //TMC2130
+static bool lcd_selfcheck_endstops();
 
 static bool lcd_selfcheck_check_heater(bool _isbed);
 enum class TestScreen : uint_least8_t
@@ -338,11 +339,9 @@ static void lcd_implementation_drawmenu_sdfile_selected(uint8_t row, const char*
     uint8_t n = LCD_WIDTH - 1;
 
     for(uint_least8_t g = 0; g<4;g++){
-      lcd_set_cursor(0, g);
-    lcd_print(' ');
+      lcd_putc_at(0, g, ' ');
     }
-    lcd_set_cursor(0, row);
-    lcd_print('>');
+    lcd_putc_at(0, row, '>');
 
     if (longFilename[0] == '\0')
     {
@@ -381,20 +380,17 @@ static void lcd_implementation_drawmenu_sdfile_selected(uint8_t row, const char*
         }
     }
     if(c!='\0'){
-      lcd_set_cursor(i, row);
-        lcd_print(c);
+        lcd_putc_at(i, row, c);
         i++;
     }
     n=n-i+1;
-    while(n--)
-        lcd_print(' ');
+    lcd_space(n);
 }
 static void lcd_implementation_drawmenu_sdfile(uint8_t row, const char* filename, char* longFilename)
 {
     char c;
     uint8_t n = LCD_WIDTH - 1;
-    lcd_set_cursor(0, row);
-    lcd_print(' ');
+    lcd_putc_at(0, row, ' ');
     if (longFilename[0] != '\0')
     {
         filename = longFilename;
@@ -406,15 +402,13 @@ static void lcd_implementation_drawmenu_sdfile(uint8_t row, const char* filename
         filename++;
         n--;
     }
-    while(n--)
-        lcd_print(' ');
+    lcd_space(n);
 }
 static void lcd_implementation_drawmenu_sddirectory_selected(uint8_t row, const char* filename, char* longFilename)
 {
     char c;
     uint8_t n = LCD_WIDTH - 2;
-    lcd_set_cursor(0, row);
-    lcd_print('>');
+    lcd_putc_at(0, row, '>');
     lcd_print(LCD_STR_FOLDER[0]);
     if (longFilename[0] != '\0')
     {
@@ -427,15 +421,13 @@ static void lcd_implementation_drawmenu_sddirectory_selected(uint8_t row, const
         filename++;
         n--;
     }
-    while(n--)
-        lcd_print(' ');
+    lcd_space(n);
 }
 static void lcd_implementation_drawmenu_sddirectory(uint8_t row, const char* filename, char* longFilename)
 {
     char c;
     uint8_t n = LCD_WIDTH - 2;
-    lcd_set_cursor(0, row);
-    lcd_print(' ');
+    lcd_putc_at(0, row, ' ');
     lcd_print(LCD_STR_FOLDER[0]);
     if (longFilename[0] != '\0')
     {
@@ -448,8 +440,7 @@ static void lcd_implementation_drawmenu_sddirectory(uint8_t row, const char* fil
         filename++;
         n--;
     }
-    while(n--)
-        lcd_print(' ');
+    lcd_space(n);
 }
 
 
@@ -668,39 +659,7 @@ void lcdui_print_extruder(void)
 // Print farm number (5 chars total)
 void lcdui_print_farm(void)
 {
-	int chars = lcd_printf_P(_N(" F0  "));
-//	lcd_space(5 - chars);
-/*
-	// Farm number display
-	if (farm_mode)
-	{
-		lcd_set_cursor(6, 2);
-		lcd_puts_P(PSTR(" F"));
-		lcd_print(farm_no);
-		lcd_puts_P(PSTR("  "));
-        
-        // Beat display
-        lcd_set_cursor(LCD_WIDTH - 1, 0);
-        if ( (_millis() - kicktime) < 60000 ) {
-        
-            lcd_puts_P(PSTR("L"));
-        
-        }else{
-            lcd_puts_P(PSTR(" "));
-        }
-        
-	}
-	else {
-#ifdef SNMM
-		lcd_puts_P(PSTR(" E"));
-		lcd_print(get_ext_nr() + 1);
-
-#else
-		lcd_set_cursor(LCD_WIDTH - 8 - 2, 2);
-		lcd_puts_P(PSTR(" "));
-#endif
-	}
-*/
+	lcd_printf_P(_N(" FRM "));
 }
 
 #ifdef CMD_DIAGNOSTICS
@@ -710,7 +669,7 @@ void lcdui_print_cmd_diag(void)
 	lcd_set_cursor(LCD_WIDTH - 8 -1, 2);
 	lcd_puts_P(PSTR("      C"));
 	lcd_print(buflen);	// number of commands in cmd buffer
-	if (buflen < 9) lcd_puts_P(" ");
+	if (buflen < 9) lcd_print(' ');
 }
 #endif //CMD_DIAGNOSTICS
 
@@ -765,32 +724,27 @@ void lcdui_print_status_line(void)
 			heating_status_counter = 0;
 		}
 		lcd_set_cursor(7, 3);
-		lcd_puts_P(PSTR("             "));
+		lcd_space(13);
 
 		for (unsigned int dots = 0; dots < heating_status_counter; dots++)
 		{
-			lcd_set_cursor(7 + dots, 3);
-			lcd_print('.');
+			lcd_putc_at(7 + dots, 3, '.');
 		}
 		switch (heating_status)
 		{
 		case 1:
-			lcd_set_cursor(0, 3);
-			lcd_puts_P(_T(MSG_HEATING));
+			lcd_puts_at_P(0, 3, _T(MSG_HEATING));
 			break;
 		case 2:
-			lcd_set_cursor(0, 3);
-			lcd_puts_P(_T(MSG_HEATING_COMPLETE));
+			lcd_puts_at_P(0, 3, _T(MSG_HEATING_COMPLETE));
 			heating_status = 0;
 			heating_status_counter = 0;
 			break;
 		case 3:
-			lcd_set_cursor(0, 3);
-			lcd_puts_P(_T(MSG_BED_HEATING));
+			lcd_puts_at_P(0, 3, _T(MSG_BED_HEATING));
 			break;
 		case 4:
-			lcd_set_cursor(0, 3);
-			lcd_puts_P(_T(MSG_BED_DONE));
+			lcd_puts_at_P(0, 3, _T(MSG_BED_DONE));
 			heating_status = 0;
 			heating_status_counter = 0;
 			break;
@@ -839,9 +793,8 @@ void lcdui_print_status_line(void)
 			if (custom_message_state > 10)
 			{
 				lcd_set_cursor(0, 3);
-				lcd_puts_P(PSTR("                    "));
-				lcd_set_cursor(0, 3);
-				lcd_puts_P(_T(MSG_CALIBRATE_Z_AUTO));
+				lcd_space(20);
+				lcd_puts_at_P(0, 3, _T(MSG_CALIBRATE_Z_AUTO));
 				lcd_puts_P(PSTR(" : "));
 				lcd_print(custom_message_state-10);
 			}
@@ -856,9 +809,8 @@ void lcdui_print_status_line(void)
 				if (custom_message_state > 3 && custom_message_state <= 10 )
 				{
 					lcd_set_cursor(0, 3);
-					lcd_puts_P(PSTR("                   "));
-					lcd_set_cursor(0, 3);
-					lcd_puts_P(_i("Calibration done"));////MSG_HOMEYZ_DONE
+					lcd_space(19);
+					lcd_puts_at_P(0, 3, _i("Calibration done"));////MSG_HOMEYZ_DONE
 					custom_message_state--;
 				}
 			}
@@ -888,8 +840,7 @@ void lcdui_print_status_line(void)
 			}
 			break;
 		case CustomMsg::TempCompPreheat: // temp compensation preheat
-			lcd_set_cursor(0, 3);
-			lcd_puts_P(_i("PINDA Heating"));////MSG_PINDA_PREHEAT c=20 r=1
+			lcd_puts_at_P(0, 3, _i("PINDA Heating"));////MSG_PINDA_PREHEAT c=20 r=1
 			if (custom_message_state <= PINDA_HEAT_T)
 			{
 				lcd_puts_P(PSTR(": "));
@@ -997,6 +948,36 @@ void lcd_status_screen()                          // NOT static due to using ins
 		}
 	}
 
+#ifdef ULTIPANEL_FEEDMULTIPLY
+	// Dead zone at 100% feedrate
+	if ((feedmultiply < 100 && (feedmultiply + int(lcd_encoder)) > 100) ||
+		(feedmultiply > 100 && (feedmultiply + int(lcd_encoder)) < 100))
+	{
+		lcd_encoder = 0;
+		feedmultiply = 100;
+	}
+	if (feedmultiply == 100 && int(lcd_encoder) > ENCODER_FEEDRATE_DEADZONE)
+	{
+		feedmultiply += int(lcd_encoder) - ENCODER_FEEDRATE_DEADZONE;
+		lcd_encoder = 0;
+	}
+	else if (feedmultiply == 100 && int(lcd_encoder) < -ENCODER_FEEDRATE_DEADZONE)
+	{
+		feedmultiply += int(lcd_encoder) + ENCODER_FEEDRATE_DEADZONE;
+		lcd_encoder = 0;
+	}
+	else if (feedmultiply != 100)
+	{
+		feedmultiply += int(lcd_encoder);
+		lcd_encoder = 0;
+	}
+#endif //ULTIPANEL_FEEDMULTIPLY
+
+	if (feedmultiply < 10)
+		feedmultiply = 10;
+	else if (feedmultiply > 999)
+		feedmultiply = 999;
+
 	if (lcd_status_update_delay)
 		lcd_status_update_delay--;
 	else
@@ -1073,36 +1054,6 @@ void lcd_status_screen()                          // NOT static due to using ins
 		menu_submenu(lcd_main_menu);
 		lcd_refresh(); // to maybe revive the LCD if static electricity killed it.
 	}
-
-#ifdef ULTIPANEL_FEEDMULTIPLY
-	// Dead zone at 100% feedrate
-	if ((feedmultiply < 100 && (feedmultiply + int(lcd_encoder)) > 100) ||
-		(feedmultiply > 100 && (feedmultiply + int(lcd_encoder)) < 100))
-	{
-		lcd_encoder = 0;
-		feedmultiply = 100;
-	}
-	if (feedmultiply == 100 && int(lcd_encoder) > ENCODER_FEEDRATE_DEADZONE)
-	{
-		feedmultiply += int(lcd_encoder) - ENCODER_FEEDRATE_DEADZONE;
-		lcd_encoder = 0;
-	}
-	else if (feedmultiply == 100 && int(lcd_encoder) < -ENCODER_FEEDRATE_DEADZONE)
-	{
-		feedmultiply += int(lcd_encoder) + ENCODER_FEEDRATE_DEADZONE;
-		lcd_encoder = 0;
-	}
-	else if (feedmultiply != 100)
-	{
-		feedmultiply += int(lcd_encoder);
-		lcd_encoder = 0;
-	}
-#endif //ULTIPANEL_FEEDMULTIPLY
-
-	if (feedmultiply < 10)
-		feedmultiply = 10;
-	else if (feedmultiply > 999)
-		feedmultiply = 999;
 }
 
 void lcd_commands()
@@ -1483,7 +1434,6 @@ void lcd_commands()
 
 		if (lcd_commands_step == 1 && !blocks_queued())
 		{
-			lcd_confirm_print();
 			lcd_commands_step = 0;
 			lcd_commands_type = LcdCommands::Idle;
 		}
@@ -1579,6 +1529,7 @@ void lcd_return_to_status()
 //! @brief Pause print, disable nozzle heater, move to park position
 void lcd_pause_print()
 {
+    SERIAL_PROTOCOLLNRPGM(MSG_OCTOPRINT_PAUSED); //pause for octoprint
     stop_and_save_print_to_ram(0.0, -default_retraction);
     lcd_return_to_status();
     isPrintPaused = true;
@@ -1586,7 +1537,6 @@ void lcd_pause_print()
     {
         lcd_commands_type = LcdCommands::LongPause;
     }
-	SERIAL_PROTOCOLLNRPGM(MSG_OCTOPRINT_PAUSED); //pause for octoprint
 }
 
 
@@ -1688,8 +1638,8 @@ void lcd_menu_extruder_info()                     // NOT static due to using ins
 //! @code{.unparsed}
 //! |01234567890123456789|
 //! | Main               |	c=18 r=1
-//! | Last print         |	c=18 r=1
-//! | Total              |	c=18 r=1
+//! | Last print         |	MSG_LAST_PRINT c=18
+//! | Total              |	MSG_TOTAL c=6
 //! |                    |
 //! ----------------------
 //! @endcode
@@ -1697,8 +1647,8 @@ static void lcd_menu_fails_stats_mmu()
 {
 	MENU_BEGIN();
 	MENU_ITEM_BACK_P(_T(MSG_MAIN));
-	MENU_ITEM_SUBMENU_P(_i("Last print"), lcd_menu_fails_stats_mmu_print); ////c=18 r=1
-	MENU_ITEM_SUBMENU_P(_i("Total"), lcd_menu_fails_stats_mmu_total); ////c=18 r=1
+	MENU_ITEM_SUBMENU_P(_T(MSG_LAST_PRINT), lcd_menu_fails_stats_mmu_print);
+	MENU_ITEM_SUBMENU_P(_T(MSG_TOTAL), lcd_menu_fails_stats_mmu_total); ////c=18 r=1
 	MENU_END();
 }
 
@@ -1706,9 +1656,9 @@ static void lcd_menu_fails_stats_mmu()
 //!
 //! @code{.unparsed}
 //! |01234567890123456789|
-//! |Last print failures |	c=20 r=1
-//! | MMU fails:      000|	c=14 r=1
-//! | MMU load fails: 000|	c=14 r=1
+//! |Last print failures |	MSG_LAST_PRINT_FAILURES c=20
+//! | MMU fails:      000|	MSG_MMU_FAILS c=14
+//! | MMU load fails: 000|	MSG_MMU_LOAD_FAILS c=14
 //! |                    |
 //! ----------------------
 //! @endcode
@@ -1720,9 +1670,9 @@ static void lcd_menu_fails_stats_mmu_print()
     uint16_t load_fails = eeprom_read_byte((uint8_t*)EEPROM_MMU_LOAD_FAIL);
     lcd_home();
     lcd_printf_P(PSTR("%S\n" " %-16.16S%-3d\n" " %-16.16S%-3d"), 
-        _i("Last print failures"), ////c=20 r=1
-        _i("MMU fails"), fails, ////c=14 r=1
-        _i("MMU load fails"), load_fails); ////c=14 r=1
+        _T(MSG_LAST_PRINT_FAILURES), ////c=20
+        _T(MSG_MMU_FAILS), fails, ////c=14
+        _T(MSG_MMU_LOAD_FAILS), load_fails); ////c=14
     menu_back_if_clicked_fb();
 }
 
@@ -1730,9 +1680,9 @@ static void lcd_menu_fails_stats_mmu_print()
 //!
 //! @code{.unparsed}
 //! |01234567890123456789|
-//! |Total failures      |	c=20 r=1
-//! | MMU fails:      000|	c=14 r=1
-//! | MMU load fails: 000|	c=14 r=1
+//! |Total failures      |	MSG_TOTAL_FAILURES c=20
+//! | MMU fails:      000|	MSG_MMU_FAILS c=14
+//! | MMU load fails: 000|	MSG_MMU_LOAD_FAILS c=14
 //! | MMU power fails:000|	c=14 r=1
 //! ----------------------
 //! @endcode
@@ -1749,10 +1699,10 @@ static void lcd_menu_fails_stats_mmu_total()
 	if (mmu_power_fails > 999) mmu_power_fails = 999;
     lcd_home();
     lcd_printf_P(PSTR("%S\n" " %-16.16S%-3d\n" " %-16.16S%-3d\n" " %-16.16S%-3d"), 
-        _i("Total failures"), ////c=20 r=1
-        _i("MMU fails"), fails, ////c=14 r=1
-        _i("MMU load fails"), load_fails, ////c=14 r=1
-        _i("MMU power fails"), mmu_power_fails); ////c=14 r=1
+        _T(MSG_TOTAL_FAILURES), ////c=20
+        _T(MSG_MMU_FAILS), fails, ////c=14
+        _T(MSG_MMU_LOAD_FAILS), load_fails, ////c=14
+        _i("MMU power fails"), mmu_power_failures); ////c=14 r=1
     menu_back_if_clicked_fb();
 }
 
@@ -1763,10 +1713,10 @@ static const char failStatsFmt[] PROGMEM = "%S\n" " %-16.16S%-3d\n" " %-16.16S%-
 //!
 //! @code{.unparsed}
 //! |01234567890123456789|
-//! |Total failures      |	c=20 r=1
-//! | Power failures: 000|	c=14 r=1
-//! | Filam. runouts: 000|	c=14 r=1
-//! | Crash   X:000 Y:000|	c=7 r=1
+//! |Total failures      |	MSG_TOTAL_FAILURES c=20
+//! | Power failures: 000|	MSG_POWER_FAILURES c=14
+//! | Fil. runouts  : 000|	MSG_FIL_RUNOUTS c=14
+//! | Crash   X:000 Y:000|	MSG_CRASH c=7
 //! ----------------------
 //! @endcode
 //! @todo Positioning of the messages and values on LCD aren't fixed to their exact place. This causes issues with translations.
@@ -1783,10 +1733,10 @@ static void lcd_menu_fails_stats_total()
 	if (crashY > 999) crashY = 999;
 	lcd_home();
     lcd_printf_P(failStatsFmt, 
-        _i("Total failures"),   ////c=20 r=1
-        _i("Power failures"), power,   ////c=14 r=1
-        _i("Filam. runouts"), filam,   ////c=14 r=1
-        _i("Crash"), crashX, crashY);  ////c=7 r=1
+        _T(MSG_TOTAL_FAILURES),   ////c=20
+        _T(MSG_POWER_FAILURES), power,   ////c=14
+        _T(MSG_FIL_RUNOUTS), filam,   ////c=14
+        _T(MSG_CRASH), crashX, crashY);  ////c=7
     menu_back_if_clicked_fb();
 }
 
@@ -1794,10 +1744,10 @@ static void lcd_menu_fails_stats_total()
 //!
 //! @code{.unparsed}
 //! |01234567890123456789|
-//! |Last print failures |	c=20 r=1
-//! | Power failures  000|	c=14 r=1
-//! | Filam. runouts  000|	c=14 r=1
-//! | Crash   X:000 Y:000|	c=7 r=1
+//! |Last print failures |	MSG_LAST_PRINT_FAILURES c=20
+//! | Power failures  000|	MSG_POWER_FAILURES c=14
+//! | Fil. runouts    000|	MSG_FIL_RUNOUTS c=14
+//! | Crash   X:000 Y:000|	MSG_CRASH c=7
 //! ----------------------
 //! @endcode
 //! @brief Show Last Print Failures Statistics with PAT9125
@@ -1822,20 +1772,20 @@ static void lcd_menu_fails_stats_print()
     lcd_home();
 #ifndef PAT9125
     lcd_printf_P(failStatsFmt,
-        _i("Last print failures"),  ////c=20 r=1
-        _i("Power failures"), power,  ////c=14 r=1
-        _i("Filam. runouts"), filam,  ////c=14 r=1
-        _i("Crash"), crashX, crashY);  ////c=7 r=1
+        _T(MSG_LAST_PRINT_FAILURES),  ////c=20
+        _T(MSG_POWER_FAILURES), power,  ////c=14
+        _T(MSG_FIL_RUNOUTS), filam,  ////c=14
+        _T(MSG_CRASH), crashX, crashY);  ////c=7
 #else
     // On the MK3 include detailed PAT9125 statistics about soft failures
     lcd_printf_P(PSTR("%S\n"
                       " %-16.16S%-3d\n"
                       " %-7.7S H %-3d S %-3d\n"
                       " %-7.7S X %-3d Y %-3d"),
-                 _i("Last print failures"), ////c=20 r=1
-                 _i("Power failures"), power, ////c=14 r=1
-                 _i("Runouts"), filam, fsensor_softfail, //c=7 r=1
-                 _i("Crash"), crashX, crashY);  ////c=7 r=1
+                 _T(MSG_LAST_PRINT_FAILURES), ////c=20
+                 _T(MSG_POWER_FAILURES), power, ////c=14
+                 _i("Runouts"), filam, fsensor_softfail, //c=7
+                 _T(MSG_CRASH), crashX, crashY);  ////c=7
 #endif
     menu_back_if_clicked_fb();
 }
@@ -1849,8 +1799,8 @@ static void lcd_menu_fails_stats_print()
 //! @code{.unparsed}
 //! |01234567890123456789|
 //! | Main               |	c=18 r=1
-//! | Last print         |	c=18 r=1
-//! | Total              |	c=18 r=1
+//! | Last print         |	MSG_LAST_PRINT c=18
+//! | Total              |	MSG_TOTAL c=6
 //! |                    |
 //! ----------------------
 //! @endcode
@@ -1859,8 +1809,8 @@ static void lcd_menu_fails_stats()
 {
 	MENU_BEGIN();
 	MENU_ITEM_BACK_P(_T(MSG_MAIN));
-	MENU_ITEM_SUBMENU_P(_i("Last print"), lcd_menu_fails_stats_print);  ////c=18 r=1
-	MENU_ITEM_SUBMENU_P(_i("Total"), lcd_menu_fails_stats_total);  ////c=18 r=1
+	MENU_ITEM_SUBMENU_P(_T(MSG_LAST_PRINT), lcd_menu_fails_stats_print);  ////c=18 r=1
+	MENU_ITEM_SUBMENU_P(_T(MSG_TOTAL), lcd_menu_fails_stats_total);  ////c=18 r=1
 	MENU_END();
 }
 
@@ -1875,10 +1825,10 @@ static const char failStatsFmt[] PROGMEM = "%S\n" " %-16.16S%-3d\n" "%S\n" " %-1
 //! Example screen:
 //! @code{.unparsed}
 //! |01234567890123456789|
-//! |Last print failures |	c=20 r=1
-//! | Filam. runouts  000|	c=14 r=1
-//! |Total failures      |	c=20 r=1
-//! | Filam. runouts  000|	c=14 r=1
+//! |Last print failures |	MSG_LAST_PRINT_FAILURES c=20
+//! | Fil.   runouts  000|	MSG_FIL_RUNOUTS c=14
+//! |Total failures      |	MSG_TOTAL_FAILURES c=20
+//! | Fil. runouts    000|	MSG_FIL_RUNOUTS c=14
 //! ----------------------
 //! @endcode
 //! @todo Positioning of the messages and values on LCD aren't fixed to their exact place. This causes issues with translations.
@@ -1890,10 +1840,10 @@ static void lcd_menu_fails_stats()
 	if (filamentTotal > 999) filamentTotal = 999;
 	lcd_home();
 	lcd_printf_P(failStatsFmt, 
-        _i("Last print failures"),   ////c=20 r=1
-        _i("Filam. runouts"), filamentLast,   ////c=14 r=1
-        _i("Total failures"),  ////c=20 r=1
-        _i("Filam. runouts"), filamentTotal);   ////c=14 r=1
+        _T(MSG_LAST_PRINT_FAILURES),   ////c=20
+        _T(MSG_FIL_RUNOUTS), filamentLast,   ////c=14
+        _T(MSG_TOTAL_FAILURES),  ////c=20
+        _T(MSG_FIL_RUNOUTS), filamentTotal);   ////c=14
 
 	menu_back_if_clicked();
 }
@@ -1972,7 +1922,7 @@ static void lcd_menu_temperatures()
     lcd_menu_temperatures_line( _i("Ambient"), (int)current_temperature_ambient );  ////c=14 r=1
 #endif //AMBIENT_THERMISTOR
 #ifdef PINDA_THERMISTOR
-    lcd_menu_temperatures_line( _i("PINDA"), (int)current_temperature_pinda );  ////c=14 r=1
+    lcd_menu_temperatures_line( _i("PINDA"), (int)current_temperature_pinda );  ////c=14
 #endif //PINDA_THERMISTOR
     menu_back_if_clicked();
 }
@@ -2001,8 +1951,7 @@ static void lcd_menu_voltages()
     lcd_home();
     lcd_printf_P(PSTR(" PWR:      %4.1fV\n" " BED:      %4.1fV"), volt_pwr, volt_bed);
 #ifdef IR_SENSOR_ANALOG
-    float volt_IR = VOLT_DIV_REF * ((float)current_voltage_raw_IR / (1023 * OVERSAMPLENR));
-    lcd_printf_P(PSTR("\n IR :       %3.1fV"),volt_IR);
+    lcd_printf_P(PSTR("\n IR :       %3.1fV"), Raw2Voltage(current_voltage_raw_IR));
 #endif //IR_SENSOR_ANALOG
     menu_back_if_clicked();
 }
@@ -2013,7 +1962,7 @@ static void lcd_menu_voltages()
 //!
 //! @code{.unparsed}
 //! |01234567890123456789|
-//! | Belt status        |	c=18 r=1
+//! | Belt status        |	c=18
 //! |  X:            000 |
 //! |  Y:            000 |
 //! |                    |
@@ -2023,7 +1972,7 @@ static void lcd_menu_voltages()
 static void lcd_menu_belt_status()
 {
 	lcd_home();
-    lcd_printf_P(PSTR("%S\n" " X %d\n" " Y %d"), _i("Belt status"), eeprom_read_word((uint16_t*)(EEPROM_BELTSTATUS_X)), eeprom_read_word((uint16_t*)(EEPROM_BELTSTATUS_Y)));
+    lcd_printf_P(PSTR("%S\n" " X %d\n" " Y %d"), _T(MSG_BELT_STATUS), eeprom_read_word((uint16_t*)(EEPROM_BELTSTATUS_X)), eeprom_read_word((uint16_t*)(EEPROM_BELTSTATUS_Y)));
     menu_back_if_clicked();
 }
 #endif //TMC2130
@@ -2093,7 +2042,7 @@ static void lcd_preheat_menu()
 //! 
 //! @code{.unparsed}
 //! | --------------     |	STR_SEPARATOR
-//! | XYZ cal. details   |	MSG_XYZ_DETAILS
+//! | XYZ cal. details   |	MSG_XYZ_DETAILS c=18
 //! | Extruder info      |	MSG_INFO_EXTRUDER
 //! | XYZ cal. details   |	MSG_INFO_SENSORS
 //! @endcode
@@ -2101,7 +2050,7 @@ static void lcd_preheat_menu()
 //! If TMC2130 defined
 //! 
 //! 	@code{.unparsed}
-//! 	| Belt status        |	MSG_MENU_BELT_STATUS
+//! 	| Belt status        |	MSG_BELT_STATUS
 //! @endcode
 //! 
 //! @code{.unparsed}
@@ -2128,8 +2077,8 @@ static void lcd_support_menu()
 	{	// 22bytes total
 		int8_t status;                 // 1byte
 		bool is_flash_air;             // 1byte
-		uint8_t ip[4];                 // 4bytes
-		char ip_str[3*4+3+1];          // 16bytes
+		uint32_t ip;                   // 4bytes
+		char ip_str[IP4_STR_SIZE];     // 16bytes
 	} _menu_data_t;
     static_assert(sizeof(menu_data)>= sizeof(_menu_data_t),"_menu_data_t doesn't fit into menu_data");
 	_menu_data_t* _md = (_menu_data_t*)&(menu_data[0]);
@@ -2138,16 +2087,12 @@ static void lcd_support_menu()
         // Menu was entered or SD card status has changed (plugged in or removed).
         // Initialize its status.
         _md->status = 1;
-        _md->is_flash_air = card.ToshibaFlashAir_isEnabled() && card.ToshibaFlashAir_GetIP(_md->ip);
-        if (_md->is_flash_air)
-            sprintf_P(_md->ip_str, PSTR("%d.%d.%d.%d"), 
-                _md->ip[0], _md->ip[1], 
-                _md->ip[2], _md->ip[3]);
-    } else if (_md->is_flash_air && 
-        _md->ip[0] == 0 && _md->ip[1] == 0 && 
-        _md->ip[2] == 0 && _md->ip[3] == 0 &&
-        ++ _md->status == 16)
-	{
+        _md->is_flash_air = card.ToshibaFlashAir_isEnabled();
+        if (_md->is_flash_air) {
+            card.ToshibaFlashAir_GetIP((uint8_t*)(&_md->ip)); // ip == 0 if it failed
+        }
+    } else if (_md->is_flash_air && _md->ip == 0 && ++ _md->status == 16)
+    {
         // Waiting for the FlashAir card to get an IP address from a router. Force an update.
         _md->status = 0;
     }
@@ -2183,18 +2128,7 @@ static void lcd_support_menu()
 #ifdef IR_SENSOR_ANALOG
   MENU_ITEM_BACK_P(STR_SEPARATOR);
   MENU_ITEM_BACK_P(PSTR("Fil. sensor v.:"));
-  switch(oFsensorPCB)
-       {
-       case ClFsensorPCB::_Old:
-            MENU_ITEM_BACK_P(PSTR(" 03 or older"));
-            break;
-       case ClFsensorPCB::_Rev03b:
-            MENU_ITEM_BACK_P(PSTR(" 03b or newer"));
-            break;
-       case ClFsensorPCB::_Undef:
-       default:
-            MENU_ITEM_BACK_P(PSTR(" state unknown"));
-       }
+  MENU_ITEM_BACK_P(FsensorIRVersionText());
 #endif // IR_SENSOR_ANALOG
 
 	MENU_ITEM_BACK_P(STR_SEPARATOR);
@@ -2219,17 +2153,35 @@ static void lcd_support_menu()
   if (_md->is_flash_air) {
       MENU_ITEM_BACK_P(STR_SEPARATOR);
       MENU_ITEM_BACK_P(PSTR("FlashAir IP Addr:"));  //c=18 r=1
-///!      MENU_ITEM(back_RAM, _md->ip_str, 0);
+      MENU_ITEM_BACK_P(PSTR(" "));
+      if (((menu_item - 1) == menu_line) && lcd_draw_update) {
+          lcd_set_cursor(2, menu_row);
+          ip4_to_str(_md->ip_str, (uint8_t*)(&_md->ip));
+          lcd_printf_P(PSTR("%s"), _md->ip_str);
+      }
+  }
+  
+  // Show the printer IP address, if it is available.
+  if (IP_address) {
+      
+      MENU_ITEM_BACK_P(STR_SEPARATOR);
+      MENU_ITEM_BACK_P(PSTR("Printer IP Addr:"));  //c=18 r=1
+      MENU_ITEM_BACK_P(PSTR(" "));
+      if (((menu_item - 1) == menu_line) && lcd_draw_update) {
+          lcd_set_cursor(2, menu_row);
+          ip4_to_str(_md->ip_str, (uint8_t*)(&IP_address));
+          lcd_printf_P(PSTR("%s"), _md->ip_str);
+      }
   }
 
   #ifndef MK1BP
   MENU_ITEM_BACK_P(STR_SEPARATOR);
-  MENU_ITEM_SUBMENU_P(_i("XYZ cal. details"), lcd_menu_xyz_y_min);////MSG_XYZ_DETAILS c=19 r=1
-  MENU_ITEM_SUBMENU_P(_i("Extruder info"), lcd_menu_extruder_info);////MSG_INFO_EXTRUDER c=18 r=1
+  MENU_ITEM_SUBMENU_P(_i("XYZ cal. details"), lcd_menu_xyz_y_min);////MSG_XYZ_DETAILS c=18
+  MENU_ITEM_SUBMENU_P(_i("Extruder info"), lcd_menu_extruder_info);////MSG_INFO_EXTRUDER c=18
   MENU_ITEM_SUBMENU_P(_i("Sensor info"), lcd_menu_show_sensors_state);////MSG_INFO_SENSORS c=18 r=1
 
 #ifdef TMC2130
-  MENU_ITEM_SUBMENU_P(_i("Belt status"), lcd_menu_belt_status);////MSG_MENU_BELT_STATUS c=18 r=1
+  MENU_ITEM_SUBMENU_P(_T(MSG_BELT_STATUS), lcd_menu_belt_status);////MSG_BELT_STATUS c=18
 #endif //TMC2130
     
   MENU_ITEM_SUBMENU_P(_i("Temperatures"), lcd_menu_temperatures);////MSG_MENU_TEMPERATURES c=18 r=1
@@ -2238,6 +2190,7 @@ static void lcd_support_menu()
   MENU_ITEM_SUBMENU_P(_i("Voltages"), lcd_menu_voltages);////MSG_MENU_VOLTAGES c=18 r=1
 #endif //defined VOLT_BED_PIN || defined VOLT_PWR_PIN
 
+
 #ifdef DEBUG_BUILD
   MENU_ITEM_SUBMENU_P(PSTR("Debug"), lcd_menu_debug);////c=18 r=1
 #endif /* DEBUG_BUILD */
@@ -2302,19 +2255,18 @@ uint8_t nLevel;
 
 lcd_set_cursor(0,0);
 lcdui_print_temp(LCD_STR_THERMOMETER[0],(int)degHotend(0),(int)degTargetHotend(0));
+lcd_puts_at_P(0,1, _i("Press the knob"));                 ////MSG_ c=20
 lcd_set_cursor(0,2);
-lcd_puts_P(_i("Press the knob"));                 ////MSG_ c=20 r=1
-lcd_set_cursor(0,3);
 switch(eFilamentAction)
      {
      case FilamentAction::Load:
      case FilamentAction::AutoLoad:
      case FilamentAction::MmuLoad:
-          lcd_puts_P(_i("to load filament"));     ////MSG_ c=20 r=1
+          lcd_puts_P(_i("to load filament"));     ////MSG_ c=20
           break;
      case FilamentAction::UnLoad:
      case FilamentAction::MmuUnLoad:
-          lcd_puts_P(_i("to unload filament"));   ////MSG_ c=20 r=1
+          lcd_puts_P(_i("to unload filament"));   ////MSG_ c=20
           break;
      case FilamentAction::MmuEject:
      case FilamentAction::MmuCut:
@@ -2439,7 +2391,7 @@ void mFilamentItem(uint16_t nTemp, uint16_t nTempBed)
         case FilamentAction::None:
         case FilamentAction::Preheat:
         case FilamentAction::Lay1Cal:
-
+            // handled earlier
             break;
         }
         if (bFilamentWaitingFlag) Sound_MakeSound(e_SOUND_TYPE_StandardPrompt);
@@ -2447,34 +2399,44 @@ void mFilamentItem(uint16_t nTemp, uint16_t nTempBed)
     }
     else
     {
-        bFilamentWaitingFlag = true;
         lcd_set_cursor(0, 0);
         lcdui_print_temp(LCD_STR_THERMOMETER[0], (int) degHotend(0), (int) degTargetHotend(0));
-        lcd_set_cursor(0, 1);
-        switch (eFilamentAction)
+
+        if (!bFilamentWaitingFlag)
         {
-        case FilamentAction::Load:
-        case FilamentAction::AutoLoad:
-        case FilamentAction::MmuLoad:
-            lcd_puts_P(_i("Preheating to load")); ////MSG_ c=20 r=1
-            break;
-        case FilamentAction::UnLoad:
-        case FilamentAction::MmuUnLoad:
-            lcd_puts_P(_i("Preheating to unload")); ////MSG_ c=20 r=1
-            break;
-        case FilamentAction::MmuEject:
-            lcd_puts_P(_i("Preheating to eject")); ////MSG_ c=20 r=1
-            break;
-        case FilamentAction::MmuCut:
-            lcd_puts_P(_i("Preheating to cut")); ////MSG_ c=20 r=1
-            break;
-        case FilamentAction::None:
-        case FilamentAction::Preheat:
-        case FilamentAction::Lay1Cal:
-            break;
+            // First run after the filament preheat selection:
+            // setup the fixed LCD parts and raise Z as we wait
+            bFilamentWaitingFlag = true;
+
+            lcd_set_cursor(0, 1);
+            switch (eFilamentAction)
+            {
+            case FilamentAction::Load:
+            case FilamentAction::AutoLoad:
+            case FilamentAction::MmuLoad:
+                lcd_puts_P(_i("Preheating to load")); ////MSG_ c=20
+                raise_z_above(MIN_Z_FOR_LOAD);
+                break;
+            case FilamentAction::UnLoad:
+            case FilamentAction::MmuUnLoad:
+                lcd_puts_P(_i("Preheating to unload")); ////MSG_ c=20
+                raise_z_above(MIN_Z_FOR_UNLOAD);
+                break;
+            case FilamentAction::MmuEject:
+                lcd_puts_P(_i("Preheating to eject")); ////MSG_ c=20
+                break;
+            case FilamentAction::MmuCut:
+                lcd_puts_P(_i("Preheating to cut")); ////MSG_ c=20
+                break;
+            case FilamentAction::None:
+            case FilamentAction::Preheat:
+            case FilamentAction::Lay1Cal:
+                // handled earlier
+                break;
+            }
+            lcd_puts_at_P(0, 3, _i(">Cancel"));                   ////MSG_ c=20 r=1
         }
-        lcd_set_cursor(0, 3);
-        lcd_puts_P(_i(">Cancel"));                   ////MSG_ c=20 r=1
+
         if (lcd_clicked())
         {
             bFilamentWaitingFlag = false;
@@ -2524,6 +2486,12 @@ static void mFilamentItem_ASA()
     mFilamentItem(ASA_PREHEAT_HOTEND_TEMP, ASA_PREHEAT_HPB_TEMP);
 }
 
+static void mFilamentItem_PC()
+{
+    bFilamentPreheatState = false;
+    mFilamentItem(PC_PREHEAT_HOTEND_TEMP, PC_PREHEAT_HPB_TEMP);
+}
+
 static void mFilamentItem_ABS()
 {
     bFilamentPreheatState = false;
@@ -2548,6 +2516,12 @@ static void mFilamentItem_FLEX()
     mFilamentItem(FLEX_PREHEAT_HOTEND_TEMP, FLEX_PREHEAT_HPB_TEMP);
 }
 
+static void mFilamentItem_PVB()
+{
+    bFilamentPreheatState = false;
+    mFilamentItem(PVB_PREHEAT_HOTEND_TEMP, PVB_PREHEAT_HPB_TEMP);
+}
+
 void mFilamentBack()
 {
     menu_back();
@@ -2583,6 +2557,8 @@ void lcd_generic_preheat_menu()
         MENU_ITEM_SUBMENU_P(PSTR("PLA  -  " STRINGIFY(PLA_PREHEAT_HOTEND_TEMP) "/" STRINGIFY(PLA_PREHEAT_HPB_TEMP)),mFilamentItem_PLA);
         MENU_ITEM_SUBMENU_P(PSTR("PET  -  " STRINGIFY(PET_PREHEAT_HOTEND_TEMP) "/" STRINGIFY(PET_PREHEAT_HPB_TEMP)),mFilamentItem_PET);
         MENU_ITEM_SUBMENU_P(PSTR("ASA  -  " STRINGIFY(ASA_PREHEAT_HOTEND_TEMP) "/" STRINGIFY(ASA_PREHEAT_HPB_TEMP)),mFilamentItem_ASA);
+        MENU_ITEM_SUBMENU_P(PSTR("PC   -  " STRINGIFY(PC_PREHEAT_HOTEND_TEMP) "/" STRINGIFY(PC_PREHEAT_HPB_TEMP)),mFilamentItem_PC);
+        MENU_ITEM_SUBMENU_P(PSTR("PVB  -  " STRINGIFY(PVB_PREHEAT_HOTEND_TEMP) "/" STRINGIFY(PVB_PREHEAT_HPB_TEMP)),mFilamentItem_PVB);
         MENU_ITEM_SUBMENU_P(PSTR("ABS  -  " STRINGIFY(ABS_PREHEAT_HOTEND_TEMP) "/" STRINGIFY(ABS_PREHEAT_HPB_TEMP)),mFilamentItem_ABS);
         MENU_ITEM_SUBMENU_P(PSTR("HIPS -  " STRINGIFY(HIPS_PREHEAT_HOTEND_TEMP) "/" STRINGIFY(HIPS_PREHEAT_HPB_TEMP)),mFilamentItem_HIPS);
         MENU_ITEM_SUBMENU_P(PSTR("PP   -  " STRINGIFY(PP_PREHEAT_HOTEND_TEMP) "/" STRINGIFY(PP_PREHEAT_HPB_TEMP)),mFilamentItem_PP);
@@ -2622,8 +2598,7 @@ void lcd_wait_interact() {
   lcd_puts_P(_i("Insert filament"));////MSG_INSERT_FILAMENT c=20
 #endif
   if (!fsensor_autoload_enabled) {
-	  lcd_set_cursor(0, 2);
-	  lcd_puts_P(_i("and press the knob"));////MSG_PRESS c=20
+	  lcd_puts_at_P(0, 2, _i("and press the knob"));////MSG_PRESS c=20 r=2
   }
 }
 
@@ -2632,9 +2607,7 @@ void lcd_change_success() {
 
   lcd_clear();
 
-  lcd_set_cursor(0, 2);
-
-  lcd_puts_P(_i("Change success!"));////MSG_CHANGE_SUCCESS
+  lcd_puts_at_P(0, 2, _i("Change success!"));////MSG_CHANGE_SUCCESS
 
 
 }
@@ -2642,8 +2615,7 @@ void lcd_change_success() {
 static void lcd_loading_progress_bar(uint16_t loading_time_ms) { 
 
 	for (uint_least8_t i = 0; i < 20; i++) {
-		lcd_set_cursor(i, 3);
-		lcd_print(".");
+		lcd_putc_at(i, 3, '.');
 		//loading_time_ms/20 delay
 		for (uint_least8_t j = 0; j < 5; j++) {
 			delay_keep_alive(loading_time_ms / 100);
@@ -2657,11 +2629,8 @@ void lcd_loading_color() {
 
   lcd_clear();
 
-  lcd_set_cursor(0, 0);
-
-  lcd_puts_P(_i("Loading color"));////MSG_LOADING_COLOR
-  lcd_set_cursor(0, 2);
-  lcd_puts_P(_T(MSG_PLEASE_WAIT));
+  lcd_puts_at_P(0, 0, _i("Loading color"));////MSG_LOADING_COLOR
+  lcd_puts_at_P(0, 2, _T(MSG_PLEASE_WAIT));
   lcd_loading_progress_bar((FILAMENTCHANGE_FINALFEED * 1000ul) / FILAMENTCHANGE_EFEED_FINAL); //show progress bar during filament loading slow sequence
 }
 
@@ -2671,16 +2640,13 @@ void lcd_loading_filament() {
 
   lcd_clear();
 
-  lcd_set_cursor(0, 0);
-
-  lcd_puts_P(_T(MSG_LOADING_FILAMENT));
-  lcd_set_cursor(0, 2);
-  lcd_puts_P(_T(MSG_PLEASE_WAIT));
+  lcd_puts_at_P(0, 0, _T(MSG_LOADING_FILAMENT));
+  lcd_puts_at_P(0, 2, _T(MSG_PLEASE_WAIT));
 #ifdef SNMM
   for (int i = 0; i < 20; i++) {
 
     lcd_set_cursor(i, 3);
-    lcd_print(".");
+    lcd_print('.');
     for (int j = 0; j < 10 ; j++) {
       manage_heater();
       manage_inactivity(true);
@@ -2709,26 +2675,11 @@ void lcd_alright() {
 
   lcd_clear();
 
-  lcd_set_cursor(0, 0);
-
-  lcd_puts_P(_i("Changed correctly?"));////MSG_CORRECTLY c=20
-
-  lcd_set_cursor(1, 1);
-
-  lcd_puts_P(_T(MSG_YES));
-
-  lcd_set_cursor(1, 2);
-
-  lcd_puts_P(_i("Filament not loaded"));////MSG_NOT_LOADED c=19
-
-
-  lcd_set_cursor(1, 3);
-  lcd_puts_P(_i("Color not correct"));////MSG_NOT_COLOR
-
-
-  lcd_set_cursor(0, 1);
-
-  lcd_print(">");
+  lcd_puts_at_P(0, 0, _i("Changed correctly?"));////MSG_CORRECTLY c=20
+  lcd_puts_at_P(1, 1, _T(MSG_YES));
+  lcd_puts_at_P(1, 2, _i("Filament not loaded"));////MSG_NOT_LOADED c=19
+  lcd_puts_at_P(1, 3, _i("Color not correct"));////MSG_NOT_COLOR
+  lcd_putc_at(0, 1, '>');
 
 
   enc_dif = lcd_encoder_diff;
@@ -2758,14 +2709,8 @@ void lcd_alright() {
           cursor_pos = 1;
 					Sound_MakeSound(e_SOUND_TYPE_BlindAlert);
         }
-        lcd_set_cursor(0, 1);
-        lcd_print(" ");
-        lcd_set_cursor(0, 2);
-        lcd_print(" ");
-        lcd_set_cursor(0, 3);
-        lcd_print(" ");
-        lcd_set_cursor(0, cursor_pos);
-        lcd_print(">");
+        lcd_puts_at_P(0, 1, PSTR(" \n \n "));
+        lcd_putc_at(0, cursor_pos, '>');
         enc_dif = lcd_encoder_diff;
 				Sound_MakeSound(e_SOUND_TYPE_EncoderMove);
         _delay(100);
@@ -2794,10 +2739,8 @@ void lcd_alright() {
 void show_preheat_nozzle_warning()
 {	
     lcd_clear();
-    lcd_set_cursor(0, 0);
-    lcd_puts_P(_T(MSG_ERROR));
-    lcd_set_cursor(0, 2);
-    lcd_puts_P(_T(MSG_PREHEAT_NOZZLE));
+    lcd_puts_at_P(0, 0, _T(MSG_ERROR));
+    lcd_puts_at_P(0, 2, _T(MSG_PREHEAT_NOZZLE));
     _delay(2000);
     lcd_clear();
 }
@@ -2847,7 +2790,7 @@ static void lcd_LoadFilament()
 //!
 //! @code{.unparsed}
 //! |01234567890123456789|
-//! |Filament used:      | c=19 r=1
+//! |Filament used:      | c=19
 //! |           0000.00m |
 //! |Print time:         | c=19 r=1
 //! |        00h 00m 00s |
@@ -2883,7 +2826,7 @@ void lcd_menu_statistics()
 			"%S:\n"
 			"%10ldh %02hhdm %02hhds"
 		    ),
-            _i("Filament used"), _met,  ////c=19 r=1
+            _i("Filament used"), _met,  ////c=19
             _i("Print time"), _h, _m, _s);  ////c=19 r=1
 		menu_back_if_clicked_fb();
 	}
@@ -2936,7 +2879,7 @@ static void _lcd_move(const char *name, int axis, int min, int max)
 			if (max_software_endstops && current_position[axis] > max) current_position[axis] = max;
 			lcd_encoder = 0;
 			world2machine_clamp(current_position[X_AXIS], current_position[Y_AXIS]);
-			plan_buffer_line_curposXYZE(manual_feedrate[axis] / 60, active_extruder);
+			plan_buffer_line_curposXYZE(manual_feedrate[axis] / 60);
 			lcd_draw_update = 1;
 		}
 	}
@@ -2950,7 +2893,7 @@ static void _lcd_move(const char *name, int axis, int min, int max)
 }
 
 
-static void lcd_move_e()
+void lcd_move_e()
 {
 	if (degHotend0() > EXTRUDE_MINTEMP)
 	{
@@ -2961,7 +2904,7 @@ static void lcd_move_e()
 			{
 				current_position[E_AXIS] += float((int)lcd_encoder) * move_menu_scale;
 				lcd_encoder = 0;
-				plan_buffer_line_curposXYZE(manual_feedrate[E_AXIS] / 60, active_extruder);
+				plan_buffer_line_curposXYZE(manual_feedrate[E_AXIS] / 60);
 				lcd_draw_update = 1;
 			}
 		}
@@ -3058,8 +3001,7 @@ static void lcd_menu_xyz_skew()
 		lcd_printf_P(_N("%3.2f\x01"), _deg(angleDiff));
 	}
 	else{
-		lcd_set_cursor(15,0);
-		lcd_puts_P(_T(MSG_NA));
+		lcd_puts_at_P(15,0, _T(MSG_NA));
 	}
     if (lcd_clicked())
         menu_goto(lcd_menu_xyz_offset, 0, true, true);
@@ -3077,8 +3019,7 @@ static void lcd_menu_xyz_skew()
 //! @todo Positioning of the messages and values on LCD aren't fixed to their exact place. This causes issues with translations.
 static void lcd_menu_xyz_offset()
 {
-    lcd_set_cursor(0,0);
-    lcd_puts_P(_i("[0;0] point offset"));////MSG_MEASURED_OFFSET
+    lcd_puts_at_P(0, 0, _i("[0;0] point offset"));////MSG_MEASURED_OFFSET
     lcd_puts_at_P(0, 1, separator);
     lcd_puts_at_P(0, 2, PSTR("X"));  ////c=10 r=1
     lcd_puts_at_P(0, 3, PSTR("Y"));  ////c=10 r=1
@@ -3282,7 +3223,7 @@ void lcd_adjust_bed(void)
     MENU_ITEM_EDIT_int3_P(_i("Right side[um]"), &_md->right, -BED_ADJUSTMENT_UM_MAX, BED_ADJUSTMENT_UM_MAX);////MSG_BED_CORRECTION_RIGHT c=14 r=1
     MENU_ITEM_EDIT_int3_P(_i("Front side[um]"), &_md->front, -BED_ADJUSTMENT_UM_MAX, BED_ADJUSTMENT_UM_MAX);////MSG_BED_CORRECTION_FRONT c=14 r=1
     MENU_ITEM_EDIT_int3_P(_i("Rear side [um]"),  &_md->rear,  -BED_ADJUSTMENT_UM_MAX, BED_ADJUSTMENT_UM_MAX);////MSG_BED_CORRECTION_REAR c=14 r=1
-    MENU_ITEM_FUNCTION_P(_i("Reset"), lcd_adjust_bed_reset);////MSG_BED_CORRECTION_RESET
+    MENU_ITEM_FUNCTION_P(_T(MSG_RESET), lcd_adjust_bed_reset);////MSG_RESET c=14
     MENU_END();
 }
 
@@ -3299,8 +3240,7 @@ void lcd_adjust_bed(void)
 void pid_extruder()
 {
 	lcd_clear();
-	lcd_set_cursor(1, 0);
-	lcd_puts_P(_i("Set temperature:"));////MSG_SET_TEMPERATURE c=19 r=1
+	lcd_puts_at_P(1, 0, _i("Set temperature:"));////MSG_SET_TEMPERATURE c=19 r=1
 	pid_temp += int(lcd_encoder);
 	if (pid_temp > HEATER_0_MAXTEMP) pid_temp = HEATER_0_MAXTEMP;
 	if (pid_temp < HEATER_0_MINTEMP) pid_temp = HEATER_0_MINTEMP;
@@ -3335,7 +3275,7 @@ void lcd_adjust_z() {
 
   lcd_set_cursor(0, 1);
 
-  lcd_print(">");
+  lcd_print('>');
 
 
   enc_dif = lcd_encoder_diff;
@@ -3364,11 +3304,11 @@ void lcd_adjust_z() {
           cursor_pos = 1;
         }
         lcd_set_cursor(0, 1);
-        lcd_print(" ");
+        lcd_print(' ');
         lcd_set_cursor(0, 2);
-        lcd_print(" ");
+        lcd_print(' ');
         lcd_set_cursor(0, cursor_pos);
-        lcd_print(">");
+        lcd_print('>');
         enc_dif = lcd_encoder_diff;
         _delay(100);
       }
@@ -3414,7 +3354,7 @@ bool lcd_wait_for_pinda(float temp) {
 		lcd_set_cursor(0, 4);
 		lcd_print(LCD_STR_THERMOMETER[0]);
 		lcd_print(ftostr3(current_temperature_pinda));
-		lcd_print("/");
+		lcd_print('/');
 		lcd_print(ftostr3(temp));
 		lcd_print(LCD_STR_DEGREE);
 		delay_keep_alive(1000);
@@ -3436,7 +3376,7 @@ void lcd_wait_for_heater() {
 		lcd_set_cursor(0, 4);
 		lcd_print(LCD_STR_THERMOMETER[0]);
 		lcd_print(ftostr3(degHotend(active_extruder)));
-		lcd_print("/");
+		lcd_print('/');
 		lcd_print(ftostr3(degTargetHotend(active_extruder)));
 		lcd_print(LCD_STR_DEGREE);
 }
@@ -3479,7 +3419,7 @@ bool lcd_calibrate_z_end_stop_manual(bool only_z)
 {
     // Don't know where we are. Let's claim we are Z=0, so the soft end stops will not be triggered when moving up.
     current_position[Z_AXIS] = 0;
-    plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
+    plan_set_position_curposXYZE();
 
     // Until confirmed by the confirmation dialog.
     for (;;) {
@@ -3501,7 +3441,7 @@ bool lcd_calibrate_z_end_stop_manual(bool only_z)
                     // Only move up, whatever direction the user rotates the encoder.
                     current_position[Z_AXIS] += fabs(lcd_encoder);
                     lcd_encoder = 0;
-                    plan_buffer_line_curposXYZE(manual_feedrate[Z_AXIS] / 60, active_extruder);
+                    plan_buffer_line_curposXYZE(manual_feedrate[Z_AXIS] / 60);
                 }
             }
             if (lcd_clicked()) {
@@ -3537,7 +3477,7 @@ calibrated:
 	else {
 		current_position[Z_AXIS] = Z_MAX_POS+4.f;
 	}
-    plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
+    plan_set_position_curposXYZE();
     return true;
 
 canceled:
@@ -3755,16 +3695,14 @@ int8_t lcd_show_multiscreen_message_two_choices_and_wait_P(const char *msg, bool
 				if (msg_next == NULL) {
 					lcd_set_cursor(0, 3);
 					if (enc_dif < lcd_encoder_diff && yes) {
-						lcd_puts_P((PSTR(" ")));
-						lcd_set_cursor(7, 3);
-						lcd_puts_P((PSTR(">")));
+						lcd_print(' ');
+						lcd_putc_at(7, 3, '>');
 						yes = false;
 						Sound_MakeSound(e_SOUND_TYPE_EncoderMove);
 					}
 					else if (enc_dif > lcd_encoder_diff && !yes) {
-						lcd_puts_P((PSTR(">")));
-						lcd_set_cursor(7, 3);
-						lcd_puts_P((PSTR(" ")));
+						lcd_print('>');
+						lcd_putc_at(7, 3, ' ');
 						yes = true;
 						Sound_MakeSound(e_SOUND_TYPE_EncoderMove);
 					}
@@ -3793,13 +3731,11 @@ int8_t lcd_show_multiscreen_message_two_choices_and_wait_P(const char *msg, bool
 		}
 		if (msg_next == NULL) {
 			lcd_set_cursor(0, 3);
-			if (yes) lcd_puts_P(PSTR(">"));
-			lcd_set_cursor(1, 3);
-			lcd_puts_P(first_choice);
+			if (yes) lcd_print('>');
+			lcd_puts_at_P(1, 3, first_choice);
 			lcd_set_cursor(7, 3);
-			if (!yes) lcd_puts_P(PSTR(">"));
-			lcd_set_cursor(8, 3);
-			lcd_puts_P(second_choice);
+			if (!yes) lcd_print('>');
+			lcd_puts_at_P(8, 3, second_choice);
 		}
 	}
 }
@@ -3817,17 +3753,13 @@ int8_t lcd_show_fullscreen_message_yes_no_and_wait_P(const char *msg, bool allow
 	lcd_display_message_fullscreen_P(msg);
 	
 	if (default_yes) {
-		lcd_set_cursor(0, 2);
-		lcd_puts_P(PSTR(">"));
+		lcd_putc_at(0, 2, '>');
 		lcd_puts_P(_T(MSG_YES));
-		lcd_set_cursor(1, 3);
-		lcd_puts_P(_T(MSG_NO));
+		lcd_puts_at_P(1, 3, _T(MSG_NO));
 	}
 	else {
-		lcd_set_cursor(1, 2);
-		lcd_puts_P(_T(MSG_YES));
-		lcd_set_cursor(0, 3);
-		lcd_puts_P(PSTR(">"));
+		lcd_puts_at_P(1, 2, _T(MSG_YES));
+		lcd_putc_at(0, 3, '>');
 		lcd_puts_P(_T(MSG_NO));
 	}
 	int8_t retval = default_yes ? true : false;
@@ -3848,17 +3780,15 @@ int8_t lcd_show_fullscreen_message_yes_no_and_wait_P(const char *msg, bool allow
 		if (abs(enc_dif - lcd_encoder_diff) > 4) {
 			lcd_set_cursor(0, 2);
 				if (enc_dif < lcd_encoder_diff && retval) {
-					lcd_puts_P((PSTR(" ")));
-					lcd_set_cursor(0, 3);
-					lcd_puts_P((PSTR(">")));
+					lcd_print(' ');
+					lcd_putc_at(0, 3, '>');
 					retval = 0;
 					Sound_MakeSound(e_SOUND_TYPE_EncoderMove);
 
 				}
 				else if (enc_dif > lcd_encoder_diff && !retval) {
-					lcd_puts_P((PSTR(">")));
-					lcd_set_cursor(0, 3);
-					lcd_puts_P((PSTR(" ")));
+					lcd_print('>');
+					lcd_putc_at(0, 3, ' ');
 					retval = 1;
 					Sound_MakeSound(e_SOUND_TYPE_EncoderMove);
 				}
@@ -3941,14 +3871,12 @@ void lcd_temp_cal_show_result(bool result) {
 		eeprom_update_byte((uint8_t*)EEPROM_CALIBRATION_STATUS_PINDA, 1);
 		SERIAL_ECHOLNPGM("Temperature calibration done. Continue with pressing the knob.");
 		lcd_show_fullscreen_message_and_wait_P(_T(MSG_TEMP_CALIBRATION_DONE));
-		temp_cal_active = true;
 		eeprom_update_byte((unsigned char *)EEPROM_TEMP_CAL_ACTIVE, 1);
 	}
 	else {
 		eeprom_update_byte((uint8_t*)EEPROM_CALIBRATION_STATUS_PINDA, 0);
 		SERIAL_ECHOLNPGM("Temperature calibration failed. Continue with pressing the knob.");
 		lcd_show_fullscreen_message_and_wait_P(_i("Temperature calibration failed"));////MSG_TEMP_CAL_FAILED c=20 r=8
-		temp_cal_active = false;
 		eeprom_update_byte((unsigned char *)EEPROM_TEMP_CAL_ACTIVE, 0);
 	}
 	lcd_update_enable(true);
@@ -3956,14 +3884,10 @@ void lcd_temp_cal_show_result(bool result) {
 }
 
 static void lcd_show_end_stops() {
-	lcd_set_cursor(0, 0);
-	lcd_puts_P((PSTR("End stops diag")));
-	lcd_set_cursor(0, 1);
-	lcd_puts_P((READ(X_MIN_PIN) ^ (bool)X_MIN_ENDSTOP_INVERTING) ? (PSTR("X1")) : (PSTR("X0")));
-	lcd_set_cursor(0, 2);
-	lcd_puts_P((READ(Y_MIN_PIN) ^ (bool)Y_MIN_ENDSTOP_INVERTING) ? (PSTR("Y1")) : (PSTR("Y0")));
-	lcd_set_cursor(0, 3);
-	lcd_puts_P((READ(Z_MIN_PIN) ^ (bool)Z_MIN_ENDSTOP_INVERTING) ? (PSTR("Z1")) : (PSTR("Z0")));
+	lcd_puts_at_P(0, 0, (PSTR("End stops diag")));
+	lcd_puts_at_P(0, 1, (READ(X_MIN_PIN) ^ (bool)X_MIN_ENDSTOP_INVERTING) ? (PSTR("X1")) : (PSTR("X0")));
+	lcd_puts_at_P(0, 2, (READ(Y_MIN_PIN) ^ (bool)Y_MIN_ENDSTOP_INVERTING) ? (PSTR("Y1")) : (PSTR("Y0")));
+	lcd_puts_at_P(0, 3, (READ(Z_MIN_PIN) ^ (bool)Z_MIN_ENDSTOP_INVERTING) ? (PSTR("Z1")) : (PSTR("Z0")));
 }
 
 #ifndef TMC2130
@@ -4020,7 +3944,7 @@ static void lcd_show_sensors_state()
 		finda_state = mmu_finda;
 	}
 	if (ir_sensor_detected) {
-		idler_state = !PIN_GET(IR_SENSOR_PIN);
+		idler_state = !READ(IR_SENSOR_PIN);
 	}
 	lcd_puts_at_P(0, 0, _i("Sensor state"));
 	lcd_puts_at_P(1, 1, _i("PINDA:"));
@@ -4048,14 +3972,14 @@ void lcd_menu_show_sensors_state()                // NOT static due to using ins
 }
 
 void prusa_statistics_err(char c){
-	SERIAL_ECHO("{[ERR:");
+	SERIAL_ECHOPGM("{[ERR:");
 	SERIAL_ECHO(c);
 	SERIAL_ECHO(']');
 	prusa_stat_farm_number();
 }
 
 static void prusa_statistics_case0(uint8_t statnr){
-	SERIAL_ECHO("{");
+	SERIAL_ECHO('{');
 	prusa_stat_printerstatus(statnr);
 	prusa_stat_farm_number();
 	prusa_stat_printinfo();
@@ -4083,7 +4007,7 @@ void prusa_statistics(int _message, uint8_t _fil_nr) {
 		}
 		else
 		{
-			SERIAL_ECHO("{");
+			SERIAL_ECHO('{');
 			prusa_stat_printerstatus(1);
 			prusa_stat_farm_number();
 			prusa_stat_diameter();
@@ -4133,7 +4057,7 @@ void prusa_statistics(int _message, uint8_t _fil_nr) {
 		return;
 		break;
 	case 4:		// print succesfull
-		SERIAL_ECHO("{[RES:1][FIL:");
+		SERIAL_ECHOPGM("{[RES:1][FIL:");
 		MYSERIAL.print(int(_fil_nr));
 		SERIAL_ECHO(']');
 		prusa_stat_printerstatus(status_number);
@@ -4141,7 +4065,7 @@ void prusa_statistics(int _message, uint8_t _fil_nr) {
 		farm_timer = 2;
 		break;
 	case 5:		// print not succesfull
-		SERIAL_ECHO("{[RES:0][FIL:");
+		SERIAL_ECHOPGM("{[RES:0][FIL:");
 		MYSERIAL.print(int(_fil_nr));
 		SERIAL_ECHO(']');
 		prusa_stat_printerstatus(status_number);
@@ -4149,22 +4073,21 @@ void prusa_statistics(int _message, uint8_t _fil_nr) {
 		farm_timer = 2;
 		break;
 	case 6:		// print done
-		SERIAL_ECHO("{[PRN:8]");
+		SERIAL_ECHOPGM("{[PRN:8]");
 		prusa_stat_farm_number();
 		status_number = 8;
 		farm_timer = 2;
 		break;
 	case 7:		// print done - stopped
-		SERIAL_ECHO("{[PRN:9]");
+		SERIAL_ECHOPGM("{[PRN:9]");
 		prusa_stat_farm_number();
 		status_number = 9;
 		farm_timer = 2;
 		break;
 	case 8:		// printer started
-		SERIAL_ECHO("{[PRN:0][PFN:");
+		SERIAL_ECHOPGM("{[PRN:0]");
+		prusa_stat_farm_number();
 		status_number = 0;
-		SERIAL_ECHO(farm_no);
-		SERIAL_ECHO(']');
 		farm_timer = 2;
 		break;
 	case 20:		// echo farm no
@@ -4180,7 +4103,7 @@ void prusa_statistics(int _message, uint8_t _fil_nr) {
 		prusa_stat_printerstatus(status_number);
 		break;
     case 22: // waiting for filament change
-        SERIAL_ECHO("{[PRN:5]");
+        SERIAL_ECHOPGM("{[PRN:5]");
 		prusa_stat_farm_number();
 		status_number = 5;
         break;
@@ -4199,12 +4122,9 @@ void prusa_statistics(int _message, uint8_t _fil_nr) {
 		break;
 
     case 99:		// heartbeat
-        SERIAL_ECHO("{[PRN:99]");
+        SERIAL_ECHOPGM("{[PRN:99]");
         prusa_stat_temperatures();
-		SERIAL_ECHO("[PFN:");
-		SERIAL_ECHO(farm_no);
-		SERIAL_ECHO(']');
-            
+		prusa_stat_farm_number();
         break;
 	}
 	SERIAL_ECHOLN('}');	
@@ -4213,47 +4133,45 @@ void prusa_statistics(int _message, uint8_t _fil_nr) {
 
 static void prusa_stat_printerstatus(int _status)
 {
-	SERIAL_ECHO("[PRN:");
+	SERIAL_ECHOPGM("[PRN:");
 	SERIAL_ECHO(_status);
 	SERIAL_ECHO(']');
 }
 
 static void prusa_stat_farm_number() {
-	SERIAL_ECHO("[PFN:");
-	SERIAL_ECHO(farm_no);
-	SERIAL_ECHO(']');
+	SERIAL_ECHOPGM("[PFN:0]");
 }
 
 static void prusa_stat_diameter() {
-	SERIAL_ECHO("[DIA:");
+	SERIAL_ECHOPGM("[DIA:");
 	SERIAL_ECHO(eeprom_read_word((uint16_t*)EEPROM_NOZZLE_DIAMETER_uM));
 	SERIAL_ECHO(']');
 }
 
 static void prusa_stat_temperatures()
 {
-	SERIAL_ECHO("[ST0:");
+	SERIAL_ECHOPGM("[ST0:");
 	SERIAL_ECHO(target_temperature[0]);
-	SERIAL_ECHO("][STB:");
+	SERIAL_ECHOPGM("][STB:");
 	SERIAL_ECHO(target_temperature_bed);
-	SERIAL_ECHO("][AT0:");
+	SERIAL_ECHOPGM("][AT0:");
 	SERIAL_ECHO(current_temperature[0]);
-	SERIAL_ECHO("][ATB:");
+	SERIAL_ECHOPGM("][ATB:");
 	SERIAL_ECHO(current_temperature_bed);
 	SERIAL_ECHO(']');
 }
 
 static void prusa_stat_printinfo()
 {
-	SERIAL_ECHO("[TFU:");
+	SERIAL_ECHOPGM("[TFU:");
 	SERIAL_ECHO(total_filament_used);
-	SERIAL_ECHO("][PCD:");
+	SERIAL_ECHOPGM("][PCD:");
 	SERIAL_ECHO(itostr3(card.percentDone()));
-	SERIAL_ECHO("][FEM:");
+	SERIAL_ECHOPGM("][FEM:");
 	SERIAL_ECHO(itostr3(feedmultiply));
-	SERIAL_ECHO("][FNM:");
+	SERIAL_ECHOPGM("][FNM:");
 	SERIAL_ECHO(longFilenameOLD);
-	SERIAL_ECHO("][TIM:");
+	SERIAL_ECHOPGM("][TIM:");
 	if (starttime != 0)
 	{
 		SERIAL_ECHO(_millis() / 1000 - starttime / 1000);
@@ -4262,8 +4180,8 @@ static void prusa_stat_printinfo()
 	{
 		SERIAL_ECHO(0);
 	}
-	SERIAL_ECHO("][FWR:");
-	SERIAL_ECHO(FW_VERSION);
+	SERIAL_ECHOPGM("][FWR:");
+	SERIAL_ECHORPGM(FW_VERSION_STR_P());
 	SERIAL_ECHO(']');
      prusa_stat_diameter();
 }
@@ -4286,23 +4204,23 @@ void lcd_pick_babystep(){
     
     lcd_set_cursor(3, 2);
     
-    lcd_print("1");
+    lcd_print('1');
     
     lcd_set_cursor(3, 3);
     
-    lcd_print("2");
+    lcd_print('2');
     
     lcd_set_cursor(12, 2);
     
-    lcd_print("3");
+    lcd_print('3');
     
     lcd_set_cursor(12, 3);
     
-    lcd_print("4");
+    lcd_print('4');
     
     lcd_set_cursor(1, 2);
     
-    lcd_print(">");
+    lcd_print('>');
     
     
     enc_dif = lcd_encoder_diff;
@@ -4333,20 +4251,20 @@ void lcd_pick_babystep(){
 
                 
                 lcd_set_cursor(1, 2);
-                lcd_print(" ");
+                lcd_print(' ');
                 lcd_set_cursor(1, 3);
-                lcd_print(" ");
+                lcd_print(' ');
                 lcd_set_cursor(10, 2);
-                lcd_print(" ");
+                lcd_print(' ');
                 lcd_set_cursor(10, 3);
-                lcd_print(" ");
+                lcd_print(' ');
                 
                 if (cursor_pos < 3) {
                     lcd_set_cursor(1, cursor_pos+1);
-                    lcd_print(">");
+                    lcd_print('>');
                 }else{
                     lcd_set_cursor(10, cursor_pos-1);
-                    lcd_print(">");
+                    lcd_print('>');
                 }
                 
    
@@ -4378,7 +4296,7 @@ void lcd_move_menu_axis()
 	MENU_ITEM_SUBMENU_P(_i("Move X"), lcd_move_x);////MSG_MOVE_X
 	MENU_ITEM_SUBMENU_P(_i("Move Y"), lcd_move_y);////MSG_MOVE_Y
 	MENU_ITEM_SUBMENU_P(_i("Move Z"), lcd_move_z);////MSG_MOVE_Z
-	MENU_ITEM_SUBMENU_P(_i("Extruder"), lcd_move_e);////MSG_MOVE_E
+	MENU_ITEM_SUBMENU_P(_T(MSG_EXTRUDER), lcd_move_e);////MSG_EXTRUDER
 	MENU_END();
 }
 
@@ -4656,9 +4574,9 @@ void lcd_pinda_calibration_menu()
 }
 
 void lcd_temp_calibration_set() {
+	bool temp_cal_active = eeprom_read_byte((unsigned char *)EEPROM_TEMP_CAL_ACTIVE);
 	temp_cal_active = !temp_cal_active;
 	eeprom_update_byte((unsigned char *)EEPROM_TEMP_CAL_ACTIVE, temp_cal_active);
-	st_current_init();
 }
 
 #ifdef HAS_SECOND_SERIAL_PORT
@@ -4849,7 +4767,7 @@ void lcd_v2_calibration()
 	    }
 	    else
 	    {
-	        loaded = lcd_show_fullscreen_message_yes_no_and_wait_P(_i("Is filament loaded?"), false, true);////MSG_PLA_FILAMENT_LOADED c=20 r=2
+	        loaded = lcd_show_fullscreen_message_yes_no_and_wait_P(_T(MSG_FILAMENT_LOADED), false, true);
 	        lcd_update_enabled = true;
 
 	    }
@@ -4916,7 +4834,7 @@ void lcd_language()
 static void wait_preheat()
 {
     current_position[Z_AXIS] = 100; //move in z axis to make space for loading filament
-    plan_buffer_line_curposXYZE(homing_feedrate[Z_AXIS] / 60, active_extruder);
+    plan_buffer_line_curposXYZE(homing_feedrate[Z_AXIS] / 60);
     delay_keep_alive(2000);
     lcd_display_message_fullscreen_P(_T(MSG_WIZARD_HEATING));
 	lcd_set_custom_characters();
@@ -5102,10 +5020,10 @@ void lcd_wizard(WizState state)
 			setTargetBed(PLA_PREHEAT_HPB_TEMP);
 			if (mmu_enabled)
 			{
-			    wizard_event = lcd_show_fullscreen_message_yes_no_and_wait_P(_i("Is filament loaded?"), true);////c=20 r=2
+			    wizard_event = lcd_show_fullscreen_message_yes_no_and_wait_P(_T(MSG_FILAMENT_LOADED), true);
 			} else
 			{
-			    wizard_event = lcd_show_fullscreen_message_yes_no_and_wait_P(_i("Is filament loaded?"), true);////MSG_WIZARD_FILAMENT_LOADED c=20 r=2
+			    wizard_event = lcd_show_fullscreen_message_yes_no_and_wait_P(_T(MSG_FILAMENT_LOADED), true);
 			}
 			if (wizard_event) state = S::Lay1CalCold;
 			else
@@ -5204,11 +5122,11 @@ void lcd_settings_linearity_correction_menu(void)
 #ifdef TMC2130_LINEARITY_CORRECTION_XYZ
 	//tmc2130_wave_fac[X_AXIS]
 
-	MENU_ITEM_EDIT_int3_P(_i("X-correct:"),  &tmc2130_wave_fac[X_AXIS],  TMC2130_WAVE_FAC1000_MIN-TMC2130_WAVE_FAC1000_STP, TMC2130_WAVE_FAC1000_MAX);////MSG_EXTRUDER_CORRECTION c=10
-	MENU_ITEM_EDIT_int3_P(_i("Y-correct:"),  &tmc2130_wave_fac[Y_AXIS],  TMC2130_WAVE_FAC1000_MIN-TMC2130_WAVE_FAC1000_STP, TMC2130_WAVE_FAC1000_MAX);////MSG_EXTRUDER_CORRECTION c=10
-	MENU_ITEM_EDIT_int3_P(_i("Z-correct:"),  &tmc2130_wave_fac[Z_AXIS],  TMC2130_WAVE_FAC1000_MIN-TMC2130_WAVE_FAC1000_STP, TMC2130_WAVE_FAC1000_MAX);////MSG_EXTRUDER_CORRECTION c=10
+	MENU_ITEM_EDIT_int3_P(_i("X-correct:"),  &tmc2130_wave_fac[X_AXIS],  TMC2130_WAVE_FAC1000_MIN-TMC2130_WAVE_FAC1000_STP, TMC2130_WAVE_FAC1000_MAX);////MSG_X_CORRECTION c=13
+	MENU_ITEM_EDIT_int3_P(_i("Y-correct:"),  &tmc2130_wave_fac[Y_AXIS],  TMC2130_WAVE_FAC1000_MIN-TMC2130_WAVE_FAC1000_STP, TMC2130_WAVE_FAC1000_MAX);////MSG_Y_CORRECTION c=13
+	MENU_ITEM_EDIT_int3_P(_i("Z-correct:"),  &tmc2130_wave_fac[Z_AXIS],  TMC2130_WAVE_FAC1000_MIN-TMC2130_WAVE_FAC1000_STP, TMC2130_WAVE_FAC1000_MAX);////MSG_Z_CORRECTION c=13
 #endif //TMC2130_LINEARITY_CORRECTION_XYZ
-	MENU_ITEM_EDIT_int3_P(_i("E-correct:"),  &tmc2130_wave_fac[E_AXIS],  TMC2130_WAVE_FAC1000_MIN-TMC2130_WAVE_FAC1000_STP, TMC2130_WAVE_FAC1000_MAX);////MSG_EXTRUDER_CORRECTION c=10
+	MENU_ITEM_EDIT_int3_P(_i("E-correct:"),  &tmc2130_wave_fac[E_AXIS],  TMC2130_WAVE_FAC1000_MIN-TMC2130_WAVE_FAC1000_STP, TMC2130_WAVE_FAC1000_MAX);////MSG_EXTRUDER_CORRECTION c=13
 	MENU_END();
 }
 #endif // TMC2130
@@ -5393,16 +5311,13 @@ do\
     else\
         MENU_ITEM_TOGGLE_P(_T(MSG_SD_CARD), _T(MSG_NORMAL), lcd_toshiba_flash_air_compatibility_toggle);\
 \
-    if (!farm_mode)\
+    uint8_t sdSort;\
+    EEPROM_read(EEPROM_SD_SORT, (uint8_t*)&sdSort, sizeof(sdSort));\
+    switch (sdSort)\
     {\
-        uint8_t sdSort;\
-        EEPROM_read(EEPROM_SD_SORT, (uint8_t*)&sdSort, sizeof(sdSort));\
-        switch (sdSort)\
-        {\
-          case SD_SORT_TIME: MENU_ITEM_TOGGLE_P(_T(MSG_SORT), _T(MSG_SORT_TIME), lcd_sort_type_set); break;\
-          case SD_SORT_ALPHA: MENU_ITEM_TOGGLE_P(_T(MSG_SORT), _T(MSG_SORT_ALPHA), lcd_sort_type_set); break;\
-          default: MENU_ITEM_TOGGLE_P(_T(MSG_SORT), _T(MSG_NONE), lcd_sort_type_set);\
-        }\
+      case SD_SORT_TIME: MENU_ITEM_TOGGLE_P(_T(MSG_SORT), _T(MSG_SORT_TIME), lcd_sort_type_set); break;\
+      case SD_SORT_ALPHA: MENU_ITEM_TOGGLE_P(_T(MSG_SORT), _T(MSG_SORT_ALPHA), lcd_sort_type_set); break;\
+      default: MENU_ITEM_TOGGLE_P(_T(MSG_SORT), _T(MSG_NONE), lcd_sort_type_set);\
     }\
 }\
 while (0)
@@ -5504,30 +5419,31 @@ do\
 }\
 while (0)
 
-static void lcd_nozzle_diameter_set(void)
-{
-uint16_t nDiameter;
-
-switch(oNozzleDiameter)
-     {
-     case ClNozzleDiameter::_Diameter_250:
-          oNozzleDiameter=ClNozzleDiameter::_Diameter_400;
-          nDiameter=400;
-          break;
-     case ClNozzleDiameter::_Diameter_400:
-          oNozzleDiameter=ClNozzleDiameter::_Diameter_600;
-          nDiameter=600;
-          break;
-     case ClNozzleDiameter::_Diameter_600:
-          oNozzleDiameter=ClNozzleDiameter::_Diameter_250;
-          nDiameter=250;
-          break;
-     default:
-          oNozzleDiameter=ClNozzleDiameter::_Diameter_400;
-          nDiameter=400;
-     }
-eeprom_update_byte((uint8_t*)EEPROM_NOZZLE_DIAMETER,(uint8_t)oNozzleDiameter);
-eeprom_update_word((uint16_t*)EEPROM_NOZZLE_DIAMETER_uM,nDiameter);
+static void lcd_nozzle_diameter_cycle(void) {
+    uint16_t nDiameter;
+    switch(oNozzleDiameter){
+    case ClNozzleDiameter::_Diameter_250:
+        oNozzleDiameter=ClNozzleDiameter::_Diameter_400;
+        nDiameter=400;
+        break;
+    case ClNozzleDiameter::_Diameter_400:
+        oNozzleDiameter=ClNozzleDiameter::_Diameter_600;
+        nDiameter=600;
+        break;
+    case ClNozzleDiameter::_Diameter_600:
+        oNozzleDiameter=ClNozzleDiameter::_Diameter_800;
+        nDiameter=800;
+        break;
+    case ClNozzleDiameter::_Diameter_800:
+        oNozzleDiameter=ClNozzleDiameter::_Diameter_250;
+        nDiameter=250;
+        break;
+    default:
+        oNozzleDiameter=ClNozzleDiameter::_Diameter_400;
+        nDiameter=400;
+    }
+    eeprom_update_byte((uint8_t*)EEPROM_NOZZLE_DIAMETER,(uint8_t)oNozzleDiameter);
+    eeprom_update_word((uint16_t*)EEPROM_NOZZLE_DIAMETER_uM,nDiameter);
 }
 
 #define SETTINGS_NOZZLE \
@@ -5539,9 +5455,10 @@ do\
         case ClNozzleDiameter::_Diameter_250: fNozzleDiam = 0.25f; break;\
         case ClNozzleDiameter::_Diameter_400: fNozzleDiam = 0.4f; break;\
         case ClNozzleDiameter::_Diameter_600: fNozzleDiam = 0.6f; break;\
+        case ClNozzleDiameter::_Diameter_800: fNozzleDiam = 0.8f; break;\
         default: fNozzleDiam = 0.4f; break;\
     }\
-    MENU_ITEM_TOGGLE(_T(MSG_NOZZLE_DIAMETER), ftostr12ns(fNozzleDiam), lcd_nozzle_diameter_set);\
+    MENU_ITEM_TOGGLE(_T(MSG_NOZZLE_DIAMETER), ftostr12ns(fNozzleDiam), lcd_nozzle_diameter_cycle);\
 }\
 while (0)
 
@@ -5623,6 +5540,7 @@ do\
 }\
 while (0)
 
+#if 0 // temporarily unused
 static void lcd_check_gcode_set(void)
 {
 switch(oCheckGcode)
@@ -5641,6 +5559,7 @@ switch(oCheckGcode)
      }
 eeprom_update_byte((uint8_t*)EEPROM_CHECK_GCODE,(uint8_t)oCheckGcode);
 }
+#endif
 
 #define SETTINGS_GCODE \
 do\
@@ -5719,7 +5638,7 @@ static void select_sheet_menu()
 static void sheets_menu()
 {
     MENU_BEGIN();
-    MENU_ITEM_BACK_P(_i("HW Setup"));
+    MENU_ITEM_BACK_P(_T(MSG_HW_SETUP));
     MENU_ITEM_SUBMENU_E(EEPROM_Sheets_base->s[0], select_sheet_menu<0>);
     MENU_ITEM_SUBMENU_E(EEPROM_Sheets_base->s[1], select_sheet_menu<1>);
     MENU_ITEM_SUBMENU_E(EEPROM_Sheets_base->s[2], select_sheet_menu<2>);
@@ -5733,17 +5652,54 @@ static void sheets_menu()
 
 void lcd_hw_setup_menu(void)                      // can not be "static"
 {
+    typedef struct
+    {// 2bytes total
+        int8_t status;
+        uint8_t experimental_menu_visibility;
+    } _menu_data_t;
+    static_assert(sizeof(menu_data)>= sizeof(_menu_data_t),"_menu_data_t doesn't fit into menu_data");
+    _menu_data_t* _md = (_menu_data_t*)&(menu_data[0]);
+
+    if (_md->status == 0 || lcd_draw_update)
+    {
+        _md->status = 1;
+        _md->experimental_menu_visibility = eeprom_read_byte((uint8_t *)EEPROM_EXPERIMENTAL_VISIBILITY);
+        if (_md->experimental_menu_visibility == EEPROM_EMPTY_VALUE)
+        {
+            _md->experimental_menu_visibility = 0;
+            eeprom_update_byte((uint8_t *)EEPROM_EXPERIMENTAL_VISIBILITY, _md->experimental_menu_visibility);
+        }
+    }
+
+
     MENU_BEGIN();
     MENU_ITEM_BACK_P(_T(bSettings?MSG_SETTINGS:MSG_BACK)); // i.e. default menu-item / menu-item after checking mismatch
 
-    MENU_ITEM_SUBMENU_P(_i("Steel sheets"), sheets_menu);
+    MENU_ITEM_SUBMENU_P(_T(MSG_STEEL_SHEETS), sheets_menu);
     SETTINGS_NOZZLE;
     MENU_ITEM_SUBMENU_P(_i("Checks"), lcd_checking_menu);
 
 #ifdef IR_SENSOR_ANALOG
     FSENSOR_ACTION_NA;
-    MENU_ITEM_FUNCTION_P(PSTR("Fsensor Detection"), lcd_detect_IRsensor);
+    //! Fsensor Detection isn't ready for mmu yet it is temporarily disabled.
+    //! @todo Don't forget to remove this as soon Fsensor Detection works with mmu
+    if(!mmu_enabled) MENU_ITEM_FUNCTION_P(PSTR("Fsensor Detection"), lcd_detect_IRsensor);
 #endif //IR_SENSOR_ANALOG
+
+    if (_md->experimental_menu_visibility)
+    {
+        MENU_ITEM_SUBMENU_P(PSTR("Experimental"), lcd_experimental_menu);////MSG_MENU_EXPERIMENTAL c=18
+    }
+
+#ifdef PINDA_TEMP_COMP
+	//! The SuperPINDA is detected when the PINDA temp is below its defined limit.
+	//! This works well on the EINSY board but not on the miniRAMBo board as
+	//! as a disconnected SuperPINDA will show higher temps compared to an EINSY board.
+	//! 
+	//! This menu allows the user to en-/disable the SuperPINDA manualy
+	MENU_ITEM_TOGGLE_P(_N("SuperPINDA"), eeprom_read_byte((uint8_t *)EEPROM_PINDA_TEMP_COMPENSATION) ? _T(MSG_YES) : _T(MSG_NO), lcd_pinda_temp_compensation_toggle);
+#endif //PINDA_TEMP_COMP
+
     MENU_END();
 }
 
@@ -5765,25 +5721,27 @@ static void lcd_settings_menu()
 
 	SETTINGS_CUTTER;
 
-	MENU_ITEM_TOGGLE_P(_i("Fans check"), fans_check_enabled ? _T(MSG_ON) : _T(MSG_OFF), lcd_set_fan_check);
+	MENU_ITEM_TOGGLE_P(_T(MSG_FANS_CHECK), fans_check_enabled ? _T(MSG_ON) : _T(MSG_OFF), lcd_set_fan_check);
 
 	SETTINGS_SILENT_MODE;
 
     if(!farm_mode)
     {
         bSettings=true;                              // flag ('fake parameter') for 'lcd_hw_setup_menu()' function
-        MENU_ITEM_SUBMENU_P(_i("HW Setup"), lcd_hw_setup_menu);////MSG_HW_SETUP
+        MENU_ITEM_SUBMENU_P(_T(MSG_HW_SETUP), lcd_hw_setup_menu);
     }
     
 	SETTINGS_MMU_MODE;
 
-	MENU_ITEM_SUBMENU_P(_i("Mesh bed leveling"), lcd_mesh_bed_leveling_settings);////MSG_MBL_SETTINGS c=18 r=1
+	MENU_ITEM_SUBMENU_P(_T(MSG_MESH_BED_LEVELING), lcd_mesh_bed_leveling_settings);
 
 #if defined (TMC2130) && defined (LINEARITY_CORRECTION)
     MENU_ITEM_SUBMENU_P(_i("Lin. correction"), lcd_settings_linearity_correction_menu);
 #endif //LINEARITY_CORRECTION && TMC2130
-
-	MENU_ITEM_TOGGLE_P(_T(MSG_TEMP_CALIBRATION), temp_cal_active ? _T(MSG_ON) : _T(MSG_OFF), lcd_temp_calibration_set);
+    if(has_temperature_compensation())
+    {
+	    MENU_ITEM_TOGGLE_P(_T(MSG_TEMP_CALIBRATION), eeprom_read_byte((unsigned char *)EEPROM_TEMP_CAL_ACTIVE) ? _T(MSG_ON) : _T(MSG_OFF), lcd_temp_calibration_set);
+    }
 
 #ifdef HAS_SECOND_SERIAL_PORT
     MENU_ITEM_TOGGLE_P(_T(MSG_RPI_PORT), (selectedSerialPort == 0) ? _T(MSG_OFF) : _T(MSG_ON), lcd_second_serial_set);
@@ -5808,7 +5766,6 @@ static void lcd_settings_menu()
 
 	if (farm_mode)
 	{
-		MENU_ITEM_SUBMENU_P(PSTR("Farm number"), lcd_farm_no);
 		MENU_ITEM_FUNCTION_P(PSTR("Disable farm mode"), lcd_disable_farm_mode);
 	}
 
@@ -5851,13 +5808,13 @@ static void lcd_calibration_menu()
 	MENU_ITEM_FUNCTION_P(_i("Wizard"), lcd_wizard);////MSG_WIZARD c=17 r=1
     if (lcd_commands_type == LcdCommands::Idle)
     {
-         MENU_ITEM_SUBMENU_P(_T(MSG_V2_CALIBRATION), lcd_first_layer_calibration_reset);
+         MENU_ITEM_SUBMENU_P(_T(MSG_V2_CALIBRATION), lcd_first_layer_calibration_reset);////MSG_V2_CALIBRATION c=18
     }
 	MENU_ITEM_GCODE_P(_T(MSG_AUTO_HOME), PSTR("G28 W"));
 #ifdef TMC2130
-	MENU_ITEM_FUNCTION_P(_i("Belt test        "), lcd_belttest_v);////MSG_BELTTEST
+	MENU_ITEM_FUNCTION_P(_i("Belt test        "), lcd_belttest_v);////MSG_BELTTEST c=17
 #endif //TMC2130
-	MENU_ITEM_FUNCTION_P(_i("Selftest         "), lcd_selftest_v);////MSG_SELFTEST
+	MENU_ITEM_FUNCTION_P(_i("Selftest         "), lcd_selftest_v);////MSG_SELFTEST c=17
 #ifdef MK1BP
     // MK1
     // "Calibrate Z"
@@ -5871,14 +5828,14 @@ static void lcd_calibration_menu()
 	//MENU_ITEM_FUNCTION_P(_i("Calibrate E"), lcd_calibrate_extruder);////MSG_CALIBRATE_E c=20 r=1
 #endif
     // "Mesh Bed Leveling"
-    MENU_ITEM_SUBMENU_P(_i("Mesh Bed Leveling"), lcd_mesh_bedleveling);////MSG_MESH_BED_LEVELING
+    MENU_ITEM_SUBMENU_P(_T(MSG_MESH_BED_LEVELING), lcd_mesh_bedleveling);
 	
 #endif //MK1BP
 
     MENU_ITEM_SUBMENU_P(_i("Bed level correct"), lcd_adjust_bed);////MSG_BED_CORRECTION_MENU
 	MENU_ITEM_SUBMENU_P(_i("PID calibration"), pid_extruder);////MSG_PID_EXTRUDER c=17 r=1
 #ifndef TMC2130
-    MENU_ITEM_SUBMENU_P(_i("Show end stops"), menu_show_end_stops);////MSG_SHOW_END_STOPS c=17 r=1
+    MENU_ITEM_SUBMENU_P(_i("Show end stops"), menu_show_end_stops);////MSG_SHOW_END_STOPS c=18
 #endif
 #ifndef MK1BP
     MENU_ITEM_GCODE_P(_i("Reset XYZ calibr."), PSTR("M44"));////MSG_CALIBRATE_BED_RESET
@@ -5887,7 +5844,10 @@ static void lcd_calibration_menu()
 	//MENU_ITEM_FUNCTION_P(MSG_RESET_CALIBRATE_E, lcd_extr_cal_reset);
 #endif
 #ifndef MK1BP
-	MENU_ITEM_SUBMENU_P(_i("Temp. calibration"), lcd_pinda_calibration_menu);////MSG_CALIBRATION_PINDA_MENU c=17 r=1
+    if(has_temperature_compensation())
+    {
+	    MENU_ITEM_SUBMENU_P(_i("Temp. calibration"), lcd_pinda_calibration_menu);////MSG_CALIBRATION_PINDA_MENU c=17 r=1
+    }
 #endif //MK1BP
   }
   
@@ -5898,11 +5858,9 @@ void bowden_menu() {
 	int enc_dif = lcd_encoder_diff;
 	int cursor_pos = 0;
 	lcd_clear();
-	lcd_set_cursor(0, 0);
-	lcd_print(">");
+	lcd_putc_at(0, 0, '>');
 	for (uint_least8_t i = 0; i < 4; i++) {
-		lcd_set_cursor(1, i);
-		lcd_print("Extruder ");
+		lcd_puts_at_P(1, i, PSTR("Extruder "));
 		lcd_print(i);
 		lcd_print(": ");
 		EEPROM_read_B(EEPROM_BOWDEN_LENGTH + i * 2, &bowden_length[i]);
@@ -5936,16 +5894,8 @@ void bowden_menu() {
 					Sound_MakeSound(e_SOUND_TYPE_BlindAlert);
 				}
 
-				lcd_set_cursor(0, 0);
-				lcd_print(" ");
-				lcd_set_cursor(0, 1);
-				lcd_print(" ");
-				lcd_set_cursor(0, 2);
-				lcd_print(" ");
-				lcd_set_cursor(0, 3);
-				lcd_print(" ");
-				lcd_set_cursor(0, cursor_pos);
-				lcd_print(">");
+				lcd_puts_at_P(0, 0, PSTR(" \n \n \n "));
+				lcd_putc_at(0, cursor_pos, '>');
 				Sound_MakeSound(e_SOUND_TYPE_EncoderMove);
 				enc_dif = lcd_encoder_diff;
 				_delay(100);
@@ -5959,8 +5909,7 @@ void bowden_menu() {
 				manage_heater();
 				manage_inactivity(true);
 
-				lcd_set_cursor(1, 1);
-				lcd_print("Extruder ");
+				lcd_puts_at_P(1, 1, PSTR("Extruder "));
 				lcd_print(cursor_pos);
 				lcd_print(": ");
 				lcd_set_cursor(13, 1);
@@ -5989,11 +5938,9 @@ void bowden_menu() {
 						lcd_update_enable(true);
 						lcd_clear();
 						enc_dif = lcd_encoder_diff;
-						lcd_set_cursor(0, cursor_pos);
-						lcd_print(">");
+						lcd_putc_at(0, cursor_pos, '>');
 						for (uint_least8_t i = 0; i < 4; i++) {
-							lcd_set_cursor(1, i);
-							lcd_print("Extruder ");
+							lcd_puts_at_P(1, i, PSTR("Extruder "));
 							lcd_print(i);
 							lcd_print(": ");
 							EEPROM_read_B(EEPROM_BOWDEN_LENGTH + i * 2, &bowden_length[i]);
@@ -6013,8 +5960,8 @@ void bowden_menu() {
 
 static char snmm_stop_print_menu() { //menu for choosing which filaments will be unloaded in stop print
 	lcd_clear();
-	lcd_puts_at_P(0,0,_T(MSG_UNLOAD_FILAMENT)); lcd_print(":");
-	lcd_set_cursor(0, 1); lcd_print(">");
+	lcd_puts_at_P(0,0,_T(MSG_UNLOAD_FILAMENT)); lcd_print(':');
+	lcd_set_cursor(0, 1); lcd_print('>');
 	lcd_puts_at_P(1,2,_i("Used during print"));////MSG_USED c=19 r=1
 	lcd_puts_at_P(1,3,_i("Current"));////MSG_CURRENT c=19 r=1
 	char cursor_pos = 1;
@@ -6038,14 +5985,9 @@ static char snmm_stop_print_menu() { //menu for choosing which filaments will be
 					Sound_MakeSound(e_SOUND_TYPE_BlindAlert);
 				}	
 
-				lcd_set_cursor(0, 1);
-				lcd_print(" ");
-				lcd_set_cursor(0, 2);
-				lcd_print(" ");
-				lcd_set_cursor(0, 3);
-				lcd_print(" ");
+				lcd_puts_at_P(0, 1, PSTR(" \n \n "));
 				lcd_set_cursor(0, cursor_pos);
-				lcd_print(">");
+				lcd_print('>');
 				enc_dif = lcd_encoder_diff;
 				Sound_MakeSound(e_SOUND_TYPE_EncoderMove);
 				_delay(100);
@@ -6148,14 +6090,8 @@ uint8_t choose_menu_P(const char *header, const char *item, const char *last_ite
 
         if (last_item&&last_visible) lcd_puts_at_P(1, 3, last_item);
 
-        lcd_set_cursor(0, 1);
-        lcd_print(" ");
-        lcd_set_cursor(0, 2);
-        lcd_print(" ");
-        lcd_set_cursor(0, 3);
-        lcd_print(" ");
-        lcd_set_cursor(0, cursor_pos);
-        lcd_print(">");
+        lcd_puts_at_P(0, 1, PSTR(" \n \n "));
+        lcd_putc_at(0, cursor_pos, '>');
         _delay(100);
 
 		if (lcd_clicked())
@@ -6169,34 +6105,31 @@ uint8_t choose_menu_P(const char *header, const char *item, const char *last_ite
 }
 
 char reset_menu() {
+    const uint8_t items_no =
 #ifdef SNMM
-	int items_no = 5;
+        5;
 #else
-	int items_no = 4;
+        4;
 #endif
-	static int first = 0;
-	int enc_dif = 0;
+    static int8_t first = 0;
+    int8_t enc_dif = 0;
 	char cursor_pos = 0;
-	const char *item [items_no];
-	
-	item[0] = "Language";
-	item[1] = "Statistics";
-	item[2] = "Shipping prep";
-	item[3] = "All Data";
-#ifdef SNMM
-	item[4] = "Bowden length";
-#endif // SNMM
 
+    const char *const item[items_no] PROGMEM = {PSTR("Language"), PSTR("Statistics"), PSTR("Shipping prep"), PSTR("All Data")
+#ifdef SNMM
+    , PSTR("Bowden length")
+#endif
+    };
+	
 	enc_dif = lcd_encoder_diff;
 	lcd_clear();
 	lcd_set_cursor(0, 0);
-	lcd_print(">");
+    lcd_putc('>');
 	lcd_consume_click();
 	while (1) {		
 
 		for (uint_least8_t i = 0; i < 4; i++) {
-			lcd_set_cursor(1, i);
-			lcd_print(item[first + i]);
+			lcd_puts_at_P(1, i, item[first + i]);
 		}
 
 		manage_heater();
@@ -6230,16 +6163,9 @@ char reset_menu() {
 						lcd_clear();
 					}
 				}
-				lcd_set_cursor(0, 0);
-				lcd_print(" ");
-				lcd_set_cursor(0, 1);
-				lcd_print(" ");
-				lcd_set_cursor(0, 2);
-				lcd_print(" ");
-				lcd_set_cursor(0, 3);
-				lcd_print(" ");
+				lcd_puts_at_P(0, 0, PSTR(" \n \n \n "));
 				lcd_set_cursor(0, cursor_pos);
-				lcd_print(">");
+				lcd_putc('>');
 				Sound_MakeSound(e_SOUND_TYPE_EncoderMove);
 				enc_dif = lcd_encoder_diff;
 				_delay(100);
@@ -6404,13 +6330,13 @@ void unload_filament()
 	//		extr_unload2();
 
 	current_position[E_AXIS] -= 45;
-	plan_buffer_line_curposXYZE(5200 / 60, active_extruder);
+	plan_buffer_line_curposXYZE(5200 / 60);
 	st_synchronize();
 	current_position[E_AXIS] -= 15;
-	plan_buffer_line_curposXYZE(1000 / 60, active_extruder);
+	plan_buffer_line_curposXYZE(1000 / 60);
 	st_synchronize();
 	current_position[E_AXIS] -= 20;
-	plan_buffer_line_curposXYZE(1000 / 60, active_extruder);
+	plan_buffer_line_curposXYZE(1000 / 60);
 	st_synchronize();
 
 	lcd_display_message_fullscreen_P(_T(MSG_PULL_OUT_FILAMENT));
@@ -6437,74 +6363,6 @@ void unload_filament()
 
 }
 
-static void lcd_farm_no()
-{
-	char step = 0;
-	int enc_dif = 0;
-	int _farmno = farm_no;
-	int _ret = 0;
-	lcd_clear();
-
-	lcd_set_cursor(0, 0);
-	lcd_print("Farm no");
-
-	do
-	{
-
-		if (abs((enc_dif - lcd_encoder_diff)) > 2) {
-			if (enc_dif > lcd_encoder_diff) {
-				switch (step) {
-				case(0): if (_farmno >= 100) _farmno -= 100; break;
-				case(1): if (_farmno % 100 >= 10) _farmno -= 10; break;
-				case(2): if (_farmno % 10 >= 1) _farmno--; break;
-				default: break;
-				}
-			}
-
-			if (enc_dif < lcd_encoder_diff) {
-				switch (step) {
-				case(0): if (_farmno < 900) _farmno += 100; break;
-				case(1): if (_farmno % 100 < 90) _farmno += 10; break;
-				case(2): if (_farmno % 10 <= 8)_farmno++; break;
-				default: break;
-				}
-			}
-			enc_dif = 0;
-			lcd_encoder_diff = 0;
-		}
-
-		lcd_set_cursor(0, 2);
-		if (_farmno < 100) lcd_print("0");
-		if (_farmno < 10) lcd_print("0");
-		lcd_print(_farmno);
-		lcd_print("  ");
-		lcd_set_cursor(0, 3);
-		lcd_print("   ");
-
-
-		lcd_set_cursor(step, 3);
-		lcd_print("^");
-		_delay(100);
-
-		if (lcd_clicked())
-		{
-			_delay(200);
-			step++;
-			if(step == 3) {
-				_ret = 1;
-				farm_no = _farmno;
-				EEPROM_save_B(EEPROM_FARM_NUMBER, &farm_no);
-				prusa_statistics(20);
-				lcd_return_to_status();
-			}
-		}
-
-		manage_heater();
-	} while (_ret == 0);
-
-}
-
-
 unsigned char lcd_choose_color() {
 	//function returns index of currently chosen item
 	//following part can be modified from 2 to 255 items:
@@ -6520,8 +6378,7 @@ unsigned char lcd_choose_color() {
 	unsigned char cursor_pos = 1;
 	enc_dif = lcd_encoder_diff;
 	lcd_clear();
-	lcd_set_cursor(0, 1);
-	lcd_print(">");
+	lcd_putc_at(0, 1, '>');
 
 	active_rows = items_no < 3 ? items_no : 3;
 	lcd_consume_click();
@@ -6562,14 +6419,10 @@ unsigned char lcd_choose_color() {
 						lcd_clear();
 					}
 				}
-				lcd_set_cursor(0, 1);
-				lcd_print(" ");
-				lcd_set_cursor(0, 2);
-				lcd_print(" ");
-				lcd_set_cursor(0, 3);
-				lcd_print(" ");
-				lcd_set_cursor(0, cursor_pos);
-				lcd_print(">");
+				lcd_putc_at(0, 1, ' ');
+				lcd_putc_at(0, 2, ' ');
+				lcd_putc_at(0, 3, ' ');
+				lcd_putc_at(0, cursor_pos, '>');
 				Sound_MakeSound(e_SOUND_TYPE_EncoderMove);
 				enc_dif = lcd_encoder_diff;
 				_delay(100);
@@ -6589,85 +6442,6 @@ unsigned char lcd_choose_color() {
 
 }
 
-void lcd_confirm_print()
-{
-	uint8_t filament_type;
-	int enc_dif = 0;
-	int cursor_pos = 1;
-	int _ret = 0;
-	int _t = 0;
-
-	enc_dif = lcd_encoder_diff;
-	lcd_clear();
-
-	lcd_set_cursor(0, 0);
-	lcd_print("Print ok ?");
-
-	do
-	{
-		if (abs(enc_dif - lcd_encoder_diff) > 12) {
-			if (enc_dif > lcd_encoder_diff) {
-				cursor_pos--;
-			}
-
-			if (enc_dif < lcd_encoder_diff) {
-				cursor_pos++;
-			}
-			enc_dif = lcd_encoder_diff;
-		}
-
-		if (cursor_pos > 2) { cursor_pos = 2; }
-		if (cursor_pos < 1) { cursor_pos = 1; }
-
-		lcd_set_cursor(0, 2); lcd_print("          ");
-		lcd_set_cursor(0, 3); lcd_print("          ");
-		lcd_set_cursor(2, 2);
-		lcd_puts_P(_T(MSG_YES));
-		lcd_set_cursor(2, 3);
-		lcd_puts_P(_T(MSG_NO));
-		lcd_set_cursor(0, 1 + cursor_pos);
-		lcd_print(">");
-		_delay(100);
-
-		_t = _t + 1;
-		if (_t>100)
-		{
-			prusa_statistics(99);
-			_t = 0;
-		}
-		if (lcd_clicked())
-		{
-               filament_type = FARM_FILAMENT_COLOR_NONE;
-			if (cursor_pos == 1)
-			{
-				_ret = 1;
-//				filament_type = lcd_choose_color();
-				prusa_statistics(4, filament_type);
-				no_response = true; //we need confirmation by recieving PRUSA thx
-				important_status = 4;
-				saved_filament_type = filament_type;
-				NcTime = _millis();
-			}
-			if (cursor_pos == 2)
-			{
-				_ret = 2;
-//				filament_type = lcd_choose_color();
-				prusa_statistics(5, filament_type);
-				no_response = true; //we need confirmation by recieving PRUSA thx
-				important_status = 5;				
-				saved_filament_type = filament_type;
-				NcTime = _millis();
-			}
-		}
-
-		manage_heater();
-		manage_inactivity();
-		proc_commands();
-
-	} while (_ret == 0);
-
-}
-
 #include "w25x20cl.h"
 
 #ifdef LCD_TEST
@@ -6690,7 +6464,7 @@ static bool fan_error_selftest()
 	fanSpeedSoftPwm = 255;
 #endif //FAN_SOFT_PWM
     manage_heater(); //enables print fan
-    setExtruderAutoFanState(EXTRUDER_0_AUTO_FAN_PIN, 1); //force enables the extruder fan untill the first manage_heater() call.
+    setExtruderAutoFanState(3); //force enables the extruder fan
 #ifdef FAN_SOFT_PWM
     extruder_autofan_last_check = _millis();
     fan_measuring = true;
@@ -6698,6 +6472,7 @@ static bool fan_error_selftest()
     _delay(1000); //delay_keep_alive would turn off extruder fan, because temerature is too low (maybe)
     manage_heater();
     fanSpeed = 0;
+	setExtruderAutoFanState(1); //releases lock on the extruder fan
 #ifdef FAN_SOFT_PWM
     fanSpeedSoftPwm = 0;
 #endif //FAN_SOFT_PWM
@@ -6726,11 +6501,12 @@ void lcd_resume_print()
     lcd_return_to_status();
     lcd_reset_alert_level(); //for fan speed error
     if (fan_error_selftest()) return; //abort if error persists
+    cmdqueue_serial_disabled = false;
 
     lcd_setstatuspgm(_T(MSG_FINISHING_MOVEMENTS));
     st_synchronize();
 
-    lcd_setstatuspgm(_T(MSG_RESUMING_PRINT));
+    lcd_setstatuspgm(_T(MSG_RESUMING_PRINT)); ////MSG_RESUMING_PRINT c=20
     isPrintPaused = false;
     restore_print_from_ram_and_continue(default_retraction);
     pause_time += (_millis() - start_pause_print); //accumulate time when print is paused for correct statistics calculation
@@ -6818,7 +6594,7 @@ static void activate_calibrate_sheet()
 static void lcd_sheet_menu()
 {
     MENU_BEGIN();
-    MENU_ITEM_BACK_P(_i("Steel sheets"));
+    MENU_ITEM_BACK_P(_T(MSG_STEEL_SHEETS));
 
 	if(eeprom_is_sheet_initialized(selected_sheet)){
 	    MENU_ITEM_SUBMENU_P(_i("Select"), change_sheet); //// c=18
@@ -6826,10 +6602,10 @@ static void lcd_sheet_menu()
 
     if (lcd_commands_type == LcdCommands::Idle)
     {
-        MENU_ITEM_SUBMENU_P(_T(MSG_V2_CALIBRATION), activate_calibrate_sheet);
+        MENU_ITEM_SUBMENU_P(_T(MSG_V2_CALIBRATION), activate_calibrate_sheet);////MSG_V2_CALIBRATION c=18
     }
     MENU_ITEM_SUBMENU_P(_i("Rename"), lcd_rename_sheet_menu); //// c=18
-	MENU_ITEM_FUNCTION_P(_i("Reset"), lcd_reset_sheet); //// c=18
+	MENU_ITEM_FUNCTION_P(_T(MSG_RESET), lcd_reset_sheet); ////MSG_RESET c=14
 
     MENU_END();
 }
@@ -6861,6 +6637,8 @@ static void lcd_main_menu()
 	MENU_ITEM_SUBMENU_P(_T(MSG_BABYSTEP_Z), lcd_babystep_z);//8
   }
 
+  if (farm_mode)
+     MENU_ITEM_FUNCTION_P(_T(MSG_FILAMENTCHANGE), lcd_colorprint_change);//8
 
   if ( moves_planned() || IS_SD_PRINTING || is_usb_printing || (lcd_commands_type == LcdCommands::Layer1Cal))
   {
@@ -6875,9 +6653,9 @@ static void lcd_main_menu()
   {
 #ifdef FANCHECK
       if((fan_check_error == EFCE_FIXED) || (fan_check_error == EFCE_OK))
-          MENU_ITEM_SUBMENU_P(_i("Resume print"), lcd_resume_print);////MSG_RESUME_PRINT
+          MENU_ITEM_SUBMENU_P(_T(MSG_RESUME_PRINT), lcd_resume_print);////MSG_RESUME_PRINT c=18
 #else
-      MENU_ITEM_SUBMENU_P(_i("Resume print"), lcd_resume_print);////MSG_RESUME_PRINT
+      MENU_ITEM_SUBMENU_P(_T(MSG_RESUME_PRINT), lcd_resume_print);////MSG_RESUME_PRINT c=18
 #endif
   }
 
@@ -6895,9 +6673,9 @@ static void lcd_main_menu()
 			{
 				#ifdef FANCHECK
 					if((fan_check_error == EFCE_FIXED) || (fan_check_error == EFCE_OK))
-						MENU_ITEM_SUBMENU_P(_i("Resume print"), lcd_resume_print);////MSG_RESUME_PRINT
+						MENU_ITEM_SUBMENU_P(_T(MSG_RESUME_PRINT), lcd_resume_print);////MSG_RESUME_PRINT c=18
 				#else
-					MENU_ITEM_SUBMENU_P(_i("Resume print"), lcd_resume_print);////MSG_RESUME_PRINT
+					MENU_ITEM_SUBMENU_P(_T(MSG_RESUME_PRINT), lcd_resume_print);////MSG_RESUME_PRINT c=18
 				#endif
 
 			}
@@ -6946,14 +6724,7 @@ static void lcd_main_menu()
   }
 
 
-  if (IS_SD_PRINTING || is_usb_printing || (lcd_commands_type == LcdCommands::Layer1Cal))
-  {
-	  if (farm_mode)
-	  {
-		  MENU_ITEM_SUBMENU_P(PSTR("Farm number"), lcd_farm_no);
-	  }
-  } 
-  else 
+  if ( ! ( IS_SD_PRINTING || is_usb_printing || (lcd_commands_type == LcdCommands::Layer1Cal) ) )
   {
 	if (mmu_enabled)
 	{
@@ -6962,9 +6733,9 @@ static void lcd_main_menu()
 //-//          MENU_ITEM_FUNCTION_P(_T(MSG_UNLOAD_FILAMENT), extr_unload);
 //bFilamentFirstRun=true;
           MENU_ITEM_SUBMENU_P(_T(MSG_UNLOAD_FILAMENT), mmu_unload_filament);
-		MENU_ITEM_SUBMENU_P(_i("Eject filament"), mmu_fil_eject_menu);
+		MENU_ITEM_SUBMENU_P(_T(MSG_EJECT_FILAMENT), mmu_fil_eject_menu);
 #ifdef  MMU_HAS_CUTTER
-        MENU_ITEM_SUBMENU_P(_i("Cut filament"), mmu_cut_filament_menu);
+        MENU_ITEM_SUBMENU_P(_T(MSG_CUT_FILAMENT), mmu_cut_filament_menu);
 #endif //MMU_HAS_CUTTER
 	}
 	else
@@ -6975,7 +6746,7 @@ static void lcd_main_menu()
 #endif
 #ifdef FILAMENT_SENSOR
 		if ((fsensor_autoload_enabled == true) && (fsensor_enabled == true) && (mmu_enabled == false))
-			MENU_ITEM_SUBMENU_P(_i("AutoLoad filament"), lcd_menu_AutoLoadFilament);////MSG_AUTOLOAD_FILAMENT c=17
+			MENU_ITEM_SUBMENU_P(_i("AutoLoad filament"), lcd_menu_AutoLoadFilament);////MSG_AUTOLOAD_FILAMENT c=18
 		else
 #endif //FILAMENT_SENSOR
           {
@@ -7144,7 +6915,8 @@ static void lcd_tune_menu()
 	MENU_ITEM_EDIT_advance_K();//7
 #endif
 #ifdef FILAMENTCHANGEENABLE
-	MENU_ITEM_FUNCTION_P(_T(MSG_FILAMENTCHANGE), lcd_colorprint_change);//8
+    if (!farm_mode)
+        MENU_ITEM_FUNCTION_P(_T(MSG_FILAMENTCHANGE), lcd_colorprint_change);//8
 #endif
 
 #ifdef FILAMENT_SENSOR
@@ -7172,7 +6944,7 @@ static void lcd_tune_menu()
 
      if(farm_mode)
      {
-       MENU_ITEM_TOGGLE_P(_i("Fans check"), fans_check_enabled ? _T(MSG_ON) : _T(MSG_OFF), lcd_set_fan_check);
+       MENU_ITEM_TOGGLE_P(_T(MSG_FANS_CHECK), fans_check_enabled ? _T(MSG_ON) : _T(MSG_OFF), lcd_set_fan_check);
      }
 
 #ifdef TMC2130
@@ -7338,6 +7110,7 @@ void lcd_print_stop()
     if (!card.sdprinting) {
         SERIAL_ECHOLNRPGM(MSG_OCTOPRINT_CANCEL);   // for Octoprint
     }
+    cmdqueue_serial_disabled = false; //for when canceling a print with a fancheck
 
     CRITICAL_SECTION_START;
 
@@ -7370,13 +7143,13 @@ void lcd_print_stop()
     cancel_heatup = true; //unroll temperature wait loop stack.
 
     current_position[Z_AXIS] += 10; //lift Z.
-    plan_buffer_line_curposXYZE(manual_feedrate[Z_AXIS] / 60, active_extruder);
+    plan_buffer_line_curposXYZE(manual_feedrate[Z_AXIS] / 60);
 
     if (axis_known_position[X_AXIS] && axis_known_position[Y_AXIS]) //if axis are homed, move to parked position.
     {
         current_position[X_AXIS] = X_CANCEL_POS;
         current_position[Y_AXIS] = Y_CANCEL_POS;
-        plan_buffer_line_curposXYZE(manual_feedrate[0] / 60, active_extruder);
+        plan_buffer_line_curposXYZE(manual_feedrate[0] / 60);
     }
     st_synchronize();
 
@@ -7397,20 +7170,16 @@ void lcd_print_stop()
 void lcd_sdcard_stop()
 {
 
-	lcd_set_cursor(0, 0);
-	lcd_puts_P(_T(MSG_STOP_PRINT));
-	lcd_set_cursor(2, 2);
-	lcd_puts_P(_T(MSG_NO));
-	lcd_set_cursor(2, 3);
-	lcd_puts_P(_T(MSG_YES));
-	lcd_set_cursor(0, 2); lcd_print(" ");
-	lcd_set_cursor(0, 3); lcd_print(" ");
+	lcd_puts_at_P(0, 0, _T(MSG_STOP_PRINT));
+	lcd_puts_at_P(2, 2, _T(MSG_NO));
+	lcd_puts_at_P(2, 3, _T(MSG_YES));
+	lcd_putc_at(0, 2, ' ');
+	lcd_putc_at(0, 3, ' ');
 
 	if ((int32_t)lcd_encoder > 2) { lcd_encoder = 2; }
 	if ((int32_t)lcd_encoder < 1) { lcd_encoder = 1; }
 	
-	lcd_set_cursor(0, 1 + lcd_encoder);
-	lcd_print(">");
+	lcd_putc_at(0, 1 + lcd_encoder, '>');
 
 	if (lcd_clicked())
 	{
@@ -7487,92 +7256,71 @@ static void lcd_belttest_v()
     lcd_belttest();
     menu_back_if_clicked();
 }
-void lcd_belttest_print(const char* msg, uint16_t X, uint16_t Y)
-{
-    lcd_clear();
-    lcd_printf_P(
-              _N(
-                 "%S:\n"
-                 "%S\n"
-                 "X:%d\n"
-                 "Y:%d"
-                 ),
-              _i("Belt status"),
-              msg,
-              X,Y
-            );
-}
+
 void lcd_belttest()
 {
-    bool _result = true;
-    
-    #ifdef TMC2130 // Belttest requires high power mode. Enable it.
-	    FORCE_HIGH_POWER_START;
-    #endif
+    lcd_clear();
+	// Belttest requires high power mode. Enable it.
+	FORCE_HIGH_POWER_START;
     
     uint16_t   X = eeprom_read_word((uint16_t*)(EEPROM_BELTSTATUS_X));
     uint16_t   Y = eeprom_read_word((uint16_t*)(EEPROM_BELTSTATUS_Y));
-    lcd_belttest_print(_i("Checking X..."), X, Y);
-
+	lcd_printf_P(_T(MSG_CHECKING_X));
+	lcd_set_cursor(0,1), lcd_printf_P(PSTR("X: %u -> ..."),X);
     KEEPALIVE_STATE(IN_HANDLER);
     
-    _result = lcd_selfcheck_axis_sg(X_AXIS);
-    X = eeprom_read_word((uint16_t*)(EEPROM_BELTSTATUS_X));
-    if (_result){
-        lcd_belttest_print(_i("Checking Y..."), X, Y);
-        _result = lcd_selfcheck_axis_sg(Y_AXIS);
-        Y = eeprom_read_word((uint16_t*)(EEPROM_BELTSTATUS_Y));
+	// N.B: it doesn't make sense to handle !lcd_selfcheck...() because selftest_sg throws its own error screen
+	// that clobbers ours, with more info than we could provide. So on fail we just fall through to take us back to status.
+    if (lcd_selfcheck_axis_sg(X_AXIS)){
+		X = eeprom_read_word((uint16_t*)(EEPROM_BELTSTATUS_X));
+		lcd_set_cursor(10,1), lcd_printf_P(PSTR("%u"),X); // Show new X value next to old one.
+        lcd_puts_at_P(0,2,_T(MSG_CHECKING_Y));
+		lcd_set_cursor(0,3), lcd_printf_P(PSTR("Y: %u -> ..."),Y);
+		if (lcd_selfcheck_axis_sg(Y_AXIS))
+		{
+			Y = eeprom_read_word((uint16_t*)(EEPROM_BELTSTATUS_Y));
+			lcd_set_cursor(10,3),lcd_printf_P(PSTR("%u"),Y);
+			lcd_set_cursor(19, 3);
+			lcd_print(LCD_STR_UPLEVEL);
+			lcd_wait_for_click_delay(10);
+		}
     }
-    
-    if (!_result) {
-        lcd_belttest_print(_i("Error"), X, Y);
-    } else {
-        lcd_belttest_print(_i("Done"), X, Y);
-    }   
-
-    #ifdef TMC2130
-	    FORCE_HIGH_POWER_END;
-    #endif
-    
+	
+	FORCE_HIGH_POWER_END;
     KEEPALIVE_STATE(NOT_BUSY);
-    _delay(3000);
 }
 #endif //TMC2130
 
 #ifdef IR_SENSOR_ANALOG
 // called also from marlin_main.cpp
-void printf_IRSensorAnalogBoardChange(bool bPCBrev03b){
-    printf_P(PSTR("Filament sensor board change detected: revision %S\n"), bPCBrev03b ? PSTR("03b or newer") : PSTR("03 or older"));
+void printf_IRSensorAnalogBoardChange(){
+    printf_P(PSTR("Filament sensor board change detected: revision%S\n"), FsensorIRVersionText());
 }
 
 static bool lcd_selftest_IRsensor(bool bStandalone)
 {
-    bool bAction;
-    bool bPCBrev03b;
+    bool bPCBrev04;
     uint16_t volt_IR_int;
-    float volt_IR;
 
-    volt_IR_int=current_voltage_raw_IR;
-    bPCBrev03b=(volt_IR_int<((int)IRsensor_Hopen_TRESHOLD));
-    volt_IR=VOLT_DIV_REF*((float)volt_IR_int/(1023*OVERSAMPLENR));
-    printf_P(PSTR("Measured filament sensor high level: %4.2fV\n"),volt_IR);
-    if(volt_IR_int < ((int)IRsensor_Hmin_TRESHOLD)){
+    volt_IR_int = current_voltage_raw_IR;
+    bPCBrev04=(volt_IR_int < IRsensor_Hopen_TRESHOLD);
+    printf_P(PSTR("Measured filament sensor high level: %4.2fV\n"), Raw2Voltage(volt_IR_int) );
+    if(volt_IR_int < IRsensor_Hmin_TRESHOLD){
         if(!bStandalone)
             lcd_selftest_error(TestError::FsensorLevel,"HIGH","");
         return(false);
     }
-    lcd_show_fullscreen_message_and_wait_P(_i("Please insert filament (but not load them!) into extruder and then press the knob."));
-    volt_IR_int=current_voltage_raw_IR;
-    volt_IR=VOLT_DIV_REF*((float)volt_IR_int/(1023*OVERSAMPLENR));
-    printf_P(PSTR("Measured filament sensor low level: %4.2fV\n"),volt_IR);
-    if(volt_IR_int > ((int)IRsensor_Lmax_TRESHOLD)){
+    lcd_show_fullscreen_message_and_wait_P(_i("Insert the filament (do not load it) into the extruder and then press the knob."));////c=20 r=6
+    volt_IR_int = current_voltage_raw_IR;
+    printf_P(PSTR("Measured filament sensor low level: %4.2fV\n"), Raw2Voltage(volt_IR_int));
+    if(volt_IR_int > (IRsensor_Lmax_TRESHOLD)){
         if(!bStandalone)
             lcd_selftest_error(TestError::FsensorLevel,"LOW","");
         return(false);
     }
-    if((bPCBrev03b?1:0)!=(uint8_t)oFsensorPCB){        // safer then "(uint8_t)bPCBrev03b"
-        printf_IRSensorAnalogBoardChange(bPCBrev03b);
-        oFsensorPCB=bPCBrev03b?ClFsensorPCB::_Rev03b:ClFsensorPCB::_Old;
+    if((bPCBrev04 ? 1 : 0) != (uint8_t)oFsensorPCB){        // safer then "(uint8_t)bPCBrev04"
+        oFsensorPCB=bPCBrev04 ? ClFsensorPCB::_Rev04 : ClFsensorPCB::_Old;
+        printf_IRSensorAnalogBoardChange();
         eeprom_update_byte((uint8_t*)EEPROM_FSENSOR_PCB,(uint8_t)oFsensorPCB);
     }
     return(true);
@@ -7580,18 +7328,26 @@ static bool lcd_selftest_IRsensor(bool bStandalone)
 
 static void lcd_detect_IRsensor(){
     bool bAction;
-
+    bool loaded;
     bMenuFSDetect = true;                               // inhibits some code inside "manage_inactivity()"
-    bAction = lcd_show_fullscreen_message_yes_no_and_wait_P(_i("Is the filament loaded?"), false, false);
-    if(!bAction){
+    /// Check if filament is loaded. If it is loaded stop detection.
+    /// @todo Add autodetection with MMU2s
+    loaded = ! READ(IR_SENSOR_PIN);
+    if(loaded ){
         lcd_show_fullscreen_message_and_wait_P(_i("Please unload the filament first, then repeat this action."));
         return;
+    } else {
+        lcd_show_fullscreen_message_and_wait_P(_i("Please check the IR sensor connection, unload filament if present."));
+        bAction = lcd_selftest_IRsensor(true);
+    }
+    if(bAction){
+        lcd_show_fullscreen_message_and_wait_P(_i("Sensor verified, remove the filament now."));////c=20 r=3
+        // the fsensor board has been successfully identified, any previous "not responding" may be cleared now
+        fsensor_not_responding = false;
+    } else {
+        lcd_show_fullscreen_message_and_wait_P(_i("Verification failed, remove the filament and try again."));////c=20 r=5
+        // here it is unclear what to to with the fsensor_not_responding flag
     }
-    bAction = lcd_selftest_IRsensor(true);
-    if(bAction)
-        lcd_show_fullscreen_message_and_wait_P(_i("Sensor verified, remove the filament now."));
-    else
-        lcd_show_fullscreen_message_and_wait_P(_i("Verification failed, remove the filament and try again."));
     bMenuFSDetect=false;                              // de-inhibits some code inside "manage_inactivity()"
 }
 #endif //IR_SENSOR_ANALOG
@@ -7606,16 +7362,22 @@ bool lcd_selftest()
 	int _progress = 0;
 	bool _result = true;
 	bool _swapped_fan = false;
-//#ifdef IR_SENSOR_ANALOG
-#if (0)
-     bool bAction;
-     bAction=lcd_show_fullscreen_message_yes_no_and_wait_P(_i("Is the filament unloaded?"),false,true);
-     if(!bAction)
-          return(false);
+#ifdef IR_SENSOR_ANALOG
+	//!   Check if IR sensor is in unknown state, if so run Fsensor Detection
+	//!   As the Fsensor Detection isn't yet ready for the mmu2s we set temporarily the IR sensor 0.3 or older for mmu2s
+	//! @todo Don't forget to remove this as soon Fsensor Detection works with mmu
+	if( oFsensorPCB == ClFsensorPCB::_Undef) {
+		if (!mmu_enabled) {
+			lcd_detect_IRsensor();
+		}
+		else {
+			eeprom_update_byte((uint8_t*)EEPROM_FSENSOR_PCB,0);
+		}
+	}
 #endif //IR_SENSOR_ANALOG
 	lcd_wait_for_cool_down();
 	lcd_clear();
-	lcd_set_cursor(0, 0); lcd_puts_P(_i("Self test start  "));////MSG_SELFTEST_START c=20
+	lcd_puts_at_P(0, 0, _i("Self test start  "));////MSG_SELFTEST_START c=20
 	#ifdef TMC2130
 	  FORCE_HIGH_POWER_START;
 	#endif // TMC2130
@@ -7687,11 +7449,7 @@ bool lcd_selftest()
 	if (_result)
 	{
 		_progress = lcd_selftest_screen(TestScreen::FansOk, _progress, 3, true, 2000);
-#ifndef TMC2130
-		_result = lcd_selfcheck_endstops();
-#else
-		_result = true;
-#endif
+		_result = lcd_selfcheck_endstops(); //With TMC2130, only the Z probe is tested.
 	}
 
 	if (_result)
@@ -7746,26 +7504,26 @@ bool lcd_selftest()
 
 		//homeaxis(X_AXIS);
 		//homeaxis(Y_AXIS);
-        current_position[X_AXIS] += pgm_read_float(bed_ref_points_4);
-		current_position[Y_AXIS] += pgm_read_float(bed_ref_points_4+1);
+        current_position[X_AXIS] = pgm_read_float(bed_ref_points_4);
+		current_position[Y_AXIS] = pgm_read_float(bed_ref_points_4+1);
 #ifdef TMC2130
 		//current_position[X_AXIS] += 0;
 		current_position[Y_AXIS] += 4;
 #endif //TMC2130
 		current_position[Z_AXIS] = current_position[Z_AXIS] + 10;
-		plan_buffer_line_curposXYZE(manual_feedrate[0] / 60, active_extruder);
+		plan_buffer_line_curposXYZE(manual_feedrate[0] / 60);
 		st_synchronize();
         set_destination_to_current();
 		_progress = lcd_selftest_screen(TestScreen::AxisZ, _progress, 3, true, 1500);
 #ifdef TMC2130
-		_result = homeaxis(Z_AXIS, false);
+		homeaxis(Z_AXIS); //In case of failure, the code gets stuck in this function.
 #else
         _result = lcd_selfcheck_axis(Z_AXIS, Z_MAX_POS);
 #endif //TMC2130
 
 		//raise Z to not damage the bed during and hotend testing
 		current_position[Z_AXIS] += 20;
-		plan_buffer_line_curposXYZE(manual_feedrate[0] / 60, active_extruder);
+		plan_buffer_line_curposXYZE(manual_feedrate[0] / 60);
 		st_synchronize();
 	}
 
@@ -7773,7 +7531,7 @@ bool lcd_selftest()
 	if (_result)
 	{
 		current_position[Z_AXIS] = current_position[Z_AXIS] + 10;
-		plan_buffer_line_curposXYZE(manual_feedrate[0] / 60, active_extruder);
+		plan_buffer_line_curposXYZE(manual_feedrate[0] / 60);
 		st_synchronize();
 		_progress = lcd_selftest_screen(TestScreen::Home, 0, 2, true, 0);
 		bool bres = tmc2130_home_calibrate(X_AXIS);
@@ -7823,10 +7581,12 @@ bool lcd_selftest()
 				_progress = lcd_selftest_screen(TestScreen::FsensorOk, _progress, 3, true, 2000); //fil sensor OK
 			}
 #endif //PAT9125
-//#ifdef IR_SENSOR_ANALOG
-#if (0)
+#if 0
+	// Intentionally disabled - that's why we moved the detection to runtime by just checking the two voltages.
+	// The idea is not to force the user to remove and insert the filament on an assembled printer.
+//def IR_SENSOR_ANALOG
 			_progress = lcd_selftest_screen(TestScreen::Fsensor, _progress, 3, true, 2000); //check filament sensor
-               _result = lcd_selftest_IRsensor();
+			_result = lcd_selftest_IRsensor();
 			if (_result)
 			{
 				_progress = lcd_selftest_screen(TestScreen::FsensorOk, _progress, 3, true, 2000); //filament sensor OK
@@ -7869,7 +7629,7 @@ bool lcd_selftest()
 
 static void reset_crash_det(unsigned char axis) {
 	current_position[axis] += 10;
-	plan_buffer_line_curposXYZE(manual_feedrate[0] / 60, active_extruder);
+	plan_buffer_line_curposXYZE(manual_feedrate[0] / 60);
 	st_synchronize();
 	if (eeprom_read_byte((uint8_t*)EEPROM_CRASH_DET)) tmc2130_sg_stop_on_crash = true;
 }
@@ -7890,17 +7650,15 @@ static bool lcd_selfcheck_axis_sg(unsigned char axis) {
 	tmc2130_home_exit();
 	enable_endstops(true);
 
-	if (axis == X_AXIS) { //there is collision between cables and PSU cover in X axis if Z coordinate is too low
-		raise_z_above(17,true);
-		tmc2130_home_enter(Z_AXIS_MASK);
-		st_synchronize();
-		tmc2130_home_exit();
-	}
+
+	raise_z_above(MESH_HOME_Z_SEARCH);
+	st_synchronize();
+	tmc2130_home_enter(1 << axis);
 
 // first axis length measurement begin	
 	
 	current_position[axis] -= (axis_length + margin);
-	plan_buffer_line_curposXYZE(manual_feedrate[0] / 60, active_extruder);
+	plan_buffer_line_curposXYZE(manual_feedrate[0] / 60);
 
 	
 	st_synchronize();
@@ -7910,11 +7668,11 @@ static bool lcd_selfcheck_axis_sg(unsigned char axis) {
 	current_position_init = st_get_position_mm(axis);
 
 	current_position[axis] += 2 * margin;
-	plan_buffer_line_curposXYZE(manual_feedrate[0] / 60, active_extruder);
+	plan_buffer_line_curposXYZE(manual_feedrate[0] / 60);
 	st_synchronize();
 
 	current_position[axis] += axis_length;
-	plan_buffer_line_curposXYZE(manual_feedrate[0] / 60, active_extruder);
+	plan_buffer_line_curposXYZE(manual_feedrate[0] / 60);
 
 	st_synchronize();
 
@@ -7930,11 +7688,11 @@ static bool lcd_selfcheck_axis_sg(unsigned char axis) {
 
 
 	current_position[axis] -= margin;
-	plan_buffer_line_curposXYZE(manual_feedrate[0] / 60, active_extruder);
+	plan_buffer_line_curposXYZE(manual_feedrate[0] / 60);
 	st_synchronize();	
 
 	current_position[axis] -= (axis_length + margin);
-	plan_buffer_line_curposXYZE(manual_feedrate[0] / 60, active_extruder);
+	plan_buffer_line_curposXYZE(manual_feedrate[0] / 60);
 		
 	st_synchronize();
 
@@ -7942,6 +7700,7 @@ static bool lcd_selfcheck_axis_sg(unsigned char axis) {
 
 	measured_axis_length[1] = abs(current_position_final - current_position_init);
 
+	tmc2130_home_exit();
 
 //end of second measurement, now check for possible errors:
 
@@ -7958,8 +7717,10 @@ static bool lcd_selfcheck_axis_sg(unsigned char axis) {
 
 			lcd_selftest_error(TestError::Axis, _error_1, "");
 			current_position[axis] = 0;
-			plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
+			plan_set_position_curposXYZE();
 			reset_crash_det(axis);
+			enable_endstops(true);
+			endstops_hit_on_purpose();
 			return false;
 		}
 	}
@@ -7976,14 +7737,15 @@ static bool lcd_selfcheck_axis_sg(unsigned char axis) {
 
 			lcd_selftest_error(TestError::Pulley, _error_1, "");
 			current_position[axis] = 0;
-			plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
+			plan_set_position_curposXYZE();
 			reset_crash_det(axis);
-
+			endstops_hit_on_purpose();
 			return false;
 		}
 		current_position[axis] = 0;
-		plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
+		plan_set_position_curposXYZE();
 		reset_crash_det(axis);
+		endstops_hit_on_purpose();
 		return true;
 }
 #endif //TMC2130
@@ -8003,13 +7765,13 @@ static bool lcd_selfcheck_axis(int _axis, int _travel)
 
 	if (_axis == X_AXIS) {
 		current_position[Z_AXIS] += 17;
-		plan_buffer_line_curposXYZE(manual_feedrate[0] / 60, active_extruder);
+		plan_buffer_line_curposXYZE(manual_feedrate[0] / 60);
 	}
 
 	do {
 		current_position[_axis] = current_position[_axis] - 1;
 
-		plan_buffer_line_curposXYZE(manual_feedrate[0] / 60, active_extruder);
+		plan_buffer_line_curposXYZE(manual_feedrate[0] / 60);
 		st_synchronize();
 #ifdef TMC2130
 		if ((READ(Z_MIN_PIN) ^ (bool)Z_MIN_ENDSTOP_INVERTING))
@@ -8089,7 +7851,7 @@ static bool lcd_selfcheck_axis(int _axis, int _travel)
 		}
 	}    
 	current_position[_axis] = 0; //simulate axis home to avoid negative numbers for axis position, especially Z.
-	plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
+	plan_set_position_curposXYZE();
 
 	return _stepresult;
 }
@@ -8112,17 +7874,17 @@ static bool lcd_selfcheck_pulleys(int axis)
 	current_position_init = current_position[axis];
 
 	current_position[axis] += 2;
-	plan_buffer_line_curposXYZE(manual_feedrate[0] / 60, active_extruder);
+	plan_buffer_line_curposXYZE(manual_feedrate[0] / 60);
 	for (i = 0; i < 5; i++) {
 		refresh_cmd_timeout();
 		current_position[axis] = current_position[axis] + move;
 		st_current_set(0, 850); //set motor current higher
-		plan_buffer_line_curposXYZE(200, active_extruder);
+		plan_buffer_line_curposXYZE(200);
 		st_synchronize();
           if (SilentModeMenu != SILENT_MODE_OFF) st_current_set(0, tmp_motor[0]); //set back to normal operation currents
 		else st_current_set(0, tmp_motor_loud[0]); //set motor current back			
 		current_position[axis] = current_position[axis] - move;
-		plan_buffer_line_curposXYZE(50, active_extruder);
+		plan_buffer_line_curposXYZE(50);
 		st_synchronize();
 		if (((READ(X_MIN_PIN) ^ X_MIN_ENDSTOP_INVERTING) == 1) ||
 			((READ(Y_MIN_PIN) ^ Y_MIN_ENDSTOP_INVERTING) == 1)) {
@@ -8138,6 +7900,9 @@ static bool lcd_selfcheck_pulleys(int axis)
 			((READ(Y_MIN_PIN) ^ Y_MIN_ENDSTOP_INVERTING) == 1)) {
 			endstop_triggered = true;
 			if (current_position_init - 1 <= current_position[axis] && current_position_init + 1 >= current_position[axis]) {
+				current_position[axis] += 10;
+				plan_buffer_line_curposXYZE(manual_feedrate[0] / 60);
+				st_synchronize();
 				return(true);
 			}
 			else {
@@ -8147,7 +7912,7 @@ static bool lcd_selfcheck_pulleys(int axis)
 		}
 		else {
 			current_position[axis] -= 1;
-			plan_buffer_line_curposXYZE(manual_feedrate[0] / 60, active_extruder);
+			plan_buffer_line_curposXYZE(manual_feedrate[0] / 60);
 			st_synchronize();
 			if (_millis() > timeout_counter) {
 				lcd_selftest_error(TestError::Pulley, (axis == 0) ? "X" : "Y", "");
@@ -8157,31 +7922,42 @@ static bool lcd_selfcheck_pulleys(int axis)
 	}
 	return(true);
 }
+#endif //not defined TMC2130
 
 
 static bool lcd_selfcheck_endstops()
 {
 	bool _result = true;
 
-	if (((READ(X_MIN_PIN) ^ X_MIN_ENDSTOP_INVERTING) == 1) ||
+	if (
+	#ifndef TMC2130
+		((READ(X_MIN_PIN) ^ X_MIN_ENDSTOP_INVERTING) == 1) ||
 		((READ(Y_MIN_PIN) ^ Y_MIN_ENDSTOP_INVERTING) == 1) ||
+	#endif //!TMC2130
 		((READ(Z_MIN_PIN) ^ Z_MIN_ENDSTOP_INVERTING) == 1))
 	{
+	#ifndef TMC2130
 		if ((READ(X_MIN_PIN) ^ X_MIN_ENDSTOP_INVERTING) == 1) current_position[0] += 10;
 		if ((READ(Y_MIN_PIN) ^ Y_MIN_ENDSTOP_INVERTING) == 1) current_position[1] += 10;
+	#endif //!TMC2130
 		if ((READ(Z_MIN_PIN) ^ Z_MIN_ENDSTOP_INVERTING) == 1) current_position[2] += 10;
 	}
-	plan_buffer_line_curposXYZE(manual_feedrate[0] / 60, active_extruder);
-	_delay(500);
+	plan_buffer_line_curposXYZE(manual_feedrate[0] / 60);
+	st_synchronize();
 
-	if (((READ(X_MIN_PIN) ^ X_MIN_ENDSTOP_INVERTING) == 1) ||
+	if (
+	#ifndef TMC2130
+		((READ(X_MIN_PIN) ^ X_MIN_ENDSTOP_INVERTING) == 1) ||
 		((READ(Y_MIN_PIN) ^ Y_MIN_ENDSTOP_INVERTING) == 1) ||
+	#endif //!TMC2130
 		((READ(Z_MIN_PIN) ^ Z_MIN_ENDSTOP_INVERTING) == 1))
 	{
 		_result = false;
 		char _error[4] = "";
+	#ifndef TMC2130
 		if ((READ(X_MIN_PIN) ^ X_MIN_ENDSTOP_INVERTING) == 1) strcat(_error, "X");
 		if ((READ(Y_MIN_PIN) ^ Y_MIN_ENDSTOP_INVERTING) == 1) strcat(_error, "Y");
+	#endif //!TMC2130
 		if ((READ(Z_MIN_PIN) ^ Z_MIN_ENDSTOP_INVERTING) == 1) strcat(_error, "Z");
 		lcd_selftest_error(TestError::Endstops, _error, "");
 	}
@@ -8189,7 +7965,6 @@ static bool lcd_selfcheck_endstops()
 	manage_inactivity(true);
 	return _result;
 }
-#endif //not defined TMC2130
 
 static bool lcd_selfcheck_check_heater(bool _isbed)
 {
@@ -8276,106 +8051,79 @@ static void lcd_selftest_error(TestError testError, const char *_error_1, const
 
 	lcd_clear();
 
-	lcd_set_cursor(0, 0);
-	lcd_puts_P(_i("Selftest error !"));////MSG_SELFTEST_ERROR
-	lcd_set_cursor(0, 1);
-	lcd_puts_P(_i("Please check :"));////MSG_SELFTEST_PLEASECHECK
+	lcd_puts_at_P(0, 0, _i("Selftest error !"));////MSG_SELFTEST_ERROR
+	lcd_puts_at_P(0, 1, _i("Please check :"));////MSG_SELFTEST_PLEASECHECK
 
 	switch (testError)
 	{
 	case TestError::Heater:
-		lcd_set_cursor(0, 2);
-		lcd_puts_P(_i("Heater/Thermistor"));////MSG_SELFTEST_HEATERTHERMISTOR
-		lcd_set_cursor(0, 3);
-		lcd_puts_P(_i("Not connected"));////MSG_SELFTEST_NOTCONNECTED
+		lcd_puts_at_P(0, 2, _i("Heater/Thermistor"));////MSG_SELFTEST_HEATERTHERMISTOR
+		lcd_puts_at_P(0, 3, _i("Not connected"));////MSG_SELFTEST_NOTCONNECTED
 		break;
 	case TestError::Bed:
-		lcd_set_cursor(0, 2);
-		lcd_puts_P(_i("Bed / Heater"));////MSG_SELFTEST_BEDHEATER
-		lcd_set_cursor(0, 3);
-		lcd_puts_P(_T(MSG_SELFTEST_WIRINGERROR));
+		lcd_puts_at_P(0, 2, _i("Bed / Heater"));////MSG_SELFTEST_BEDHEATER
+		lcd_puts_at_P(0, 3, _T(MSG_SELFTEST_WIRINGERROR));
 		break;
 	case TestError::Endstops:
-		lcd_set_cursor(0, 2);
-		lcd_puts_P(_i("Endstops"));////MSG_SELFTEST_ENDSTOPS
-		lcd_set_cursor(0, 3);
-		lcd_puts_P(_T(MSG_SELFTEST_WIRINGERROR));
+		lcd_puts_at_P(0, 2, _i("Endstops"));////MSG_SELFTEST_ENDSTOPS
+		lcd_puts_at_P(0, 3, _T(MSG_SELFTEST_WIRINGERROR));
 		lcd_set_cursor(17, 3);
 		lcd_print(_error_1);
 		break;
 	case TestError::Motor:
-		lcd_set_cursor(0, 2);
-		lcd_puts_P(_T(MSG_SELFTEST_MOTOR));
+		lcd_puts_at_P(0, 2, _T(MSG_SELFTEST_MOTOR));
 		lcd_set_cursor(18, 2);
 		lcd_print(_error_1);
-		lcd_set_cursor(0, 3);
-		lcd_puts_P(_i("Endstop"));////MSG_SELFTEST_ENDSTOP
+		lcd_puts_at_P(0, 3, _i("Endstop"));////MSG_SELFTEST_ENDSTOP
 		lcd_set_cursor(18, 3);
 		lcd_print(_error_2);
 		break;
 	case TestError::Endstop:
-		lcd_set_cursor(0, 2);
-		lcd_puts_P(_i("Endstop not hit"));////MSG_SELFTEST_ENDSTOP_NOTHIT c=20 r=1
-		lcd_set_cursor(0, 3);
-		lcd_puts_P(_T(MSG_SELFTEST_MOTOR));
+		lcd_puts_at_P(0, 2, _i("Endstop not hit"));////MSG_SELFTEST_ENDSTOP_NOTHIT c=20
+		lcd_puts_at_P(0, 3, _T(MSG_SELFTEST_MOTOR));
 		lcd_set_cursor(18, 3);
 		lcd_print(_error_1);
 		break;
 	case TestError::PrintFan:
-		lcd_set_cursor(0, 2);
-		lcd_puts_P(_T(MSG_SELFTEST_COOLING_FAN));
-		lcd_set_cursor(0, 3);
-		lcd_puts_P(_T(MSG_SELFTEST_WIRINGERROR));
+		lcd_puts_at_P(0, 2, _T(MSG_SELFTEST_COOLING_FAN));
+		lcd_puts_at_P(0, 3, _T(MSG_SELFTEST_WIRINGERROR));
 		lcd_set_cursor(18, 3);
 		lcd_print(_error_1);
 		break;
 	case TestError::ExtruderFan:
-		lcd_set_cursor(0, 2);
-		lcd_puts_P(_T(MSG_SELFTEST_EXTRUDER_FAN));
-		lcd_set_cursor(0, 3);
-		lcd_puts_P(_T(MSG_SELFTEST_WIRINGERROR));
+		lcd_puts_at_P(0, 2, _T(MSG_SELFTEST_EXTRUDER_FAN));
+		lcd_puts_at_P(0, 3, _T(MSG_SELFTEST_WIRINGERROR));
 		lcd_set_cursor(18, 3);
 		lcd_print(_error_1);
 		break;
 	case TestError::Pulley:
-		lcd_set_cursor(0, 2);
-		lcd_puts_P(_i("Loose pulley"));////MSG_LOOSE_PULLEY c=20 r=1
-		lcd_set_cursor(0, 3);
-		lcd_puts_P(_T(MSG_SELFTEST_MOTOR));
+		lcd_puts_at_P(0, 2, _i("Loose pulley"));////MSG_LOOSE_PULLEY c=20 r=1
+		lcd_puts_at_P(0, 3, _T(MSG_SELFTEST_MOTOR));
 		lcd_set_cursor(18, 3);
 		lcd_print(_error_1);
 		break;
 	case TestError::Axis:
-		lcd_set_cursor(0, 2);
-		lcd_puts_P(_i("Axis length"));////MSG_SELFTEST_AXIS_LENGTH
-		lcd_set_cursor(0, 3);
-		lcd_puts_P(_i("Axis"));////MSG_SELFTEST_AXIS
+		lcd_puts_at_P(0, 2, _i("Axis length"));////MSG_SELFTEST_AXIS_LENGTH
+		lcd_puts_at_P(0, 3, _i("Axis"));////MSG_SELFTEST_AXIS
 		lcd_set_cursor(18, 3);
 		lcd_print(_error_1);
 		break;
 	case TestError::SwappedFan:
-		lcd_set_cursor(0, 2);
-		lcd_puts_P(_i("Front/left fans"));////MSG_SELFTEST_FANS
-		lcd_set_cursor(0, 3);
-		lcd_puts_P(_i("Swapped"));////MSG_SELFTEST_SWAPPED
+		lcd_puts_at_P(0, 2, _i("Front/left fans"));////MSG_SELFTEST_FANS
+		lcd_puts_at_P(0, 3, _i("Swapped"));////MSG_SELFTEST_SWAPPED
 		lcd_set_cursor(18, 3);
 		lcd_print(_error_1);
 		break;
 	case TestError::WiringFsensor:
-		lcd_set_cursor(0, 2);
-		lcd_puts_P(_T(MSG_SELFTEST_FILAMENT_SENSOR));
-		lcd_set_cursor(0, 3);
-		lcd_puts_P(_T(MSG_SELFTEST_WIRINGERROR));
+		lcd_puts_at_P(0, 2, _T(MSG_SELFTEST_FILAMENT_SENSOR));
+		lcd_puts_at_P(0, 3, _T(MSG_SELFTEST_WIRINGERROR));
 		break;
 	case TestError::TriggeringFsensor:
-          lcd_set_cursor(0, 2);
-          lcd_puts_P(_T(MSG_SELFTEST_FILAMENT_SENSOR));
-          lcd_set_cursor(0, 3);
-          lcd_puts_P(_i("False triggering"));////c=20
+          lcd_puts_at_P(0, 2, _T(MSG_SELFTEST_FILAMENT_SENSOR));
+          lcd_puts_at_P(0, 3, _i("False triggering"));////c=20
           break;
 	case TestError::FsensorLevel:
-          lcd_set_cursor(0, 2);
-          lcd_puts_P(_T(MSG_SELFTEST_FILAMENT_SENSOR));
+          lcd_puts_at_P(0, 2, _T(MSG_SELFTEST_FILAMENT_SENSOR));
           lcd_set_cursor(0, 3);
           lcd_printf_P(_i("%s level expected"),_error_1);////c=20
           break;
@@ -8454,7 +8202,7 @@ static bool selftest_irsensor()
         mmu_load_step(false);
         while (blocks_queued())
         {
-            if (PIN_GET(IR_SENSOR_PIN) == 0)
+            if (READ(IR_SENSOR_PIN) == 0)
             {
                 lcd_selftest_error(TestError::TriggeringFsensor, "", "");
                 return false;
@@ -8484,23 +8232,18 @@ static bool lcd_selftest_manual_fan_check(int _fan, bool check_opposite,
 	bool _result = check_opposite;
 	lcd_clear();
 
-	lcd_set_cursor(0, 0); lcd_puts_P(_T(MSG_SELFTEST_FAN));
+	lcd_puts_at_P(0, 0, _T(MSG_SELFTEST_FAN));
 
 	switch (_fan)
 	{
 	case 0:
 		// extruder cooling fan
-		lcd_set_cursor(0, 1);
-		if(check_opposite == true) lcd_puts_P(_T(MSG_SELFTEST_COOLING_FAN)); 
-		else lcd_puts_P(_T(MSG_SELFTEST_EXTRUDER_FAN));
-		SET_OUTPUT(EXTRUDER_0_AUTO_FAN_PIN);
-		WRITE(EXTRUDER_0_AUTO_FAN_PIN, 1);
+		lcd_puts_at_P(0, 1, check_opposite ? _T(MSG_SELFTEST_COOLING_FAN) : _T(MSG_SELFTEST_EXTRUDER_FAN));
+		setExtruderAutoFanState(3);
 		break;
 	case 1:
 		// object cooling fan
-		lcd_set_cursor(0, 1);
-		if (check_opposite == true) lcd_puts_P(_T(MSG_SELFTEST_EXTRUDER_FAN));
-		else lcd_puts_P(_T(MSG_SELFTEST_COOLING_FAN));
+		lcd_puts_at_P(0, 1, check_opposite ? _T(MSG_SELFTEST_EXTRUDER_FAN) : _T(MSG_SELFTEST_COOLING_FAN));
 		SET_OUTPUT(FAN_PIN);
 #ifdef FAN_SOFT_PWM
 		fanSpeedSoftPwm = 255;
@@ -8512,9 +8255,9 @@ static bool lcd_selftest_manual_fan_check(int _fan, bool check_opposite,
 	}
 	_delay(500);
 
-	lcd_set_cursor(1, 2); lcd_puts_P(_T(MSG_SELFTEST_FAN_YES));
-	lcd_set_cursor(0, 3); lcd_print(">");
-	lcd_set_cursor(1, 3); lcd_puts_P(_T(MSG_SELFTEST_FAN_NO));
+	lcd_puts_at_P(1, 2, _T(MSG_SELFTEST_FAN_YES));
+	lcd_putc_at(0, 3, '>');
+	lcd_puts_at_P(1, 3, _T(MSG_SELFTEST_FAN_NO));
 
 	int8_t enc_dif = int(_default)*3;
 
@@ -8523,38 +8266,21 @@ static bool lcd_selftest_manual_fan_check(int _fan, bool check_opposite,
 	lcd_button_pressed = false;
 	do
 	{
-		switch (_fan)
-		{
-		case 0:
-			// extruder cooling fan
-			SET_OUTPUT(EXTRUDER_0_AUTO_FAN_PIN);
-			WRITE(EXTRUDER_0_AUTO_FAN_PIN, 1);
-			break;
-		case 1:
-			// object cooling fan
-			SET_OUTPUT(FAN_PIN);
-#ifdef FAN_SOFT_PWM
-			fanSpeedSoftPwm = 255;
-#else //FAN_SOFT_PWM
-			analogWrite(FAN_PIN, 255);
-#endif //FAN_SOFT_PWM
-			break;
-		}
 		if (abs((enc_dif - lcd_encoder_diff)) > 2) {
 			if (enc_dif > lcd_encoder_diff) {
 				_result = !check_opposite;
-				lcd_set_cursor(0, 2); lcd_print(">");
-				lcd_set_cursor(1, 2); lcd_puts_P(_T(MSG_SELFTEST_FAN_YES));
-				lcd_set_cursor(0, 3); lcd_print(" ");
-				lcd_set_cursor(1, 3); lcd_puts_P(_T(MSG_SELFTEST_FAN_NO));
+				lcd_putc_at(0, 2, '>');
+				lcd_puts_at_P(1, 2, _T(MSG_SELFTEST_FAN_YES));
+				lcd_putc_at(0, 3, ' ');
+				lcd_puts_at_P(1, 3, _T(MSG_SELFTEST_FAN_NO));
 			}
 
 			if (enc_dif < lcd_encoder_diff) {
 				_result = check_opposite;
-				lcd_set_cursor(0, 2); lcd_print(" ");
-				lcd_set_cursor(1, 2); lcd_puts_P(_T(MSG_SELFTEST_FAN_YES));
-				lcd_set_cursor(0, 3); lcd_print(">");
-				lcd_set_cursor(1, 3); lcd_puts_P(_T(MSG_SELFTEST_FAN_NO));
+				lcd_putc_at(0, 2, ' ');
+				lcd_puts_at_P(1, 2, _T(MSG_SELFTEST_FAN_YES));
+				lcd_putc_at(0, 3, '>');
+				lcd_puts_at_P(1, 3, _T(MSG_SELFTEST_FAN_NO));
 			}
 			enc_dif = 0;
 			lcd_encoder_diff = 0;
@@ -8566,8 +8292,7 @@ static bool lcd_selftest_manual_fan_check(int _fan, bool check_opposite,
 
 	} while (!lcd_clicked());
 	KEEPALIVE_STATE(IN_HANDLER);
-	SET_OUTPUT(EXTRUDER_0_AUTO_FAN_PIN);
-	WRITE(EXTRUDER_0_AUTO_FAN_PIN, 0);
+	setExtruderAutoFanState(0);
 	SET_OUTPUT(FAN_PIN);
 #ifdef FAN_SOFT_PWM
 	fanSpeedSoftPwm = 0;
@@ -8587,20 +8312,20 @@ static FanCheck lcd_selftest_fan_auto(int _fan)
 	case 0:
 		fanSpeed = 0;
 		manage_heater();			//turn off fan
-		setExtruderAutoFanState(EXTRUDER_0_AUTO_FAN_PIN, 1); //extruder fan
+		setExtruderAutoFanState(3); //extruder fan
 #ifdef FAN_SOFT_PWM
 		extruder_autofan_last_check = _millis();
 		fan_measuring = true;
 #endif //FAN_SOFT_PWM
-		_delay(2000);				//delay_keep_alive would turn off extruder fan, because temerature is too low
-
+		_delay(2000);
+		setExtruderAutoFanState(0); //extruder fan
 		manage_heater();			//count average fan speed from 2s delay and turn off fans
 
-		printf_P(PSTR("Test 1:\n"));
-		printf_P(PSTR("Print fan speed: %d \n"), fan_speed[1]);
-		printf_P(PSTR("Extr fan speed: %d \n"), fan_speed[0]);
+		puts_P(PSTR("Test 1:"));
+		printf_P(PSTR("Print fan speed: %d\n"), fan_speed[1]);
+		printf_P(PSTR("Extr fan speed: %d\n"), fan_speed[0]);
 
-		if (!fan_speed[0]) {
+		if (fan_speed[0] < 20) { // < 1200 RPM would mean either a faulty Noctua or Altfan
 			return FanCheck::ExtruderFan;
 		}
 #ifdef FAN_SOFT_PWM
@@ -8622,11 +8347,9 @@ static FanCheck lcd_selftest_fan_auto(int _fan)
 #endif //FAN_SOFT_PWM
 		for (uint8_t i = 0; i < 5; i++) {
 			delay_keep_alive(1000);
-			lcd_set_cursor(18, 3);
-			lcd_print("-");
+			lcd_putc_at(18, 3, '-');
 			delay_keep_alive(1000);
-			lcd_set_cursor(18, 3);
-			lcd_print("|");
+			lcd_putc_at(18, 3, '|');
 		}
 		fanSpeed = 0;
 
@@ -8636,9 +8359,9 @@ static FanCheck lcd_selftest_fan_auto(int _fan)
 		manage_heater();			//turn off fan
 		manage_inactivity(true);	//to turn off print fan
 #endif //FAN_SOFT_PWM
-		printf_P(PSTR("Test 2:\n"));
-		printf_P(PSTR("Print fan speed: %d \n"), fan_speed[1]);
-		printf_P(PSTR("Extr fan speed: %d \n"), fan_speed[0]);
+		puts_P(PSTR("Test 2:"));
+		printf_P(PSTR("Print fan speed: %d\n"), fan_speed[1]);
+		printf_P(PSTR("Extr fan speed: %d\n"), fan_speed[0]);
 		if (!fan_speed[1]) {
 			return FanCheck::PrintFan;
 		}
@@ -8649,11 +8372,9 @@ static FanCheck lcd_selftest_fan_auto(int _fan)
 
 		for (uint8_t i = 0; i < 5; i++) {
 			delay_keep_alive(1000);
-			lcd_set_cursor(18, 3);
-			lcd_print("-");
+			lcd_putc_at(18, 3, '-');
 			delay_keep_alive(1000);
-			lcd_set_cursor(18, 3);
-			lcd_print("|");
+			lcd_putc_at(18, 3, '|');
 		}
 		fanSpeed = 0;
 
@@ -8678,7 +8399,7 @@ static FanCheck lcd_selftest_fan_auto(int _fan)
 static int lcd_selftest_screen(TestScreen screen, int _progress, int _progress_scale, bool _clear, int _delay)
 {
 
-    lcd_update_enable(false);
+	lcd_update_enable(false);
 
 	const char *_indicator = (_progress >= _progress_scale) ? "-" : "|";
 
@@ -8691,8 +8412,8 @@ static int lcd_selftest_screen(TestScreen screen, int _progress, int _progress_s
 	if (screen == TestScreen::PrintFan) lcd_puts_P(_T(MSG_SELFTEST_FAN));
 	if (screen == TestScreen::FansOk) lcd_puts_P(_T(MSG_SELFTEST_FAN));
 	if (screen == TestScreen::EndStops) lcd_puts_P(_i("Checking endstops"));////MSG_SELFTEST_CHECK_ENDSTOPS c=20
-	if (screen == TestScreen::AxisX) lcd_puts_P(_i("Checking X axis  "));////MSG_SELFTEST_CHECK_X c=20
-	if (screen == TestScreen::AxisY) lcd_puts_P(_i("Checking Y axis  "));////MSG_SELFTEST_CHECK_Y c=20
+	if (screen == TestScreen::AxisX) lcd_puts_P(_T(MSG_CHECKING_X));
+	if (screen == TestScreen::AxisY) lcd_puts_P(_T(MSG_CHECKING_Y));
 	if (screen == TestScreen::AxisZ) lcd_puts_P(_i("Checking Z axis  "));////MSG_SELFTEST_CHECK_Z c=20
 	if (screen == TestScreen::Bed) lcd_puts_P(_T(MSG_SELFTEST_CHECK_BED));
 	if (screen == TestScreen::Hotend
@@ -8703,8 +8424,7 @@ static int lcd_selftest_screen(TestScreen screen, int _progress, int _progress_s
 	if (screen == TestScreen::Failed) lcd_puts_P(_T(MSG_SELFTEST_FAILED));
 	if (screen == TestScreen::Home) lcd_puts_P(_i("Calibrating home"));////c=20 r=1
 
-	lcd_set_cursor(0, 1);
-	lcd_puts_P(separator);
+	lcd_puts_at_P(0, 1, separator);
 	if ((screen >= TestScreen::ExtruderFan) && (screen <= TestScreen::FansOk))
 	{
 		//SERIAL_ECHOLNPGM("Fan test");
@@ -8726,20 +8446,20 @@ static int lcd_selftest_screen(TestScreen screen, int _progress, int _progress_s
 	{
 		//SERIAL_ECHOLNPGM("Other tests");
 
-	    TestScreen _step_block = TestScreen::AxisX;
-		lcd_selftest_screen_step(2, 2, ((screen == _step_block) ? 1 : (screen < _step_block) ? 0 : 2), "X", _indicator);
+		TestScreen _step_block = TestScreen::AxisX;
+		lcd_selftest_screen_step(2, 2, ((screen == _step_block) ? 1 : (screen < _step_block) ? 0 : 2), PSTR("X"), _indicator);
 
 		_step_block = TestScreen::AxisY;
-		lcd_selftest_screen_step(2, 8, ((screen == _step_block) ? 1 : (screen < _step_block) ? 0 : 2), "Y", _indicator);
+		lcd_selftest_screen_step(2, 8, ((screen == _step_block) ? 1 : (screen < _step_block) ? 0 : 2), PSTR("Y"), _indicator);
 
 		_step_block = TestScreen::AxisZ;
-		lcd_selftest_screen_step(2, 14, ((screen == _step_block) ? 1 : (screen < _step_block) ? 0 : 2), "Z", _indicator);
+		lcd_selftest_screen_step(2, 14, ((screen == _step_block) ? 1 : (screen < _step_block) ? 0 : 2), PSTR("Z"), _indicator);
 
 		_step_block = TestScreen::Bed;
-		lcd_selftest_screen_step(3, 0, ((screen == _step_block) ? 1 : (screen < _step_block) ? 0 : 2), "Bed", _indicator);
+		lcd_selftest_screen_step(3, 0, ((screen == _step_block) ? 1 : (screen < _step_block) ? 0 : 2), PSTR("Bed"), _indicator);
 
-        _step_block = TestScreen::Hotend;
-        lcd_selftest_screen_step(3, 9, ((screen == _step_block) ? 1 : (screen < _step_block) ? 0 : 2), "Hotend", _indicator);
+		_step_block = TestScreen::Hotend;
+		lcd_selftest_screen_step(3, 9, ((screen == _step_block) ? 1 : (screen < _step_block) ? 0 : 2), PSTR("Hotend"), _indicator);
 	}
 
 	if (_delay > 0) delay_keep_alive(_delay);
@@ -8748,28 +8468,26 @@ static int lcd_selftest_screen(TestScreen screen, int _progress, int _progress_s
 	return (_progress >= _progress_scale * 2) ? 0 : _progress;
 }
 
-static void lcd_selftest_screen_step(int _row, int _col, int _state, const char *_name, const char *_indicator)
+static void lcd_selftest_screen_step(int _row, int _col, int _state, const char *_name_PROGMEM, const char *_indicator)
 {
 	lcd_set_cursor(_col, _row);
+    uint8_t strlenNameP = strlen_P(_name_PROGMEM);
 
 	switch (_state)
 	{
 	case 1:
-		lcd_print(_name);
-		lcd_set_cursor(_col + strlen(_name), _row);
-		lcd_print(":");
-		lcd_set_cursor(_col + strlen(_name) + 1, _row);
+		lcd_puts_P(_name_PROGMEM);
+		lcd_putc_at(_col + strlenNameP, _row, ':');
+		lcd_set_cursor(_col + strlenNameP + 1, _row);
 		lcd_print(_indicator);
 		break;
 	case 2:
-		lcd_print(_name);
-		lcd_set_cursor(_col + strlen(_name), _row);
-		lcd_print(":");
-		lcd_set_cursor(_col + strlen(_name) + 1, _row);
-		lcd_print("OK");
+		lcd_puts_P(_name_PROGMEM);
+		lcd_putc_at(_col + strlenNameP, _row, ':');
+		lcd_puts_at_P(_col + strlenNameP + 1, _row, PSTR("OK"));
 		break;
 	default:
-		lcd_print(_name);
+		lcd_puts_P(_name_PROGMEM);
 	}
 }
 
@@ -8780,26 +8498,42 @@ static void lcd_selftest_screen_step(int _row, int _col, int _state, const char
 
 static bool check_file(const char* filename) {
 	if (farm_mode) return true;
-	bool result = false;
-	uint32_t filesize;
 	card.openFile((char*)filename, true);
-	filesize = card.getFileSize();
+	bool result = false;
+	const uint32_t filesize = card.getFileSize();
+	uint32_t startPos = 0;
+	const uint16_t bytesToCheck = min(END_FILE_SECTION, filesize);
+	uint8_t blocksPrinted = 0;
 	if (filesize > END_FILE_SECTION) {
-		card.setIndex(filesize - END_FILE_SECTION);
-		
+		startPos = filesize - END_FILE_SECTION;
+		card.setIndex(startPos);
 	}
-	
-		while (!card.eof() && !result) {
+	cmdqueue_reset();
+	cmdqueue_serial_disabled = true;
+
+	lcd_clear();
+	lcd_puts_at_P(0, 1, _i("Checking file"));////c=20 r=1
+	lcd_set_cursor(0, 2);
+	while (!card.eof() && !result) {
+		for (; blocksPrinted < (((card.get_sdpos() - startPos) * LCD_WIDTH) / bytesToCheck); blocksPrinted++)
+			lcd_print('\xFF'); //simple progress bar
+
 		card.sdprinting = true;
 		get_command();
 		result = check_commands();
-		
 	}
+
+	for (; blocksPrinted < LCD_WIDTH; blocksPrinted++)
+		lcd_print('\xFF'); //simple progress bar
+	_delay(100); //for the user to see the end of the progress bar.
+
+	
+	cmdqueue_serial_disabled = false;
 	card.printingHasFinished();
+
 	strncpy_P(lcd_status_message, _T(WELCOME_MSG), LCD_WIDTH);
 	lcd_finishstatus();
 	return result;
-	
 }
 
 static void menu_action_sdfile(const char* filename)
@@ -8836,7 +8570,7 @@ static void menu_action_sdfile(const char* filename)
   }
   
   if (!check_file(filename)) {
-	  result = lcd_show_fullscreen_message_yes_no_and_wait_P(_i("File incomplete. Continue anyway?"), false, false);////MSG_FILE_INCOMPLETE c=20 r=2
+	  result = lcd_show_fullscreen_message_yes_no_and_wait_P(_i("File incomplete. Continue anyway?"), false, false);////MSG_FILE_INCOMPLETE c=20 r=3
 	  lcd_update_enable(true);
   }
   if (result) {
@@ -8967,6 +8701,7 @@ void lcd_ignore_click(bool b)
 }
 
 void lcd_finishstatus() {
+  SERIAL_PROTOCOLLNRPGM(MSG_LCD_STATUS_CHANGED);
   int len = strlen(lcd_status_message);
   if (len > 0) {
     while (len < LCD_WIDTH) {
@@ -8977,13 +8712,14 @@ void lcd_finishstatus() {
   lcd_draw_update = 2;
 
 }
+
 void lcd_setstatus(const char* message)
 {
   if (lcd_status_message_level > 0)
     return;
-  strncpy(lcd_status_message, message, LCD_WIDTH);
-  lcd_finishstatus();
+  lcd_updatestatus(message);
 }
+
 void lcd_updatestatuspgm(const char *message){
 	strncpy_P(lcd_status_message, message, LCD_WIDTH);
 	lcd_status_message[LCD_WIDTH] = 0;
@@ -8998,12 +8734,29 @@ void lcd_setstatuspgm(const char* message)
     return;
   lcd_updatestatuspgm(message);
 }
+
+void lcd_updatestatus(const char *message){
+	strncpy(lcd_status_message, message, LCD_WIDTH);
+	lcd_status_message[LCD_WIDTH] = 0;
+	lcd_finishstatus();
+	// hack lcd_draw_update to 1, i.e. without clear
+	lcd_draw_update = 1;
+}
+
 void lcd_setalertstatuspgm(const char* message)
 {
   lcd_setstatuspgm(message);
   lcd_status_message_level = 1;
   lcd_return_to_status();
 }
+
+void lcd_setalertstatus(const char* message)
+{
+  lcd_setstatus(message);
+  lcd_status_message_level = 1;
+  lcd_return_to_status();
+}
+
 void lcd_reset_alert_level()
 {
   lcd_status_message_level = 0;
@@ -9023,6 +8776,13 @@ void menu_lcd_longpress_func(void)
         lcd_quick_feedback();
         return;
     }
+    if (menu_menu == lcd_hw_setup_menu)
+    {
+        // only toggle the experimental menu visibility flag
+        lcd_quick_feedback();
+        lcd_experimental_toggle();
+        return;
+    }
 
     // explicitely listed menus which are allowed to rise the move-z or live-adj-z functions
     // The lists are not the same for both functions, so first decide which function is to be performed
@@ -9186,3 +8946,39 @@ void lcd_crash_detect_disable()
     eeprom_update_byte((uint8_t*)EEPROM_CRASH_DET, 0x00);
 }
 #endif
+
+void lcd_experimental_toggle()
+{
+    uint8_t oldVal = eeprom_read_byte((uint8_t *)EEPROM_EXPERIMENTAL_VISIBILITY);
+    if (oldVal == EEPROM_EMPTY_VALUE)
+        oldVal = 0;
+    else
+        oldVal = !oldVal;
+    eeprom_update_byte((uint8_t *)EEPROM_EXPERIMENTAL_VISIBILITY, oldVal);
+}
+
+void lcd_experimental_menu()
+{
+    MENU_BEGIN();
+    MENU_ITEM_BACK_P(_T(MSG_BACK));
+
+#ifdef EXTRUDER_ALTFAN_DETECT
+    MENU_ITEM_TOGGLE_P(_N("ALTFAN det."), altfanOverride_get()?_T(MSG_OFF):_T(MSG_ON), altfanOverride_toggle);////MSG_MENU_ALTFAN c=18
+#endif //EXTRUDER_ALTFAN_DETECT
+
+    MENU_END();
+}
+
+#ifdef PINDA_TEMP_COMP
+void lcd_pinda_temp_compensation_toggle()
+{
+	uint8_t pinda_temp_compensation = eeprom_read_byte((uint8_t*)EEPROM_PINDA_TEMP_COMPENSATION);
+	if (pinda_temp_compensation == EEPROM_EMPTY_VALUE) // On MK2.5/S the EEPROM_EMPTY_VALUE will be set to 0 during eeprom_init.
+		pinda_temp_compensation = 1;                   // But for MK3/S it should be 1 so SuperPINDA is "active"
+	else
+		pinda_temp_compensation = !pinda_temp_compensation;
+	eeprom_update_byte((uint8_t*)EEPROM_PINDA_TEMP_COMPENSATION, pinda_temp_compensation);
+	SERIAL_ECHOLNPGM("SuperPINDA:");
+	SERIAL_ECHOLN(pinda_temp_compensation);
+}
+#endif //PINDA_TEMP_COMP

+ 10 - 10
Firmware/ultralcd.h

@@ -23,9 +23,11 @@ void lcd_setstatuspgm(const char* message);
 //! - always returns the display to the main status screen
 //! - always makes lcd_reset (which is slow and causes flicker)
 //! - does not update the message if there is already one (i.e. lcd_status_message_level > 0)
+void lcd_setalertstatus(const char* message);
 void lcd_setalertstatuspgm(const char* message);
 //! only update the alert message on the main status screen
 //! has no sideeffects, may be called multiple times
+void lcd_updatestatus(const char *message);
 void lcd_updatestatuspgm(const char *message);
 
 void lcd_reset_alert_level();
@@ -45,7 +47,6 @@ void lcd_pause_print();
 void lcd_resume_print();
 void lcd_print_stop();
 void prusa_statistics(int _message, uint8_t _col_nr = 0);
-void lcd_confirm_print();
 unsigned char lcd_choose_color();
 void lcd_load_filament_color_check();
 //void lcd_mylang();
@@ -125,7 +126,6 @@ extern CustomMsg custom_message_type;
 extern unsigned int custom_message_state;
 
 extern uint8_t farm_mode;
-extern int farm_no;
 extern int farm_timer;
 extern uint8_t farm_status;
 
@@ -142,7 +142,7 @@ extern uint8_t farm_status;
 
 #ifdef IR_SENSOR_ANALOG
 extern bool bMenuFSDetect;
-void printf_IRSensorAnalogBoardChange(bool bPCBrev03b);
+void printf_IRSensorAnalogBoardChange();
 #endif //IR_SENSOR_ANALOG
 
 extern int8_t SilentModeMenu;
@@ -205,6 +205,7 @@ void lcd_farm_sdcard_menu_w();
 
 void lcd_wait_for_heater();
 void lcd_wait_for_cool_down();
+void lcd_move_e(); // NOT static due to usage in Marlin_main
 void lcd_extr_cal_reset();
 
 void lcd_temp_cal_show_result(bool result);
@@ -257,12 +258,11 @@ enum class WizState : uint8_t
 
 void lcd_wizard(WizState state);
 
-#define VOLT_DIV_REF 5
-#ifdef IR_SENSOR_ANALOG
-#define IRsensor_Hmin_TRESHOLD (3.0*1023*OVERSAMPLENR/VOLT_DIV_REF) // ~3.0V (0.6*Vcc)
-#define IRsensor_Lmax_TRESHOLD (1.5*1023*OVERSAMPLENR/VOLT_DIV_REF) // ~1.5V (0.3*Vcc)
-#define IRsensor_Hopen_TRESHOLD (4.6*1023*OVERSAMPLENR/VOLT_DIV_REF) // ~4.6V (N.C. @ Ru~20-50k, Rd'=56k, Ru'=10k)
-#define IRsensor_Ldiode_TRESHOLD (0.3*1023*OVERSAMPLENR/VOLT_DIV_REF) // ~0.3V
-#endif //IR_SENSOR_ANALOG
+extern void lcd_experimental_toggle();
+extern void lcd_experimental_menu();
+
+#ifdef PINDA_TEMP_COMP
+extern void lcd_pinda_temp_compensation_toggle();
+#endif //PINDA_TEMP_COMP
 
 #endif //ULTRALCD_H

+ 11 - 4
Firmware/util.cpp

@@ -4,6 +4,7 @@
 #include "sound.h"
 #include "language.h"
 #include "util.h"
+#include <avr/pgmspace.h>
 
 // Allocate the version string in the program memory. Otherwise the string lands either on the stack or in the global RAM.
 const char FW_VERSION_STR[] PROGMEM = FW_VERSION;
@@ -428,13 +429,13 @@ switch(oCheckModel)
      {
      case ClCheckModel::_Warn:
 //          lcd_show_fullscreen_message_and_wait_P(_i("Printer model differs from the G-code. Continue?"));
-lcd_display_message_fullscreen_P(_i("G-code sliced for a different printer type. Continue?"));
+lcd_display_message_fullscreen_P(_T(MSG_GCODE_DIFF_PRINTER_CONTINUE));
 lcd_wait_for_click_delay(MSG_PRINT_CHECKING_FAILED_TIMEOUT);
 //???custom_message_type=CUSTOM_MSG_TYPE_STATUS; // display / status-line recovery
 lcd_update_enable(true);           // display / status-line recovery
           break;
      case ClCheckModel::_Strict:
-          lcd_show_fullscreen_message_and_wait_P(_i("G-code sliced for a different printer type. Please re-slice the model again. Print cancelled."));
+          lcd_show_fullscreen_message_and_wait_P(_T(MSG_GCODE_DIFF_PRINTER_CANCELLED));
           lcd_print_stop();
           break;
      case ClCheckModel::_None:
@@ -577,13 +578,13 @@ switch(oCheckModel)
      {
      case ClCheckModel::_Warn:
 //          lcd_show_fullscreen_message_and_wait_P(_i("Printer model differs from the G-code. Continue?"));
-lcd_display_message_fullscreen_P(_i("G-code sliced for a different printer type. Continue?"));
+lcd_display_message_fullscreen_P(_T(MSG_GCODE_DIFF_PRINTER_CONTINUE));
 lcd_wait_for_click_delay(MSG_PRINT_CHECKING_FAILED_TIMEOUT);
 //???custom_message_type=CUSTOM_MSG_TYPE_STATUS; // display / status-line recovery
 lcd_update_enable(true);           // display / status-line recovery
           break;
      case ClCheckModel::_Strict:
-          lcd_show_fullscreen_message_and_wait_P(_i("G-code sliced for a different printer type. Please re-slice the model again. Print cancelled."));
+          lcd_show_fullscreen_message_and_wait_P(_T(MSG_GCODE_DIFF_PRINTER_CANCELLED));
           lcd_print_stop();
           break;
      case ClCheckModel::_None:
@@ -604,3 +605,9 @@ else {
      sPrinterName=_sPrinterName;
      }
 }
+
+
+void ip4_to_str(char* dest, uint8_t* IP)
+{
+    sprintf_P(dest, PSTR("%u.%u.%u.%u"), IP[0], IP[1], IP[2], IP[3]);
+}

+ 4 - 0
Firmware/util.h

@@ -51,6 +51,7 @@ enum class ClNozzleDiameter:uint_least8_t
     _Diameter_250=25,
     _Diameter_400=40,
     _Diameter_600=60,
+    _Diameter_800=80,
     _Diameter_Undef=EEPROM_EMPTY_VALUE
 };
 
@@ -109,4 +110,7 @@ void gcode_level_check(uint16_t nGcodeLevel);
 
 void fSetMmuMode(bool bMMu);
 
+#define IP4_STR_SIZE 16
+extern void ip4_to_str(char* dest, uint8_t* IP);
+
 #endif /* UTIL_H */

+ 10 - 1
Firmware/variants/1_75mm_MK2-RAMBo10a-E3Dv6full.h

@@ -90,8 +90,9 @@ AXIS SETTINGS
 #define DEFAULT_MAX_ACCELERATION      {9000,9000,500,10000}    // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for Skeinforge 40+, for older versions raise them a lot.
 #define DEFAULT_MAX_ACCELERATION_SILENT     {960, 960, 200, 5000}    // (mm/sec^2) max acceleration (M201), silent mode
 
-#define DEFAULT_ACCELERATION          1500    // X, Y, Z and E max acceleration in mm/s^2 for printing moves
+#define DEFAULT_ACCELERATION          1500   // X, Y, Z and E max acceleration in mm/s^2 for printing moves
 #define DEFAULT_RETRACT_ACCELERATION  1500   // X, Y, Z and E max acceleration in mm/s^2 for retracts
+#define DEFAULT_TRAVEL_ACCELERATION   1500   // X, Y, Z and E max acceleration in mm/s^2 for travels
 
 
 #define MANUAL_FEEDRATE {3000, 3000, 1000, 100}   // set the speeds for manual moves (mm/min)
@@ -326,10 +327,18 @@ PREHEAT SETTINGS
 #define PLA_PREHEAT_HPB_TEMP 55
 #define PLA_PREHEAT_FAN_SPEED 0
 
+#define PVB_PREHEAT_HOTEND_TEMP 215
+#define PVB_PREHEAT_HPB_TEMP 75
+#define PVB_PREHEAT_FAN_SPEED 0
+
 #define ASA_PREHEAT_HOTEND_TEMP 260
 #define ASA_PREHEAT_HPB_TEMP 105
 #define ASA_PREHEAT_FAN_SPEED 0
 
+#define PC_PREHEAT_HOTEND_TEMP 275
+#define PC_PREHEAT_HPB_TEMP 105
+#define PC_PREHEAT_FAN_SPEED 0
+
 #define ABS_PREHEAT_HOTEND_TEMP 255
 #define ABS_PREHEAT_HPB_TEMP 100
 #define ABS_PREHEAT_FAN_SPEED 0 

+ 8 - 1
Firmware/variants/1_75mm_MK2-RAMBo13a-E3Dv6full.h

@@ -90,8 +90,9 @@ AXIS SETTINGS
 #define DEFAULT_MAX_ACCELERATION      {9000,9000,500,10000}    // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for Skeinforge 40+, for older versions raise them a lot.
 #define DEFAULT_MAX_ACCELERATION_SILENT     {960, 960, 200, 5000}    // (mm/sec^2) max acceleration (M201), silent mode
 
-#define DEFAULT_ACCELERATION          1500    // X, Y, Z and E max acceleration in mm/s^2 for printing moves
+#define DEFAULT_ACCELERATION          1500   // X, Y, Z and E max acceleration in mm/s^2 for printing moves
 #define DEFAULT_RETRACT_ACCELERATION  1500   // X, Y, Z and E max acceleration in mm/s^2 for retracts
+#define DEFAULT_TRAVEL_ACCELERATION   1500   // X, Y, Z and E max acceleration in mm/s^2 for travels
 
 
 #define MANUAL_FEEDRATE {3000, 3000, 1000, 100}   // set the speeds for manual moves (mm/min)
@@ -323,9 +324,15 @@ PREHEAT SETTINGS
 #define PLA_PREHEAT_HOTEND_TEMP 215
 #define PLA_PREHEAT_HPB_TEMP 55
 
+#define PVB_PREHEAT_HOTEND_TEMP 215
+#define PVB_PREHEAT_HPB_TEMP 75
+
 #define ASA_PREHEAT_HOTEND_TEMP 260
 #define ASA_PREHEAT_HPB_TEMP 105
 
+#define PC_PREHEAT_HOTEND_TEMP 275
+#define PC_PREHEAT_HPB_TEMP 105
+
 #define ABS_PREHEAT_HOTEND_TEMP 255
 #define ABS_PREHEAT_HPB_TEMP 100
 

+ 12 - 2
Firmware/variants/1_75mm_MK25-RAMBo10a-E3Dv6full.h

@@ -94,8 +94,9 @@
 #define DEFAULT_MAX_ACCELERATION      {1000, 1000, 200, 5000}  // (mm/sec^2) max acceleration (M201)
 #define DEFAULT_MAX_ACCELERATION_SILENT     {960, 960, 200, 5000}    // (mm/sec^2) max acceleration (M201), silent mode
 
-#define DEFAULT_ACCELERATION          1250   // X, Y, Z and E max acceleration in mm/s^2 for printing moves (M204S)
-#define DEFAULT_RETRACT_ACCELERATION  1250   // X, Y, Z and E max acceleration in mm/s^2 for retracts (M204T)
+#define DEFAULT_ACCELERATION          1250   // X, Y, Z and E max acceleration in mm/s^2 for printing moves (M204P)
+#define DEFAULT_RETRACT_ACCELERATION  1250   // X, Y, Z and E max acceleration in mm/s^2 for retracts (M204R)
+#define DEFAULT_TRAVEL_ACCELERATION   1250   // X, Y, Z and E max acceleration in mm/s^2 for travels (M204T)
 
 #define MANUAL_FEEDRATE {2700, 2700, 1000, 100}   // set the speeds for manual moves (mm/min)
 
@@ -175,6 +176,9 @@
 #if BED_MINTEMP_DELAY>USHRT_MAX
 #error "Check maximal allowed value @ ShortTimer (see BED_MINTEMP_DELAY definition)"
 #endif
+#define SUPERPINDA_SUPPORT
+#define PINDA_MINTEMP 30 //The miniRAMBo thermistor readings below 30°C aren't very accurate
+#define PINDA_TEMP_COMP //Used to enable SuperPINDA toggle menu/function
 
 // Maxtemps
 #if defined(E3D_PT100_EXTRUDER_WITH_AMP) || defined(E3D_PT100_EXTRUDER_NO_AMP)
@@ -381,9 +385,15 @@
 #define PLA_PREHEAT_HOTEND_TEMP 215
 #define PLA_PREHEAT_HPB_TEMP 60
 
+#define PVB_PREHEAT_HOTEND_TEMP 215
+#define PVB_PREHEAT_HPB_TEMP 75
+
 #define ASA_PREHEAT_HOTEND_TEMP 260
 #define ASA_PREHEAT_HPB_TEMP 105
 
+#define PC_PREHEAT_HOTEND_TEMP 275
+#define PC_PREHEAT_HPB_TEMP 105
+
 #define ABS_PREHEAT_HOTEND_TEMP 255
 #define ABS_PREHEAT_HPB_TEMP 100
 

+ 12 - 2
Firmware/variants/1_75mm_MK25-RAMBo13a-E3Dv6full.h

@@ -95,8 +95,9 @@
 #define DEFAULT_MAX_ACCELERATION_SILENT     {960, 960, 200, 5000}    // (mm/sec^2) max acceleration (M201), silent mode
 
 
-#define DEFAULT_ACCELERATION          1250   // X, Y, Z and E max acceleration in mm/s^2 for printing moves (M204S)
-#define DEFAULT_RETRACT_ACCELERATION  1250   // X, Y, Z and E max acceleration in mm/s^2 for retracts (M204T)
+#define DEFAULT_ACCELERATION          1250   // X, Y, Z and E max acceleration in mm/s^2 for printing moves (M204P)
+#define DEFAULT_RETRACT_ACCELERATION  1250   // X, Y, Z and E max acceleration in mm/s^2 for retracts (M204R)
+#define DEFAULT_TRAVEL_ACCELERATION   1250   // X, Y, Z and E max acceleration in mm/s^2 for travels (M204T)
 
 #define MANUAL_FEEDRATE {2700, 2700, 1000, 100}   // set the speeds for manual moves (mm/min)
 
@@ -176,6 +177,9 @@
 #if BED_MINTEMP_DELAY>USHRT_MAX
 #error "Check maximal allowed value @ ShortTimer (see BED_MINTEMP_DELAY definition)"
 #endif
+#define SUPERPINDA_SUPPORT
+#define PINDA_MINTEMP 30 //The miniRAMBo thermistor readings below 30°C aren't very accurate
+#define PINDA_TEMP_COMP //Used to enable SuperPINDA toggle menu/function
 
 // Maxtemps
 #if defined(E3D_PT100_EXTRUDER_WITH_AMP) || defined(E3D_PT100_EXTRUDER_NO_AMP)
@@ -382,9 +386,15 @@
 #define PLA_PREHEAT_HOTEND_TEMP 215
 #define PLA_PREHEAT_HPB_TEMP 60
 
+#define PVB_PREHEAT_HOTEND_TEMP 215
+#define PVB_PREHEAT_HPB_TEMP 75
+
 #define ASA_PREHEAT_HOTEND_TEMP 260
 #define ASA_PREHEAT_HPB_TEMP 105
 
+#define PC_PREHEAT_HOTEND_TEMP 275
+#define PC_PREHEAT_HPB_TEMP 105
+
 #define ABS_PREHEAT_HOTEND_TEMP 255
 #define ABS_PREHEAT_HPB_TEMP 100
 

+ 12 - 2
Firmware/variants/1_75mm_MK25S-RAMBo10a-E3Dv6full.h

@@ -94,8 +94,9 @@
 #define DEFAULT_MAX_ACCELERATION      {1000, 1000, 200, 5000}  // (mm/sec^2) max acceleration (M201)
 #define DEFAULT_MAX_ACCELERATION_SILENT     {960, 960, 200, 5000}    // (mm/sec^2) max acceleration (M201), silent mode
 
-#define DEFAULT_ACCELERATION          1250   // X, Y, Z and E max acceleration in mm/s^2 for printing moves (M204S)
-#define DEFAULT_RETRACT_ACCELERATION  1250   // X, Y, Z and E max acceleration in mm/s^2 for retracts (M204T)
+#define DEFAULT_ACCELERATION          1250   // X, Y, Z and E max acceleration in mm/s^2 for printing moves (M204P)
+#define DEFAULT_RETRACT_ACCELERATION  1250   // X, Y, Z and E max acceleration in mm/s^2 for retracts (M204R)
+#define DEFAULT_TRAVEL_ACCELERATION   1250   // X, Y, Z and E max acceleration in mm/s^2 for travels (M204T)
 
 #define MANUAL_FEEDRATE {2700, 2700, 1000, 100}   // set the speeds for manual moves (mm/min)
 
@@ -175,6 +176,9 @@
 #if BED_MINTEMP_DELAY>USHRT_MAX
 #error "Check maximal allowed value @ ShortTimer (see BED_MINTEMP_DELAY definition)"
 #endif
+#define SUPERPINDA_SUPPORT
+#define PINDA_MINTEMP 30 //The miniRAMBo thermistor readings below 30°C aren't very accurate
+#define PINDA_TEMP_COMP //Used to enable SuperPINDA toggle menu/function
 
 // Maxtemps
 #if defined(E3D_PT100_EXTRUDER_WITH_AMP) || defined(E3D_PT100_EXTRUDER_NO_AMP)
@@ -381,9 +385,15 @@
 #define PLA_PREHEAT_HOTEND_TEMP 215
 #define PLA_PREHEAT_HPB_TEMP 60
 
+#define PVB_PREHEAT_HOTEND_TEMP 215
+#define PVB_PREHEAT_HPB_TEMP 75
+
 #define ASA_PREHEAT_HOTEND_TEMP 260
 #define ASA_PREHEAT_HPB_TEMP 105
 
+#define PC_PREHEAT_HOTEND_TEMP 275
+#define PC_PREHEAT_HPB_TEMP 105
+
 #define ABS_PREHEAT_HOTEND_TEMP 255
 #define ABS_PREHEAT_HPB_TEMP 100
 

+ 12 - 2
Firmware/variants/1_75mm_MK25S-RAMBo13a-E3Dv6full.h

@@ -95,8 +95,9 @@
 #define DEFAULT_MAX_ACCELERATION_SILENT     {960, 960, 200, 5000}    // (mm/sec^2) max acceleration (M201), silent mode
 
 
-#define DEFAULT_ACCELERATION          1250   // X, Y, Z and E max acceleration in mm/s^2 for printing moves (M204S)
-#define DEFAULT_RETRACT_ACCELERATION  1250   // X, Y, Z and E max acceleration in mm/s^2 for retracts (M204T)
+#define DEFAULT_ACCELERATION          1250   // X, Y, Z and E max acceleration in mm/s^2 for printing moves (M204P)
+#define DEFAULT_RETRACT_ACCELERATION  1250   // X, Y, Z and E max acceleration in mm/s^2 for retracts (M204R)
+#define DEFAULT_TRAVEL_ACCELERATION   1250   // X, Y, Z and E max acceleration in mm/s^2 for travels (M204T)
 
 #define MANUAL_FEEDRATE {2700, 2700, 1000, 100}   // set the speeds for manual moves (mm/min)
 
@@ -176,6 +177,9 @@
 #if BED_MINTEMP_DELAY>USHRT_MAX
 #error "Check maximal allowed value @ ShortTimer (see BED_MINTEMP_DELAY definition)"
 #endif
+#define SUPERPINDA_SUPPORT
+#define PINDA_MINTEMP 30 //The miniRAMBo thermistor readings below 30°C aren't very accurate
+#define PINDA_TEMP_COMP //Used to enable SuperPINDA toggle menu/function
 
 // Maxtemps
 #if defined(E3D_PT100_EXTRUDER_WITH_AMP) || defined(E3D_PT100_EXTRUDER_NO_AMP)
@@ -382,9 +386,15 @@
 #define PLA_PREHEAT_HOTEND_TEMP 215
 #define PLA_PREHEAT_HPB_TEMP 60
 
+#define PVB_PREHEAT_HOTEND_TEMP 215
+#define PVB_PREHEAT_HPB_TEMP 75
+
 #define ASA_PREHEAT_HOTEND_TEMP 260
 #define ASA_PREHEAT_HPB_TEMP 105
 
+#define PC_PREHEAT_HOTEND_TEMP 275
+#define PC_PREHEAT_HPB_TEMP 105
+
 #define ABS_PREHEAT_HOTEND_TEMP 255
 #define ABS_PREHEAT_HPB_TEMP 100
 

+ 15 - 3
Firmware/variants/1_75mm_MK3-EINSy10a-E3Dv6full.h

@@ -99,8 +99,9 @@
 #define DEFAULT_MAX_ACCELERATION_SILENT     {960, 960, 200, 5000}    // (mm/sec^2) max acceleration (M201), silent mode
 
 
-#define DEFAULT_ACCELERATION          1250   // X, Y, Z and E max acceleration in mm/s^2 for printing moves (M204S)
-#define DEFAULT_RETRACT_ACCELERATION  1250   // X, Y, Z and E max acceleration in mm/s^2 for retracts (M204T)
+#define DEFAULT_ACCELERATION          1250   // X, Y, Z and E max acceleration in mm/s^2 for printing moves (M204P)
+#define DEFAULT_RETRACT_ACCELERATION  1250   // X, Y, Z and E max acceleration in mm/s^2 for retracts (M204R)
+#define DEFAULT_TRAVEL_ACCELERATION   1250   // X, Y, Z and E max acceleration in mm/s^2 for travels (M204T)
 
 #define MANUAL_FEEDRATE {2700, 2700, 1000, 100}   // set the speeds for manual moves (mm/min)
 
@@ -266,9 +267,9 @@
 #define TMC2130_CURRENTS_H {16, 20, 35, 30}  // default holding currents for all axes
 #define TMC2130_CURRENTS_R {16, 20, 35, 30}  // default running currents for all axes
 #define TMC2130_CURRENTS_R_HOME {8, 10, 20, 18}  // homing running currents for all axes
-// #define TMC2130_UNLOAD_CURRENT_R 12			 // lower current for M600 to protect filament sensor - Unused
 
 #define TMC2130_STEALTH_Z
+#define TMC2130_DEDGE_STEPPING
 
 //#define TMC2130_SERVICE_CODES_M910_M918
 
@@ -294,6 +295,10 @@
 #if BED_MINTEMP_DELAY>USHRT_MAX
 #error "Check maximal allowed value @ ShortTimer (see BED_MINTEMP_DELAY definition)"
 #endif
+#define SUPERPINDA_SUPPORT
+#define PINDA_MINTEMP 10
+//#define PINDA_TEMP_COMP //Used to enable SuperPINDA toggle menu/function
+#define AMBIENT_MINTEMP -30
 
 // Maxtemps
 #if defined(E3D_PT100_EXTRUDER_WITH_AMP) || defined(E3D_PT100_EXTRUDER_NO_AMP)
@@ -304,6 +309,7 @@
 #define HEATER_1_MAXTEMP 305
 #define HEATER_2_MAXTEMP 305
 #define BED_MAXTEMP 125
+#define AMBIENT_MAXTEMP 100
 
 #if defined(E3D_PT100_EXTRUDER_WITH_AMP) || defined(E3D_PT100_EXTRUDER_NO_AMP)
 // Define PID constants for extruder with PT100
@@ -493,9 +499,15 @@
 #define PLA_PREHEAT_HOTEND_TEMP 215
 #define PLA_PREHEAT_HPB_TEMP 60
 
+#define PVB_PREHEAT_HOTEND_TEMP 215
+#define PVB_PREHEAT_HPB_TEMP 75
+
 #define ASA_PREHEAT_HOTEND_TEMP 260
 #define ASA_PREHEAT_HPB_TEMP 105
 
+#define PC_PREHEAT_HOTEND_TEMP 275
+#define PC_PREHEAT_HPB_TEMP 110
+
 #define ABS_PREHEAT_HOTEND_TEMP 255
 #define ABS_PREHEAT_HPB_TEMP 100
 

+ 17 - 3
Firmware/variants/1_75mm_MK3S-EINSy10a-E3Dv6full.h

@@ -101,8 +101,9 @@
 #define DEFAULT_MAX_ACCELERATION_SILENT     {960, 960, 200, 5000}    // (mm/sec^2) max acceleration (M201), silent mode
 
 
-#define DEFAULT_ACCELERATION          1250   // X, Y, Z and E max acceleration in mm/s^2 for printing moves (M204S)
-#define DEFAULT_RETRACT_ACCELERATION  1250   // X, Y, Z and E max acceleration in mm/s^2 for retracts (M204T)
+#define DEFAULT_ACCELERATION          1250   // X, Y, Z and E max acceleration in mm/s^2 for printing moves (M204P)
+#define DEFAULT_RETRACT_ACCELERATION  1250   // X, Y, Z and E max acceleration in mm/s^2 for retracts (M204R)
+#define DEFAULT_TRAVEL_ACCELERATION   1250   // X, Y, Z and E max acceleration in mm/s^2 for travels (M204T)
 
 #define MANUAL_FEEDRATE {2700, 2700, 1000, 100}   // set the speeds for manual moves (mm/min)
 
@@ -268,9 +269,9 @@
 #define TMC2130_CURRENTS_H {16, 20, 35, 30}  // default holding currents for all axes
 #define TMC2130_CURRENTS_R {16, 20, 35, 30}  // default running currents for all axes
 #define TMC2130_CURRENTS_R_HOME {8, 10, 20, 18}  // homing running currents for all axes
-// #define TMC2130_UNLOAD_CURRENT_R 12			 // lower current for M600 to protect filament sensor - Unused
 
 #define TMC2130_STEALTH_Z
+#define TMC2130_DEDGE_STEPPING
 
 //#define TMC2130_SERVICE_CODES_M910_M918
 
@@ -296,6 +297,10 @@
 #if BED_MINTEMP_DELAY>USHRT_MAX
 #error "Check maximal allowed value @ ShortTimer (see BED_MINTEMP_DELAY definition)"
 #endif
+#define SUPERPINDA_SUPPORT
+#define PINDA_MINTEMP 10
+//#define PINDA_TEMP_COMP //Used to enable SuperPINDA toggle menu/function
+#define AMBIENT_MINTEMP -30
 
 // Maxtemps
 #if defined(E3D_PT100_EXTRUDER_WITH_AMP) || defined(E3D_PT100_EXTRUDER_NO_AMP)
@@ -306,6 +311,7 @@
 #define HEATER_1_MAXTEMP 305
 #define HEATER_2_MAXTEMP 305
 #define BED_MAXTEMP 125
+#define AMBIENT_MAXTEMP 100
 
 #if defined(E3D_PT100_EXTRUDER_WITH_AMP) || defined(E3D_PT100_EXTRUDER_NO_AMP)
 // Define PID constants for extruder with PT100
@@ -331,6 +337,8 @@
 #define EXTRUDER_2_AUTO_FAN_PIN   -1
 #define EXTRUDER_AUTO_FAN_TEMPERATURE 50
 #define EXTRUDER_AUTO_FAN_SPEED   255  // == full speed
+#define EXTRUDER_ALTFAN_DETECT
+#define EXTRUDER_ALTFAN_SPEED_SILENT 128
 
 
 
@@ -495,9 +503,15 @@
 #define PLA_PREHEAT_HOTEND_TEMP 215
 #define PLA_PREHEAT_HPB_TEMP 60
 
+#define PVB_PREHEAT_HOTEND_TEMP 215
+#define PVB_PREHEAT_HPB_TEMP 75
+
 #define ASA_PREHEAT_HOTEND_TEMP 260
 #define ASA_PREHEAT_HPB_TEMP 105
 
+#define PC_PREHEAT_HOTEND_TEMP 275
+#define PC_PREHEAT_HPB_TEMP 110
+
 #define ABS_PREHEAT_HOTEND_TEMP 255
 #define ABS_PREHEAT_HPB_TEMP 100
 

+ 4 - 4
Firmware/w25x20cl.c

@@ -3,8 +3,8 @@
 #include "w25x20cl.h"
 #include <avr/io.h>
 #include <avr/pgmspace.h>
-#include "io_atmega2560.h"
 #include "spi.h"
+#include "fastio.h"
 
 #define _MFRID             0xEF
 #define _DEVID             0x11
@@ -31,8 +31,8 @@
 #define _CMD_JEDEC_ID      0x9f
 #define _CMD_RD_UID        0x4b
 
-#define _CS_LOW()  PORT(W25X20CL_PIN_CS) &= ~__MSK(W25X20CL_PIN_CS)
-#define _CS_HIGH() PORT(W25X20CL_PIN_CS) |= __MSK(W25X20CL_PIN_CS)
+#define _CS_LOW() WRITE(W25X20CL_PIN_CS, 0)
+#define _CS_HIGH() WRITE(W25X20CL_PIN_CS, 1)
 
 //#define _SPI_TX swspi_tx
 //#define _SPI_RX swspi_rx
@@ -45,8 +45,8 @@ int w25x20cl_mfrid_devid(void);
 
 int8_t w25x20cl_init(void)
 {
-	PIN_OUT(W25X20CL_PIN_CS);
 	_CS_HIGH();
+	SET_OUTPUT(W25X20CL_PIN_CS);
 	W25X20CL_SPI_ENTER();
 	if (!w25x20cl_mfrid_devid()) return 0;
 	return 1;

+ 633 - 460
Firmware/xyzcal.cpp

@@ -9,7 +9,6 @@
 #include "temperature.h"
 #include "sm4.h"
 
-
 #define XYZCAL_PINDA_HYST_MIN 20  //50um
 #define XYZCAL_PINDA_HYST_MAX 100 //250um
 #define XYZCAL_PINDA_HYST_DIF 5   //12.5um
@@ -19,6 +18,8 @@
 
 #define _PINDA ((READ(Z_MIN_PIN) != Z_MIN_ENDSTOP_INVERTING)?1:0)
 
+static const char endl[2] PROGMEM = "\n";
+
 #define DBG(args...) printf_P(args)
 //#define DBG(args...)
 #ifndef _n
@@ -30,13 +31,109 @@
 #define _Z ((int16_t)count_position[Z_AXIS])
 #define _E ((int16_t)count_position[E_AXIS])
 
-#define _PI 3.14159265F
+#define _X_ (count_position[X_AXIS])
+#define _Y_ (count_position[Y_AXIS])
+#define _Z_ (count_position[Z_AXIS])
+#define _E_ (count_position[E_AXIS])
+
+#ifndef M_PI
+const constexpr float M_PI = 3.1415926535897932384626433832795f;
+#endif
+
+const constexpr uint8_t X_PLUS = 0;
+const constexpr uint8_t X_MINUS = 1;
+const constexpr uint8_t Y_PLUS = 0;
+const constexpr uint8_t Y_MINUS = 1;
+const constexpr uint8_t Z_PLUS = 0;
+const constexpr uint8_t Z_MINUS = 1;
+
+const constexpr uint8_t X_PLUS_MASK = 0;
+const constexpr uint8_t X_MINUS_MASK = X_AXIS_MASK;
+const constexpr uint8_t Y_PLUS_MASK = 0;
+const constexpr uint8_t Y_MINUS_MASK = Y_AXIS_MASK;
+const constexpr uint8_t Z_PLUS_MASK = 0;
+const constexpr uint8_t Z_MINUS_MASK = Z_AXIS_MASK;
+
+/// Max. jerk in PrusaSlicer, 10000 = 1 mm/s
+const constexpr uint16_t MAX_DELAY = 10000;
+const constexpr float MIN_SPEED = 0.01f / (MAX_DELAY * 0.000001f);
+/// 200 = 50 mm/s
+const constexpr uint16_t Z_MIN_DELAY = 200;
+const constexpr uint16_t Z_ACCEL = 1000;
+
+/// \returns positive value always
+#define ABS(a) \
+    ({ __typeof__ (a) _a = (a); \
+    _a >= 0 ? _a : (-_a); })
+
+/// \returns maximum of the two
+#define MAX(a, b) \
+    ({ __typeof__ (a) _a = (a); \
+    __typeof__ (b) _b = (b); \
+    _a >= _b ? _a : _b; })
+
+/// \returns minimum of the two
+#define MIN(a, b) \
+    ({ __typeof__ (a) _a = (a); \
+    __typeof__ (b) _b = (b); \
+    _a <= _b ? _a : _b; })
+
+/// swap values
+#define SWAP(a, b) \
+    ({ __typeof__ (a) c = (a); \
+        a = (b); \
+        b = c; })
+
+/// Saturates value
+/// \returns min if value is less than min
+/// \returns max if value is more than min
+/// \returns value otherwise
+#define CLAMP(value, min, max) \
+    ({ __typeof__ (value) a_ = (value); \
+		__typeof__ (min) min_ = (min); \
+		__typeof__ (max) max_ = (max); \
+        ( a_ < min_ ? min_ : (a_ <= max_ ? a_ : max_)); })
+
+/// \returns square of the value
+#define SQR(a) \
+    ({ __typeof__ (a) a_ = (a); \
+        (a_ * a_); })
+
+/// position types
+typedef int16_t pos_i16_t;
+typedef long pos_i32_t;
+typedef float pos_mm_t;
+typedef int16_t usteps_t;
 
 uint8_t check_pinda_0();
 uint8_t check_pinda_1();
 void xyzcal_update_pos(uint16_t dx, uint16_t dy, uint16_t dz, uint16_t de);
 uint16_t xyzcal_calc_delay(uint16_t nd, uint16_t dd);
 
+uint8_t round_to_u8(float f){
+	return (uint8_t)(f + .5f);
+}
+
+uint16_t round_to_u16(float f){
+	return (uint16_t)(f + .5f);
+}
+
+int16_t round_to_i16(float f){
+	return (int16_t)(f + .5f);
+}
+
+/// converts millimeters to integer position
+pos_i16_t mm_2_pos(pos_mm_t mm){
+	return (pos_i16_t)(0.5f + mm * 100);
+}
+
+/// converts integer position to millimeters
+pos_mm_t pos_2_mm(pos_i16_t pos){
+	return pos * 0.01f;
+}
+pos_mm_t pos_2_mm(float pos){
+	return pos * 0.01f;
+}
 
 void xyzcal_meassure_enter(void)
 {
@@ -142,6 +239,10 @@ uint16_t xyzcal_calc_delay(uint16_t, uint16_t)
 }
 #endif //SM4_ACCEL_TEST
 
+/// Moves printer to absolute position [x,y,z] defined in integer position system
+/// check_pinda == 0: ordinary move
+/// check_pinda == 1: stop when PINDA triggered
+/// check_pinda == -1: stop when PINDA untriggered
 bool xyzcal_lineXYZ_to(int16_t x, int16_t y, int16_t z, uint16_t delay_us, int8_t check_pinda)
 {
 //	DBG(_n("xyzcal_lineXYZ_to x=%d y=%d z=%d  check=%d\n"), x, y, z, check_pinda);
@@ -152,17 +253,21 @@ bool xyzcal_lineXYZ_to(int16_t x, int16_t y, int16_t z, uint16_t delay_us, int8_
 	sm4_set_dir_bits(xyzcal_dm);
 	sm4_stop_cb = check_pinda?((check_pinda<0)?check_pinda_0:check_pinda_1):0;
 	xyzcal_sm4_delay = delay_us;
-//	uint32_t u = _micros();
-	bool ret = sm4_line_xyze_ui(abs(x), abs(y), abs(z), 0)?true:false;
-//	u = _micros() - u;
+	//	uint32_t u = _micros();
+	bool ret = sm4_line_xyz_ui(abs(x), abs(y), abs(z)) ? true : false;
+	//	u = _micros() - u;
 	return ret;
 }
 
+/// Moves printer to absolute position [x,y,z] defined in millimeters
+bool xyzcal_lineXYZ_to_float(pos_mm_t x, pos_mm_t y, pos_mm_t z, uint16_t delay_us, int8_t check_pinda){
+	return xyzcal_lineXYZ_to(mm_2_pos(x), mm_2_pos(y), mm_2_pos(z), delay_us, check_pinda);
+}
+
 bool xyzcal_spiral2(int16_t cx, int16_t cy, int16_t z0, int16_t dz, int16_t radius, int16_t rotation, uint16_t delay_us, int8_t check_pinda, uint16_t* pad)
 {
 	bool ret = false;
 	float r = 0; //radius
-	uint8_t n = 0; //point number
 	uint16_t ad = 0; //angle [deg]
 	float ar; //angle [rad]
 	uint8_t dad = 0; //delta angle [deg]
@@ -171,7 +276,14 @@ bool xyzcal_spiral2(int16_t cx, int16_t cy, int16_t z0, int16_t dz, int16_t radi
 	uint8_t k = 720 / (dad_max - dad_min); //delta calculation constant
 	ad = 0;
 	if (pad) ad = *pad % 720;
+	
+    //@size=214
 	DBG(_n("xyzcal_spiral2 cx=%d cy=%d z0=%d dz=%d radius=%d ad=%d\n"), cx, cy, z0, dz, radius, ad);
+	// lcd_set_cursor(0, 4);
+	// char text[10];
+	// snprintf(text, 10, "%4d", z0);
+	// lcd_print(text);
+
 	for (; ad < 720; ad++)
 	{
 		if (radius > 0)
@@ -184,11 +296,9 @@ bool xyzcal_spiral2(int16_t cx, int16_t cy, int16_t z0, int16_t dz, int16_t radi
 			dad = dad_max - ((719 - ad) / k);
 			r = (float)(((uint32_t)(719 - ad)) * (-radius)) / 720;
 		}
-		ar = (ad + rotation)* (float)_PI / 180;
-		float _cos = cos(ar);
-		float _sin = sin(ar);
-		int x = (int)(cx + (_cos * r));
-		int y = (int)(cy + (_sin * r));
+		ar = radians(ad + rotation);
+		int x = (int)(cx + (cos(ar) * r));
+		int y = (int)(cy + (sin(ar) * r));
 		int z = (int)(z0 - ((float)((int32_t)dz * ad) / 720));
 		if (xyzcal_lineXYZ_to(x, y, z, delay_us, check_pinda))
 		{
@@ -196,10 +306,13 @@ bool xyzcal_spiral2(int16_t cx, int16_t cy, int16_t z0, int16_t dz, int16_t radi
 			ret = true;
 			break;
 		}
-		n++;
 		ad += dad;
 	}
 	if (pad) *pad = ad;
+	// if(ret){
+	// 	lcd_set_cursor(0, 4);
+	// 	lcd_print("         ");
+	// }
 	return ret;
 }
 
@@ -208,6 +321,7 @@ bool xyzcal_spiral8(int16_t cx, int16_t cy, int16_t z0, int16_t dz, int16_t radi
 	bool ret = false;
 	uint16_t ad = 0;
 	if (pad) ad = *pad;
+    //@size=274
 	DBG(_n("xyzcal_spiral8 cx=%d cy=%d z0=%d dz=%d radius=%d ad=%d\n"), cx, cy, z0, dz, radius, ad);
 	if (!ret && (ad < 720))
 		if ((ret = xyzcal_spiral2(cx, cy, z0 - 0*dz, dz, radius, 0, delay_us, check_pinda, &ad)) != 0)
@@ -275,540 +389,599 @@ int8_t xyzcal_meassure_pinda_hysterezis(int16_t min_z, int16_t max_z, uint16_t d
 }
 #endif //XYZCAL_MEASSURE_PINDA_HYSTEREZIS
 
+void print_hysteresis(int16_t min_z, int16_t max_z, int16_t step){
+	int16_t delay_us = 600;
+	int16_t trigger = 0;
+	int16_t untrigger = 0;
+	DBG(_n("Hysteresis\n"));
 
-void xyzcal_scan_pixels_32x32(int16_t cx, int16_t cy, int16_t min_z, int16_t max_z, uint16_t delay_us, uint8_t* pixels)
-{
-	DBG(_n("xyzcal_scan_pixels_32x32 cx=%d cy=%d min_z=%d max_z=%d\n"), cx, cy, min_z, max_z);
-//	xyzcal_lineXYZ_to(cx - 1024, cy - 1024, max_z, 2*delay_us, 0);
-//	xyzcal_lineXYZ_to(cx, cy, max_z, delay_us, 0);
-	int16_t z = (int16_t)count_position[2];
-	xyzcal_lineXYZ_to(cx, cy, z, 2*delay_us, 0);
-	for (uint8_t r = 0; r < 32; r++)
-	{
-//		int8_t _pinda = _PINDA;
-		xyzcal_lineXYZ_to((r&1)?(cx+1024):(cx-1024), cy - 1024 + r*64, z, 2*delay_us, 0);
+	xyzcal_lineXYZ_to(_X, _Y, min_z, delay_us, 0);
+
+	for (int16_t z = min_z; z <= max_z; z += step){
+		xyzcal_lineXYZ_to(_X, _Y, z, delay_us, -1);
+		untrigger = _Z;
+		xyzcal_lineXYZ_to(_X, _Y, z, delay_us, 0);
 		xyzcal_lineXYZ_to(_X, _Y, min_z, delay_us, 1);
-		xyzcal_lineXYZ_to(_X, _Y, max_z, delay_us, -1);
-		z = (int16_t)count_position[2];
-		sm4_set_dir(X_AXIS, (r&1)?1:0);
-		for (uint8_t c = 0; c < 32; c++)
-		{
-			uint16_t sum = 0;
-			int16_t z_sum = 0;
-			for (uint8_t i = 0; i < 64; i++)
-			{
-				int8_t pinda = _PINDA;
-				int16_t pix = z - min_z;
-				pix += (pinda)?23:-24;
-				if (pix < 0) pix = 0;
-				if (pix > 255) pix = 255;
-				sum += pix;
-				z_sum += z;
-//				if (_pinda != pinda)
-//				{
-//					if (pinda)
-//						DBG(_n("!1 x=%d z=%d\n"), c*64+i, z+23);
-//					else
-//						DBG(_n("!0 x=%d z=%d\n"), c*64+i, z-24);
-//				}
-				sm4_set_dir(Z_AXIS, !pinda);
-				if (!pinda)
-				{
-					if (z > min_z)
-					{
-						sm4_do_step(Z_AXIS_MASK);
-						z--;
-					}
-				}
-				else
-				{
-					if (z < max_z)
-					{
-						sm4_do_step(Z_AXIS_MASK);
-						z++;
-					}
-				}
-				sm4_do_step(X_AXIS_MASK);
-				delayMicroseconds(600);
-//				_pinda = pinda;
-			}
-			sum >>= 6; //div 64
-			if (z_sum < 0)
-			{
-				z_sum = -z_sum;
-				z_sum >>= 6; //div 64
-				z_sum = -z_sum;
-			}
-			else
-				z_sum >>= 6; //div 64
-			if (pixels) pixels[((uint16_t)r<<5) + ((r&1)?(31-c):c)] = sum;
-//			DBG(_n("c=%d r=%d l=%d z=%d\n"), c, r, sum, z_sum);
-			count_position[0] += (r&1)?-64:64;
-			count_position[2] = z;
-		}
-		if (pixels)
-			for (uint8_t c = 0; c < 32; c++)
-				DBG(_n("%02x"), pixels[((uint16_t)r<<5) + c]);
-		DBG(_n("\n"));
+		trigger = _Z;
+		//xyzcal_lineXYZ_to(_X, _Y, min_z, delay_us, 0);
+
+        //@size=114
+		DBG(_n("min, trigger, untrigger, max: [%d %d %d %d]\n"), _Z, trigger, untrigger, z);
 	}
-//	xyzcal_lineXYZ_to(cx, cy, z, 2*delay_us, 0);
 }
 
-void xyzcal_histo_pixels_32x32(uint8_t* pixels, uint16_t* histo)
-{
-	for (uint8_t l = 0; l < 16; l++)
-		histo[l] = 0;
-	for (uint8_t r = 0; r < 32; r++)
-		for (uint8_t c = 0; c < 32; c++)
-		{
-			uint8_t pix = pixels[((uint16_t)r<<5) + c];
-			histo[pix >> 4]++;
-		}
-	for (uint8_t l = 0; l < 16; l++)
-		DBG(_n(" %2d %d\n"), l, histo[l]);
+void update_position_1_step(uint8_t axis, uint8_t dir){
+	if (axis & X_AXIS_MASK)
+		_X_ += dir & X_AXIS_MASK ? -1 : 1;
+	if (axis & Y_AXIS_MASK)
+		_Y_ += dir & Y_AXIS_MASK ? -1 : 1;
+	if (axis & Z_AXIS_MASK)
+		_Z_ += dir & Z_AXIS_MASK ? -1 : 1;
 }
 
-void xyzcal_adjust_pixels(uint8_t* pixels, uint16_t* histo)
-{
-	uint8_t l;
-	uint16_t max_c = histo[1];
-	uint8_t max_l = 1;
-	for (l = 1; l < 16; l++)
-	{
-		uint16_t c = histo[l];
-		if (c > max_c)
-		{
-			max_c = c;
-			max_l = l;
-		}
+void set_axes_dir(uint8_t axes, uint8_t dir){
+	if (axes & X_AXIS_MASK)
+		sm4_set_dir(X_AXIS, dir & X_AXIS_MASK);
+	if (axes & Y_AXIS_MASK)
+		sm4_set_dir(Y_AXIS, dir & Y_AXIS_MASK);
+	if (axes & Z_AXIS_MASK)
+		sm4_set_dir(Z_AXIS, dir & Z_AXIS_MASK);
+}
+
+/// Accelerate up to max.speed (defined by @min_delay_us)
+/// does not update global positions
+void accelerate_1_step(uint8_t axes, int16_t acc, uint16_t &delay_us, uint16_t min_delay_us){
+	sm4_do_step(axes);
+
+	/// keep max speed (avoid extra computation)
+	if (acc > 0 && delay_us == min_delay_us){
+		delayMicroseconds(delay_us);
+		return;
 	}
-	DBG(_n("max_c=%2d max_l=%d\n"), max_c, max_l);
-	for (l = 14; l > 8; l--)
-		if (histo[l] >= 10)
-			break;
-	uint8_t pix_min = 0;
-	uint8_t pix_max = l << 4;
-	if (histo[0] < (32*32 - 144))
-	{
-		pix_min = (max_l << 4) / 2;
+
+	// v1 = v0 + a * t
+	// 0.01 = length of a step
+	const float t0 = delay_us * 0.000001f;
+	const float v1 = (0.01f / t0 + acc * t0);
+	uint16_t t1;
+	if (v1 <= 0.16f){ ///< slowest speed convertible to uint16_t delay
+		t1 = MAX_DELAY; ///< already too slow so it wants to move back
+	} else {
+		/// don't exceed max.speed
+		t1 = MAX(min_delay_us, round_to_u16(0.01f / v1 * 1000000.f));
 	}
-	uint8_t pix_dif = pix_max - pix_min;
-	DBG(_n(" min=%d max=%d dif=%d\n"), pix_min, pix_max, pix_dif);
-	for (int16_t i = 0; i < 32*32; i++)
-	{
-		uint16_t pix = pixels[i];
-		if (pix > pix_min) pix -= pix_min;
-		else pix = 0;
-		pix <<= 8;
-		pix /= pix_dif;
-//		if (pix < 0) pix = 0;
-		if (pix > 255) pix = 255;
-		pixels[i] = (uint8_t)pix;
+
+	/// make sure delay has changed a bit at least
+	if (t1 == delay_us && acc != 0){
+		if (acc > 0)
+			t1--;
+		else
+			t1++;
 	}
-	for (uint8_t r = 0; r < 32; r++)
-	{
-		for (uint8_t c = 0; c < 32; c++)
-			DBG(_n("%02x"), pixels[((uint16_t)r<<5) + c]);
-		DBG(_n("\n"));
+	
+	//DBG(_n("%d "), t1);
+
+	delayMicroseconds(t1);
+	delay_us = t1;
+}
+
+/// Goes defined number of steps while accelerating
+/// updates global positions
+void accelerate(uint8_t axes, uint8_t dir, int16_t acc, uint16_t &delay_us, uint16_t min_delay_us, uint16_t steps){
+	set_axes_dir(axes, dir);
+	while (steps--){
+		accelerate_1_step(axes, acc, delay_us, min_delay_us);
+		update_position_1_step(axes, dir);
 	}
 }
 
-/*
-void xyzcal_draw_pattern_12x12_in_32x32(uint8_t* pattern, uint32_t* pixels, int w, int h, uint8_t x, uint8_t y, uint32_t and, uint32_t or)
-{
-	for (int i = 0; i < 8; i++)
-		for (int j = 0; j < 8; j++)
-		{
-			int idx = (x + j) + w * (y + i);
-			if (pattern[i] & (1 << j))
-			{
-				pixels[idx] &= and;
-				pixels[idx] |= or;
+/// keeps speed and then it decelerates to a complete stop (if possible)
+/// it goes defined number of steps
+/// returns after each step
+/// \returns true if step was done
+/// does not update global positions
+bool go_and_stop_1_step(uint8_t axes, int16_t dec, uint16_t &delay_us, uint16_t &steps){
+	if (steps <= 0 || dec <= 0)
+		return false;
+
+	/// deceleration distance in steps, s = 1/2 v^2 / a
+	uint16_t s = round_to_u16(100 * 0.5f * SQR(0.01f) / (SQR((float)delay_us) * dec));
+	if (steps > s){
+		/// go steady
+		sm4_do_step(axes);
+		delayMicroseconds(delay_us);
+	} else {
+		/// decelerate
+		accelerate_1_step(axes, -dec, delay_us, delay_us);
+	}
+	--steps;
+	return true;
+}
+
+/// \param dir sets direction of movement
+/// updates global positions
+void go_and_stop(uint8_t axes, uint8_t dir, int16_t dec, uint16_t &delay_us, uint16_t steps){
+	set_axes_dir(axes, dir);
+	while (go_and_stop_1_step(axes, dec, delay_us, steps)){
+		update_position_1_step(axes, dir);
+	}
+}
+
+/// goes all the way to stop
+/// \returns steps done
+/// updates global positions
+void stop_smoothly(uint8_t axes, uint8_t dir, int16_t dec, uint16_t &delay_us){
+	if (dec <= 0)
+		return;
+	set_axes_dir(axes, dir);
+	while (delay_us < MAX_DELAY){
+		accelerate_1_step(axes, -dec, delay_us, delay_us);
+		update_position_1_step(axes, dir);
+	}
+}
+
+void go_start_stop(uint8_t axes, uint8_t dir, int16_t acc, uint16_t min_delay_us, uint16_t steps){
+	if (steps == 0)
+		return;
+	uint16_t current_delay_us = MAX_DELAY;
+	const uint16_t half = steps / 2;
+	accelerate(axes, dir, acc, current_delay_us, min_delay_us, half);
+	go_and_stop(axes, dir, -acc, current_delay_us, steps - half);
+}
+
+/// moves X, Y, Z one after each other
+/// starts and ends at 0 speed
+void go_manhattan(int16_t x, int16_t y, int16_t z, int16_t acc, uint16_t min_delay_us){
+	int32_t length;
+
+	// DBG(_n("x %d -> %d, "), x, _X);
+	length = x - _X;
+	go_start_stop(X_AXIS_MASK, length < 0 ? X_MINUS_MASK : X_PLUS_MASK, acc, min_delay_us, ABS(length));
+
+	// DBG(_n("y %d -> %d, "), y, _Y);
+	length = y - _Y;
+	go_start_stop(Y_AXIS_MASK, length < 0 ? Y_MINUS_MASK : Y_PLUS_MASK, acc, min_delay_us, ABS(length));
+
+	// DBG(_n("z %d -> %d\n"), z, _Z);
+	length = z - _Z;
+	go_start_stop(Z_AXIS_MASK, length < 0 ? Z_MINUS_MASK : Z_PLUS_MASK, acc, min_delay_us, ABS(length));
+	// DBG(_n("\n"));
+}
+
+void xyzcal_scan_pixels_32x32_Zhop(int16_t cx, int16_t cy, int16_t min_z, int16_t max_z, uint16_t delay_us, uint8_t *pixels){
+	if (!pixels)
+		return;
+	int16_t z_trig;
+	uint16_t line_buffer[32];
+	uint16_t current_delay_us = MAX_DELAY; ///< defines current speed
+	int16_t start_z;
+	uint16_t steps_to_go;
+
+	DBG(_n("Scan countdown: "));
+
+	for (uint8_t r = 0; r < 32; r++){ ///< Y axis
+		for (uint8_t d = 0; d < 2; ++d){
+			go_manhattan((d & 1) ? (cx + 992) : (cx - 992), cy - 992 + r * 64, _Z, Z_ACCEL, Z_MIN_DELAY);
+			xyzcal_lineXYZ_to((d & 1) ? (cx + 992) : (cx - 992), cy - 992 + r * 64, _Z, delay_us, 0);
+			sm4_set_dir(X_AXIS, d);
+            //@size=242
+			DBG(_n("%d\n"), 64 - (r * 2 + d)); ///< to keep OctoPrint connection alive
+
+			for (uint8_t c = 0; c < 32; c++){ ///< X axis
+				/// move to the next point and move Z up diagonally (if needed)
+				current_delay_us = MAX_DELAY;
+				const int16_t end_x = ((d & 1) ? 1 : -1) * (64 * (16 - c) - 32) + cx;
+				const int16_t length_x = ABS(end_x - _X);
+				const int16_t half_x = length_x / 2;
+				/// don't go up if PINDA not triggered (optimization)
+				const bool up = _PINDA;
+				const uint8_t axes = up ? X_AXIS_MASK | Z_AXIS_MASK : X_AXIS_MASK;
+				const uint8_t dir = Z_PLUS_MASK | (d & 1 ? X_MINUS_MASK : X_PLUS_MASK);
+
+				accelerate(axes, dir, Z_ACCEL, current_delay_us, Z_MIN_DELAY, half_x);
+				go_and_stop(axes, dir, Z_ACCEL, current_delay_us, length_x - half_x);
+				
+				
+				z_trig = min_z;
+
+				/// move up to un-trigger (surpress hysteresis)
+				sm4_set_dir(Z_AXIS, Z_PLUS);
+				/// speed up from stop, go half the way
+				current_delay_us = MAX_DELAY;
+				for (start_z = _Z; _Z < (max_z + start_z) / 2; ++_Z_){
+					if (!_PINDA){
+						break;
+					}
+					accelerate_1_step(Z_AXIS_MASK, Z_ACCEL, current_delay_us, Z_MIN_DELAY);
+				}
+
+				if (_PINDA){
+					steps_to_go = MAX(0, max_z - _Z);
+					while (_PINDA && _Z < max_z){
+						go_and_stop_1_step(Z_AXIS_MASK, Z_ACCEL, current_delay_us, steps_to_go);
+						++_Z_;
+					}
+				}
+				stop_smoothly(Z_AXIS_MASK, Z_PLUS_MASK, Z_ACCEL, current_delay_us);
+
+				/// move down to trigger
+				sm4_set_dir(Z_AXIS, Z_MINUS);
+				/// speed up
+				current_delay_us = MAX_DELAY;
+				for (start_z = _Z; _Z > (min_z + start_z) / 2; --_Z_){
+					if (_PINDA){
+						z_trig = _Z;
+						break;
+					}
+					accelerate_1_step(Z_AXIS_MASK, Z_ACCEL, current_delay_us, Z_MIN_DELAY);
+				}
+				/// slow down
+				if (!_PINDA){
+					steps_to_go = MAX(0, _Z - min_z);
+					while (!_PINDA && _Z > min_z){
+						go_and_stop_1_step(Z_AXIS_MASK, Z_ACCEL, current_delay_us, steps_to_go);
+						--_Z_;
+					}
+					z_trig = _Z;
+				}
+				/// slow down to stop but not lower than min_z
+				while (_Z > min_z && current_delay_us < MAX_DELAY){
+					accelerate_1_step(Z_AXIS_MASK, -Z_ACCEL, current_delay_us, Z_MIN_DELAY);
+					--_Z_;
+				}
+
+				if (d == 0){
+					line_buffer[c] = (uint16_t)(z_trig - min_z);
+				} else {
+					/// !!! data reversed in X
+					// DBG(_n("%04x"), ((uint32_t)line_buffer[31 - c] + (z_trig - min_z)) / 2);
+					/// save average of both directions (filters effect of hysteresis)
+					pixels[(uint16_t)r * 32 + (31 - c)] = (uint8_t)MIN((uint32_t)255, ((uint32_t)line_buffer[31 - c] + (z_trig - min_z)) / 2);
+				}
 			}
 		}
+	}
+	DBG(endl);
 }
-*/
 
-int16_t xyzcal_match_pattern_12x12_in_32x32(uint16_t* pattern, uint8_t* pixels, uint8_t c, uint8_t r)
-{
+/// Returns rate of match
+/// max match = 132, min match = 0
+uint8_t xyzcal_match_pattern_12x12_in_32x32(uint16_t* pattern, uint8_t* pixels, uint8_t c, uint8_t r){
 	uint8_t thr = 16;
-	int16_t match = 0;
-	for (uint8_t i = 0; i < 12; i++)
-		for (uint8_t j = 0; j < 12; j++)
-		{
-			if (((i == 0) || (i == 11)) && ((j < 2) || (j >= 10))) continue; //skip corners
+	uint8_t match = 0;
+	for (uint8_t i = 0; i < 12; ++i){
+		for (uint8_t j = 0; j < 12; ++j){
+			/// skip corners (3 pixels in each)
+			if (((i == 0) || (i == 11)) && ((j < 2) || (j >= 10))) continue;
 			if (((j == 0) || (j == 11)) && ((i < 2) || (i >= 10))) continue;
-			uint16_t idx = (c + j) + 32 * (r + i);
-			uint8_t val = pixels[idx];
-			if (pattern[i] & (1 << j))
-			{
-				if (val > thr) match ++;
-				else match --;
-			}
-			else
-			{
-				if (val <= thr) match ++;
-				else match --;
-			}
+			const uint16_t idx = (c + j) + 32 * ((uint16_t)r + i);
+			const bool high_pix = pixels[idx] > thr;
+			const bool high_pat = pattern[i] & (1 << j);
+			if (high_pix == high_pat)
+				match++;
 		}
+	}
 	return match;
 }
 
-int16_t xyzcal_find_pattern_12x12_in_32x32(uint8_t* pixels, uint16_t* pattern, uint8_t* pc, uint8_t* pr)
-{
+/// Searches for best match of pattern by shifting it
+/// Returns rate of match and the best location
+/// max match = 132, min match = 0
+uint8_t xyzcal_find_pattern_12x12_in_32x32(uint8_t* pixels, uint16_t* pattern, uint8_t* pc, uint8_t* pr){
+	if (!pixels || !pattern || !pc || !pr)
+		return -1;
 	uint8_t max_c = 0;
 	uint8_t max_r = 0;
-	int16_t max_match = 0;
-	for (uint8_t r = 0; r < (32 - 12); r++)
-		for (uint8_t c = 0; c < (32 - 12); c++)
-		{
-			int16_t match = xyzcal_match_pattern_12x12_in_32x32(pattern, pixels, c, r);
-			if (max_match < match)
-			{
+	uint8_t max_match = 0;
+
+	// DBG(_n("Matching:\n"));
+	/// pixel precision
+	for (uint8_t r = 0; r < (32 - 12); ++r){
+		for (uint8_t c = 0; c < (32 - 12); ++c){
+			const uint8_t match = xyzcal_match_pattern_12x12_in_32x32(pattern, pixels, c, r);
+			if (max_match < match){
 				max_c = c;
 				max_r = r;
 				max_match = match;
 			}
+			// DBG(_n("%d "), match);
 		}
-	DBG(_n("max_c=%d max_r=%d max_match=%d\n"), max_c, max_r, max_match);
-	if (pc) *pc = max_c;
-	if (pr) *pr = max_r;
+		// DBG(_n("\n"));
+	}
+    //@size=278
+	DBG(_n("Pattern center [%f %f], match %f%%\n"), max_c + 5.5f, max_r + 5.5f, max_match / 1.32f);
+
+	*pc = max_c;
+	*pr = max_r;
 	return max_match;
 }
 
-#define MAX_DIAMETR 600
-#define XYZCAL_FIND_CENTER_DIAGONAL
+const uint16_t xyzcal_point_pattern_10[12] PROGMEM = {0x000, 0x0f0, 0x1f8, 0x3fc, 0x7fe, 0x7fe, 0x7fe, 0x7fe, 0x3fc, 0x1f8, 0x0f0, 0x000};
+const uint16_t xyzcal_point_pattern_08[12] PROGMEM = {0x000, 0x000, 0x0f0, 0x1f8, 0x3fc, 0x3fc, 0x3fc, 0x3fc, 0x1f8, 0x0f0, 0x000, 0x000};
 
-int8_t xyzcal_find_point_center2(uint16_t delay_us)
+bool xyzcal_searchZ(void)
 {
-	printf_P(PSTR("xyzcal_find_point_center2\n"));
+    //@size=118
+	DBG(_n("xyzcal_searchZ x=%ld y=%ld z=%ld\n"), count_position[X_AXIS], count_position[Y_AXIS], count_position[Z_AXIS]);
 	int16_t x0 = _X;
 	int16_t y0 = _Y;
 	int16_t z0 = _Z;
-	printf_P(PSTR(" x0=%d\n"), x0);
-	printf_P(PSTR(" y0=%d\n"), y0);
-	printf_P(PSTR(" z0=%d\n"), z0);
-
-	xyzcal_lineXYZ_to(_X, _Y, z0 + 400, 500, -1);
-	xyzcal_lineXYZ_to(_X, _Y, z0 - 400, 500, 1);
-	xyzcal_lineXYZ_to(_X, _Y, z0 + 400, 500, -1);
-	xyzcal_lineXYZ_to(_X, _Y, z0 - 400, 500, 1);
-
-	z0 = _Z - 20;
-	xyzcal_lineXYZ_to(_X, _Y, z0, 500, 0);
-
-//	xyzcal_lineXYZ_to(x0, y0, z0 - 100, 500, 1);
-//	z0 = _Z;
-//	printf_P(PSTR("  z0=%d\n"), z0);
-//	xyzcal_lineXYZ_to(x0, y0, z0 + 100, 500, -1);
-//	z0 += _Z;
-//	z0 /= 2;
-	printf_P(PSTR("   z0=%d\n"), z0);
-//	xyzcal_lineXYZ_to(x0, y0, z0 - 100, 500, 1);
-//	z0 = _Z - 10;
-
-	int8_t ret = 1;
-
-#ifdef XYZCAL_FIND_CENTER_DIAGONAL
-	int32_t xc = 0;
-	int32_t yc = 0;
-	int16_t ad = 45;
-	for (; ad < 360; ad += 90)
+//	int16_t min_z = -6000;
+//	int16_t dz = 100;
+	int16_t z = z0;
+	while (z > -2300) //-6mm + 0.25mm
 	{
-		float ar = (float)ad * _PI / 180;
-		int16_t x = x0 + MAX_DIAMETR * cos(ar);
-		int16_t y = y0 + MAX_DIAMETR * sin(ar);
-		if (!xyzcal_lineXYZ_to(x, y, z0, delay_us, -1))
+		uint16_t ad = 0;
+		if (xyzcal_spiral8(x0, y0, z, 100, 900, 320, 1, &ad)) //dz=100 radius=900 delay=400
 		{
-			printf_P(PSTR("ERROR ad=%d\n"), ad);
-			ret = 0;
-			break;
+			int16_t x_on = _X;
+			int16_t y_on = _Y;
+			int16_t z_on = _Z;
+			//@size=82
+            DBG(_n(" ON-SIGNAL at x=%d y=%d z=%d ad=%d\n"), x_on, y_on, z_on, ad);
+			return true;
 		}
-		xc += _X;
-		yc += _Y;
-		xyzcal_lineXYZ_to(x0, y0, z0, delay_us, 0);
-	}
-	if (ret)
-	{
-		printf_P(PSTR("OK\n"), ad);
-		x0 = xc / 4;
-		y0 = yc / 4;
-		printf_P(PSTR(" x0=%d\n"), x0);
-		printf_P(PSTR(" y0=%d\n"), y0);
+		z -= 400;
 	}
+    //@size=138
+	DBG(_n("xyzcal_searchZ no signal\n x=%ld y=%ld z=%ld\n"), count_position[X_AXIS], count_position[Y_AXIS], count_position[Z_AXIS]);
+	return false;
+}
 
-#else //XYZCAL_FIND_CENTER_DIAGONAL
-	xyzcal_lineXYZ_to(x0 - MAX_DIAMETR, y0, z0, delay_us, -1);
-	int16_t dx1 = x0 - _X;
-	if (dx1 >= MAX_DIAMETR)
-	{
-		printf_P(PSTR("!!! dx1 = %d\n"), dx1);
-		return 0;
-	}
-	xyzcal_lineXYZ_to(x0, y0, z0, delay_us, 0);
-	xyzcal_lineXYZ_to(x0 + MAX_DIAMETR, y0, z0, delay_us, -1);
-	int16_t dx2 = _X - x0;
-	if (dx2 >= MAX_DIAMETR)
-	{
-		printf_P(PSTR("!!! dx2 = %d\n"), dx2);
-		return 0;
-	}
-	xyzcal_lineXYZ_to(x0, y0, z0, delay_us, 0);
-	xyzcal_lineXYZ_to(x0 , y0 - MAX_DIAMETR, z0, delay_us, -1);
-	int16_t dy1 = y0 - _Y;
-	if (dy1 >= MAX_DIAMETR)
-	{
-		printf_P(PSTR("!!! dy1 = %d\n"), dy1);
+/// returns value of any location within data
+/// uses bilinear interpolation
+float get_value(uint8_t * matrix_32x32, float c, float r){
+	if (c <= 0 || r <= 0 || c >= 31 || r >= 31)
 		return 0;
-	}
-	xyzcal_lineXYZ_to(x0, y0, z0, delay_us, 0);
-	xyzcal_lineXYZ_to(x0, y0 + MAX_DIAMETR, z0, delay_us, -1);
-	int16_t dy2 = _Y - y0;
-	if (dy2 >= MAX_DIAMETR)
-	{
-		printf_P(PSTR("!!! dy2 = %d\n"), dy2);
-		return 0;
-	}
-	printf_P(PSTR("dx1=%d\n"), dx1);
-	printf_P(PSTR("dx2=%d\n"), dx2);
-	printf_P(PSTR("dy1=%d\n"), dy1);
-	printf_P(PSTR("dy2=%d\n"), dy2);
-
-	x0 += (dx2 - dx1) / 2;
-	y0 += (dy2 - dy1) / 2;
 
-	printf_P(PSTR(" x0=%d\n"), x0);
-	printf_P(PSTR(" y0=%d\n"), y0);
+	/// calculate weights of nearby points
+	const float wc1 = c - floor(c);
+	const float wr1 = r - floor(r);
+	const float wc0 = 1 - wc1;
+	const float wr0 = 1 - wr1;
+
+	const float w00 = wc0 * wr0;
+	const float w01 = wc0 * wr1;
+	const float w10 = wc1 * wr0;
+	const float w11 = wc1 * wr1;
+
+	const uint16_t c0 = c;
+	const uint16_t c1 = c0 + 1;
+	const uint16_t r0 = r;
+	const uint16_t r1 = r0 + 1;
+
+	const uint16_t idx00 = c0 + 32 * r0;
+	const uint16_t idx01 = c0 + 32 * r1;
+	const uint16_t idx10 = c1 + 32 * r0;
+	const uint16_t idx11 = c1 + 32 * r1;
+
+	/// bilinear resampling
+	return w00 * matrix_32x32[idx00] + w01 * matrix_32x32[idx01] + w10 * matrix_32x32[idx10] + w11 * matrix_32x32[idx11];
+}
 
-#endif //XYZCAL_FIND_CENTER_DIAGONAL
+const constexpr float m_infinity = -1000.f;
 
-	xyzcal_lineXYZ_to(x0, y0, z0, delay_us, 0);
+/// replaces the highest number by m_infinity
+void remove_highest(float *points, const uint8_t num_points){
+	if (num_points <= 0)
+		return;
 
-	return ret;
+	float max = points[0];
+	uint8_t max_i = 0;
+	for (uint8_t i = 0; i < num_points; ++i){
+		if (max < points[i]){
+			max = points[i];
+			max_i = i;
+		}
+	}
+	points[max_i] = m_infinity;
 }
 
-#ifdef XYZCAL_FIND_POINT_CENTER
-int8_t xyzcal_find_point_center(int16_t x0, int16_t y0, int16_t z0, int16_t min_z, int16_t max_z, uint16_t delay_us, uint8_t turns)
-{
-	uint8_t n;
-	uint16_t ad;
-	float ar;
-	float _cos;
-	float _sin;
-	int16_t r_min = 0;
-	int16_t r_max = 0;
-	int16_t x_min = 0;
-	int16_t x_max = 0;
-	int16_t y_min = 0;
-	int16_t y_max = 0;
-	int16_t r = 10;
-	int16_t x = x0;
-	int16_t y = y0;
-	int16_t z = z0;
-	int8_t _pinda = _PINDA;
-	for (n = 0; n < turns; n++)
-	{
-		uint32_t r_sum = 0;
-		for (ad = 0; ad < 720; ad++)
-		{
-			ar = ad * _PI / 360;
-			_cos = cos(ar);
-			_sin = sin(ar);
-			x = x0 + (int)(_cos * r);
-			y = y0 + (int)(_sin * r);
-			xyzcal_lineXYZ_to(x, y, z, 1000, 0);
-			int8_t pinda = _PINDA;
-			if (pinda)
-				r += 1;
-			else
-			{
-				r -= 1;
-				ad--;
-				r_sum -= r;
-			}
-			if (ad == 0)
-			{
-				x_min = x0;
-				x_max = x0;
-				y_min = y0;
-				y_max = y0;
-				r_min = r;
-				r_max = r;
-			}
-			else if (pinda)
-			{
-				if (x_min > x) x_min = (2*x + x_min) / 3;
-				if (x_max < x) x_max = (2*x + x_max) / 3;
-				if (y_min > y) y_min = (2*y + y_min) / 3;
-				if (y_max < y) y_max = (2*y + y_max) / 3;
-/*				if (x_min > x) x_min = x;
-				if (x_max < x) x_max = x;
-				if (y_min > y) y_min = y;
-				if (y_max < y) y_max = y;*/
-				if (r_min > r) r_min = r;
-				if (r_max < r) r_max = r;
-			}
-			r_sum += r;
-/*			if (_pinda != pinda)
-			{
-				if (pinda)
-					DBG(_n("!1 x=%d y=%d\n"), x, y);
-				else
-					DBG(_n("!0 x=%d y=%d\n"), x, y);
-			}*/
-			_pinda = pinda;
-//			DBG(_n("x=%d y=%d rx=%d ry=%d\n"), x, y, rx, ry);
+/// return the highest number in the list
+float highest(float *points, const uint8_t num_points){
+	if (num_points <= 0)
+		return 0;
+
+	float max = points[0];
+	for (uint8_t i = 0; i < num_points; ++i){
+		if (max < points[i]){
+			max = points[i];
 		}
-		DBG(_n("x_min=%d x_max=%d y_min=%d y_max=%d r_min=%d r_max=%d r_avg=%d\n"), x_min, x_max, y_min, y_max, r_min, r_max, r_sum / 720);
-		if ((n > 2) && (n & 1))
-		{
-			x0 += (x_min + x_max);
-			y0 += (y_min + y_max);
-			x0 /= 3;
-			y0 /= 3;
-			int rx = (x_max - x_min) / 2;
-			int ry = (y_max - y_min) / 2;
-			r = (rx + ry) / 3;//(rx < ry)?rx:ry;
-			DBG(_n("x0=%d y0=%d r=%d\n"), x0, y0, r);
+	}
+	return max;
+}
+
+/// slow bubble sort but short
+void sort(float *points, const uint8_t num_points){
+	/// one direction bubble sort
+	for (uint8_t i = 0; i < num_points; ++i){
+		for (uint8_t j = 0; j < num_points - i - 1; ++j){
+			if (points[j] > points[j + 1])
+				SWAP(points[j], points[j + 1]);
 		}
 	}
-	xyzcal_lineXYZ_to(x0, y0, z, 200, 0);
+	
+	// DBG(_n("Sorted: "));
+	// for (uint8_t i = 0; i < num_points; ++i)
+	// 	DBG(_n("%f "), points[i]);
+	// DBG(_n("\n"));
 }
-#endif //XYZCAL_FIND_POINT_CENTER
 
 
-uint8_t xyzcal_xycoords2point(int16_t x, int16_t y)
-{
-	uint8_t ix = (x > 10000)?1:0;
-	uint8_t iy = (y > 10000)?1:0;
-	return iy?(3-ix):ix;
+/// sort array and returns median value
+/// don't send empty array or nullptr
+float median(float *points, const uint8_t num_points){
+	sort(points, num_points);
+	return points[num_points / 2];
 }
 
-//MK3
-#if ((MOTHERBOARD == BOARD_EINSY_1_0a))
-const int16_t xyzcal_point_xcoords[4] PROGMEM = {1200, 22000, 22000, 1200};
-const int16_t xyzcal_point_ycoords[4] PROGMEM = {600, 600, 19800, 19800};
-#endif //((MOTHERBOARD == BOARD_EINSY_1_0a))
+float __attribute__ ((noinline)) CLAMP_median(float *shifts, uint8_t blocks, float norm){
+    const constexpr float max_change = 0.5f; ///< avoids too fast changes (avoid oscillation)
+    return CLAMP( median(shifts, blocks) * norm, -max_change, max_change);
+}
 
-//MK2.5
-#if ((MOTHERBOARD == BOARD_RAMBO_MINI_1_0) || (MOTHERBOARD == BOARD_RAMBO_MINI_1_3))
-const int16_t xyzcal_point_xcoords[4] PROGMEM = {1200, 22000, 22000, 1200};
-const int16_t xyzcal_point_ycoords[4] PROGMEM = {700, 700, 19800, 19800};
-#endif //((MOTHERBOARD == BOARD_RAMBO_MINI_1_0) || (MOTHERBOARD == BOARD_RAMBO_MINI_1_3))
+/// Searches for circle iteratively
+/// Uses points on the perimeter. If point is high it pushes circle out of the center (shift or change of radius),
+/// otherwise to the center.
+/// Algorithm is stopped after fixed number of iterations. Move is limited to 0.5 px per iteration.
+void dynamic_circle(uint8_t *matrix_32x32, float &x, float &y, float &r, uint8_t iterations){
+	/// circle of 10.5 diameter has 33 in circumference, don't go much above
+	const constexpr uint8_t num_points = 33;
+	const float pi_2_div_num_points = 2 * M_PI / num_points;
+	const constexpr uint8_t target_z = 32; ///< target z height of the circle
+	const uint8_t blocks = num_points;
+	float shifts_x[blocks];
+	float shifts_y[blocks];	
+	float shifts_r[blocks];	
+
+	// DBG(_n(" [%f, %f][%f] start circle\n"), x, y, r);
+
+	for (int8_t i = iterations; i > 0; --i){
+	
+        //@size=128B
+		DBG(_n(" [%f, %f][%f] circle\n"), x, y, r);
+
+		/// read points on the circle
+		for (uint8_t p = 0; p < num_points; ++p){
+			const float angle = p * pi_2_div_num_points;
+			const float height = get_value(matrix_32x32, r * cos(angle) + x, r * sin(angle) + y) - target_z;
+			// DBG(_n("%f "), point);
+
+			shifts_x[p] = cos(angle) * height;
+			shifts_y[p] = sin(angle) * height;
+			shifts_r[p] = height;
+		}
+		// DBG(_n(" points\n"));
 
-const uint16_t xyzcal_point_pattern[12] PROGMEM = {0x000, 0x0f0, 0x1f8, 0x3fc, 0x7fe, 0x7fe, 0x7fe, 0x7fe, 0x3fc, 0x1f8, 0x0f0, 0x000};
+		const float reducer = 32.f; ///< reduces speed of convergency to avoid oscillation
+		const float norm = 1.f / reducer;
+//		x += CLAMP(median(shifts_x, blocks) * norm, -max_change, max_change);
+//		y += CLAMP(median(shifts_y, blocks) * norm, -max_change, max_change);
+//		r += CLAMP(median(shifts_r, blocks) * norm * .5f, -max_change, max_change);
+        //104B down
+        x += CLAMP_median(shifts_x, blocks, norm);
+        y += CLAMP_median(shifts_y, blocks, norm);
+        r += CLAMP_median(shifts_r, blocks, norm * .5f);
 
-bool xyzcal_searchZ(void)
-{
-	DBG(_n("xyzcal_searchZ x=%ld y=%ld z=%ld\n"), count_position[X_AXIS], count_position[Y_AXIS], count_position[Z_AXIS]);
-	int16_t x0 = _X;
-	int16_t y0 = _Y;
-	int16_t z0 = _Z;
-//	int16_t min_z = -6000;
-//	int16_t dz = 100;
-	int16_t z = z0;
-	while (z > -2300) //-6mm + 0.25mm
-	{
-		uint16_t ad = 0;
-		if (xyzcal_spiral8(x0, y0, z, 100, 900, 320, 1, &ad)) //dz=100 radius=900 delay=400
-		{
-			int16_t x_on = _X;
-			int16_t y_on = _Y;
-			int16_t z_on = _Z;
-			DBG(_n(" ON-SIGNAL at x=%d y=%d z=%d ad=%d\n"), x_on, y_on, z_on, ad);
-			return true;
+		r = MAX(2, r);
+
+	}
+    //@size=118
+	DBG(_n(" [%f, %f][%f] final circle\n"), x, y, r);
+}
+
+/// Prints matrix in hex to debug output (serial line)
+void print_image(const uint8_t *matrix_32x32){
+	for (uint8_t y = 0; y < 32; ++y){
+		const uint16_t idx_y = y * 32;
+		for (uint8_t x = 0; x < 32; ++x){
+			DBG(_n("%02x"), matrix_32x32[idx_y + x]);
 		}
-		z -= 400;
+		DBG(endl);
 	}
-	DBG(_n("xyzcal_searchZ no signal\n x=%ld y=%ld z=%ld\n"), count_position[X_AXIS], count_position[Y_AXIS], count_position[Z_AXIS]);
-	return false;
+	DBG(endl);
 }
 
-bool xyzcal_scan_and_process(void)
-{
+/// Takes two patterns and searches them in matrix32
+/// \returns best match
+uint8_t find_patterns(uint8_t *matrix32, uint16_t *pattern08, uint16_t *pattern10, uint8_t &col, uint8_t &row){
+	uint8_t c08 = 0;
+	uint8_t r08 = 0;
+	uint8_t match08 = 0;
+	uint8_t c10 = 0;
+	uint8_t r10 = 0;
+	uint8_t match10 = 0;
+
+	match08 = xyzcal_find_pattern_12x12_in_32x32(matrix32, pattern08, &c08, &r08);
+	match10 = xyzcal_find_pattern_12x12_in_32x32(matrix32, pattern10, &c10, &r10);
+
+	if (match08 > match10){
+		col = c08;
+		row = r08;
+		return match08;
+	}
+	
+	col = c10;
+	row = r10;
+	return match10;
+}
+
+/// scans area around the current head location and
+/// searches for the center of the calibration pin
+bool xyzcal_scan_and_process(void){
+    //@size=44
 	DBG(_n("sizeof(block_buffer)=%d\n"), sizeof(block_t)*BLOCK_BUFFER_SIZE);
-//	DBG(_n("sizeof(pixels)=%d\n"), 32*32);
-//	DBG(_n("sizeof(histo)=%d\n"), 2*16);
-//	DBG(_n("sizeof(pattern)=%d\n"), 2*12);
-	DBG(_n("sizeof(total)=%d\n"), 32*32+2*16+2*12);
 	bool ret = false;
 	int16_t x = _X;
 	int16_t y = _Y;
-	int16_t z = _Z;
+	const int16_t z = _Z;
 
-	uint8_t* pixels = (uint8_t*)block_buffer;
-	xyzcal_scan_pixels_32x32(x, y, z - 72, 2400, 200, pixels);
+	uint8_t *matrix32 = (uint8_t *)block_buffer;
+	uint16_t *pattern08 = (uint16_t *)(matrix32 + 32 * 32);
+	uint16_t *pattern10 = (uint16_t *)(pattern08 + 12);
 
-	uint16_t* histo = (uint16_t*)(pixels + 32*32);
-	xyzcal_histo_pixels_32x32(pixels, histo);
+	for (uint8_t i = 0; i < 12; i++){
+		pattern08[i] = pgm_read_word((uint16_t*)(xyzcal_point_pattern_08 + i));
+		pattern10[i] = pgm_read_word((uint16_t*)(xyzcal_point_pattern_10 + i));
+	}
 
-	xyzcal_adjust_pixels(pixels, histo);
+	xyzcal_scan_pixels_32x32_Zhop(x, y, z, 2400, 200, matrix32);
+	print_image(matrix32);
+
+	/// SEARCH FOR BINARY CIRCLE
+	uint8_t uc = 0;
+	uint8_t ur = 0;
+
+	/// max match = 132, 1/2 good = 66, 2/3 good = 88
+	if (find_patterns(matrix32, pattern08, pattern10, uc, ur) >= 88){
+		/// find precise circle
+		/// move to the center of the pattern (+5.5)
+		float xf = uc + 5.5f;
+		float yf = ur + 5.5f;
+		float radius = 4.5f; ///< default radius
+		constexpr const uint8_t iterations = 20;
+		dynamic_circle(matrix32, xf, yf, radius, iterations);
+		if (fabs(xf - (uc + 5.5f)) > 3 || fabs(yf - (ur + 5.5f)) > 3 || fabs(radius - 5) > 3){
+			//@size=88
+            DBG(_n(" [%f %f][%f] mm divergence\n"), xf - (uc + 5.5f), yf - (ur + 5.5f), radius - 5);
+			/// dynamic algorithm diverged, use original position instead
+			xf = uc + 5.5f;
+			yf = ur + 5.5f;
+		}
 
-	uint16_t* pattern = (uint16_t*)(histo + 2*16);
-	for (uint8_t i = 0; i < 12; i++)
-	{
-		pattern[i] = pgm_read_word((uint16_t*)(xyzcal_point_pattern + i));
-//		DBG(_n(" pattern[%d]=%d\n"), i, pattern[i]);
-	}
-	uint8_t c = 0;
-	uint8_t r = 0;
-	if (xyzcal_find_pattern_12x12_in_32x32(pixels, pattern, &c, &r) > 66) //total pixels=144, corner=12 (1/2 = 66)
-	{
-		DBG(_n(" pattern found at %d %d\n"), c, r);
-		c += 6;
-		r += 6;
-		x += ((int16_t)c - 16) << 6;
-		y += ((int16_t)r - 16) << 6;
-		DBG(_n(" x=%d y=%d z=%d\n"), x, y, z);
+		/// move to the center of area and convert to position
+		xf = (float)x + (xf - 15.5f) * 64;
+		yf = (float)y + (yf - 15.5f) * 64;
+		//@size=114
+        DBG(_n(" [%f %f] mm pattern center\n"), pos_2_mm(xf), pos_2_mm(yf));
+		x = round_to_i16(xf);
+		y = round_to_i16(yf);
 		xyzcal_lineXYZ_to(x, y, z, 200, 0);
 		ret = true;
 	}
+
+	/// wipe buffer
 	for (uint16_t i = 0; i < sizeof(block_t)*BLOCK_BUFFER_SIZE; i++)
-		pixels[i] = 0;
+		matrix32[i] = 0;
 	return ret;
 }
 
-bool xyzcal_find_bed_induction_sensor_point_xy(void)
-{
-	DBG(_n("xyzcal_find_bed_induction_sensor_point_xy x=%ld y=%ld z=%ld\n"), count_position[X_AXIS], count_position[Y_AXIS], count_position[Z_AXIS]);
+bool xyzcal_find_bed_induction_sensor_point_xy(void){
 	bool ret = false;
+
+    //@size=258
+    DBG(_n("xyzcal_find_bed_induction_sensor_point_xy x=%ld y=%ld z=%ld\n"), count_position[X_AXIS], count_position[Y_AXIS], count_position[Z_AXIS]);
 	st_synchronize();
-	int16_t x = _X;
-	int16_t y = _Y;
-	int16_t z = _Z;
-	uint8_t point = xyzcal_xycoords2point(x, y);
-	x = pgm_read_word((uint16_t*)(xyzcal_point_xcoords + point));
-	y = pgm_read_word((uint16_t*)(xyzcal_point_ycoords + point));
-	DBG(_n("point=%d x=%d y=%d z=%d\n"), point, x, y, z);
+	///< magic constant, lowers min_z after searchZ to obtain more dense data in scan
+	const pos_i16_t lower_z = 72; 
+
 	xyzcal_meassure_enter();
-	xyzcal_lineXYZ_to(x, y, z, 200, 0);
-	if (xyzcal_searchZ())
-	{
-		int16_t z = _Z;
-		xyzcal_lineXYZ_to(x, y, z, 200, 0);
-		if (xyzcal_scan_and_process())
-		{
-			if (xyzcal_find_point_center2(500))
-			{
-				uint32_t x_avg = 0;
-				uint32_t y_avg = 0;
-				uint8_t n; for (n = 0; n < 4; n++)
-				{
-					if (!xyzcal_find_point_center2(1000)) break;
-					x_avg += _X;
-					y_avg += _Y;	
-				}
-				if (n == 4)
-				{
-					xyzcal_lineXYZ_to(x_avg >> 2, y_avg >> 2, _Z, 200, 0);
-					ret = true;
-				}
-			}
-		}
+	if (xyzcal_searchZ()){
+		xyzcal_lineXYZ_to(_X, _Y, _Z - lower_z, 200, 0);
+		ret = xyzcal_scan_and_process();
 	}
 	xyzcal_meassure_leave();
 	return ret;
 }
 
-
 #endif //NEW_XYZCAL

+ 0 - 14
Firmware/xyzcal.h

@@ -17,20 +17,6 @@ extern bool xyzcal_spiral8(int16_t cx, int16_t cy, int16_t z0, int16_t dz, int16
 
 //extern int8_t xyzcal_meassure_pinda_hysterezis(int16_t min_z, int16_t max_z, uint16_t delay_us, uint8_t samples);
 
-extern void xyzcal_scan_pixels_32x32(int16_t cx, int16_t cy, int16_t min_z, int16_t max_z, uint16_t delay_us, uint8_t* pixels);
-
-extern void xyzcal_histo_pixels_32x32(uint8_t* pixels, uint16_t* histo);
-
-extern void xyzcal_adjust_pixels(uint8_t* pixels, uint16_t* histo);
-
-extern int16_t xyzcal_match_pattern_12x12_in_32x32(uint16_t* pattern, uint8_t* pixels, uint8_t x, uint8_t y);
-
-extern int16_t xyzcal_find_pattern_12x12_in_32x32(uint8_t* pixels, uint16_t* pattern, uint8_t* pc, uint8_t* pr);
-
-extern int8_t xyzcal_find_point_center2(uint16_t delay_us);
-
-//extern int8_t xyzcal_find_point_center(int16_t x0, int16_t y0, int16_t z0, int16_t min_z, int16_t max_z, uint16_t delay_us, uint8_t turns);
-
 extern bool xyzcal_searchZ(void);
 
 extern bool xyzcal_scan_and_process(void);

+ 283 - 65
PF-build.sh

@@ -15,7 +15,7 @@
 # 3. Install zip with 'apt-get install zip'
 # 4. Install python3 with 'apt-get install python3'
 # 5. Add command 'ln -sf /usr/bin/python3.5 /usr/bin/python' to link python3 to python.
-#    Donnot istall 'python' as python 2.x has end of life see https://pythonclock.org/
+#    Do not install 'python' as python 2.x has end of life see https://pythonclock.org/
 # 6. Add at top of ~/.bashrc following lines by using 'sudo nano ~/.bashrc'
 #
 #    export OS="Linux"
@@ -37,7 +37,7 @@
 # 2. Another great tool to compare your custom mod and stock firmware is WinMerge http://winmerge.org/downloads/?lang=en
 # 
 # Example for MK3: open git bash and change to your Firmware directory 
-# <username>@<machinename> MINGW64 /<drive>/path
+# <username>@<machine name> MINGW64 /<drive>/path
 # bash build.sh 1_75mm_MK3-EINSy10a-E3Dv6full
 #
 # Example for MK25: open git bash and change to your directory 
@@ -56,15 +56,15 @@
 #   Some may argue that this is only used by a script, BUT as soon someone accidentally or on purpose starts Arduino IDE
 #   it will use the default Arduino IDE folders and so can corrupt the build environment.
 #
-# Version: 1.0.6-Build_13
+# Version: 1.0.6-Build_36
 # Change log:
 # 12 Jan 2019, 3d-gussner, Fixed "compiler.c.elf.flags=-w -Os -Wl,-u,vfprintf -lprintf_flt -lm -Wl,--gc-sections" in 'platform.txt'
 # 16 Jan 2019, 3d-gussner, Build_2, Added development check to modify 'Configuration.h' to prevent unwanted LCD messages that Firmware is unknown
 # 17 Jan 2019, 3d-gussner, Build_3, Check for OS Windows or Linux and use the right build environment
 # 10 Feb 2019, ropaha, Pull Request, Select variant from list while using build.sh
 # 10 Feb 2019, ropaha, change FW_DEV_VERSION automatically depending on FW_VERSION RC/BETA/ALPHA
-# 10 Feb 2019, 3d-gussner, 1st tests with english only 
-# 10 Feb 2019, ropaha, added compiling of all variants and english only
+# 10 Feb 2019, 3d-gussner, 1st tests with English only 
+# 10 Feb 2019, ropaha, added compiling of all variants and English only
 # 10 Feb 2019, 3d-gussner, Set OUTPUT_FOLDER for hex files
 # 11 Feb 2019, 3d-gussner/ropaha, Minor changes and fixes
 # 11 Feb 2019, 3d-gussner, Ready for RC
@@ -80,44 +80,63 @@
 #                                              Configuration_prusa.h
 #                                              language build files
 #                                              multi language firmware files exist and clean them up
-# 15 Feb 2019, 3d-gussner, Fixed selction GOLD/UNKNOWN DEV_STATUS for ALL variants builds, so you have to choose only once
+# 15 Feb 2019, 3d-gussner, Fixed selection GOLD/UNKNOWN DEV_STATUS for ALL variants builds, so you have to choose only once
 # 15 Feb 2019, 3d-gussner, Added some colored output
 # 15 Feb 2019, 3d-gussner, troubleshooting and minor fixes
 # 16 Feb 2019, 3d-gussner, Script can be run using arguments
 #                          $1 = variant, example "1_75mm_MK3-EINSy10a-E3Dv6full.h" at this moment it is not possible to use ALL
-#                          $2 = multi language OR english only [ALL/EN_ONLY]
+#                          $2 = multi language OR English only [ALL/EN_ONLY]
 #                          $3 = development status [GOLD/RC/BETA/ALPHA/DEVEL/DEBUG]
 #                          If one argument is wrong a list of valid one will be shown
-# 13 Mar 2019, 3d-gussner, MKbel updated the linux build environment to version 1.0.2 with an Fix maximum firmware flash size.
+# 13 Mar 2019, 3d-gussner, MKbel updated the Linux build environment to version 1.0.2 with an Fix maximum firmware flash size.
 #                          So did I
 # 11 Jul 2019, deliopoulos,Updated to v1.0.6 as Prusa needs a new board definition for Firmware 3.8.x86_64
-#						   - Splitted the Download of Windows Arduino IDE 1.8.5 and Prusa specific part
+#						   - Split the Download of Windows Arduino IDE 1.8.5 and Prusa specific part
 #                            --> less download volume needed and saves some time
 #
-# 13 Jul 2019, deliopoulos,Splitting of Ardunio IDE and Prusa parts also for Linux64
+# 13 Jul 2019, deliopoulos,Splitting of Arduino IDE and Prusa parts also for Linux64
 # 13 Jul 2019, 3d-gussner, Added Linux 32-bit version (untested yet)
 #                          MacOS could be added in future if needs
 # 14 Jul 2019, 3d-gussner, Update preferences and make it really portable
-# 15 Jul 2019, 3d-gussner, New PF-build-env gihub branch
-# 16 Jul 2019, 3d-gussner, New Arduino_boards github fork
+# 15 Jul 2019, 3d-gussner, New PF-build-env GitHub branch
+# 16 Jul 2019, 3d-gussner, New Arduino_boards GitHub fork
 # 17 Jul 2019, 3d-gussner, Final tests under Windows 10 and Linux Subsystem for Windows   
 # 18 Jul 2019, 3d-gussner, Added python check
 # 18 Jul 2019, deliopoulos, No need more for changing 'platform.txt' file as it comes with the Arduino Boards.
 # 18 Jul 2019, deliopoulos, Modified 'PF_BUILD_FILE_URL' to use 'BUILD_ENV' variable
-# 22 Jul 2019, 3d-gussner, Modiffied checks to check folder and/or installation output exists.
+# 22 Jul 2019, 3d-gussner, Modified checks to check folder and/or installation output exists.
 # 22 Jul 2019, 3d-gussner, Added check if Arduino IDE 1.8.5 boards have been updated
 # 22 Jul 2019, 3d-gussner, Changed exit numbers 1-13 for prepare build env 21-28 for prepare compiling 31-36 compiling
-# 22 Jul 2019, 3d-gussner, Changed BOARD_URL to DRracers respository after he pulled my PR https://github.com/DRracer/Arduino_Boards/pull/1
+# 22 Jul 2019, 3d-gussner, Changed BOARD_URL to DRracers repository after he pulled my PR https://github.com/DRracer/Arduino_Boards/pull/1
 # 23 Jul 2019, 3d-gussner, Changed Build-env path to "PF-build-dl" as requested in PR https://github.com/prusa3d/Prusa-Firmware/pull/2028
 #                          Changed Hex-files folder to PF-build-hex as requested in PR
 # 23 Jul 2019, 3d-gussner, Added Finding OS version routine so supporting new OS should get easier
 # 26 Jul 2019, 3d-gussner, Change JSON repository to prusa3d after PR https://github.com/prusa3d/Arduino_Boards/pull/1 was merged
-# 23 Sep 2019, 3d-gussner, Prepare PF-build.sh for comming Prusa3d/Arduino_Boards version 1.0.2 Pull Request
-# 17 Oct 2019, 3d-gussner, Changed folder and check file names to have seperated build enviroments depening on Arduino IDE version and
+# 23 Sep 2019, 3d-gussner, Prepare PF-build.sh for coming Prusa3d/Arduino_Boards version 1.0.2 Pull Request
+# 17 Oct 2019, 3d-gussner, Changed folder and check file names to have separated build environments depending on Arduino IDE version and
 #                          board-versions.
 # 15 Dec 2019, 3d-gussner, Prepare for switch to Prusa3d/PF-build-env repository
-# 15 Dec 2019, 3d-gussner, Fix Audrino user preferences for the chosen board.
+# 15 Dec 2019, 3d-gussner, Fix Arduino user preferences for the chosen board.
 # 17 Dec 2019, 3d-gussner, Fix "timer0_fract = 0" warning by using Arduino_boards v1.0.3
+# 28 Apr 2020, 3d-gussner, Added RC3 detection
+# 03 May 2020, deliopoulos, Accept all RCx as RC versions
+# 05 May 2020, 3d-gussner, Make a copy of `not_tran.txt`and `not_used.txt` as `not_tran_$VARIANT.txt`and `not_used_$VARIANT.txt`
+#                          After compiling All multi-language variants it makes it easier to find missing or unused translations.
+# 12 May 2020, DRracer   , Cleanup double MK2/s MK25/s `not_tran` and `not_used` files
+# 13 May 2020, leptun    , If cleanup files do not exist don't try to.
+# 01 Oct 2020, 3d-gussner, Bug fix if using argument EN_ONLY. Thank to @leptun for pointing out.
+#                          Change Build number to script commits 'git rev-list --count HEAD PF-build.sh'
+# 02 Oct 2020, 3d-gussner, Add UNKNOWN as argument option
+# 05 Oct 2020, 3d-gussner, Disable pause and warnings using command line with all needed arguments
+#                          Install needed apps under linux if needed.
+#                          Clean PF-Firmware build when changing git branch
+# 02 Nov 2020, 3d-gussner, Check for "gawk" on Linux
+#                          Add argument to change build number automatically to current commit or define own number
+#                          Update exit numbers 1-13 for prepare build env 21-29 for prepare compiling 30-36 compiling
+# 08 Jan 2021, 3d-gussner, Comment out 'sudo' auto installation
+#                          Add '-?' '-h' help option
+# 27 Jan 2021, 3d-gussner, Add `-c`, `-p` and `-n` options
+
 #### Start check if OSTYPE is supported
 OS_FOUND=$( command -v uname)
 
@@ -192,13 +211,14 @@ if ! type zip > /dev/null; then
 	elif [ $TARGET_OS == "linux" ]; then
 		echo "$(tput setaf 1)Missing 'zip' which is important to run this script"
 		echo "install it with the command $(tput setaf 2)'sudo apt-get install zip'$(tput sgr0)"
+		#sudo apt-get update && apt-get install zip
 		exit 3
 	fi
 fi
 # Check python ... needed during language build
 if ! type python > /dev/null; then
 	if [ $TARGET_OS == "windows" ]; then
-		echo "$(tput setaf 1)Missing 'python' which is important to run this script"
+		echo "$(tput setaf 1)Missing 'python3' which is important to run this script"
 		exit 4
 	elif [ $TARGET_OS == "linux" ]; then
 		echo "$(tput setaf 1)Missing 'python' which is important to run this script"
@@ -206,6 +226,17 @@ if ! type python > /dev/null; then
 		echo "install it with the command $(tput setaf 2)'sudo apt-get install python3'."
 		echo "Check which version of Python3 has been installed using 'ls /usr/bin/python3*'"
 		echo "Use 'sudo ln -sf /usr/bin/python3.x /usr/bin/python' (where 'x' is your version number) to make it default.$(tput sgr0)"
+		#sudo apt-get update && apt-get install python3 && ln -sf /usr/bin/python3 /usr/bin/python
+		exit 4
+	fi
+fi
+
+# Check gawk ... needed during language build
+if ! type gawk > /dev/null; then
+	if [ $TARGET_OS == "linux" ]; then
+		echo "$(tput setaf 1)Missing 'gawk' which is important to run this script"
+		echo "install it with the command $(tput setaf 2)'sudo apt-get install gawk'."
+		#sudo apt-get update && apt-get install gawk
 		exit 4
 	fi
 fi
@@ -235,7 +266,7 @@ echo "Script path :" $SCRIPT_PATH
 echo "OS          :" $OS
 echo "OS type     :" $TARGET_OS
 echo ""
-echo "Ardunio IDE :" $ARDUINO_ENV
+echo "Arduino IDE :" $ARDUINO_ENV
 echo "Build env   :" $BUILD_ENV
 echo "Board       :" $BOARD
 echo "Package name:" $BOARD_PACKAGE_NAME
@@ -416,8 +447,73 @@ fi
 #### Start 
 cd $SCRIPT_PATH
 
-# First argument defines which variant of the Prusa Firmware will be compiled 
-if [ -z "$1" ] ; then
+# Check if git is available
+if type git > /dev/null; then
+	git_available="1"
+fi
+
+while getopts v:l:d:b:o:c:p:n:?h flag
+	do
+	    case "${flag}" in
+	        v) variant_flag=${OPTARG};;
+	        l) language_flag=${OPTARG};;
+	        d) devel_flag=${OPTARG};;
+			b) build_flag=${OPTARG};;
+			o) output_flag=${OPTARG};;
+			c) clean_flag=${OPTARG};;
+			p) prusa_flag=${OPTARG};;
+			n) new_build_flag=${OPTARG};;
+			?) help_flag=1;;
+			h) help_flag=1;;
+	    esac
+	done
+#echo "variant_flag: $variant_flag";
+#echo "language_flag: $language_flag";
+#echo "devel_flag: $devel_flag";
+#echo "build_flag: $build_flag";
+#echo "output_flag: $output_flag";
+#echo "help_flag: $help_flag"
+#echo "clean_flag: $clean_flag"
+#echo "prusa_flag: $prusa_flag"
+#echo "new_build_flag: $new_build_flag"
+
+#
+# '?' 'h' argument usage and help
+if [ "$help_flag" == "1" ] ; then
+echo "***************************************"
+echo "* PF-build.sh Version: 1.0.6-Build_33 *"
+echo "***************************************"
+echo "Arguments:"
+echo "$(tput setaf 2)-v$(tput sgr0) Variant '$(tput setaf 2)All$(tput sgr0)' or variant file name"
+echo "$(tput setaf 2)-l$(tput sgr0) Languages '$(tput setaf 2)ALL$(tput sgr0)' for multi language or '$(tput setaf 2)EN_ONLY$(tput sgr0)' for English only"
+echo "$(tput setaf 2)-d$(tput sgr0) Devel build '$(tput setaf 2)GOLD$(tput sgr0)', '$(tput setaf 2)RC$(tput sgr0)', '$(tput setaf 2)BETA$(tput sgr0)', '$(tput setaf 2)ALPHA$(tput sgr0)', '$(tput setaf 2)DEBUG$(tput sgr0)', '$(tput setaf 2)DEVEL$(tput sgr0)' and '$(tput setaf 2)UNKNOWN$(tput sgr0)'"
+echo "$(tput setaf 2)-b$(tput sgr0) Build/commit number '$(tput setaf 2)Auto$(tput sgr0)' needs git or a number"
+echo "$(tput setaf 2)-o$(tput sgr0) Output '$(tput setaf 2)1$(tput sgr0)' force or '$(tput setaf 2)0$(tput sgr0)' block output and delays"
+echo "$(tput setaf 2)-c$(tput sgr0) Do not clean up lang build'$(tput setaf 2)0$(tput sgr0)' no '$(tput setaf 2)1$(tput sgr0)' yes"
+echo "$(tput setaf 2)-p$(tput sgr0) Keep Configuration_prusa.h '$(tput setaf 2)0$(tput sgr0)' no '$(tput setaf 2)1$(tput sgr0)' yes"
+echo "$(tput setaf 2)-n$(tput sgr0) New fresh build '$(tput setaf 2)0$(tput sgr0)' no '$(tput setaf 2)1$(tput sgr0)' yes"
+echo "$(tput setaf 2)-?$(tput sgr0) Help"
+echo "$(tput setaf 2)-h$(tput sgr0) Help"
+echo 
+echo "Brief USAGE:"
+echo "  $(tput setaf 2)./PF-build.sh$(tput sgr0)  [-v] [-l] [-d] [-b] [-o] [-c] [-p] [-n]"
+echo
+echo "Example:"
+echo "  $(tput setaf 2)./PF-build.sh -v All -l ALL -d GOLD$(tput sgr0)"
+echo "  Will build all variants as multi language and final GOLD version"
+echo
+echo "  $(tput setaf 2) ./PF-build.sh -v 1_75mm_MK3S-EINSy10a-E3Dv6full.h -b Auto -l ALL -d GOLD -o 1 -c 1 -p 1 -n 1$(tput sgr0)"
+echo "  Will build MK3S multi language final GOLD firmware "
+echo "  with current commit count number and output extra information,"
+echo "  not delete lang build temporary files, keep Configuration_prusa.h and build with new fresh build folder."
+echo
+exit 
+
+fi
+
+#
+# '-v' argument defines which variant of the Prusa Firmware will be compiled 
+if [ -z "$variant_flag" ] ; then
 	# Select which variant of the Prusa Firmware will be compiled, like
 	PS3="Select a variant: "
 	while IFS= read -r -d $'\0' f; do
@@ -437,7 +533,7 @@ if [ -z "$1" ] ; then
 				;;
 			"Quit")
 				echo "You chose to stop"
-					exit
+					exit 20
 					;;
 			*)
 				echo "$(tput setaf 1)This is not a valid variant$(tput sgr0)"
@@ -445,21 +541,28 @@ if [ -z "$1" ] ; then
 		esac
 	done
 else
-	if [ -f "$SCRIPT_PATH/Firmware/variants/$1" ] ; then 
-		VARIANTS=$1
+	if [ -f "$SCRIPT_PATH/Firmware/variants/$variant_flag" ] ; then 
+		VARIANTS=$variant_flag
+	elif [ "$variant_flag" == "All" ] ; then
+		while IFS= read -r -d $'\0' f; do
+			options[i++]="$f"
+		done < <(find Firmware/variants/ -maxdepth 1 -type f -name "*.h" -print0 )
+		VARIANT="All"
+		VARIANTS=${options[*]}
 	else
-		echo "$(tput setaf 1)$1 could not be found in Firmware/variants please choose a valid one$(tput setaf 2)"
+		echo "$(tput setaf 1)Argument $variant_flag could not be found in Firmware/variants please choose a valid one.$(tput sgr0)"
+		echo "Only $(tput setaf 2)'All'$(tput sgr0) and file names below are allowed as variant '-v' argument.$(tput setaf 2)"
 		ls -1 $SCRIPT_PATH/Firmware/variants/*.h | xargs -n1 basename
 		echo "$(tput sgr0)"
 		exit 21
 	fi
 fi
 
-#Second argument defines if it is an english only version. Known values EN_ONLY / ALL
+#'-l' argument defines if it is an English only version. Known values EN_ONLY / ALL
 #Check default language mode
 MULTI_LANGUAGE_CHECK=$(grep --max-count=1 "^#define LANG_MODE *" $SCRIPT_PATH/Firmware/config.h|sed -e's/  */ /g'|cut -d ' ' -f3)
 
-if [ -z "$2" ] ; then
+if [ -z "$language_flag" ] ; then
 	PS3="Select a language: "
 	echo
 	echo "Which lang-build do you want?"
@@ -467,12 +570,10 @@ if [ -z "$2" ] ; then
 		case $yn in
 			"Multi languages")
 				LANGUAGES="ALL"
-				sed -i -- "s/^#define LANG_MODE *0/#define LANG_MODE              1/g" $SCRIPT_PATH/Firmware/config.h
 				break
 				;;
 			"English only") 
 				LANGUAGES="EN_ONLY"
-				sed -i -- "s/^#define LANG_MODE *1/#define LANG_MODE              0/g" $SCRIPT_PATH/Firmware/config.h
 				break
 				;;
 			*)
@@ -481,53 +582,112 @@ if [ -z "$2" ] ; then
 		esac
 	done
 else
-	if [[ "$2" == "ALL" || "$2" == "EN_ONLY" ]] ; then
-		LANGUAGES=$2
+	if [[ "$language_flag" == "ALL" || "$language_flag" == "EN_ONLY" ]] ; then
+		LANGUAGES=$language_flag
 	else
 		echo "$(tput setaf 1)Language argument is wrong!$(tput sgr0)"
-		echo "Only $(tput setaf 2)'ALL'$(tput sgr0) or $(tput setaf 2)'EN_ONLY'$(tput sgr0) are allowed as 2nd argument!"
+		echo "Only $(tput setaf 2)'ALL'$(tput sgr0) or $(tput setaf 2)'EN_ONLY'$(tput sgr0) are allowed as language '-l' argument!"
 		exit 22
 	fi
 fi
-#Check if DEV_STATUS is selected via argument 3
-if [ ! -z "$3" ] ; then
-	if [[ "$3" == "GOLD" || "$3" == "RC" || "$3" == "BETA" || "$3" == "ALPHA" || "$3" == "DEVEL" || "$3" == "DEBUG" ]] ; then
-		DEV_STATUS_SELECTED=$3
+#Check if DEV_STATUS is selected via argument '-d'
+if [ ! -z "$devel_flag" ] ; then
+	if [[ "$devel_flag" == "GOLD" || "$devel_flag" == "RC" || "$devel_flag" == "BETA" || "$devel_flag" == "ALPHA" || "$devel_flag" == "DEVEL" || "$devel_flag" == "DEBUG" || "$devel_flag" == "UNKNOWN" ]] ; then
+		DEV_STATUS_SELECTED=$devel_flag
 	else
 		echo "$(tput setaf 1)Development argument is wrong!$(tput sgr0)"
-		echo "Only $(tput setaf 2)'GOLD', 'RC', 'BETA', 'ALPHA', 'DEVEL' or 'DEBUG'$(tput sgr0) are allowed as 3rd argument!$(tput sgr0)"
+		echo "Only $(tput setaf 2)'GOLD', 'RC', 'BETA', 'ALPHA', 'DEVEL', 'DEBUG' or 'UNKNOWN' $(tput sgr0) are allowed as devel '-d' argument!$(tput sgr0)"
 		exit 23
 	fi
 fi
 
+#Check if Build is selected via argument '-b'
+if [ ! -z "$build_flag" ] ; then
+	if [[ "$build_flag" == "Auto" && "$git_available" == "1" ]] ; then
+		echo "Build changed to $build_flag"
+		BUILD=$(git rev-list --count HEAD)
+	elif [[ $build_flag =~ ^[0-9]+$ ]] ; then
+		BUILD=$build_flag
+	else
+		echo "$(tput setaf 1)Build number argument is wrong!$(tput sgr0)"
+		echo "Only $(tput setaf 2)'Auto' (git needed) or numbers $(tput sgr0) are allowed as build '-b' argument!$(tput sgr0)"
+		exit 24
+
+	fi
+	echo "New Build number is: $BUILD"
+fi
+
+# check if script has been started with arguments 
+if [[ "$#" -eq  "0" || "$output_flag" == 1 ]] ; then
+	OUTPUT=1
+else
+	OUTPUT=0
+fi
+#echo "Output is:" $OUTPUT
+
+#Check git branch has changed
+if [ ! -z "git_available" ]; then
+	BRANCH=""
+	CLEAN_PF_FW_BUILD=0
+else
+	BRANCH=$(git branch --show-current)
+	echo "Current branch is:" $BRANCH
+	if [ ! -f "$SCRIPT_PATH/../PF-build.branch" ]; then
+		echo "$BRANCH" >| $SCRIPT_PATH/../PF-build.branch
+		echo "created PF-build.branch file"
+	else
+		PRE_BRANCH=$(cat "$SCRIPT_PATH/../PF-build.branch")
+		echo "Previous branch was:" $PRE_BRANCH
+		if [ ! "$BRANCH" == "$PRE_BRANCH" ] ; then
+			CLEAN_PF_FW_BUILD=1
+			echo "$BRANCH" >| $SCRIPT_PATH/../PF-build.branch
+		fi
+	fi
+fi
+
 #Set BUILD_ENV_PATH
-cd ../PF-build-env-$BUILD_ENV/$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor || exit 24
+cd ../PF-build-env-$BUILD_ENV/$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor || exit 25
 BUILD_ENV_PATH="$( pwd -P )"
 
 cd ../..
 
 #Checkif BUILD_PATH exists and if not creates it
 if [ ! -d "Prusa-Firmware-build" ]; then
-    mkdir Prusa-Firmware-build  || exit 25
+    mkdir Prusa-Firmware-build  || exit 26
 fi
 
 #Set the BUILD_PATH for Arduino IDE
-cd Prusa-Firmware-build || exit 26
+cd Prusa-Firmware-build || exit 27
 BUILD_PATH="$( pwd -P )"
 
+#Check git branch has changed
+if [ "$CLEAN_PF_FW_BUILD" == "1" ]; then
+	read -t 10 -p "Branch changed, cleaning Prusa-Firmware-build folder"
+	rm -r *
+else
+	echo "Nothing to clean up"
+fi
+
 for v in ${VARIANTS[*]}
 do
 	VARIANT=$(basename "$v" ".h")
 	# Find firmware version in Configuration.h file and use it to generate the hex filename
 	FW=$(grep --max-count=1 "\bFW_VERSION\b" $SCRIPT_PATH/Firmware/Configuration.h | sed -e's/  */ /g'|cut -d '"' -f2|sed 's/\.//g')
-	# Find build version in Configuration.h file and use it to generate the hex filename
-	BUILD=$(grep --max-count=1 "\bFW_COMMIT_NR\b" $SCRIPT_PATH/Firmware/Configuration.h | sed -e's/  */ /g'|cut -d ' ' -f3)
+	if [ -z "$BUILD" ] ; then	
+		# Find build version in Configuration.h file and use it to generate the hex filename
+		BUILD=$(grep --max-count=1 "\bFW_COMMIT_NR\b" $SCRIPT_PATH/Firmware/Configuration.h | sed -e's/  */ /g'|cut -d ' ' -f3)
+	else
+		# Find and replace build version in Configuration.h file
+		BUILD_ORG=$(grep --max-count=1 "\bFW_COMMIT_NR\b" $SCRIPT_PATH/Firmware/Configuration.h | sed -e's/  */ /g'|cut -d ' ' -f3)
+		echo "Original build number: $BUILD_ORG"
+		sed -i -- "s/^#define FW_COMMIT_NR.*/#define FW_COMMIT_NR $BUILD/g" $SCRIPT_PATH/Firmware/Configuration.h
+	fi
 	# Check if the motherboard is an EINSY and if so only one hex file will generated
 	MOTHERBOARD=$(grep --max-count=1 "\bMOTHERBOARD\b" $SCRIPT_PATH/Firmware/variants/$VARIANT.h | sed -e's/  */ /g' |cut -d ' ' -f3)
 	# Check development status
 	DEV_CHECK=$(grep --max-count=1 "\bFW_VERSION\b" $SCRIPT_PATH/Firmware/Configuration.h | sed -e's/  */ /g'|cut -d '"' -f2|sed 's/\.//g'|cut -d '-' -f2)
 	if [ -z "$DEV_STATUS_SELECTED" ] ; then
-		if [[ "$DEV_CHECK" == "RC1"  ||  "$DEV_CHECK" == "RC2" ]] ; then
+		if [[ "$DEV_CHECK" == *"RC"* ]] ; then
 			DEV_STATUS="RC"
 		elif [[ "$DEV_CHECK" == "ALPHA" ]]; then
 			DEV_STATUS="ALPHA"
@@ -565,7 +725,7 @@ do
 	fi
 	#Prepare hex files folders
 	if [ ! -d "$SCRIPT_PATH/../PF-build-hex/FW$FW-Build$BUILD/$MOTHERBOARD" ]; then
-		mkdir -p $SCRIPT_PATH/../PF-build-hex/FW$FW-Build$BUILD/$MOTHERBOARD || exit 27
+		mkdir -p $SCRIPT_PATH/../PF-build-hex/FW$FW-Build$BUILD/$MOTHERBOARD || exit 28
 	fi
 	OUTPUT_FOLDER="PF-build-hex/FW$FW-Build$BUILD/$MOTHERBOARD"
 	
@@ -574,18 +734,24 @@ do
 		echo ""
 		ls -1 $SCRIPT_PATH/../$OUTPUT_FOLDER/FW$FW-Build$BUILD-$VARIANT.hex | xargs -n1 basename
 		echo "$(tput setaf 6)This hex file to be compiled already exists! To cancel this process press CRTL+C and rename existing hex file.$(tput sgr 0)"
-		read -t 10 -p "Press Enter to continue..."
+		if [ $OUTPUT == "1" ] ; then
+			read -t 10 -p "Press Enter to continue..."
+		fi
 	elif [[ -f "$SCRIPT_PATH/../$OUTPUT_FOLDER/FW$FW-Build$BUILD-$VARIANT-EN_ONLY.hex"  &&  "$LANGUAGES" == "EN_ONLY" ]]; then
 		echo ""
 		ls -1 $SCRIPT_PATH/../$OUTPUT_FOLDER/FW$FW-Build$BUILD-$VARIANT-EN_ONLY.hex | xargs -n1 basename
 		echo "$(tput setaf 6)This hex file to be compiled already exists! To cancel this process press CRTL+C and rename existing hex file.$(tput sgr 0)"
-		read -t 10 -p "Press Enter to continue..."
+		if [ $OUTPUT == "1" ] ; then
+			read -t 10 -p "Press Enter to continue..."
+		fi
 	fi
 	if [[ -f "$SCRIPT_PATH/../$OUTPUT_FOLDER/FW$FW-Build$BUILD-$VARIANT.zip"  &&  "$LANGUAGES" == "ALL" ]]; then
 		echo ""
 		ls -1 $SCRIPT_PATH/../$OUTPUT_FOLDER/FW$FW-Build$BUILD-$VARIANT.zip | xargs -n1 basename
 		echo "$(tput setaf 6)This zip file to be compiled already exists! To cancel this process press CRTL+C and rename existing hex file.$(tput sgr 0)"
-		read -t 10 -p "Press Enter to continue..."
+		if [ $OUTPUT == "1" ] ; then
+			read -t 10 -p "Press Enter to continue..."
+		fi
 	fi
 	
 	#List some useful data
@@ -602,11 +768,13 @@ do
 
 	#Prepare Firmware to be compiled by copying variant as Configuration_prusa.h
 	if [ ! -f "$SCRIPT_PATH/Firmware/Configuration_prusa.h" ]; then
-		cp -f $SCRIPT_PATH/Firmware/variants/$VARIANT.h $SCRIPT_PATH/Firmware/Configuration_prusa.h || exit 28
+		cp -f $SCRIPT_PATH/Firmware/variants/$VARIANT.h $SCRIPT_PATH/Firmware/Configuration_prusa.h || exit 29
 	else
 		echo "$(tput setaf 6)Configuration_prusa.h already exist it will be overwritten in 10 seconds by the chosen variant.$(tput sgr 0)"
-		read -t 10 -p "Press Enter to continue..."
-		cp -f $SCRIPT_PATH/Firmware/variants/$VARIANT.h $SCRIPT_PATH/Firmware/Configuration_prusa.h || exit 28
+		if [ $OUTPUT == "1" ] ; then
+			read -t 10 -p "Press Enter to continue..."
+		fi
+		cp -f $SCRIPT_PATH/Firmware/variants/$VARIANT.h $SCRIPT_PATH/Firmware/Configuration_prusa.h || exit 29
 	fi
 
 	#Prepare Configuration.h to use the correct FW_DEV_VERSION to prevent LCD messages when connecting with OctoPrint
@@ -615,14 +783,16 @@ do
 	# set FW_REPOSITORY
 	sed -i -- 's/#define FW_REPOSITORY "Unknown"/#define FW_REPOSITORY "Prusa3d"/g' $SCRIPT_PATH/Firmware/Configuration.h
 
-	#Prepare english only or multilanguage version to be build
-	if [ $LANGUAGES == "ALL" ]; then
+	#Prepare English only or multi-language version to be build
+	if [ $LANGUAGES == "EN_ONLY" ]; then
 		echo " "
-		echo "Multi-language firmware will be built"
+		echo "English only language firmware will be built"
+		sed -i -- "s/^#define LANG_MODE *1/#define LANG_MODE              0/g" $SCRIPT_PATH/Firmware/config.h
 		echo " "
 	else
 		echo " "
-		echo "English only language firmware will be built"
+		echo "Multi-language firmware will be built"
+		sed -i -- "s/^#define LANG_MODE *0/#define LANG_MODE              1/g" $SCRIPT_PATH/Firmware/config.h
 		echo " "
 	fi
 		
@@ -645,9 +815,17 @@ do
 
 	echo "Start to build Prusa Firmware ..."
 	echo "Using variant $VARIANT$(tput setaf 3)"
-	sleep 2
+	if [ $OUTPUT == "1" ] ; then
+		sleep 2
+	fi
+
+	#New fresh PF-Firmware-build
+	if [ "$new_build_flag" == "1" ]; then
+		rm -r -f $BUILD_PATH/* || exit 36
+	fi
+
 	#$BUILD_ENV_PATH/arduino-builder -dump-prefs -debug-level 10 -compile -hardware $ARDUINO/hardware -hardware $ARDUINO/portable/packages -tools $ARDUINO/tools-builder -tools $ARDUINO/hardware/tools/avr -tools $ARDUINO/portable/packages -built-in-libraries $ARDUINO/libraries -libraries $ARDUINO/portable/sketchbook/libraries -fqbn=$BOARD_PACKAGE_NAME:avr:$BOARD -build-path=$BUILD_PATH -warnings=all $SCRIPT_PATH/Firmware/Firmware.ino || exit 14
-	$BUILD_ENV_PATH/arduino-builder -compile -hardware $ARDUINO/hardware -hardware $ARDUINO/portable/packages -tools $ARDUINO/tools-builder -tools $ARDUINO/hardware/tools/avr -tools $ARDUINO/portable/packages -built-in-libraries $ARDUINO/libraries -libraries $ARDUINO/portable/sketchbook/libraries -fqbn=$BOARD_PACKAGE_NAME:avr:$BOARD -build-path=$BUILD_PATH -warnings=all $SCRIPT_PATH/Firmware/Firmware.ino || exit 14
+	$BUILD_ENV_PATH/arduino-builder -compile -hardware $ARDUINO/hardware -hardware $ARDUINO/portable/packages -tools $ARDUINO/tools-builder -tools $ARDUINO/hardware/tools/avr -tools $ARDUINO/portable/packages -built-in-libraries $ARDUINO/libraries -libraries $ARDUINO/portable/sketchbook/libraries -fqbn=$BOARD_PACKAGE_NAME:avr:$BOARD -build-path=$BUILD_PATH -warnings=all $SCRIPT_PATH/Firmware/Firmware.ino || exit 30
 	echo "$(tput sgr 0)"
 
 	if [ $LANGUAGES ==  "ALL" ]; then
@@ -655,7 +833,9 @@ do
 
 		echo "Building multi language firmware" $MULTI_LANGUAGE_CHECK
 		echo "$(tput sgr 0)"
-		sleep 2
+		if [ $OUTPUT == "1" ] ; then
+			sleep 2
+		fi
 		cd $SCRIPT_PATH/lang
 		echo "$(tput setaf 3)"
 		./config.sh || exit 31
@@ -664,7 +844,9 @@ do
 		if [ -f "lang_en.tmp" ]; then
 			echo ""
 			echo "$(tput setaf 6)Previous lang build files already exist these will be cleaned up in 10 seconds.$(tput sgr 0)"
-			read -t 10 -p "Press Enter to continue..."
+			if [ $OUTPUT == "1" ] ; then
+				read -t 10 -p "Press Enter to continue..."
+			fi
 			echo "$(tput setaf 3)"
 			./lang-clean.sh
 			echo "$(tput sgr 0)"
@@ -672,7 +854,9 @@ do
 		if [ -f "progmem.out" ]; then
 			echo ""
 			echo "$(tput setaf 6)Previous firmware build files already exist these will be cleaned up in 10 seconds.$(tput sgr 0)"
-			read -t 10 -p "Press Enter to continue..."
+			if [ $OUTPUT == "1" ] ; then
+				read -t 10 -p "Press Enter to continue..."
+			fi
 			echo "$(tput setaf 3)"
 			./fw-clean.sh
 			echo "$(tput sgr 0)"
@@ -682,6 +866,8 @@ do
 		./lang-build.sh || exit 32
 		# Combine compiled firmware with languages 
 		./fw-build.sh || exit 33
+		cp not_tran.txt not_tran_$VARIANT.txt
+		cp not_used.txt not_used_$VARIANT.txt
 		echo "$(tput sgr 0)"
 		# Check if the motherboard is an EINSY and if so only one hex file will generated
 		MOTHERBOARD=$(grep --max-count=1 "\bMOTHERBOARD\b" $SCRIPT_PATH/Firmware/variants/$VARIANT.h | sed -e's/  */ /g' |cut -d ' ' -f3)
@@ -705,24 +891,56 @@ do
 			fi
 		fi
 		# Cleanup after build
-		echo "$(tput setaf 3)"
-		./fw-clean.sh || exit 34
-		./lang-clean.sh || exit 35
-		echo "$(tput sgr 0)"
+		if [[ -z "$clean_flag" || "$clean_flag" == "0" ]]; then
+			echo "$(tput setaf 3)"
+			./fw-clean.sh || exit 34
+			./lang-clean.sh || exit 35
+			echo "$(tput sgr 0)"
+		fi
 	else
 		echo "$(tput setaf 2)Copying English only firmware to PF-build-hex folder$(tput sgr 0)"
 		cp -f $BUILD_PATH/Firmware.ino.hex $SCRIPT_PATH/../$OUTPUT_FOLDER/FW$FW-Build$BUILD-$VARIANT-EN_ONLY.hex || exit 34
 	fi
 
 	# Cleanup Firmware
-	rm $SCRIPT_PATH/Firmware/Configuration_prusa.h || exit 36
+	if [[ -z "$prusa_flag" || "$prusa_flag" == "0" ]]; then
+		rm $SCRIPT_PATH/Firmware/Configuration_prusa.h || exit 36
+	fi
+	if find $SCRIPT_PATH/lang/ -name '*RAMBo10a*.txt' -printf 1 -quit | grep -q 1
+	then
+		rm $SCRIPT_PATH/lang/*RAMBo10a*.txt
+	fi
+	if find $SCRIPT_PATH/lang/ -name '*MK2-RAMBo13a*' -printf 1 -quit | grep -q 1
+	then
+		rm $SCRIPT_PATH/lang/*MK2-RAMBo13a*.txt
+	fi
+	if find $SCRIPT_PATH/lang/ -name 'not_tran.txt' -printf 1 -quit | grep -q 1
+	then
+		rm $SCRIPT_PATH/lang/not_tran.txt
+	fi
+	if find $SCRIPT_PATH/lang/ -name 'not_used.txt' -printf 1 -quit | grep -q 1
+	then
+		rm $SCRIPT_PATH/lang/not_used.txt
+	fi
+
+	#New fresh PF-Firmware-build
+	if [ "$new_build_flag" == "1" ]; then
+		rm -r -f $BUILD_PATH/* || exit 36
+	fi
+
+	# Restore files to previous state
 	sed -i -- "s/^#define FW_DEV_VERSION FW_VERSION_$DEV_STATUS/#define FW_DEV_VERSION FW_VERSION_UNKNOWN/g" $SCRIPT_PATH/Firmware/Configuration.h
 	sed -i -- 's/^#define FW_REPOSITORY "Prusa3d"/#define FW_REPOSITORY "Unknown"/g' $SCRIPT_PATH/Firmware/Configuration.h
+	if [ ! -z "$BUILD_ORG" ] ; then
+		sed -i -- "s/^#define FW_COMMIT_NR.*/#define FW_COMMIT_NR $BUILD_ORG/g" $SCRIPT_PATH/Firmware/Configuration.h
+	fi
 	echo $MULTI_LANGUAGE_CHECK
 	#sed -i -- "s/^#define LANG_MODE * /#define LANG_MODE              $MULTI_LANGUAGE_CHECK/g" $SCRIPT_PATH/Firmware/config.h
 	sed -i -- "s/^#define LANG_MODE *1/#define LANG_MODE              ${MULTI_LANGUAGE_CHECK}/g" $SCRIPT_PATH/Firmware/config.h
 	sed -i -- "s/^#define LANG_MODE *0/#define LANG_MODE              ${MULTI_LANGUAGE_CHECK}/g" $SCRIPT_PATH/Firmware/config.h
-	sleep 5
+	if [ $OUTPUT == "1" ] ; then
+		sleep 5
+	fi
 done
 
 # Switch to hex path and list build files

+ 224 - 198
README.md

@@ -1,198 +1,224 @@
-# Table of contents
-
-<!--ts-->
-   * [Linux build](#linux)
-   * Windows build
-     * [Using Arduino](#using-arduino)
-     * [Using Linux subsystem](#using-linux-subsystem-under-windows-10-64-bit)
-     * [Using Git-bash](#using-git-bash-under-windows-10-64-bit)
-   * [Automated tests](#3-automated-tests)
-   * [Documentation](#4-documentation)
-   * [FAQ](#5-faq)
-<!--te-->
-
-
-# Build
-## Linux
-
-1. Clone this repository and checkout the correct branch for your desired release version.
-
-2. Set your printer model. 
-   - For MK3 --> skip to step 3. 
-   - If you have a different printer model, follow step [2.b](#2b) from Windows build
-   
-3. Run `sudo ./build.sh`
-   - Output hex file is at `"PrusaFirmware/lang/firmware.hex"` . In the same folder you can hex files for other languages as well.
-
-4. Connect your printer and flash with PrusaSlicer ( Configuration --> Flash printer firmware ) or Slic3r PE.
-   - If you wish to flash from Arduino, follow step [2.c](#2c) from Windows build first.
-
-
-_Notes:_
-
-The script downloads Arduino with our modifications and Rambo board support installed, unpacks it into folder `PF-build-env-\<version\>` on the same level, as your Prusa-Firmware folder is located, builds firmware for MK3 using that Arduino in Prusa-Firmware-build folder on the same level as Prusa-Firmware, runs secondary language support scripts. Firmware with secondary language support is generated in lang subfolder. Use firmware.hex for MK3 variant. Use `firmware_\<lang\>.hex` for other printers. Don't forget to follow step [2.b](#2b) first for non-MK3 printers.
-
-## Windows
-### Using Arduino
-_Note: Multi language build is not supported._
-
-#### 1. Development environment preparation
-
-**a.** Install `"Arduino Software IDE"` from the official website `https://www.arduino.cc -> Software->Downloads` 
-   
-   _It is recommended to use version `"1.8.5"`, as it is used on out build server to produce official builds._
-
-**b.** Setup Arduino to use Prusa Rambo board definition
-
-* Open Arduino and navigate to File -> Preferences -> Settings
-* To the text field `"Additional Boards Manager URLSs"` add `https://raw.githubusercontent.com/prusa3d/Arduino_Boards/master/IDE_Board_Manager/package_prusa3d_index.json`
-* Open Board manager (`Tools->Board->Board manager`), and install `Prusa Research AVR Boards by Prusa Research`
-
-**c.** Modify compiler flags in `platform.txt` file
-     
-* The platform.txt file can be found in Arduino instalation directory, or after Arduino has been updated at: `"C:\Users\(user)\AppData\Local\Arduino15\packages\arduino\hardware\avr\(version)"` If you can locate the file in both places, file from user profile is probably used.
-       
-* Add `"-Wl,-u,vfprintf -lprintf_flt -lm"` to `"compiler.c.elf.flags="` before existing flag "-Wl,--gc-sections"  
-
-    For example:  `"compiler.c.elf.flags=-w -Os -Wl,-u,vfprintf -lprintf_flt -lm -Wl,--gc-sections"`
-   
-_Notes:_
-
-
-_In the case of persistent compilation problems, check the version of the currently used C/C++ compiler (GCC) - should be at leas `4.8.1`; 
-If you are not sure where the file is placed (depends on how `"Arduino Software IDE"` was installed), you can use the search feature within the file system_
-
-_Name collision for `"LiquidCrystal"` library known from previous versions is now obsolete (so there is no need to delete or rename original file/-s)_
-
-#### 2. Source code compilation
-
-**a.** Clone this repository`https://github.com/prusa3d/Prusa-Firmware/` to your local drive.
-
-**b.**<a name="2b"></a> In the subdirectory `"Firmware/variants/"` select the configuration file (`.h`) corresponding to your printer model, make copy named `"Configuration_prusa.h"` (or make simple renaming) and copy it into `"Firmware/"` directory.  
-
-**c.**<a name="2c"></a> In file `"Firmware/config.h"` set LANG_MODE to 0.
-
-**d.** Run `"Arduino IDE"`; select the file `"Firmware.ino"` from the subdirectory `"Firmware/"` at the location, where you placed the source code `File->Open` Make the desired code customizations; **all changes are on your own risk!**  
-
-**e.** Select the target board `"Tools->Board->PrusaResearch Einsy RAMBo"`  
-
-**f.** Run the compilation `Sketch->Verify/Compile`  
-
-**g.** Upload the result code into the connected printer `Sketch->Upload`  
-
-* or you can also save the output code to the file (in so called `HEX`-format) `"Firmware.ino.rambo.hex"`:  `Sketch->ExportCompiledBinary` and then upload it to the printer using the program `"FirmwareUpdater"`  
-_note: this file is created in the directory `"Firmware/"`_  
-
-### Using Linux subsystem under Windows 10 64-bit
-_notes: Script and instructions contributed by 3d-gussner. Use at your own risk. Script downloads Arduino executables outside of Prusa control. Report problems [there.](https://github.com/3d-gussner/Prusa-Firmware/issues) Multi language build is supported._
-- follow the Microsoft guide https://docs.microsoft.com/en-us/windows/wsl/install-win10
-  You can also use the 'prepare_winbuild.ps1' powershell script with Administrator rights
-- Tested versions are at this moment
-  - Ubuntu other may different
-  - After the installation and reboot please open your Ubuntu bash and do following steps
-  - run command `apt-get update`
-  - to install zip run `apt-get install zip`
-  - add few lines at the top of `~/.bashrc` by running `sudo nano ~/.bashrc`
-	
-	export OS="Linux"
-	export JAVA_TOOL_OPTIONS="-Djava.net.preferIPv4Stack=true"
-	export GPG_TTY=$(tty)
-	
-	use `CRTL-X` to close nano and confirm to write the new entries
-  - restart Ubuntu bash
-Now your Ubuntu subsystem is ready to use the automatic `PF-build.sh` script and compile your firmware correctly
-
-#### Some Tips for Ubuntu
-- Linux is case sensetive so please don't forget to use capital letters where needed, like changing to a directory
-- To change the path to your Prusa-Firmware location you downloaded and unzipped
-  - Example: You files are under `C:\Users\<your-username>\Downloads\Prusa-Firmware-MK3`
-  - use under Ubuntu the following command `cd /mnt/c/Users/<your-username>/Downloads/Prusa-Firmware-MK3`
-    to change to the right folder
-- Unix and windows have different line endings (LF vs CRLF), try dos2unix to convert
-  - This should fix the `"$'\r': command not found"` error
-  - to install run `apt-get install dos2unix`
-- If your Windows isn't in English the Paths may look different
-  Example in other languages
-  - English `/mnt/c/Users/<your-username>/Downloads/Prusa-Firmware-MK3` will be on a German Windows`/mnt/c/Anwender/<your-username>/Downloads/Prusa-Firmware-MK3`
-#### Compile Prusa-firmware with Ubuntu Linux subsystem installed
-- open Ubuntu bash
-- change to your source code folder (case sensitive)
-- run `./PF-build.sh`
-- follow the instructions
-
-### Using Git-bash under Windows 10 64-bit
-_notes: Script and instructions contributed by 3d-gussner. Use at your own risk. Script downloads Arduino executables outside of Prusa control. Report problems [there.](https://github.com/3d-gussner/Prusa-Firmware/issues) Multi language build is supported._
-- Download and install the 64bit Git version https://git-scm.com/download/win
-- Also follow these instructions https://gist.github.com/evanwill/0207876c3243bbb6863e65ec5dc3f058
-- Download and install 7z-zip from its official website https://www.7-zip.org/
-  By default, it is installed under the directory /c/Program\ Files/7-Zip in Windows 10
-- Run `Git-Bash` under Administrator privilege
-- navigate to the directory /c/Program\ Files/Git/mingw64/bin
-- run `ln -s /c/Program\ Files/7-Zip/7z.exe zip.exe`
-- If your Windows isn't in English the Paths may look different
-  Example in other languages
-  - English `/mnt/c/Users/<your-username>/Downloads/Prusa-Firmware-MK3` will be on a German Windows`/mnt/c/Anwender/<your-username>/Downloads/Prusa-Firmware-MK3`
-  - English `ln -s /c/Program\ Files/7-Zip/7z.exe zip.exe` will be on a Spanish Windows `ln -s /c/Archivos\ de\ programa/7-Zip/7z.exe zip.exe`
-#### Compile Prusa-firmware with Git-bash installed
-- open Git-bash
-- change to your source code folder
-- run `bash PF-build.sh`
-- follow the instructions
-
-
-# 3. Automated tests
-## Prerequisites
-* c++11 compiler e.g. g++ 6.3.1
-* cmake
-* build system - ninja or gnu make
-
-## Building
-Create a folder where you want to build tests.
-
-Example:
-
-`cd ..`
-
-`mkdir Prusa-Firmware-test`
-
-Generate build scripts in target folder.
-
-Example:
-
-`cd Prusa-Firmware-test`
-
-`cmake -G "Eclipse CDT4 - Ninja" ../Prusa-Firmware`
-
-or for DEBUG build:
-
-`cmake -G "Eclipse CDT4 - Ninja" -DCMAKE_BUILD_TYPE=Debug ../Prusa-Firmware`
-
-Build it.
-
-Example:
-
-`ninja`
-
-## Runing
-`./tests`
-
-# 4. Documentation
-run [doxygen](http://www.doxygen.nl/) in Firmware folder
-or visit https://prusa3d.github.io/Prusa-Firmware-Doc for doxygen generated output
-
-# 5. FAQ
-Q:I built firmware using Arduino and I see "?" instead of numbers in printer user interface.
-
-A:Step 1.c was ommited or you updated Arduino and now platform.txt located somewhere in your user profile is used.
-
-Q:I built firmware using Arduino and printer now speaks Klingon (nonsense characters and symbols are displayed @^#$&*°;~ÿ)
-
-A:Step 2.c was omitted.
-
-Q:What environment does Prusa use to build the firmware in the first place?
-
-A:Our production builds are 99.9% equivalent to https://github.com/prusa3d/Prusa-Firmware#linux this is also easiest way to build as only one step is needed - run single script, which downloads patched Arduino from github, builds using it, then extracts translated strings and creates language variants (for MK2x) or language hex file for external SPI flash (MK3x). But you need Linux or Linux in virtual machine. This is also what happens when you open pull request to our repository - all variants are built by Travis http://travis-ci.org/ (to check for compilation errors). You can see, what is happening in .travis.yml. It would be also possible to get hex built by travis, only deploy step is missing in .travis.yml. You can get inspiration how to deploy hex by travis and how to setup travis in https://github.com/prusa3d/MM-control-01/ repository. Final hex is located in ./lang/firmware.hex Community reproduced this for Windows in https://github.com/prusa3d/Prusa-Firmware#using-linux-subsystem-under-windows-10-64-bit or https://github.com/prusa3d/Prusa-Firmware#using-git-bash-under-windows-10-64-bit .
-
-Q:Why are build instructions for Arduino mess.
-
-Y:We are too lazy to ship proper board definition for Arduino. We plan to swich to cmake + ninja to be inherently multiplatform, easily integrate build tools, suport more IDEs, get 10 times shorter build times and be able to update compiler whenewer we want.
+# Prusa Firmware MK3
+
+This repository contains the source code and the development versions of the firmware running on the [Original Prusa i3](https://prusa3d.com/) MK3S/MK3/MK2.5S/MK2.5 line of printers.
+
+The latest official builds can be downloaded from [Prusa Drivers](https://www.prusa3d.com/drivers/). Pre-built development releases are also [available here](https://github.com/prusa3d/Prusa-Firmware/releases).
+
+The firmware for the Original Prusa i3 printers is proudly based on [Marlin 1.0.x](https://github.com/MarlinFirmware/Marlin/) by Scott Lahteine (@thinkyhead) et al. and is distributed under the terms of the [GNU GPL 3 license](LICENSE).
+
+
+# Table of contents
+
+<!--ts-->
+   * [Linux build](#linux)
+   * Windows build
+     * [Using Arduino](#using-arduino)
+     * [Using Linux subsystem](#using-linux-subsystem-under-windows-10-64-bit)
+     * [Using Git-bash](#using-git-bash-under-windows-10-64-bit)
+   * [Automated tests](#3-automated-tests)
+   * [Documentation](#4-documentation)
+   * [FAQ](#5-faq)
+<!--te-->
+
+
+# Build
+## Linux
+
+1. Clone this repository and checkout the correct branch for your desired release version.
+
+1. Set your printer model. 
+   - For MK3 --> skip to step 3. 
+   - If you have a different printer model, follow step [2.b](#2b) from Windows build
+1. Install GNU AWK  `sudo apt-get install gawk`  
+If you use mawk instead of gawk you get strange errors when multi language support is generated like:  
+`awk: line 2: function strtonum never defined
+sed: couldn't write 4 items to stdout: Broken pipe
+./lang-build.sh: 121: ./lang-build.sh: arithmetic expression: expecting EOF: "0x"awk: line 2: function strtonum never defined
+sed: couldn't write 4 items to stdout: Broken pipe
+tr: write error: Broken pipe
+./lang-build.sh: 121: ./lang-build.sh: arithmetic expression: expecting EOF: "0x"awk: line 2: function strtonum never defined
+sed: couldn't write 4 items to stdout: Broken pipe
+tr: write error: Broken pipe
+tr: write error
+cut: write error: Broken pipeNG! - some texts not found in lang_en.txt! updating binary:
+  primary language ids...awk: line 2: function strtonum never defined
+sed: couldn't flush stdout: Broken pipe`
+   
+1. Run `./build.sh`
+   - Output hex file is at `"PrusaFirmware/lang/firmware.hex"` . In the same folder you can hex files for other languages as well.
+
+1. Connect your printer and flash with PrusaSlicer ( Configuration --> Flash printer firmware ) or Slic3r PE.
+   - If you wish to flash from Arduino, follow step [2.c](#2c) from Windows build first.
+
+
+_Notes:_
+
+The script downloads Arduino with our modifications and Rambo board support installed, unpacks it into folder `PF-build-env-\<version\>` on the same level, as your Prusa-Firmware folder is located, builds firmware for MK3 using that Arduino in Prusa-Firmware-build folder on the same level as Prusa-Firmware, runs secondary language support scripts. Firmware with secondary language support is generated in lang subfolder. Use firmware.hex for MK3 variant. Use `firmware_\<lang\>.hex` for other printers. Don't forget to follow step [2.b](#2b) first for non-MK3 printers.
+
+## Windows
+### Using Arduino
+_Note: Multi language build is not supported._
+
+#### 1. Development environment preparation
+
+**a.** Install `"Arduino Software IDE"` from the official website `https://www.arduino.cc -> Software->Downloads` 
+   
+   _It is recommended to use version `"1.8.5"`, as it is used on out build server to produce official builds._
+
+**b.** Setup Arduino to use Prusa Rambo board definition
+
+* Open Arduino and navigate to File -> Preferences -> Settings
+* To the text field `"Additional Boards Manager URLSs"` add `https://raw.githubusercontent.com/prusa3d/Arduino_Boards/master/IDE_Board_Manager/package_prusa3d_index.json`
+* Open Board manager (`Tools->Board->Board manager`), and install `Prusa Research AVR Boards by Prusa Research`
+
+**c.** Modify compiler flags in `platform.txt` file
+     
+* The platform.txt file can be found in Arduino installation directory, or after Arduino has been updated at: `"C:\Users\(user)\AppData\Local\Arduino15\packages\arduino\hardware\avr\(version)"` If you can locate the file in both places, file from user profile is probably used.
+       
+* Add `"-Wl,-u,vfprintf -lprintf_flt -lm"` to `"compiler.c.elf.flags="` before existing flag "-Wl,--gc-sections"  
+
+    For example:  `"compiler.c.elf.flags=-w -Os -Wl,-u,vfprintf -lprintf_flt -lm -Wl,--gc-sections"`
+   
+_Notes:_
+
+
+_In the case of persistent compilation problems, check the version of the currently used C/C++ compiler (GCC) - should be at leas `4.8.1`; 
+If you are not sure where the file is placed (depends on how `"Arduino Software IDE"` was installed), you can use the search feature within the file system_
+
+_Name collision for `"LiquidCrystal"` library known from previous versions is now obsolete (so there is no need to delete or rename original file/-s)_
+
+#### 2. Source code compilation
+
+**a.** Clone this repository`https://github.com/prusa3d/Prusa-Firmware/` to your local drive.
+
+**b.**<a name="2b"></a> In the subdirectory `"Firmware/variants/"` select the configuration file (`.h`) corresponding to your printer model, make copy named `"Configuration_prusa.h"` (or make simple renaming) and copy it into `"Firmware/"` directory.  
+
+**c.**<a name="2c"></a> In file `"Firmware/config.h"` set LANG_MODE to 0.
+
+**d.** Run `"Arduino IDE"`; select the file `"Firmware.ino"` from the subdirectory `"Firmware/"` at the location, where you placed the source code `File->Open` Make the desired code customizations; **all changes are on your own risk!**  
+
+**e.** Select the target board `"Tools->Board->PrusaResearch Einsy RAMBo"`  
+
+**f.** Run the compilation `Sketch->Verify/Compile`  
+
+**g.** Upload the result code into the connected printer `Sketch->Upload`  
+
+* or you can also save the output code to the file (in so called `HEX`-format) `"Firmware.ino.rambo.hex"`:  `Sketch->ExportCompiledBinary` and then upload it to the printer using the program `"FirmwareUpdater"`  
+_note: this file is created in the directory `"Firmware/"`_  
+
+### Using Linux subsystem under Windows 10 64-bit
+_notes: Script and instructions contributed by 3d-gussner. Use at your own risk. Script downloads Arduino executables outside of Prusa control. Report problems [there.](https://github.com/3d-gussner/Prusa-Firmware/issues) Multi language build is supported._
+- follow the Microsoft guide https://docs.microsoft.com/en-us/windows/wsl/install-win10
+  You can also use the 'prepare_winbuild.ps1' powershell script with Administrator rights
+- Tested versions are at this moment
+  - Ubuntu and Debian, other may different
+  - After the installation and reboot please open your Ubuntu bash and do following steps
+  - run command `sudo apt-get update`
+  - run command `sudo apt-get upgrade`
+  - to install zip run `sudo apt-get install zip`
+  - to install dos2unix run `sudo apt-get install dos2unix`
+  - run `dos2unix PF-build.sh` to convert the windows line endings to unix line endings
+  - add few lines at the top of `~/.bashrc` by running `sudo nano ~/.bashrc`
+	
+	export OS="Linux"
+	export JAVA_TOOL_OPTIONS="-Djava.net.preferIPv4Stack=true"
+	export GPG_TTY=$(tty)
+	
+	use `CRTL-X` to close nano and confirm to write the new entries
+  - restart Ubuntu/Debian bash
+  - Now your Ubuntu/Debian subsystem is ready to use the automatic `PF-build.sh` script and compile your firmware correctly
+
+#### Some Tips for Ubuntu and Debian
+- Linux is case sensitive so please don't forget to use capital letters where needed, like changing to a directory
+- To change the path to your Prusa-Firmware location you downloaded and unzipped
+  - Example: You files are under `C:\Users\<your-username>\Downloads\Prusa-Firmware-MK3`
+  - use under Ubuntu the following command `cd /mnt/c/Users/<your-username>/Downloads/Prusa-Firmware-MK3`
+    to change to the right folder
+- Unix and windows have different line endings (LF vs CRLF), try dos2unix to convert
+  - This should fix the `"$'\r': command not found"` error
+  - to install run `apt-get install dos2unix`
+- If your Windows isn't in English the Paths may look different
+  Example in other languages
+  - English `/mnt/c/Users/<your-username>/Downloads/Prusa-Firmware-MK3` will be on a German Windows`/mnt/c/Anwender/<your-username>/Downloads/Prusa-Firmware-MK3`
+#### Compile Prusa-firmware with Ubuntu/Debian Linux subsystem installed
+- open Ubuntu bash
+- change to your source code folder (case sensitive)
+- run `./PF-build.sh`
+- follow the instructions
+
+### Using Git-bash under Windows 10 64-bit
+_notes: Script and instructions contributed by 3d-gussner. Use at your own risk. Script downloads Arduino executables outside of Prusa control. Report problems [there.](https://github.com/3d-gussner/Prusa-Firmware/issues) Multi language build is supported._
+- Download and install the 64bit Git version https://git-scm.com/download/win
+- Also follow these instructions https://gist.github.com/evanwill/0207876c3243bbb6863e65ec5dc3f058
+- Download and install 7z-zip from its official website https://www.7-zip.org/
+  By default, it is installed under the directory /c/Program\ Files/7-Zip in Windows 10
+- Run `Git-Bash` under Administrator privilege
+- navigate to the directory /c/Program\ Files/Git/mingw64/bin
+- run `ln -s /c/Program\ Files/7-Zip/7z.exe zip.exe`
+- If your Windows isn't in English the Paths may look different
+  Example in other languages
+  - English `/mnt/c/Users/<your-username>/Downloads/Prusa-Firmware-MK3` will be on a German Windows`/mnt/c/Anwender/<your-username>/Downloads/Prusa-Firmware-MK3`
+  - English `ln -s /c/Program\ Files/7-Zip/7z.exe zip.exe` will be on a Spanish Windows `ln -s /c/Archivos\ de\ programa/7-Zip/7z.exe zip.exe`
+#### Compile Prusa-firmware with Git-bash installed
+- open Git-bash
+- change to your source code folder
+- run `bash PF-build.sh`
+- follow the instructions
+
+
+# 3. Automated tests
+## Prerequisites
+* c++11 compiler e.g. g++ 6.3.1
+* cmake
+* build system - ninja or gnu make
+
+## Building
+Create a folder where you want to build tests.
+
+Example:
+
+`cd ..`
+
+`mkdir Prusa-Firmware-test`
+
+Generate build scripts in target folder.
+
+Example:
+
+`cd Prusa-Firmware-test`
+
+`cmake -G "Eclipse CDT4 - Ninja" ../Prusa-Firmware`
+
+or for DEBUG build:
+
+`cmake -G "Eclipse CDT4 - Ninja" -DCMAKE_BUILD_TYPE=Debug ../Prusa-Firmware`
+
+Build it.
+
+Example:
+
+`ninja`
+
+## Running
+`./tests`
+
+# 4. Documentation
+run [doxygen](http://www.doxygen.nl/) in Firmware folder
+or visit https://prusa3d.github.io/Prusa-Firmware-Doc for doxygen generated output
+
+# 5. FAQ
+Q:I built firmware using Arduino and I see "?" instead of numbers in printer user interface.
+
+A:Step 1.c was omitted or you updated Arduino and now platform.txt located somewhere in your user profile is used.
+
+Q:I built firmware using Arduino and printer now speaks Klingon (nonsense characters and symbols are displayed @^#$&*°;~ÿ)
+
+A:Step 2.c was omitted.
+
+Q:What environment does Prusa use to build the firmware in the first place?
+
+A:Our production builds are 99.9% equivalent to https://github.com/prusa3d/Prusa-Firmware#linux this is also easiest way to build as only one step is needed - run single script, which downloads patched Arduino from github, builds using it, then extracts translated strings and creates language variants (for MK2x) or language hex file for external SPI flash (MK3x). But you need Linux or Linux in virtual machine. This is also what happens when you open pull request to our repository - all variants are built by Travis http://travis-ci.org/ (to check for compilation errors). You can see, what is happening in .travis.yml. It would be also possible to get hex built by travis, only deploy step is missing in .travis.yml. You can get inspiration how to deploy hex by travis and how to setup travis in https://github.com/prusa3d/MM-control-01/ repository. Final hex is located in ./lang/firmware.hex Community reproduced this for Windows in https://github.com/prusa3d/Prusa-Firmware#using-linux-subsystem-under-windows-10-64-bit or https://github.com/prusa3d/Prusa-Firmware#using-git-bash-under-windows-10-64-bit .
+
+Q:Why are build instructions for Arduino mess.
+
+Y:We are too lazy to ship proper board definition for Arduino. We plan to switch to cmake + ninja to be inherently multiplatform, easily integrate build tools, suport more IDEs, get 10 times shorter build times and be able to update compiler whenever we want.

+ 1 - 1
lang/lang-add.sh

@@ -69,5 +69,5 @@ cat lang_add.txt | sed 's/^/"/;s/$/"/' | while read new_s; do
 	fi
 done
 
-read x
+read -t 5
 exit 0

+ 2 - 2
lang/lang-build.sh

@@ -5,7 +5,7 @@
 #
 # Input files:
 #  lang_en.txt or lang_en_xx.txt
-#  
+#
 # Output files:
 #  lang_xx.bin
 #
@@ -82,7 +82,7 @@ generate_binary()
  rm -f lang_$1.dat
  LNG=$1
  #check lang dictionary
- /usr/bin/env python lang-check.py $1 --no-warning
+ ./lang-check.py $1 --no-warning
  #create lang_xx.tmp - different processing for 'en' language
  if [ "$1" = "en" ]; then
   #remove comments and empty lines

+ 0 - 0
lang/lang-check.py


+ 1 - 1
lang/lang-check.sh

@@ -71,5 +71,5 @@ else
  echo 'binary data NG!'
 fi
 
-read
+read -t 5
 exit

+ 158 - 66
lang/lang_en.txt

@@ -1,6 +1,21 @@
 #
 "[%.7s]Live adj. Z\x0avalue set, continue\x0aor start from zero?\x0a%cContinue%cReset"
 
+#MSG_IR_03_OR_OLDER c=18
+" 0.3 or older"
+
+# c=18
+"FS v0.3 or older"
+
+#MSG_IR_04_OR_NEWER c=18
+" 0.4 or newer"
+
+# c=18
+"FS v0.4 or newer"
+
+#MSG_IR_UNKNOWN c=18
+"unknown state"
+
 #MSG_IMPROVE_BED_OFFSET_AND_SKEW_LINE2 c=14
 " of 4"
 
@@ -31,7 +46,10 @@
 #
 "Ambient"
 
-#MSG_PRESS c=20
+#MSG_AUTO c=6
+"Auto"
+
+#MSG_PRESS c=20 r=2
 "and press the knob"
 
 #MSG_CONFIRM_CARRIAGE_AT_THE_TOP c=20 r=2
@@ -43,7 +61,7 @@
 #MSG_AUTO_HOME
 "Auto home"
 
-#MSG_AUTOLOAD_FILAMENT c=17
+#MSG_AUTOLOAD_FILAMENT c=18
 "AutoLoad filament"
 
 #MSG_AUTOLOADING_ONLY_IF_FSENS_ON c=20 r=4
@@ -70,13 +88,22 @@
 #MSG_BED_CORRECTION_MENU
 "Bed level correct"
 
-#MSG_BED_LEVELING_FAILED_POINT_LOW c=20 r=4
+#MSG_BELTTEST c=17
+"Belt test        "
+
+#MSG_BED_LEVELING_FAILED_POINT_LOW c=20 r=5
 "Bed leveling failed. Sensor didnt trigger. Debris on nozzle? Waiting for reset."
 
+#MSG_BRIGHT c=6
+"Bright"
+
+#MSG_BRIGHTNESS c=18
+"Brightness"
+
 #MSG_BED
 "Bed"
 
-#MSG_MENU_BELT_STATUS c=15 r=1
+#MSG_BELT_STATUS c=18
 "Belt status"
 
 #MSG_RECOVER_PRINT c=20 r=2
@@ -124,8 +151,9 @@
 #
 "Copy selected language?"
 
-#MSG_CRASHDETECT
+#MSG_CRASHDETECT c=13
 "Crash det."
+
 #
 "Choose a filament for the First Layer Calibration and select it in the on-screen menu."
 
@@ -135,7 +163,7 @@
 #
 "Crash detected. Resume print?"
 
-#
+#MSG_CRASH c=7
 "Crash"
 
 #MSG_CURRENT c=19 r=1
@@ -150,19 +178,22 @@
 #MSG_BABYSTEP_Z_NOT_SET c=20 r=12
 "Distance between tip of the nozzle and the bed surface has not been set yet. Please follow the manual, chapter First steps, section First layer calibration."
 
+#MSG_FS_CONTINUE c=5
+"Cont."
+
 #MSG_WIZARD_REPEAT_V2_CAL c=20 r=7
 "Do you want to repeat last step to readjust distance between nozzle and heatbed?"
 
-#MSG_EXTRUDER_CORRECTION c=10
+#MSG_EXTRUDER_CORRECTION c=13
 "E-correct:"
 
-#MSG_EJECT_FILAMENT c=17 r=1
+#MSG_EJECT_FILAMENT c=16
 "Eject filament"
 
 #MSG_EJECTING_FILAMENT c=20 r=1
 "Ejecting filament"
 
-#MSG_SELFTEST_ENDSTOP_NOTHIT c=20 r=1
+#MSG_SELFTEST_ENDSTOP_NOTHIT c=20
 "Endstop not hit"
 
 #MSG_SELFTEST_ENDSTOP
@@ -174,25 +205,37 @@
 #MSG_STACK_ERROR c=20 r=4
 "Error - static memory has been overwritten"
 
+#MSG_CUT_FILAMENT c=16
+"Cut filament"
+
+#MSG_CUTTER c=9
+"Cutter"
+
+# c=18
+"Cutting filament"
+
 #MSG_FSENS_NOT_RESPONDING c=20 r=4
 "ERROR: Filament sensor is not responding, please check connection."
 
+#MSG_DIM c=6
+"Dim"
+
 #MSG_ERROR
 "ERROR:"
 
 #MSG_SELFTEST_EXTRUDER_FAN_SPEED c=18
 "Extruder fan:"
 
-#MSG_INFO_EXTRUDER c=15 r=1
+#MSG_INFO_EXTRUDER c=18
 "Extruder info"
 
-#MSG_MOVE_E
+#MSG_EXTRUDER c=17
 "Extruder"
 
 #
 "Fail stats MMU"
 
-#MSG_FSENSOR_AUTOLOAD
+#MSG_FSENSOR_AUTOLOAD c=13
 "F. autoload"
 
 #
@@ -204,14 +247,14 @@
 #MSG_SELFTEST_FAN c=20
 "Fan test"
 
-#MSG_FANS_CHECK
+#MSG_FANS_CHECK c=13
 "Fans check"
 
 #MSG_FSENSOR
 "Fil. sensor"
 
-#
-"Filam. runouts"
+#MSG_FIL_RUNOUTS c=14
+"Fil. runouts  "
 
 #MSG_FILAMENT_CLEAN c=20 r=2
 "Filament extruding & with correct color?"
@@ -222,19 +265,22 @@
 #MSG_FILAMENT_SENSOR c=20
 "Filament sensor"
 
-#MSG_FILAMENT_USED c=19 r=1
+#MSG_FILAMENT_USED c=19
 "Filament used"
 
 #MSG_PRINT_TIME c=19 r=1
 "Print time"
 
-#MSG_FILE_INCOMPLETE c=20 r=2
+#MSG_FS_ACTION c=10
+"FS Action"
+
+#MSG_FILE_INCOMPLETE c=20 r=3
 "File incomplete. Continue anyway?"
 
-#MSG_FINISHING_MOVEMENTS c=20 r=1
+#MSG_FINISHING_MOVEMENTS c=20
 "Finishing movements"
 
-#MSG_V2_CALIBRATION c=17 r=1
+#MSG_V2_CALIBRATION c=18
 "First layer cal."
 
 #MSG_WIZARD_SELFTEST c=20 r=8
@@ -297,14 +343,14 @@
 #MSG_SELFTEST_CHECK_FSENSOR c=20
 "Checking sensors "
 
-#MSG_SELFTEST_CHECK_X c=20
-"Checking X axis  "
+#MSG_CHECKING_X c=20
+"Checking X axis"
 
-#MSG_SELFTEST_CHECK_Y c=20
-"Checking Y axis  "
+#MSG_CHECKING_Y c=20
+"Checking Y axis"
 
 #MSG_SELFTEST_CHECK_Z c=20
-"Checking Z axis  "
+"Checking Z axis"
 
 #MSG_CHOOSE_EXTRUDER c=20 r=1
 "Choose extruder:"
@@ -327,19 +373,19 @@
 #MSG_INSERT_FILAMENT c=20
 "Insert filament"
 
-#MSG_WIZARD_FILAMENT_LOADED c=20 r=2
+#MSG_FILAMENT_LOADED c=20 r=2
 "Is filament loaded?"
 
 #MSG_STEEL_SHEET_CHECK c=20 r=2
 "Is steel sheet on heatbed?"
 
-#
+#MSG_LAST_PRINT_FAILURES c=20
 "Last print failures"
 
 #
 "If you have additional steel sheets, calibrate their presets in Settings - HW Setup - Steel sheets."
 
-#
+#MSG_LAST_PRINT c=18
 "Last print"
 
 #MSG_SELFTEST_EXTRUDER_FAN c=20
@@ -357,6 +403,9 @@
 #MSG_BABYSTEP_Z
 "Live adjust Z"
 
+# c=20 r=6
+"Insert the filament (do not load it) into the extruder and then press the knob."
+
 #MSG_LOAD_FILAMENT c=17
 "Load filament"
 
@@ -372,16 +421,22 @@
 #
 "Load to nozzle"
 
-#MSG_M117_V2_CALIBRATION c=25 r=1
+#MSG_M117_V2_CALIBRATION c=25
 "M117 First layer cal."
 
 #MSG_MAIN
 "Main"
 
+#MSG_BL_HIGH c=12
+"Level Bright"
+
+#MSG_BL_LOW c=12
+"Level Dimmed"
+
 #MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE1 c=60
 "Measuring reference height of calibration point"
 
-#MSG_MESH_BED_LEVELING
+#MSG_MESH_BED_LEVELING c=18
 "Mesh Bed Leveling"
 
 #MSG_MMU_OK_RESUMING_POSITION c=20 r=4
@@ -393,13 +448,13 @@
 #
 "Measured skew"
 
-#
+#MSG_MMU_FAILS c=14
 "MMU fails"
 
 #
 "MMU load failed     "
 
-#
+#MSG_MMU_LOAD_FAILS c=14
 "MMU load fails"
 
 #MSG_MMU_OK_RESUMING c=20 r=4
@@ -408,6 +463,9 @@
 #MSG_MODE
 "Mode"
 
+# c=20 r=3
+"MK3 firmware detected on MK3S printer"
+
 #MSG_NORMAL
 "Normal"
 
@@ -477,7 +535,7 @@
 #MSG_NOZZLE
 "Nozzle"
 
-#MSG_DEFAULT_SETTINGS_LOADED c=20 r=4
+#MSG_DEFAULT_SETTINGS_LOADED c=20 r=5
 "Old settings found. Default PID, Esteps etc. will be set."
 
 #
@@ -501,7 +559,7 @@
 #MSG_PINDA_PREHEAT c=20 r=1
 "PINDA Heating"
 
-#MSG_PAPER c=20 r=8
+#MSG_PAPER c=20 r=10
 "Place a sheet of paper under the nozzle during the calibration of first 4 points. If the nozzle catches the paper, power off the printer immediately."
 
 #MSG_WIZARD_CLEAN_HEATBED c=20 r=8
@@ -555,22 +613,28 @@
 #MSG_WIZARD_HEATING c=20 r=3
 "Preheating nozzle. Please wait."
 
+# c=14
+"PINDA"
+
 #
 "Please upgrade."
 
 #MSG_PRESS_TO_PREHEAT c=20 r=4
-"Press knob to preheat nozzle and continue."
+"Press the knob to preheat nozzle and continue."
 
-#
+#MSG_FS_PAUSE c=5
+"Pause"
+
+#MSG_POWER_FAILURES c=14
 "Power failures"
 
 #MSG_PRINT_ABORTED c=20
 "Print aborted"
 
-#
+# c=20
 "Preheating to load"
 
-#
+# c=20
 "Preheating to unload"
 
 #MSG_SELFTEST_PRINT_FAN_SPEED c=18
@@ -579,7 +643,7 @@
 #MSG_CARD_MENU
 "Print from SD"
 
-#
+# c=20
 "Press the knob"
 
 #MSG_PRINT_PAUSED c=20 r=1
@@ -609,25 +673,31 @@
 #MSG_BED_CORRECTION_REAR c=14 r=1
 "Rear side [um]"
 
-#MSG_RECOVERING_PRINT c=20 r=1
+# c=20 r=4
+"Please unload the filament first, then repeat this action."
+
+# c=20 r=4
+"Please check the IR sensor connection, unload filament if present."
+
+#MSG_RECOVERING_PRINT c=20
 "Recovering print    "
 
-#MSG_REMOVE_OLD_FILAMENT c=20 r=4
+#MSG_REMOVE_OLD_FILAMENT c=20 r=5
 "Remove old filament and press the knob to start loading new filament."
 
-#
+# c=20
 "Prusa i3 MK3S OK."
 
 #MSG_CALIBRATE_BED_RESET
 "Reset XYZ calibr."
 
-#MSG_BED_CORRECTION_RESET
+#MSG_RESET c=14
 "Reset"
 
-#MSG_RESUME_PRINT
+#MSG_RESUME_PRINT c=18
 "Resume print"
 
-#MSG_RESUMING_PRINT c=20 r=1
+#MSG_RESUMING_PRINT c=20
 "Resuming print"
 
 #MSG_BED_CORRECTION_RIGHT c=14 r=1
@@ -678,16 +748,25 @@
 #MSG_SET_TEMPERATURE c=19 r=1
 "Set temperature:"
 
+# c=20
+"Prusa i3 MK2.5 OK."
+
+# c=20
+"Prusa i3 MK2.5S OK."
+
+# c=20
+"Prusa i3 MK3 OK."
+
 #MSG_SETTINGS
 "Settings"
 
-#MSG_SHOW_END_STOPS c=17 r=1
+#MSG_SHOW_END_STOPS c=18
 "Show end stops"
 
 #
 "Sensor state"
 
-#MSG_FILE_CNT c=20 r=4
+#MSG_FILE_CNT c=20 r=6
 "Some files will not be sorted. Max. No. of files in 1 folder for sorting is 100."
 
 #MSG_SORT
@@ -717,6 +796,9 @@
 #MSG_SOUND
 "Sound"
 
+# c=7
+"Runouts"
+
 #
 "Some problem encountered, Z-leveling enforced ..."
 
@@ -750,7 +832,7 @@
 #
 "Select filament:"
 
-#MSG_TEMP_CALIBRATION c=12 r=1
+#MSG_TEMP_CALIBRATION c=14
 "Temp. cal."
 
 #
@@ -765,13 +847,16 @@
 #MSG_TEMP_CALIBRATION_DONE c=20 r=12
 "Temperature calibration is finished and active. Temp. calibration can be disabled in menu Settings->Temp. cal."
 
+# c=20 r=3
+"Sensor verified, remove the filament now."
+
 #MSG_TEMPERATURE
 "Temperature"
 
 #MSG_MENU_TEMPERATURES c=15 r=1
 "Temperatures"
 
-#MSG_FOLLOW_Z_CALIBRATION_FLOW c=20 r=4
+#MSG_FOLLOW_Z_CALIBRATION_FLOW c=20 r=9
 "There is still a need to make Z calibration. Please follow the manual, chapter First steps, section Calibration flow."
 
 #
@@ -786,13 +871,13 @@
 #
 "Unload"
 
-#
+#MSG_TOTAL_FAILURES c=20
 "Total failures"
 
-#
+# c=20
 "to load filament"
 
-#
+# c=20
 "to unload filament"
 
 #MSG_UNLOAD_FILAMENT c=17
@@ -801,7 +886,7 @@
 #MSG_UNLOADING_FILAMENT c=20 r=1
 "Unloading filament"
 
-#
+#MSG_TOTAL c=6
 "Total"
 
 #MSG_USED c=19 r=1
@@ -843,7 +928,7 @@
 #MSG_WIZARD c=17 r=1
 "Wizard"
 
-#MSG_XYZ_DETAILS c=19 r=1
+#MSG_XYZ_DETAILS c=18
 "XYZ cal. details"
 
 #MSG_BED_SKEW_OFFSET_DETECTION_FITTING_FAILED c=20 r=8
@@ -861,7 +946,10 @@
 #MSG_BED_SKEW_OFFSET_DETECTION_SKEW_MILD c=20 r=8
 "XYZ calibration all right. X/Y axes are slightly skewed. Good job!"
 
-#
+#MSG_TIMEOUT c=12
+"Timeout"
+
+#MSG_X_CORRECTION c=13
 "X-correct:"
 
 #MSG_BED_SKEW_OFFSET_DETECTION_PERFECT c=20 r=8
@@ -891,7 +979,10 @@
 #
 "The printer will start printing a zig-zag line. Rotate the knob until you reach the optimal height. Check the pictures in the handbook (Calibration chapter)."
 
-#
+# c=20 r=5
+"Verification failed, remove the filament and try again."
+
+#MSG_Y_CORRECTION c=13
 "Y-correct:"
 
 #MSG_OFF
@@ -921,7 +1012,7 @@
 #MSG_WARN
 "Warn"
 
-#
+#MSG_HW_SETUP c=18
 "HW Setup"
 
 #
@@ -933,9 +1024,6 @@
 #MSG_MESH
 "Mesh"
 
-#
-"Mesh bed leveling"
-
 #
 "MK3S firmware detected on MK3 printer"
 
@@ -957,10 +1045,10 @@
 #
 "G-code sliced for a different level. Please re-slice the model again. Print cancelled."
 
-#
+#MSG_GCODE_DIFF_PRINTER_CONTINUE c=20 r=5
 "G-code sliced for a different printer type. Continue?"
 
-#
+#MSG_GCODE_DIFF_PRINTER_CANCELLED c=20 r=6
 "G-code sliced for a different printer type. Please re-slice the model again. Print cancelled."
 
 #
@@ -972,10 +1060,10 @@
 #
 "PINDA:"
 
-#
+# c=20
 "Preheating to cut"
 
-#
+# c=20
 "Preheating to eject"
 
 #
@@ -984,6 +1072,9 @@
 #
 "Printer nozzle diameter differs from the G-code. Please check the value in settings. Print cancelled."
 
+# c=20
+"%s level expected"
+
 #
 "Rename"
 
@@ -993,17 +1084,18 @@
 #
 "Sensor info"
 
-#
+#MSG_SHEET c=10
 "Sheet"
 
 #MSG_SOUND_BLIND
 "Assist"
 
-#
+#MSG_STEEL_SHEET c=18
 "Steel sheets"
 
-#
+#MSG_Z_CORRECTION c=13
 "Z-correct:"
 
 #MSG_Z_PROBE_NR
 "Z-probe nr."
+

+ 194 - 73
lang/lang_en_cz.txt

@@ -2,6 +2,26 @@
 "[%.7s]Live adj. Z\x0avalue set, continue\x0aor start from zero?\x0a%cContinue%cReset"
 "[%.7s]Doladeni Z\x0auz nastaveno, pouzit\x0anebo reset od nuly?\x0a%cPokracovat%cReset"
 
+#MSG_IR_03_OR_OLDER c=18
+" 0.3 or older"
+" 0.3 nebo starsi"
+
+# c=18
+"FS v0.3 or older"
+"FS 0.3 nebo starsi"
+
+#MSG_IR_04_OR_NEWER c=18
+" 0.4 or newer"
+" 0.4 nebo novejsi"
+
+# c=18
+"FS v0.4 or newer"
+"FS 0.4 a novejsi"
+
+#MSG_IR_UNKNOWN c=18
+"unknown state"
+"neznamy stav"
+
 #MSG_IMPROVE_BED_OFFSET_AND_SKEW_LINE2 c=14
 " of 4"
 " z 4"
@@ -42,7 +62,11 @@
 "Ambient"
 "Okoli"
 
-#MSG_PRESS c=20
+#MSG_AUTO c=6
+"Auto"
+"\x00"
+
+#MSG_PRESS c=20 r=2
 "and press the knob"
 "a stisknete tlacitko"
 
@@ -58,7 +82,7 @@
 "Auto home"
 "\x00"
 
-#MSG_AUTOLOAD_FILAMENT c=17
+#MSG_AUTOLOAD_FILAMENT c=18
 "AutoLoad filament"
 "AutoZavedeni fil."
 
@@ -94,15 +118,27 @@
 "Bed level correct"
 "Korekce podlozky"
 
-#MSG_BED_LEVELING_FAILED_POINT_LOW c=20 r=4
+#MSG_BELTTEST c=17
+"Belt test        "
+"Test remenu      "
+
+#MSG_BED_LEVELING_FAILED_POINT_LOW c=20 r=5
 "Bed leveling failed. Sensor didnt trigger. Debris on nozzle? Waiting for reset."
 "Kalibrace Z selhala. Sensor nesepnul. Znecistena tryska? Cekam na reset."
 
+#MSG_BRIGHT c=6
+"Bright"
+"Jasny"
+
+#MSG_BRIGHTNESS c=18
+"Brightness"
+"Podsviceni"
+
 #MSG_BED
 "Bed"
 "Podlozka"
 
-#MSG_MENU_BELT_STATUS c=15 r=1
+#MSG_BELT_STATUS c=18
 "Belt status"
 "Stav remenu"
 
@@ -166,13 +202,13 @@
 "Copy selected language?"
 "Kopirovat vybrany jazyk?"
 
-#MSG_CRASHDETECT
+#MSG_CRASHDETECT c=13
 "Crash det."
 "\x00"
 
 #
-"Zvolte filament pro kalibraci prvni vrstvy z nasledujiciho menu"
 "Choose a filament for the First Layer Calibration and select it in the on-screen menu."
+"Zvolte filament pro kalibraci prvni vrstvy z nasledujiciho menu"
 
 #MSG_CRASH_DETECTED c=20 r=1
 "Crash detected."
@@ -182,7 +218,7 @@
 "Crash detected. Resume print?"
 "Detekovan naraz. Obnovit tisk?"
 
-#
+#MSG_CRASH c=7
 "Crash"
 "Naraz"
 
@@ -202,23 +238,27 @@
 "Distance between tip of the nozzle and the bed surface has not been set yet. Please follow the manual, chapter First steps, section First layer calibration."
 "Neni zkalibrovana vzdalenost trysky od tiskove podlozky. Postupujte prosim podle manualu, kapitola Zaciname, odstavec Nastaveni prvni vrstvy."
 
+#MSG_FS_CONTINUE c=5
+"Cont."
+"Pokr."
+
 #MSG_WIZARD_REPEAT_V2_CAL c=20 r=7
 "Do you want to repeat last step to readjust distance between nozzle and heatbed?"
 "Chcete opakovat posledni krok a pozmenit vzdalenost mezi tryskou a podlozkou?"
 
-#MSG_EXTRUDER_CORRECTION c=10
+#MSG_EXTRUDER_CORRECTION c=13
 "E-correct:"
 "Korekce E:"
 
-#MSG_EJECT_FILAMENT c=17 r=1
+#MSG_EJECT_FILAMENT c=16
 "Eject filament"
-"Vysunout filament"
+"Vysunout fil."
 
 #MSG_EJECTING_FILAMENT c=20 r=1
 "Ejecting filament"
 "Vysouvam filament"
 
-#MSG_SELFTEST_ENDSTOP_NOTHIT c=20 r=1
+#MSG_SELFTEST_ENDSTOP_NOTHIT c=20
 "Endstop not hit"
 "Kon. spinac nesepnut"
 
@@ -234,9 +274,25 @@
 "Error - static memory has been overwritten"
 "Chyba - Doslo k prepisu staticke pameti!"
 
+#MSG_CUT_FILAMENT c=16
+"Cut filament"
+"Ustrihnout"
+
+#MSG_CUTTER c=9
+"Cutter"
+"Strihani"
+
+# c=18
+"Cutting filament"
+"Strihani filamentu"
+
 #MSG_FSENS_NOT_RESPONDING c=20 r=4
 "ERROR: Filament sensor is not responding, please check connection."
-"CHYBA: Filament senzor nereaguje, zkontrolujte zapojeni."
+"CHYBA: Filament senzor nereaguje, zkontrolujte prosim zapojeni."
+
+#MSG_DIM c=6
+"Dim"
+"Temny"
 
 #MSG_ERROR
 "ERROR:"
@@ -246,11 +302,11 @@
 "Extruder fan:"
 "Levy vent.:"
 
-#MSG_INFO_EXTRUDER c=15 r=1
+#MSG_INFO_EXTRUDER c=18
 "Extruder info"
 "\x00"
 
-#MSG_MOVE_E
+#MSG_EXTRUDER c=17
 "Extruder"
 "\x00"
 
@@ -258,7 +314,7 @@
 "Fail stats MMU"
 "Selhani MMU"
 
-#MSG_FSENSOR_AUTOLOAD
+#MSG_FSENSOR_AUTOLOAD c=13
 "F. autoload"
 "F. autozav."
 
@@ -274,7 +330,7 @@
 "Fan test"
 "Test ventilatoru"
 
-#MSG_FANS_CHECK
+#MSG_FANS_CHECK c=13
 "Fans check"
 "Kontr. vent."
 
@@ -282,8 +338,8 @@
 "Fil. sensor"
 "Fil. senzor"
 
-#
-"Filam. runouts"
+#MSG_FIL_RUNOUTS c=14
+"Fil. runouts  "
 "Vypadky filam."
 
 #MSG_FILAMENT_CLEAN c=20 r=2
@@ -298,23 +354,27 @@
 "Filament sensor"
 "Senzor filamentu"
 
-#MSG_FILAMENT_USED c=19 r=1
+#MSG_FILAMENT_USED c=19
 "Filament used"
-"Spotrebovano filamentu"
+"Spotrebovano filam."
 
 #MSG_PRINT_TIME c=19 r=1
 "Print time"
 "Cas tisku"
 
-#MSG_FILE_INCOMPLETE c=20 r=2
+#MSG_FS_ACTION c=10
+"FS Action"
+"FS reakce"
+
+#MSG_FILE_INCOMPLETE c=20 r=3
 "File incomplete. Continue anyway?"
 "Soubor nekompletni. Pokracovat?"
 
-#MSG_FINISHING_MOVEMENTS c=20 r=1
+#MSG_FINISHING_MOVEMENTS c=20
 "Finishing movements"
 "Dokoncovani pohybu"
 
-#MSG_V2_CALIBRATION c=17 r=1
+#MSG_V2_CALIBRATION c=18
 "First layer cal."
 "Kal. prvni vrstvy"
 
@@ -398,16 +458,16 @@
 "Checking sensors "
 "Kontrola senzoru"
 
-#MSG_SELFTEST_CHECK_X c=20
-"Checking X axis  "
+#MSG_CHECKING_X c=20
+"Checking X axis"
 "Kontrola osy X"
 
-#MSG_SELFTEST_CHECK_Y c=20
-"Checking Y axis  "
+#MSG_CHECKING_Y c=20
+"Checking Y axis"
 "Kontrola osy Y"
 
 #MSG_SELFTEST_CHECK_Z c=20
-"Checking Z axis  "
+"Checking Z axis"
 "Kontrola osy Z"
 
 #MSG_CHOOSE_EXTRUDER c=20 r=1
@@ -438,7 +498,7 @@
 "Insert filament"
 "Vlozte filament"
 
-#MSG_WIZARD_FILAMENT_LOADED c=20 r=2
+#MSG_FILAMENT_LOADED c=20 r=2
 "Is filament loaded?"
 "Je filament zaveden?"
 
@@ -446,7 +506,7 @@
 "Is steel sheet on heatbed?"
 "Je tiskovy plat na podlozce?"
 
-#
+#MSG_LAST_PRINT_FAILURES c=20
 "Last print failures"
 "Selhani posl. tisku"
 
@@ -454,7 +514,7 @@
 "If you have additional steel sheets, calibrate their presets in Settings - HW Setup - Steel sheets."
 "Mate-li vice tiskovych platu, kalibrujte je v menu Nastaveni - HW nastaveni - Tiskove platy"
 
-#
+#MSG_LAST_PRINT c=18
 "Last print"
 "Posledni tisk"
 
@@ -478,6 +538,10 @@
 "Live adjust Z"
 "Doladeni osy Z"
 
+# c=20 r=6
+"Insert the filament (do not load it) into the extruder and then press the knob."
+"Vlozte filament (nezavadejte) do extruderu a stisknete tlacitko"
+
 #MSG_LOAD_FILAMENT c=17
 "Load filament"
 "Zavest filament"
@@ -498,7 +562,7 @@
 "Load to nozzle"
 "Zavest do trysky"
 
-#MSG_M117_V2_CALIBRATION c=25 r=1
+#MSG_M117_V2_CALIBRATION c=25
 "M117 First layer cal."
 "M117 Kal. prvni vrstvy"
 
@@ -506,11 +570,19 @@
 "Main"
 "Hlavni nabidka"
 
+#MSG_BL_HIGH c=12
+"Level Bright"
+"\x00"
+
+#MSG_BL_LOW c=12
+"Level Dimmed"
+"\x00"
+
 #MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE1 c=60
 "Measuring reference height of calibration point"
 "Merim referencni vysku kalibracniho bodu"
 
-#MSG_MESH_BED_LEVELING
+#MSG_MESH_BED_LEVELING c=18
 "Mesh Bed Leveling"
 "\x00"
 
@@ -526,7 +598,7 @@
 "Measured skew"
 "Merene zkoseni"
 
-#
+#MSG_MMU_FAILS c=14
 "MMU fails"
 "Selhani MMU"
 
@@ -534,7 +606,7 @@
 "MMU load failed     "
 "Zavedeni MMU selhalo"
 
-#
+#MSG_MMU_LOAD_FAILS c=14
 "MMU load fails"
 "MMU selhani zavadeni"
 
@@ -546,6 +618,10 @@
 "Mode"
 "Mod"
 
+# c=20 r=3
+"MK3 firmware detected on MK3S printer"
+"\x00"
+
 #MSG_NORMAL
 "Normal"
 "\x00"
@@ -638,7 +714,7 @@
 "Nozzle"
 "Tryska"
 
-#MSG_DEFAULT_SETTINGS_LOADED c=20 r=4
+#MSG_DEFAULT_SETTINGS_LOADED c=20 r=5
 "Old settings found. Default PID, Esteps etc. will be set."
 "Neplatne hodnoty nastaveni. Bude pouzito vychozi PID, Esteps atd."
 
@@ -670,7 +746,7 @@
 "PINDA Heating"
 "Nahrivani PINDA"
 
-#MSG_PAPER c=20 r=8
+#MSG_PAPER c=20 r=10
 "Place a sheet of paper under the nozzle during the calibration of first 4 points. If the nozzle catches the paper, power off the printer immediately."
 "Umistete list papiru na podlozku a udrzujte jej pod tryskou behem mereni prvnich 4 bodu. Pokud tryska zachyti papir, okamzite vypnete tiskarnu."
 
@@ -742,15 +818,23 @@
 "Preheating nozzle. Please wait."
 "Predehrev trysky. Prosim cekejte."
 
+# c=14
+"PINDA"
+"\x00"
+
 #
 "Please upgrade."
 "Prosim aktualizujte."
 
 #MSG_PRESS_TO_PREHEAT c=20 r=4
-"Press knob to preheat nozzle and continue."
+"Press the knob to preheat nozzle and continue."
 "Pro nahrati trysky a pokracovani stisknete tlacitko."
 
-#
+#MSG_FS_PAUSE c=5
+"Pause"
+"\x00"
+
+#MSG_POWER_FAILURES c=14
 "Power failures"
 "Vypadky proudu"
 
@@ -758,11 +842,11 @@
 "Print aborted"
 "Tisk prerusen"
 
-#
+# c=20
 "Preheating to load"
 "Predehrev k zavedeni"
 
-#
+# c=20
 "Preheating to unload"
 "Predehrev k vyjmuti"
 
@@ -774,7 +858,7 @@
 "Print from SD"
 "Tisk z SD"
 
-#
+# c=20
 "Press the knob"
 "Stisknete hl. tlacitko"
 
@@ -814,15 +898,23 @@
 "Rear side [um]"
 "Vzadu [um]"
 
-#MSG_RECOVERING_PRINT c=20 r=1
+# c=20 r=4
+"Please unload the filament first, then repeat this action."
+"Prosim vyjmete filament a zopakujte tuto akci"
+
+# c=20 r=4
+"Please check the IR sensor connection, unload filament if present."
+"Prosim zkontrolujte zapojeni IR senzoru a vyjmuty filament"
+
+#MSG_RECOVERING_PRINT c=20
 "Recovering print    "
-"Obnovovani tisku "
+"Obnovovani tisku    "
 
-#MSG_REMOVE_OLD_FILAMENT c=20 r=4
+#MSG_REMOVE_OLD_FILAMENT c=20 r=5
 "Remove old filament and press the knob to start loading new filament."
 "Vyjmete stary filament a stisknete tlacitko pro zavedeni noveho."
 
-#
+# c=20
 "Prusa i3 MK3S OK."
 "\x00"
 
@@ -830,15 +922,15 @@
 "Reset XYZ calibr."
 "Reset XYZ kalibr."
 
-#MSG_BED_CORRECTION_RESET
+#MSG_RESET c=14
 "Reset"
 "\x00"
 
-#MSG_RESUME_PRINT
+#MSG_RESUME_PRINT c=18
 "Resume print"
 "Pokracovat"
 
-#MSG_RESUMING_PRINT c=20 r=1
+#MSG_RESUMING_PRINT c=20
 "Resuming print"
 "Obnoveni tisku"
 
@@ -906,11 +998,23 @@
 "Set temperature:"
 "Nastavte teplotu:"
 
+# c=20
+"Prusa i3 MK2.5 OK."
+"\x00"
+
+# c=20
+"Prusa i3 MK2.5S OK."
+"\x00"
+
+# c=20
+"Prusa i3 MK3 OK."
+"\x00"
+
 #MSG_SETTINGS
 "Settings"
 "Nastaveni"
 
-#MSG_SHOW_END_STOPS c=17 r=1
+#MSG_SHOW_END_STOPS c=18
 "Show end stops"
 "Stav konc. spin."
 
@@ -918,7 +1022,7 @@
 "Sensor state"
 "Stav senzoru"
 
-#MSG_FILE_CNT c=20 r=4
+#MSG_FILE_CNT c=20 r=6
 "Some files will not be sorted. Max. No. of files in 1 folder for sorting is 100."
 "Nektere soubory nebudou setrideny. Maximalni pocet souboru ve slozce pro setrideni je 100."
 
@@ -958,6 +1062,10 @@
 "Sound"
 "Zvuk"
 
+# c=7
+"Runouts"
+"\x00"
+
 #
 "Some problem encountered, Z-leveling enforced ..."
 "Vyskytl se problem, srovnavam osu Z ..."
@@ -1002,7 +1110,7 @@
 "Select filament:"
 "Zvolte filament:"
 
-#MSG_TEMP_CALIBRATION c=12 r=1
+#MSG_TEMP_CALIBRATION c=14
 "Temp. cal."
 "Tepl. kal."
 
@@ -1022,6 +1130,10 @@
 "Temperature calibration is finished and active. Temp. calibration can be disabled in menu Settings->Temp. cal."
 "Teplotni kalibrace dokoncena a je nyni aktivni. Teplotni kalibraci je mozno deaktivovat v menu Nastaveni->Tepl. kal."
 
+# c=20 r=3
+"Sensor verified, remove the filament now."
+"Senzor overen, vyjmete filament."
+
 #MSG_TEMPERATURE
 "Temperature"
 "Teplota"
@@ -1030,7 +1142,7 @@
 "Temperatures"
 "Teploty"
 
-#MSG_FOLLOW_Z_CALIBRATION_FLOW c=20 r=4
+#MSG_FOLLOW_Z_CALIBRATION_FLOW c=20 r=9
 "There is still a need to make Z calibration. Please follow the manual, chapter First steps, section Calibration flow."
 "Je potreba kalibrovat osu Z. Prosim postupujte dle prirucky, kapitola Zaciname, sekce Postup kalibrace."
 
@@ -1050,15 +1162,15 @@
 "Unload"
 "Vysunout"
 
-#
+#MSG_TOTAL_FAILURES c=20
 "Total failures"
 "Celkem selhani"
 
-#
+# c=20
 "to load filament"
 "k zavedeni filamentu"
 
-#
+# c=20
 "to unload filament"
 "k vyjmuti filamentu"
 
@@ -1070,7 +1182,7 @@
 "Unloading filament"
 "Vysouvam filament"
 
-#
+#MSG_TOTAL c=6
 "Total"
 "Celkem"
 
@@ -1126,7 +1238,7 @@
 "Wizard"
 "Pruvodce"
 
-#MSG_XYZ_DETAILS c=19 r=1
+#MSG_XYZ_DETAILS c=18
 "XYZ cal. details"
 "Detaily XYZ kal."
 
@@ -1150,7 +1262,11 @@
 "XYZ calibration all right. X/Y axes are slightly skewed. Good job!"
 "Kalibrace XYZ v poradku. X/Y osy mirne zkosene. Dobra prace!"
 
-#
+#MSG_TIMEOUT c=12
+"Timeout"
+"\x00"
+
+#MSG_X_CORRECTION c=13
 "X-correct:"
 "Korekce X:"
 
@@ -1190,7 +1306,11 @@
 "The printer will start printing a zig-zag line. Rotate the knob until you reach the optimal height. Check the pictures in the handbook (Calibration chapter)."
 "Tiskarna zacne tisknout lomenou caru. Otacenim tlacitka nastavte optimalni vysku. Postupujte podle obrazku v handbooku (kapitola Kalibrace)."
 
-#
+# c=20 r=5
+"Verification failed, remove the filament and try again."
+"Overeni selhalo, vyjmete filament a zkuste znovu."
+
+#MSG_Y_CORRECTION c=13
 "Y-correct:"
 "Korekce Y:"
 
@@ -1230,7 +1350,7 @@
 "Warn"
 "Varovat"
 
-#
+#MSG_HW_SETUP c=18
 "HW Setup"
 "HW nastaveni"
 
@@ -1246,10 +1366,6 @@
 "Mesh"
 "\x00"
 
-#
-"Mesh bed leveling"
-"Mesh Bed Leveling"
-
 #
 "MK3S firmware detected on MK3 printer"
 "MK3S firmware detekovan na tiskarne MK3"
@@ -1278,11 +1394,11 @@
 "G-code sliced for a different level. Please re-slice the model again. Print cancelled."
 "\x00"
 
-#
+#MSG_GCODE_DIFF_PRINTER_CONTINUE c=20 r=5
 "G-code sliced for a different printer type. Continue?"
 "G-code je pripraven pro jiny typ tiskarny. Pokracovat?"
 
-#
+#MSG_GCODE_DIFF_PRINTER_CANCELLED c=20 r=6
 "G-code sliced for a different printer type. Please re-slice the model again. Print cancelled."
 "G-code je pripraven pro jiny typ tiskarny. Prosim preslicujte model znovu. Tisk zrusen."
 
@@ -1298,11 +1414,11 @@
 "PINDA:"
 "\x00"
 
-#
+# c=20
 "Preheating to cut"
-"Predehrev k ustrizeni"
+"Predehrev ke strihu"
 
-#
+# c=20
 "Preheating to eject"
 "Predehrev k vysunuti"
 
@@ -1314,6 +1430,10 @@
 "Printer nozzle diameter differs from the G-code. Please check the value in settings. Print cancelled."
 "Prumer trysky tiskarny se lisi od G-code. Prosim zkontrolujte nastaveni. Tisk zrusen."
 
+# c=20
+"%s level expected"
+"\x00"
+
 #
 "Rename"
 "Prejmenovat"
@@ -1326,7 +1446,7 @@
 "Sensor info"
 "Senzor info"
 
-#
+#MSG_SHEET c=10
 "Sheet"
 "Plat"
 
@@ -1334,14 +1454,15 @@
 "Assist"
 "Asist."
 
-#
+#MSG_STEEL_SHEET c=18
 "Steel sheets"
 "Tiskove platy"
 
-#
+#MSG_Z_CORRECTION c=13
 "Z-correct:"
 "Korekce Z:"
 
 #MSG_Z_PROBE_NR
 "Z-probe nr."
 "Pocet mereni Z"
+

+ 197 - 76
lang/lang_en_de.txt

@@ -2,6 +2,26 @@
 "[%.7s]Live adj. Z\x0avalue set, continue\x0aor start from zero?\x0a%cContinue%cReset"
 "[%.7s]Z Einstell.\x0aWert gesetzt,weiter\x0aoder mit 0 beginnen?\x0a%cWeiter%cNeu beginnen"
 
+#MSG_IR_03_OR_OLDER c=18
+" 0.3 or older"
+" 0.3 oder aelter"
+
+# c=18
+"FS v0.3 or older"
+"FS 0.3 oder aelter"
+
+#MSG_IR_04_OR_NEWER c=18
+" 0.4 or newer"
+" 0.4 oder neuer"
+
+# c=18
+"FS v0.4 or newer"
+"FS 0.4 oder neuer"
+
+#MSG_IR_UNKNOWN c=18
+"unknown state"
+"Status unbekannt"
+
 #MSG_IMPROVE_BED_OFFSET_AND_SKEW_LINE2 c=14
 " of 4"
 " von 4"
@@ -42,7 +62,11 @@
 "Ambient"
 "Raumtemp."
 
-#MSG_PRESS c=20
+#MSG_AUTO c=6
+"Auto"
+"\x00"
+
+#MSG_PRESS c=20 r=2
 "and press the knob"
 "und Knopf druecken"
 
@@ -58,7 +82,7 @@
 "Auto home"
 "Startposition"
 
-#MSG_AUTOLOAD_FILAMENT c=17
+#MSG_AUTOLOAD_FILAMENT c=18
 "AutoLoad filament"
 "AutoLaden Filament"
 
@@ -94,15 +118,27 @@
 "Bed level correct"
 "Ausgleich Bett ok"
 
-#MSG_BED_LEVELING_FAILED_POINT_LOW c=20 r=4
+#MSG_BELTTEST c=17
+"Belt test        "
+"Riementest       "
+
+#MSG_BED_LEVELING_FAILED_POINT_LOW c=20 r=5
 "Bed leveling failed. Sensor didnt trigger. Debris on nozzle? Waiting for reset."
 "Z-Kal. fehlgeschlg. Sensor nicht ausgeloest. Schmutzige Duese? Warte auf Reset."
 
+#MSG_BRIGHT c=6
+"Bright"
+"Hell"
+
+#MSG_BRIGHTNESS c=18
+"Brightness"
+"Helligkeit"
+
 #MSG_BED
 "Bed"
 "Bett"
 
-#MSG_MENU_BELT_STATUS c=15 r=1
+#MSG_BELT_STATUS c=18
 "Belt status"
 "Gurtstatus"
 
@@ -166,7 +202,7 @@
 "Copy selected language?"
 "Gewaehlte Sprache kopieren?"
 
-#MSG_CRASHDETECT
+#MSG_CRASHDETECT c=13
 "Crash det."
 "Crash Erk."
 
@@ -182,7 +218,7 @@
 "Crash detected. Resume print?"
 "Crash erkannt. Druck fortfuehren?"
 
-#
+#MSG_CRASH c=7
 "Crash"
 "\x00"
 
@@ -202,15 +238,19 @@
 "Distance between tip of the nozzle and the bed surface has not been set yet. Please follow the manual, chapter First steps, section First layer calibration."
 "Der Abstand zwischen der Spitze der Duese und dem Bett ist noch nicht eingestellt. Bitte folgen Sie dem Handbuch, Kapitel Erste Schritte, Abschnitt Erste Schicht Kalibrierung."
 
+#MSG_FS_CONTINUE c=5
+"Cont."
+"\x00"
+
 #MSG_WIZARD_REPEAT_V2_CAL c=20 r=7
 "Do you want to repeat last step to readjust distance between nozzle and heatbed?"
 "Moechten Sie den letzten Schritt wiederholen, um den Abstand zwischen Duese und Druckbett neu einzustellen?"
 
-#MSG_EXTRUDER_CORRECTION c=10
+#MSG_EXTRUDER_CORRECTION c=13
 "E-correct:"
 "E-Korrektur:"
 
-#MSG_EJECT_FILAMENT c=17 r=1
+#MSG_EJECT_FILAMENT c=16
 "Eject filament"
 "Filamentauswurf"
 
@@ -218,7 +258,7 @@
 "Ejecting filament"
 "werfe Filament aus"
 
-#MSG_SELFTEST_ENDSTOP_NOTHIT c=20 r=1
+#MSG_SELFTEST_ENDSTOP_NOTHIT c=20
 "Endstop not hit"
 "Ende nicht getroffen"
 
@@ -234,10 +274,26 @@
 "Error - static memory has been overwritten"
 "Fehler - statischer Speicher wurde ueberschrieben"
 
+#MSG_CUT_FILAMENT c=16
+"Cut filament"
+"Fil. schneiden"
+
+#MSG_CUTTER c=9
+"Cutter"
+"Messer"
+
+# c=18
+"Cutting filament"
+"Schneide filament"
+
 #MSG_FSENS_NOT_RESPONDING c=20 r=4
 "ERROR: Filament sensor is not responding, please check connection."
 "FEHLER: Filament- sensor reagiert nicht, bitte Verbindung pruefen."
 
+#MSG_DIM c=6
+"Dim"
+"Dimm"
+
 #MSG_ERROR
 "ERROR:"
 "FEHLER:"
@@ -246,11 +302,11 @@
 "Extruder fan:"
 "Extruder Luefter:"
 
-#MSG_INFO_EXTRUDER c=15 r=1
+#MSG_INFO_EXTRUDER c=18
 "Extruder info"
 "Extruder Info"
 
-#MSG_MOVE_E
+#MSG_EXTRUDER c=17
 "Extruder"
 "\x00"
 
@@ -258,7 +314,7 @@
 "Fail stats MMU"
 "MMU-Fehler"
 
-#MSG_FSENSOR_AUTOLOAD
+#MSG_FSENSOR_AUTOLOAD c=13
 "F. autoload"
 "F. autoladen"
 
@@ -274,17 +330,17 @@
 "Fan test"
 "Lueftertest"
 
-#MSG_FANS_CHECK
+#MSG_FANS_CHECK c=13
 "Fans check"
 "Luefter Chk."
 
 #MSG_FSENSOR
 "Fil. sensor"
-"\x00"
+"Fil. Sensor"
 
-#
-"Filam. runouts"
-"Filam. Maengel"
+#MSG_FIL_RUNOUTS c=14
+"Fil. runouts  "
+"Fil. Maengel  "
 
 #MSG_FILAMENT_CLEAN c=20 r=2
 "Filament extruding & with correct color?"
@@ -298,7 +354,7 @@
 "Filament sensor"
 "Filamentsensor"
 
-#MSG_FILAMENT_USED c=19 r=1
+#MSG_FILAMENT_USED c=19
 "Filament used"
 "Filament benutzt"
 
@@ -306,15 +362,19 @@
 "Print time"
 "Druckzeit"
 
-#MSG_FILE_INCOMPLETE c=20 r=2
+#MSG_FS_ACTION c=10
+"FS Action"
+"FS Aktion"
+
+#MSG_FILE_INCOMPLETE c=20 r=3
 "File incomplete. Continue anyway?"
 "Datei unvollstaendig Trotzdem fortfahren?"
 
-#MSG_FINISHING_MOVEMENTS c=20 r=1
+#MSG_FINISHING_MOVEMENTS c=20
 "Finishing movements"
 "Bewegung beenden"
 
-#MSG_V2_CALIBRATION c=17 r=1
+#MSG_V2_CALIBRATION c=18
 "First layer cal."
 "Erste-Schicht Kal."
 
@@ -398,17 +458,17 @@
 "Checking sensors "
 "Pruefe Sensoren "
 
-#MSG_SELFTEST_CHECK_X c=20
-"Checking X axis  "
-"Pruefe X Achse "
+#MSG_CHECKING_X c=20
+"Checking X axis"
+"Pruefe X Achse"
 
-#MSG_SELFTEST_CHECK_Y c=20
-"Checking Y axis  "
-"Pruefe Y Achse "
+#MSG_CHECKING_Y c=20
+"Checking Y axis"
+"Pruefe Y Achse"
 
 #MSG_SELFTEST_CHECK_Z c=20
-"Checking Z axis  "
-"Pruefe Z Achse "
+"Checking Z axis"
+"Pruefe Z Achse"
 
 #MSG_CHOOSE_EXTRUDER c=20 r=1
 "Choose extruder:"
@@ -438,7 +498,7 @@
 "Insert filament"
 "Filament einlegen"
 
-#MSG_WIZARD_FILAMENT_LOADED c=20 r=2
+#MSG_FILAMENT_LOADED c=20 r=2
 "Is filament loaded?"
 "Ist das Filament geladen?"
 
@@ -446,7 +506,7 @@
 "Is steel sheet on heatbed?"
 "Liegt das Stahlblech auf dem Heizbett?"
 
-#
+#MSG_LAST_PRINT_FAILURES c=20
 "Last print failures"
 "Letzte Druckfehler"
 
@@ -454,7 +514,7 @@
 "If you have additional steel sheets, calibrate their presets in Settings - HW Setup - Steel sheets."
 "Wenn Sie zusaetzliche Stahlbleche haben, kalibrieren Sie deren Voreinstellungen unter Einstellungen - HW Setup - Stahlbleche."
 
-#
+#MSG_LAST_PRINT c=18
 "Last print"
 "Letzter Druck"
 
@@ -478,6 +538,10 @@
 "Live adjust Z"
 "Z einstellen"
 
+# c=20 r=6
+"Insert the filament (do not load it) into the extruder and then press the knob."
+"Stecken Sie das Filament (nicht laden) in den Extruder und druecken Sie dann den Knopf."
+
 #MSG_LOAD_FILAMENT c=17
 "Load filament"
 "Filament laden"
@@ -498,7 +562,7 @@
 "Load to nozzle"
 "In Druckduese laden"
 
-#MSG_M117_V2_CALIBRATION c=25 r=1
+#MSG_M117_V2_CALIBRATION c=25
 "M117 First layer cal."
 "M117 Erste-Schicht Kal."
 
@@ -506,11 +570,19 @@
 "Main"
 "Hauptmenue"
 
+#MSG_BL_HIGH c=12
+"Level Bright"
+"Hell.wert"
+
+#MSG_BL_LOW c=12
+"Level Dimmed"
+"Dimmwert"
+
 #MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE1 c=60
 "Measuring reference height of calibration point"
 "Messen der Referenzhoehe des Kalibrierpunktes"
 
-#MSG_MESH_BED_LEVELING
+#MSG_MESH_BED_LEVELING c=18
 "Mesh Bed Leveling"
 "MeshBett Ausgleich"
 
@@ -526,7 +598,7 @@
 "Measured skew"
 "Schraeglauf"
 
-#
+#MSG_MMU_FAILS c=14
 "MMU fails"
 "MMU Fehler"
 
@@ -534,7 +606,7 @@
 "MMU load failed     "
 "MMU Ladefehler"
 
-#
+#MSG_MMU_LOAD_FAILS c=14
 "MMU load fails"
 "MMU Ladefehler"
 
@@ -546,6 +618,10 @@
 "Mode"
 "Modus"
 
+# c=20 r=3
+"MK3 firmware detected on MK3S printer"
+"MK3-Firmware am MK3S-Drucker erkannt"
+
 #MSG_NORMAL
 "Normal"
 "\x00"
@@ -568,7 +644,7 @@
 
 #MSG_AUTO_POWER
 "Auto power"
-"\x00"
+"Auto Leist"
 
 #MSG_HIGH_POWER
 "High power"
@@ -638,7 +714,7 @@
 "Nozzle"
 "Duese"
 
-#MSG_DEFAULT_SETTINGS_LOADED c=20 r=4
+#MSG_DEFAULT_SETTINGS_LOADED c=20 r=5
 "Old settings found. Default PID, Esteps etc. will be set."
 "Alte Einstellungen gefunden. Standard PID, E-Steps u.s.w. werden gesetzt."
 
@@ -670,7 +746,7 @@
 "PINDA Heating"
 "PINDA erwaermen"
 
-#MSG_PAPER c=20 r=8
+#MSG_PAPER c=20 r=10
 "Place a sheet of paper under the nozzle during the calibration of first 4 points. If the nozzle catches the paper, power off the printer immediately."
 "Legen Sie ein Blatt Papier unter die Duese waehrend der Kalibrierung der ersten 4 Punkte. Wenn die Duese das Papier erfasst, den Drucker sofort ausschalten."
 
@@ -742,15 +818,23 @@
 "Preheating nozzle. Please wait."
 "Vorheizen der Duese. Bitte warten."
 
+# c=14
+"PINDA"
+"\x00"
+
 #
 "Please upgrade."
 "Bitte aktualisieren."
 
 #MSG_PRESS_TO_PREHEAT c=20 r=4
-"Press knob to preheat nozzle and continue."
+"Press the knob to preheat nozzle and continue."
 "Bitte druecken Sie den Knopf um die Duese vorzuheizen und fortzufahren."
 
-#
+#MSG_FS_PAUSE c=5
+"Pause"
+"\x00"
+
+#MSG_POWER_FAILURES c=14
 "Power failures"
 "Netzfehler"
 
@@ -758,11 +842,11 @@
 "Print aborted"
 "Druck abgebrochen"
 
-#
+# c=20
 "Preheating to load"
 "Heizen zum Laden"
 
-#
+# c=20
 "Preheating to unload"
 "Heizen zum Entladen"
 
@@ -774,7 +858,7 @@
 "Print from SD"
 "Drucken von SD"
 
-#
+# c=20
 "Press the knob"
 "Knopf druecken zum"
 
@@ -814,15 +898,23 @@
 "Rear side [um]"
 "Hinten [um]"
 
-#MSG_RECOVERING_PRINT c=20 r=1
+# c=20 r=4
+"Please unload the filament first, then repeat this action."
+"Bitte entladen Sie erst das Filament und versuchen Sie es nochmal."
+
+# c=20 r=4
+"Please check the IR sensor connection, unload filament if present."
+"Bitte IR Sensor Verbindungen ueber- pruefen und Filament entladen ist."
+
+#MSG_RECOVERING_PRINT c=20
 "Recovering print    "
-"Druck wiederherst    "
+"Druck wiederherst   "
 
-#MSG_REMOVE_OLD_FILAMENT c=20 r=4
+#MSG_REMOVE_OLD_FILAMENT c=20 r=5
 "Remove old filament and press the knob to start loading new filament."
 "Entfernen Sie das alte Filament und druecken Sie den Knopf, um das neue zu laden."
 
-#
+# c=20
 "Prusa i3 MK3S OK."
 "\x00"
 
@@ -830,15 +922,15 @@
 "Reset XYZ calibr."
 "Reset XYZ Kalibr."
 
-#MSG_BED_CORRECTION_RESET
+#MSG_RESET c=14
 "Reset"
 "Ruecksetzen"
 
-#MSG_RESUME_PRINT
+#MSG_RESUME_PRINT c=18
 "Resume print"
 "Druck fortsetzen"
 
-#MSG_RESUMING_PRINT c=20 r=1
+#MSG_RESUMING_PRINT c=20
 "Resuming print"
 "Druck fortgesetzt"
 
@@ -906,11 +998,23 @@
 "Set temperature:"
 "Temp. einstellen:"
 
+# c=20
+"Prusa i3 MK2.5 OK."
+"\x00"
+
+# c=20
+"Prusa i3 MK2.5S OK."
+"\x00"
+
+# c=20
+"Prusa i3 MK3 OK."
+"\x00"
+
 #MSG_SETTINGS
 "Settings"
 "Einstellungen"
 
-#MSG_SHOW_END_STOPS c=17 r=1
+#MSG_SHOW_END_STOPS c=18
 "Show end stops"
 "Endschalter Status"
 
@@ -918,7 +1022,7 @@
 "Sensor state"
 "Sensorstatus"
 
-#MSG_FILE_CNT c=20 r=4
+#MSG_FILE_CNT c=20 r=6
 "Some files will not be sorted. Max. No. of files in 1 folder for sorting is 100."
 "Einige Dateien wur- den nicht sortiert. Max. Dateien pro Verzeichnis = 100."
 
@@ -956,6 +1060,10 @@
 
 #MSG_SOUND
 "Sound"
+"Ton"
+
+# c=7
+"Runouts"
 "\x00"
 
 #
@@ -1002,7 +1110,7 @@
 "Select filament:"
 "Filament auswaehlen:"
 
-#MSG_TEMP_CALIBRATION c=12 r=1
+#MSG_TEMP_CALIBRATION c=14
 "Temp. cal."
 "Temp Kalib."
 
@@ -1022,6 +1130,10 @@
 "Temperature calibration is finished and active. Temp. calibration can be disabled in menu Settings->Temp. cal."
 "Temp.kalibrierung ist fertig + aktiv. Temp.kalibrierung kann ausgeschaltet werden im Menu Einstellungen -> Temp.kal."
 
+# c=20 r=3
+"Sensor verified, remove the filament now."
+"Sensor ueberprueft, entladen Sie jetzt das Filament."
+
 #MSG_TEMPERATURE
 "Temperature"
 "Temperatur"
@@ -1030,9 +1142,9 @@
 "Temperatures"
 "Temperaturen"
 
-#MSG_FOLLOW_Z_CALIBRATION_FLOW c=20 r=4
+#MSG_FOLLOW_Z_CALIBRATION_FLOW c=20 r=9
 "There is still a need to make Z calibration. Please follow the manual, chapter First steps, section Calibration flow."
-"Es ist noch notwendig die Z-Kalibrierung auszufuehren. Bitte befolgen Sie das Handbuch, Kapitel Erste Schritte, Abschnitt Kalibrierablauf."
+"Es ist noch not- wendig die Z- Kalibrierung aus- zufuehren. Bitte befolgen Sie das Handbuch, Kapitel Erste Schritte, Abschnitt Kalibrierablauf."
 
 #
 "Total filament"
@@ -1050,15 +1162,15 @@
 "Unload"
 "Entladen"
 
-#
+#MSG_TOTAL_FAILURES c=20
 "Total failures"
 "Gesamte Fehler"
 
-#
+# c=20
 "to load filament"
 "Filament laden"
 
-#
+# c=20
 "to unload filament"
 "Filament entladen"
 
@@ -1070,7 +1182,7 @@
 "Unloading filament"
 "Filament auswerfen"
 
-#
+#MSG_TOTAL c=6
 "Total"
 "Gesamt"
 
@@ -1126,7 +1238,7 @@
 "Wizard"
 "Assistent"
 
-#MSG_XYZ_DETAILS c=19 r=1
+#MSG_XYZ_DETAILS c=18
 "XYZ cal. details"
 "XYZ Kal. Details"
 
@@ -1150,7 +1262,11 @@
 "XYZ calibration all right. X/Y axes are slightly skewed. Good job!"
 "XYZ Kalibrierung in Ordnung. X/Y Achsen sind etwas schraeg."
 
-#
+#MSG_TIMEOUT c=12
+"Timeout"
+"Verzoegerung"
+
+#MSG_X_CORRECTION c=13
 "X-correct:"
 "X-Korrektur:"
 
@@ -1190,7 +1306,11 @@
 "The printer will start printing a zig-zag line. Rotate the knob until you reach the optimal height. Check the pictures in the handbook (Calibration chapter)."
 "Der Drucker beginnt mit dem Drucken einer Zickzacklinie. Drehen Sie den Knopf, bis Sie die optimale Hoehe erreicht haben. Ueberpruefen Sie die Bilder im Handbuch (Kapitel Kalibrierung)."
 
-#
+# c=20 r=5
+"Verification failed, remove the filament and try again."
+"Ueberpruefung fehl- geschlagen, entladen Sie das Filament und versuchen Sie es erneut."
+
+#MSG_Y_CORRECTION c=13
 "Y-correct:"
 "Y-Korrektur:"
 
@@ -1230,7 +1350,7 @@
 "Warn"
 "Warnen"
 
-#
+#MSG_HW_SETUP c=18
 "HW Setup"
 "HW Einstellungen"
 
@@ -1246,10 +1366,6 @@
 "Mesh"
 "Gitter"
 
-#
-"Mesh bed leveling"
-"MeshBett Ausgleich"
-
 #
 "MK3S firmware detected on MK3 printer"
 "MK3S-Firmware auf MK3-Drucker erkannt"
@@ -1278,11 +1394,11 @@
 "G-code sliced for a different level. Please re-slice the model again. Print cancelled."
 "G-Code ist fuer einen anderen Level geslict. Bitte slicen Sie das Modell erneut. Druck abgebrochen."
 
-#
+#MSG_GCODE_DIFF_PRINTER_CONTINUE c=20 r=5
 "G-code sliced for a different printer type. Continue?"
 "G-Code ist fuer einen anderen Drucker geslict. Fortfahren?"
 
-#
+#MSG_GCODE_DIFF_PRINTER_CANCELLED c=20 r=6
 "G-code sliced for a different printer type. Please re-slice the model again. Print cancelled."
 "G-Code ist fuer einen anderen Drucker geslict. Bitte slicen Sie das Modell erneut. Druck abgebrochen."
 
@@ -1298,11 +1414,11 @@
 "PINDA:"
 "\x00"
 
-#
+# c=20
 "Preheating to cut"
 "Heizen zum Schnitt"
 
-#
+# c=20
 "Preheating to eject"
 "Heizen zum Auswurf"
 
@@ -1314,6 +1430,10 @@
 "Printer nozzle diameter differs from the G-code. Please check the value in settings. Print cancelled."
 "Der Durchmesser der Druckerduese weicht vom G-Code ab. Bitte ueberpruefen Sie den Wert in den Einstellungen. Druck abgebrochen."
 
+# c=20
+"%s level expected"
+"\x00"
+
 #
 "Rename"
 "Umbenennen"
@@ -1326,22 +1446,23 @@
 "Sensor info"
 "Sensor Info"
 
-#
+#MSG_SHEET c=10
 "Sheet"
-"Blech"
+"Stahlblech"
 
 #MSG_SOUND_BLIND
 "Assist"
 "\x00"
 
-#
+#MSG_STEEL_SHEET c=18
 "Steel sheets"
 "Stahlbleche"
 
-#
+#MSG_Z_CORRECTION c=13
 "Z-correct:"
 "Z-Korrektur:"
 
 #MSG_Z_PROBE_NR
 "Z-probe nr."
 "\x00"
+

+ 210 - 89
lang/lang_en_es.txt

@@ -2,6 +2,26 @@
 "[%.7s]Live adj. Z\x0avalue set, continue\x0aor start from zero?\x0a%cContinue%cReset"
 "[%.7s]Ajuste Z\x0aAjustado, continuar\x0ao empezar de nuevo?\x0a%cContinuar%cRepetir"
 
+#MSG_IR_03_OR_OLDER c=18
+" 0.3 or older"
+" 0.3 o mayor"
+
+# c=18
+"FS v0.3 or older"
+"FS 0.3 o mayor"
+
+#MSG_IR_04_OR_NEWER c=18
+" 0.4 or newer"
+" 0.4 o mas nueva"
+
+# c=18
+"FS v0.4 or newer"
+"FS 0.4 o mas nueva"
+
+#MSG_IR_UNKNOWN c=18
+"unknown state"
+"estado desconocido"
+
 #MSG_IMPROVE_BED_OFFSET_AND_SKEW_LINE2 c=14
 " of 4"
 " de 4"
@@ -42,7 +62,11 @@
 "Ambient"
 "Ambiente"
 
-#MSG_PRESS c=20
+#MSG_AUTO c=6
+"Auto"
+"\x00"
+
+#MSG_PRESS c=20 r=2
 "and press the knob"
 "Haz clic"
 
@@ -58,9 +82,9 @@
 "Auto home"
 "Llevar al origen"
 
-#MSG_AUTOLOAD_FILAMENT c=17
+#MSG_AUTOLOAD_FILAMENT c=18
 "AutoLoad filament"
-"Carga automatica de filamento"
+"Carga auto. filam."
 
 #MSG_AUTOLOADING_ONLY_IF_FSENS_ON c=20 r=4
 "Autoloading filament available only when filament sensor is turned on..."
@@ -94,17 +118,29 @@
 "Bed level correct"
 "Corr. de la cama"
 
-#MSG_BED_LEVELING_FAILED_POINT_LOW c=20 r=4
+#MSG_BELTTEST c=17
+"Belt test        "
+"Test cinturon    "
+
+#MSG_BED_LEVELING_FAILED_POINT_LOW c=20 r=5
 "Bed leveling failed. Sensor didnt trigger. Debris on nozzle? Waiting for reset."
 "Nivelacion fallada. Sensor no funciona. Restos en boquilla? Esperando reset."
 
+#MSG_BRIGHT c=6
+"Bright"
+"Brill."
+
+#MSG_BRIGHTNESS c=18
+"Brightness"
+"Brillo"
+
 #MSG_BED
 "Bed"
 "Base"
 
-#MSG_MENU_BELT_STATUS c=15 r=1
+#MSG_BELT_STATUS c=18
 "Belt status"
-"Estado de la correa"
+"Estado de correa"
 
 #MSG_RECOVER_PRINT c=20 r=2
 "Blackout occurred. Recover print?"
@@ -166,7 +202,7 @@
 "Copy selected language?"
 "Copiar idioma seleccionado?"
 
-#MSG_CRASHDETECT
+#MSG_CRASHDETECT c=13
 "Crash det."
 "Det. choque"
 
@@ -182,7 +218,7 @@
 "Crash detected. Resume print?"
 "Choque detectado. Continuar impresion?"
 
-#
+#MSG_CRASH c=7
 "Crash"
 "Choque"
 
@@ -202,23 +238,27 @@
 "Distance between tip of the nozzle and the bed surface has not been set yet. Please follow the manual, chapter First steps, section First layer calibration."
 "Distancia entre la punta del boquilla y la superficie de la base aun no fijada. Por favor siga el manual, capitulo Primeros Pasos, Calibracion primera capa."
 
+#MSG_FS_CONTINUE c=5
+"Cont."
+"\x00"
+
 #MSG_WIZARD_REPEAT_V2_CAL c=20 r=7
 "Do you want to repeat last step to readjust distance between nozzle and heatbed?"
 "Quieres repetir el ultimo paso para reajustar la distancia boquilla-base?"
 
-#MSG_EXTRUDER_CORRECTION c=10
+#MSG_EXTRUDER_CORRECTION c=13
 "E-correct:"
 "Corregir-E:"
 
-#MSG_EJECT_FILAMENT c=17 r=1
+#MSG_EJECT_FILAMENT c=16
 "Eject filament"
-"Expulsar filamento"
+"Expulsar fil."
 
 #MSG_EJECTING_FILAMENT c=20 r=1
 "Ejecting filament"
 "Expulsando filamento"
 
-#MSG_SELFTEST_ENDSTOP_NOTHIT c=20 r=1
+#MSG_SELFTEST_ENDSTOP_NOTHIT c=20
 "Endstop not hit"
 "Endstop no alcanzado"
 
@@ -234,10 +274,26 @@
 "Error - static memory has been overwritten"
 "Error - se ha sobre-escrito la memoria estatica"
 
+#MSG_CUT_FILAMENT c=16
+"Cut filament"
+"Cortar filament"
+
+#MSG_CUTTER c=9
+"Cutter"
+"Cuchillo"
+
+# c=18
+"Cutting filament"
+"Corte de filament"
+
 #MSG_FSENS_NOT_RESPONDING c=20 r=4
 "ERROR: Filament sensor is not responding, please check connection."
 "ERROR: El sensor de filamento no responde, por favor comprueba la conexion."
 
+#MSG_DIM c=6
+"Dim"
+"\x00"
+
 #MSG_ERROR
 "ERROR:"
 "\x00"
@@ -246,11 +302,11 @@
 "Extruder fan:"
 "Vent.extrusor:"
 
-#MSG_INFO_EXTRUDER c=15 r=1
+#MSG_INFO_EXTRUDER c=18
 "Extruder info"
-"Informacion del extrusor"
+"Info. del extrusor"
 
-#MSG_MOVE_E
+#MSG_EXTRUDER c=17
 "Extruder"
 "Extruir"
 
@@ -258,7 +314,7 @@
 "Fail stats MMU"
 "Estadistica de fallos MMU"
 
-#MSG_FSENSOR_AUTOLOAD
+#MSG_FSENSOR_AUTOLOAD c=13
 "F. autoload"
 "Autocarg.fil."
 
@@ -268,13 +324,13 @@
 
 #MSG_FAN_SPEED c=14
 "Fan speed"
-"Velocidad Vent."
+"Velocidad Vent"
 
 #MSG_SELFTEST_FAN c=20
 "Fan test"
 "Test ventiladores"
 
-#MSG_FANS_CHECK
+#MSG_FANS_CHECK c=13
 "Fans check"
 "Comprob.vent"
 
@@ -282,9 +338,9 @@
 "Fil. sensor"
 "Sensor Fil."
 
-#
-"Filam. runouts"
-"Filam. acabado"
+#MSG_FIL_RUNOUTS c=14
+"Fil. runouts  "
+"Fil. acabado  "
 
 #MSG_FILAMENT_CLEAN c=20 r=2
 "Filament extruding & with correct color?"
@@ -298,7 +354,7 @@
 "Filament sensor"
 "Sensor de filamento"
 
-#MSG_FILAMENT_USED c=19 r=1
+#MSG_FILAMENT_USED c=19
 "Filament used"
 "Filamento usado"
 
@@ -306,15 +362,19 @@
 "Print time"
 "Tiempo de imp.:"
 
-#MSG_FILE_INCOMPLETE c=20 r=2
+#MSG_FS_ACTION c=10
+"FS Action"
+"FS accion"
+
+#MSG_FILE_INCOMPLETE c=20 r=3
 "File incomplete. Continue anyway?"
 "Archivo incompleto. ?Continuar de todos modos?"
 
-#MSG_FINISHING_MOVEMENTS c=20 r=1
+#MSG_FINISHING_MOVEMENTS c=20
 "Finishing movements"
 "Term. movimientos"
 
-#MSG_V2_CALIBRATION c=17 r=1
+#MSG_V2_CALIBRATION c=18
 "First layer cal."
 "Cal. primera cap."
 
@@ -356,7 +416,7 @@
 
 #MSG_HEATING_COMPLETE c=20
 "Heating done."
-"Calentamiento acabado."
+"Calentando acabado."
 
 #MSG_HEATING
 "Heating"
@@ -396,18 +456,18 @@
 
 #MSG_SELFTEST_CHECK_FSENSOR c=20
 "Checking sensors "
-"Comprobando los sensores"
+"Comprobando sensores"
 
-#MSG_SELFTEST_CHECK_X c=20
-"Checking X axis  "
+#MSG_CHECKING_X c=20
+"Checking X axis"
 "Control sensor X"
 
-#MSG_SELFTEST_CHECK_Y c=20
-"Checking Y axis  "
+#MSG_CHECKING_Y c=20
+"Checking Y axis"
 "Control sensor Y"
 
 #MSG_SELFTEST_CHECK_Z c=20
-"Checking Z axis  "
+"Checking Z axis"
 "Control sensor Z"
 
 #MSG_CHOOSE_EXTRUDER c=20 r=1
@@ -438,23 +498,23 @@
 "Insert filament"
 "Introducir filamento"
 
-#MSG_WIZARD_FILAMENT_LOADED c=20 r=2
+#MSG_FILAMENT_LOADED c=20 r=2
 "Is filament loaded?"
 "Esta el filamento cargado?"
 
 #MSG_STEEL_SHEET_CHECK c=20 r=2
 "Is steel sheet on heatbed?"
-"?Esta colocada la lamina de acero sobre la base?"
+"?Esta colocada la lamina sobre la base"
 
-#
+#MSG_LAST_PRINT_FAILURES c=20
 "Last print failures"
-"Ultimas impresiones fallidas"
+"Ultimos imp. fallos"
 
 #
 "If you have additional steel sheets, calibrate their presets in Settings - HW Setup - Steel sheets."
 "Si tienes planchas de acero adicionales, calibra sus ajustes en Ajustes - Ajustes HW - Planchas acero."
 
-#
+#MSG_LAST_PRINT c=18
 "Last print"
 "Ultima impresion"
 
@@ -478,6 +538,10 @@
 "Live adjust Z"
 "Micropaso Eje Z"
 
+# c=20 r=6
+"Insert the filament (do not load it) into the extruder and then press the knob."
+"Inserte el filamento (no lo cargue) en el extrusor y luego presione el dial."
+
 #MSG_LOAD_FILAMENT c=17
 "Load filament"
 "Introducir filam."
@@ -498,7 +562,7 @@
 "Load to nozzle"
 "Cargar a la boquilla"
 
-#MSG_M117_V2_CALIBRATION c=25 r=1
+#MSG_M117_V2_CALIBRATION c=25
 "M117 First layer cal."
 "M117 Cal. primera cap."
 
@@ -506,13 +570,21 @@
 "Main"
 "Menu principal"
 
+#MSG_BL_HIGH c=12
+"Level Bright"
+"Valor brill."
+
+#MSG_BL_LOW c=12
+"Level Dimmed"
+"\x00"
+
 #MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE1 c=60
 "Measuring reference height of calibration point"
 "Midiendo altura del punto de calibracion"
 
-#MSG_MESH_BED_LEVELING
+#MSG_MESH_BED_LEVELING c=18
 "Mesh Bed Leveling"
-"Nivelacion Mesh Level"
+"Nivela. Mesh Level"
 
 #MSG_MMU_OK_RESUMING_POSITION c=20 r=4
 "MMU OK. Resuming position..."
@@ -526,7 +598,7 @@
 "Measured skew"
 "Desviacion med:"
 
-#
+#MSG_MMU_FAILS c=14
 "MMU fails"
 "Fallos MMU"
 
@@ -534,7 +606,7 @@
 "MMU load failed     "
 "Carga MMU fallida"
 
-#
+#MSG_MMU_LOAD_FAILS c=14
 "MMU load fails"
 "Carga MMU falla"
 
@@ -546,6 +618,10 @@
 "Mode"
 "Modo"
 
+# c=20 r=3
+"MK3 firmware detected on MK3S printer"
+"Firmware MK3 detectado en impresora MK3S"
+
 #MSG_NORMAL
 "Normal"
 "\x00"
@@ -638,7 +714,7 @@
 "Nozzle"
 "Boquilla"
 
-#MSG_DEFAULT_SETTINGS_LOADED c=20 r=4
+#MSG_DEFAULT_SETTINGS_LOADED c=20 r=5
 "Old settings found. Default PID, Esteps etc. will be set."
 "Se han encontrado ajustes anteriores. Se ajustara el PID, los pasos del extrusor, etc"
 
@@ -670,7 +746,7 @@
 "PINDA Heating"
 "Calentando PINDA"
 
-#MSG_PAPER c=20 r=8
+#MSG_PAPER c=20 r=10
 "Place a sheet of paper under the nozzle during the calibration of first 4 points. If the nozzle catches the paper, power off the printer immediately."
 "Colocar una hoja de papel sobre la superficie de impresion durante la calibracion de los primeros 4 puntos. Si la boquilla mueve el papel, apagar impresora inmediatamente."
 
@@ -732,7 +808,7 @@
 
 #MSG_PREHEAT_NOZZLE c=20
 "Preheat the nozzle!"
-"Precalienta extrusor!"
+"Precalienta extrusor"
 
 #MSG_PREHEAT
 "Preheat"
@@ -742,15 +818,23 @@
 "Preheating nozzle. Please wait."
 "Precalentando nozzle. Espera por favor."
 
+# c=14
+"PINDA"
+"\x00"
+
 #
 "Please upgrade."
 "Actualize por favor"
 
 #MSG_PRESS_TO_PREHEAT c=20 r=4
-"Press knob to preheat nozzle and continue."
+"Press the knob to preheat nozzle and continue."
 "Pulsa el dial para precalentar la boquilla y continue."
 
-#
+#MSG_FS_PAUSE c=5
+"Pause"
+"Pausa"
+
+#MSG_POWER_FAILURES c=14
 "Power failures"
 "Cortes de energia"
 
@@ -758,13 +842,13 @@
 "Print aborted"
 "Impresion cancelada"
 
-#
+# c=20
 "Preheating to load"
-"Precalentar para cargar"
+"Precalent. cargar"
 
-#
+# c=20
 "Preheating to unload"
-"Precalentar para descargar"
+"Precalent. descargar"
 
 #MSG_SELFTEST_PRINT_FAN_SPEED c=18
 "Print fan:"
@@ -774,7 +858,7 @@
 "Print from SD"
 "Menu tarjeta SD"
 
-#
+# c=20
 "Press the knob"
 "Pulsa el dial"
 
@@ -814,15 +898,23 @@
 "Rear side [um]"
 "Trasera [um]"
 
-#MSG_RECOVERING_PRINT c=20 r=1
+# c=20 r=4
+"Please unload the filament first, then repeat this action."
+"Primero descargue el filamento, luego repita esta accion."
+
+# c=20 r=4
+"Please check the IR sensor connection, unload filament if present."
+"Por favor comprueba la conexion del IR sensor y filamento esta descargado."
+
+#MSG_RECOVERING_PRINT c=20
 "Recovering print    "
-"Recuperando impresion"
+"Recuper. impresion  "
 
-#MSG_REMOVE_OLD_FILAMENT c=20 r=4
+#MSG_REMOVE_OLD_FILAMENT c=20 r=5
 "Remove old filament and press the knob to start loading new filament."
 "Retire el filamento viejo y presione el dial para comenzar a cargar el nuevo filamento."
 
-#
+# c=20
 "Prusa i3 MK3S OK."
 "\x00"
 
@@ -830,17 +922,17 @@
 "Reset XYZ calibr."
 "\x00"
 
-#MSG_BED_CORRECTION_RESET
+#MSG_RESET c=14
 "Reset"
 "\x00"
 
-#MSG_RESUME_PRINT
+#MSG_RESUME_PRINT c=18
 "Resume print"
 "Reanudar impres."
 
-#MSG_RESUMING_PRINT c=20 r=1
+#MSG_RESUMING_PRINT c=20
 "Resuming print"
-"Continuando impresion"
+"Continuan. impresion"
 
 #MSG_BED_CORRECTION_RIGHT c=14 r=1
 "Right side[um]"
@@ -884,7 +976,7 @@
 
 #MSG_SELFTEST
 "Selftest         "
-"Selftest"
+"\x00"
 
 #MSG_SELFTEST_ERROR
 "Selftest error !"
@@ -906,11 +998,23 @@
 "Set temperature:"
 "Establecer temp.:"
 
+# c=20
+"Prusa i3 MK2.5 OK."
+"\x00"
+
+# c=20
+"Prusa i3 MK2.5S OK."
+"\x00"
+
+# c=20
+"Prusa i3 MK3 OK."
+"\x00"
+
 #MSG_SETTINGS
 "Settings"
 "Configuracion"
 
-#MSG_SHOW_END_STOPS c=17 r=1
+#MSG_SHOW_END_STOPS c=18
 "Show end stops"
 "Mostrar endstops"
 
@@ -918,7 +1022,7 @@
 "Sensor state"
 "Estado del sensor"
 
-#MSG_FILE_CNT c=20 r=4
+#MSG_FILE_CNT c=20 r=6
 "Some files will not be sorted. Max. No. of files in 1 folder for sorting is 100."
 "Algunos archivos no se ordenaran. Maximo 100 archivos por carpeta para ordenar. "
 
@@ -958,6 +1062,10 @@
 "Sound"
 "Sonido"
 
+# c=7
+"Runouts"
+"\x00"
+
 #
 "Some problem encountered, Z-leveling enforced ..."
 "Problema encontrado, nivelacion Z forzosa ..."
@@ -1002,7 +1110,7 @@
 "Select filament:"
 "Selecciona filamento:"
 
-#MSG_TEMP_CALIBRATION c=12 r=1
+#MSG_TEMP_CALIBRATION c=14
 "Temp. cal."
 "Cal. temp."
 
@@ -1022,6 +1130,10 @@
 "Temperature calibration is finished and active. Temp. calibration can be disabled in menu Settings->Temp. cal."
 "Calibracion temperatura terminada. Haz clic para continuar."
 
+# c=20 r=3
+"Sensor verified, remove the filament now."
+"Sensor verificado, retire el filamento ahora."
+
 #MSG_TEMPERATURE
 "Temperature"
 "Temperatura"
@@ -1030,7 +1142,7 @@
 "Temperatures"
 "Temperaturas"
 
-#MSG_FOLLOW_Z_CALIBRATION_FLOW c=20 r=4
+#MSG_FOLLOW_Z_CALIBRATION_FLOW c=20 r=9
 "There is still a need to make Z calibration. Please follow the manual, chapter First steps, section Calibration flow."
 "Todavia es necesario hacer una calibracion Z. Por favor siga el manual, capitulo Primeros pasos, seccion Calibracion del flujo."
 
@@ -1050,17 +1162,17 @@
 "Unload"
 "Descargar"
 
-#
+#MSG_TOTAL_FAILURES c=20
 "Total failures"
 "Fallos totales"
 
-#
+# c=20
 "to load filament"
-"para cargar el filamento"
+"para cargar el fil."
 
-#
+# c=20
 "to unload filament"
-"para descargar el filamento"
+"para descargar fil."
 
 #MSG_UNLOAD_FILAMENT c=17
 "Unload filament"
@@ -1070,7 +1182,7 @@
 "Unloading filament"
 "Soltando filamento"
 
-#
+#MSG_TOTAL c=6
 "Total"
 "\x00"
 
@@ -1126,9 +1238,9 @@
 "Wizard"
 "\x00"
 
-#MSG_XYZ_DETAILS c=19 r=1
+#MSG_XYZ_DETAILS c=18
 "XYZ cal. details"
-"Detalles de calibracion XYZ"
+"Detalles cal. XYZ"
 
 #MSG_BED_SKEW_OFFSET_DETECTION_FITTING_FAILED c=20 r=8
 "XYZ calibration failed. Please consult the manual."
@@ -1150,7 +1262,11 @@
 "XYZ calibration all right. X/Y axes are slightly skewed. Good job!"
 "Calibracion XYZ correcta. Los ejes X / Y estan ligeramente inclinados. Buen trabajo!"
 
-#
+#MSG_TIMEOUT c=12
+"Timeout"
+"Expirar"
+
+#MSG_X_CORRECTION c=13
 "X-correct:"
 "Corregir-X:"
 
@@ -1190,7 +1306,11 @@
 "The printer will start printing a zig-zag line. Rotate the knob until you reach the optimal height. Check the pictures in the handbook (Calibration chapter)."
 "La impresora comenzara a imprimir una linea en zig-zag. Gira el dial hasta que la linea alcance la altura optima. Mira las fotos del manual (Capitulo de calibracion)."
 
-#
+# c=20 r=5
+"Verification failed, remove the filament and try again."
+"La verificacion fallo, retire el filamento e intente nuevamente."
+
+#MSG_Y_CORRECTION c=13
 "Y-correct:"
 "Corregir-Y:"
 
@@ -1230,7 +1350,7 @@
 "Warn"
 "Aviso"
 
-#
+#MSG_HW_SETUP c=18
 "HW Setup"
 "Configuracion HW"
 
@@ -1246,10 +1366,6 @@
 "Mesh"
 "Malla"
 
-#
-"Mesh bed leveling"
-"Nivelacion Malla Base"
-
 #
 "MK3S firmware detected on MK3 printer"
 "Firmware MK3S detectado en impresora MK3"
@@ -1278,11 +1394,11 @@
 "G-code sliced for a different level. Please re-slice the model again. Print cancelled."
 "Codigo G laminado para un nivel diferente. Por favor relamina el modelo de nuevo. Impresion cancelada."
 
-#
+#MSG_GCODE_DIFF_PRINTER_CONTINUE c=20 r=5
 "G-code sliced for a different printer type. Continue?"
 "Codigo G laminado para un tipo de impresora diferente. ?Continuar?"
 
-#
+#MSG_GCODE_DIFF_PRINTER_CANCELLED c=20 r=6
 "G-code sliced for a different printer type. Please re-slice the model again. Print cancelled."
 "Codigo G laminado para una impresora diferente. Por favor relamina el modelo de nuevo. Impresion cancelada."
 
@@ -1298,13 +1414,13 @@
 "PINDA:"
 "PINDA:"
 
-#
+# c=20
 "Preheating to cut"
-"Precalentando para laminar"
+"Precalent. laminar"
 
-#
+# c=20
 "Preheating to eject"
-"Precalentar para expulsar"
+"Precalent. expulsar"
 
 #
 "Printer nozzle diameter differs from the G-code. Continue?"
@@ -1314,6 +1430,10 @@
 "Printer nozzle diameter differs from the G-code. Please check the value in settings. Print cancelled."
 "Diametro nozzle Impresora difiere de cod.G. Comprueba los valores en ajustes. Impresion cancelada."
 
+# c=20
+"%s level expected"
+"\x00"
+
 #
 "Rename"
 "Renombrar"
@@ -1326,7 +1446,7 @@
 "Sensor info"
 "Info sensor"
 
-#
+#MSG_SHEET c=10
 "Sheet"
 "Lamina"
 
@@ -1334,14 +1454,15 @@
 "Assist"
 "Asistido"
 
-#
+#MSG_STEEL_SHEET c=18
 "Steel sheets"
 "Lamina de acero"
 
-#
+#MSG_Z_CORRECTION c=13
 "Z-correct:"
 "Corregir-Z:"
 
 #MSG_Z_PROBE_NR
 "Z-probe nr."
 "Z-sensor nr."
+

+ 209 - 85
lang/lang_en_fr.txt

@@ -2,6 +2,26 @@
 "[%.7s]Live adj. Z\x0avalue set, continue\x0aor start from zero?\x0a%cContinue%cReset"
 "[%.7s]Ajust. du Z\x0aValeur enreg, contin\x0aou depart a zero?\x0a%cContinuer%cReset"
 
+#MSG_IR_03_OR_OLDER c=18
+" 0.3 or older"
+" 0.3 ou +ancien"
+
+# c=18
+"FS v0.3 or older"
+"FS v0.3 ou +ancien"
+
+#MSG_IR_04_OR_NEWER c=18
+" 0.4 or newer"
+" 0.4 ou +recent"
+
+# c=18
+"FS v0.4 or newer"
+"FS v0.4 ou +recent"
+
+#MSG_IR_UNKNOWN c=18
+"unknown state"
+"Etat inconnu"
+
 #MSG_IMPROVE_BED_OFFSET_AND_SKEW_LINE2 c=14
 " of 4"
 " de 4"
@@ -42,9 +62,13 @@
 "Ambient"
 "Ambiant"
 
-#MSG_PRESS c=20
+#MSG_AUTO c=6
+"Auto"
+"\x00"
+
+#MSG_PRESS c=20 r=2
 "and press the knob"
-"et pressez le bouton"
+"et appuyez sur le bouton"
 
 #MSG_CONFIRM_CARRIAGE_AT_THE_TOP c=20 r=2
 "Are left and right Z~carriages all up?"
@@ -58,7 +82,7 @@
 "Auto home"
 "Mise a 0 des axes"
 
-#MSG_AUTOLOAD_FILAMENT c=17
+#MSG_AUTOLOAD_FILAMENT c=18
 "AutoLoad filament"
 "Autocharge du fil."
 
@@ -94,15 +118,27 @@
 "Bed level correct"
 "Corr. niveau plateau"
 
-#MSG_BED_LEVELING_FAILED_POINT_LOW c=20 r=4
+#MSG_BELTTEST c=17
+"Belt test        "
+"Test de courroie "
+
+#MSG_BED_LEVELING_FAILED_POINT_LOW c=20 r=5
 "Bed leveling failed. Sensor didnt trigger. Debris on nozzle? Waiting for reset."
-"Echec bed leveling. Capt. non declenche. Debris sur buse? En attente d'un reset."
+"Capt. non declenche pendant que je nivele le plateau. Debris sur buse? En attente d'un reset."
+
+#MSG_BRIGHT c=6
+"Bright"
+"Brill."
+
+#MSG_BRIGHTNESS c=18
+"Brightness"
+"Luminosite"
 
 #MSG_BED
 "Bed"
 "Lit"
 
-#MSG_MENU_BELT_STATUS c=15 r=1
+#MSG_BELT_STATUS c=18
 "Belt status"
 "Statut courroie"
 
@@ -164,9 +200,9 @@
 
 #
 "Copy selected language?"
-"Copier la langue selectionne?"
+"Copier la langue choisie?"
 
-#MSG_CRASHDETECT
+#MSG_CRASHDETECT c=13
 "Crash det."
 "Detect.crash"
 
@@ -182,7 +218,7 @@
 "Crash detected. Resume print?"
 "Crash detecte. Poursuivre l'impression?"
 
-#
+#MSG_CRASH c=7
 "Crash"
 "\x00"
 
@@ -202,15 +238,19 @@
 "Distance between tip of the nozzle and the bed surface has not been set yet. Please follow the manual, chapter First steps, section First layer calibration."
 "La distance entre la pointe de la buse et la surface du plateau n'a pas encore ete reglee. Suivez le manuel, chapitre Premiers pas, section Calibration de la premiere couche."
 
+#MSG_FS_CONTINUE c=5
+"Cont."
+"\x00"
+
 #MSG_WIZARD_REPEAT_V2_CAL c=20 r=7
 "Do you want to repeat last step to readjust distance between nozzle and heatbed?"
-"Voulez-vous repeter la derniere etape pour reajuster la distance entre la buse et le plateau chauffant?"
+"Voulez-vous refaire l'etape pour reajuster la hauteur entre la buse et le plateau chauffant?"
 
-#MSG_EXTRUDER_CORRECTION c=10
+#MSG_EXTRUDER_CORRECTION c=13
 "E-correct:"
 "Correct-E:"
 
-#MSG_EJECT_FILAMENT c=17 r=1
+#MSG_EJECT_FILAMENT c=16
 "Eject filament"
 "Remonter le fil."
 
@@ -218,7 +258,7 @@
 "Ejecting filament"
 "Le fil. remonte"
 
-#MSG_SELFTEST_ENDSTOP_NOTHIT c=20 r=1
+#MSG_SELFTEST_ENDSTOP_NOTHIT c=20
 "Endstop not hit"
 "Butee non atteinte"
 
@@ -234,10 +274,26 @@
 "Error - static memory has been overwritten"
 "Erreur - la memoire statique a ete ecrasee"
 
+#MSG_CUT_FILAMENT c=16
+"Cut filament"
+"Coupe filament"
+
+#MSG_CUTTER c=9
+"Cutter"
+"Coupeur"
+
+# c=18
+"Cutting filament"
+"Je coupe filament"
+
 #MSG_FSENS_NOT_RESPONDING c=20 r=4
 "ERROR: Filament sensor is not responding, please check connection."
 "ERREUR: Le capteur de filament ne repond pas, verifiez le branchement."
 
+#MSG_DIM c=6
+"Dim"
+"\x00"
+
 #MSG_ERROR
 "ERROR:"
 "ERREUR:"
@@ -246,11 +302,11 @@
 "Extruder fan:"
 "Ventilo extrudeur:"
 
-#MSG_INFO_EXTRUDER c=15 r=1
+#MSG_INFO_EXTRUDER c=18
 "Extruder info"
 "Infos extrudeur"
 
-#MSG_MOVE_E
+#MSG_EXTRUDER c=17
 "Extruder"
 "Extrudeur"
 
@@ -258,9 +314,10 @@
 "Fail stats MMU"
 "Stat. d'echec MMU"
 
-#MSG_FSENSOR_AUTOLOAD
+#MSG_FSENSOR_AUTOLOAD c=13
 "F. autoload"
-"Autochargeur"
+"F. autocharg."
+
 #
 "Fail stats"
 "Stat. d'echec"
@@ -273,16 +330,17 @@
 "Fan test"
 "Test du ventilateur"
 
-#MSG_FANS_CHECK
+#MSG_FANS_CHECK c=13
 "Fans check"
 "Verif vent."
 
 #MSG_FSENSOR
 "Fil. sensor"
 "Capteur Fil."
-#
-"Filam. runouts"
-"Fins de filament"
+
+#MSG_FIL_RUNOUTS c=14
+"Fil. runouts  "
+"Fins filament "
 
 #MSG_FILAMENT_CLEAN c=20 r=2
 "Filament extruding & with correct color?"
@@ -296,7 +354,7 @@
 "Filament sensor"
 "Capteur de filament"
 
-#MSG_FILAMENT_USED c=19 r=1
+#MSG_FILAMENT_USED c=19
 "Filament used"
 "Filament utilise"
 
@@ -304,15 +362,19 @@
 "Print time"
 "Temps d'impression"
 
-#MSG_FILE_INCOMPLETE c=20 r=2
+#MSG_FS_ACTION c=10
+"FS Action"
+"\x00"
+
+#MSG_FILE_INCOMPLETE c=20 r=3
 "File incomplete. Continue anyway?"
 "Fichier incomplet. Continuer qd meme?"
 
-#MSG_FINISHING_MOVEMENTS c=20 r=1
+#MSG_FINISHING_MOVEMENTS c=20
 "Finishing movements"
 "Mouvement final"
 
-#MSG_V2_CALIBRATION c=17 r=1
+#MSG_V2_CALIBRATION c=18
 "First layer cal."
 "Cal. 1ere couche"
 
@@ -382,7 +444,7 @@
 
 #MSG_SELFTEST_CHECK_BED c=20
 "Checking bed     "
-"Verification du lit"
+"Verif. plateau chauf"
 
 #MSG_SELFTEST_CHECK_ENDSTOPS c=20
 "Checking endstops"
@@ -396,16 +458,16 @@
 "Checking sensors "
 "Verif. des capteurs"
 
-#MSG_SELFTEST_CHECK_X c=20
-"Checking X axis  "
+#MSG_CHECKING_X c=20
+"Checking X axis"
 "Verification axe X"
 
-#MSG_SELFTEST_CHECK_Y c=20
-"Checking Y axis  "
+#MSG_CHECKING_Y c=20
+"Checking Y axis"
 "Verification axe Y"
 
 #MSG_SELFTEST_CHECK_Z c=20
-"Checking Z axis  "
+"Checking Z axis"
 "Verification axe Z"
 
 #MSG_CHOOSE_EXTRUDER c=20 r=1
@@ -436,29 +498,29 @@
 "Insert filament"
 "Inserez le filament"
 
-#MSG_WIZARD_FILAMENT_LOADED c=20 r=2
+#MSG_FILAMENT_LOADED c=20 r=2
 "Is filament loaded?"
 "Fil. est-il charge?"
 
 #MSG_STEEL_SHEET_CHECK c=20 r=2
 "Is steel sheet on heatbed?"
-"Plaque d'impression sur le lit chauffant?"
+"Est la plaque sur le plat. chauffant?"
 
-#
+#MSG_LAST_PRINT_FAILURES c=20
 "Last print failures"
 "Echecs derniere imp."
 
 #
 "If you have additional steel sheets, calibrate their presets in Settings - HW Setup - Steel sheets."
-"Si vous avez d'autres feuilles d'acier,  calibrez leurs pre-reglages dans Reglages - Config HW - Feuilles d'acier."
+"Si vous avez d'autres feuilles d'acier,  calibrez leurs pre-reglages dans Reglages - Config HW - Plaque en acier."
 
-#
+#MSG_LAST_PRINT c=18
 "Last print"
 "Derniere impres."
 
 #MSG_SELFTEST_EXTRUDER_FAN c=20
 "Left hotend fan?"
-"Ventilo tete gauche?"
+"Ventilo gauche?"
 
 #
 "Left"
@@ -476,6 +538,10 @@
 "Live adjust Z"
 "Ajuster Z en dir."
 
+# c=20 r=6
+"Insert the filament (do not load it) into the extruder and then press the knob."
+"Veuillez inserer le filament ( ne le chargez pas) dans l'extrudeur, puis appuyez sur le bouton."
+
 #MSG_LOAD_FILAMENT c=17
 "Load filament"
 "Charger filament"
@@ -496,7 +562,7 @@
 "Load to nozzle"
 "Charger la buse"
 
-#MSG_M117_V2_CALIBRATION c=25 r=1
+#MSG_M117_V2_CALIBRATION c=25
 "M117 First layer cal."
 "M117 Cal. 1ere couche"
 
@@ -504,11 +570,19 @@
 "Main"
 "Menu principal"
 
+#MSG_BL_HIGH c=12
+"Level Bright"
+"Niveau brill"
+
+#MSG_BL_LOW c=12
+"Level Dimmed"
+"\x00"
+
 #MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE1 c=60
 "Measuring reference height of calibration point"
-"Mesure de la hauteur de reference du point de calibration"
+"Je mesure la hauteur de reference du point de calibrage"
 
-#MSG_MESH_BED_LEVELING
+#MSG_MESH_BED_LEVELING c=18
 "Mesh Bed Leveling"
 "\x00"
 
@@ -524,7 +598,7 @@
 "Measured skew"
 "Deviat.mesuree"
 
-#
+#MSG_MMU_FAILS c=14
 "MMU fails"
 "Echecs MMU"
 
@@ -532,7 +606,7 @@
 "MMU load failed     "
 "Echec chargement MMU"
 
-#
+#MSG_MMU_LOAD_FAILS c=14
 "MMU load fails"
 "Echecs charg. MMU"
 
@@ -544,6 +618,10 @@
 "Mode"
 "\x00"
 
+# c=20 r=3
+"MK3 firmware detected on MK3S printer"
+"Firmware MK3 detecte sur imprimante MK3S"
+
 #MSG_NORMAL
 "Normal"
 "\x00"
@@ -636,7 +714,7 @@
 "Nozzle"
 "Buse"
 
-#MSG_DEFAULT_SETTINGS_LOADED c=20 r=4
+#MSG_DEFAULT_SETTINGS_LOADED c=20 r=5
 "Old settings found. Default PID, Esteps etc. will be set."
 "Anciens reglages trouves. Le PID, les Esteps etc. par defaut seront regles"
 
@@ -668,13 +746,13 @@
 "PINDA Heating"
 "Chauffe de la PINDA"
 
-#MSG_PAPER c=20 r=8
+#MSG_PAPER c=20 r=10
 "Place a sheet of paper under the nozzle during the calibration of first 4 points. If the nozzle catches the paper, power off the printer immediately."
 "Placez une feuille de papier sous la buse pendant la calibration des 4 premiers points. Si la buse accroche le papier, eteignez vite l'imprimante."
 
 #MSG_WIZARD_CLEAN_HEATBED c=20 r=8
 "Please clean heatbed and then press the knob."
-"Nettoyez la plaque en acier et appuyez sur le bouton."
+"Nettoyez plateau chauffant en acier et appuyez sur le bouton."
 
 #MSG_CONFIRM_NOZZLE_CLEAN c=20 r=8
 "Please clean the nozzle for calibration. Click when done."
@@ -740,15 +818,23 @@
 "Preheating nozzle. Please wait."
 "Prechauffage de la buse. Merci de patienter."
 
+# c=14
+"PINDA"
+"\x00"
+
 #
 "Please upgrade."
 "Mettez a jour le FW."
 
 #MSG_PRESS_TO_PREHEAT c=20 r=4
-"Press knob to preheat nozzle and continue."
+"Press the knob to preheat nozzle and continue."
 "Appuyez sur le bouton pour prechauffer la buse et continuer."
 
-#
+#MSG_FS_PAUSE c=5
+"Pause"
+"\x00"
+
+#MSG_POWER_FAILURES c=14
 "Power failures"
 "Coup.de courant"
 
@@ -756,11 +842,11 @@
 "Print aborted"
 "Impression annulee"
 
-# c=20 r=1
+# c=20
 "Preheating to load"
 "Chauffe pour charger"
 
-# c=20 r=1
+# c=20
 "Preheating to unload"
 "Chauf.pour decharger"
 
@@ -772,7 +858,7 @@
 "Print from SD"
 "Impr. depuis la SD"
 
-#
+# c=20
 "Press the knob"
 "App. sur sur bouton"
 
@@ -812,15 +898,23 @@
 "Rear side [um]"
 "Arriere [um]"
 
-#MSG_RECOVERING_PRINT c=20 r=1
+# c=20 r=4
+"Please unload the filament first, then repeat this action."
+"SVP, dechargez le filament et reessayez."
+
+# c=20 r=4
+"Please check the IR sensor connection, unload filament if present."
+"SVP, verifiez la connexion du capteur IR et decharge le filament."
+
+#MSG_RECOVERING_PRINT c=20
 "Recovering print    "
-"Recup. impression"
+"Recup. impression   "
 
-#MSG_REMOVE_OLD_FILAMENT c=20 r=4
+#MSG_REMOVE_OLD_FILAMENT c=20 r=5
 "Remove old filament and press the knob to start loading new filament."
 "Retirez l'ancien filament puis appuyez sur le bouton pour charger le nouveau."
 
-#
+# c=20
 "Prusa i3 MK3S OK."
 "\x00"
 
@@ -828,15 +922,15 @@
 "Reset XYZ calibr."
 "Reinit. calib. XYZ"
 
-#MSG_BED_CORRECTION_RESET
+#MSG_RESET c=14
 "Reset"
 "Reinitialiser"
 
-#MSG_RESUME_PRINT
+#MSG_RESUME_PRINT c=18
 "Resume print"
 "Reprendre impression"
 
-#MSG_RESUMING_PRINT c=20 r=1
+#MSG_RESUMING_PRINT c=20
 "Resuming print"
 "Reprise de l'impr."
 
@@ -866,7 +960,7 @@
 
 #MSG_FIND_BED_OFFSET_AND_SKEW_LINE1 c=60
 "Searching bed calibration point"
-"Recherche du point de calibration du lit"
+"Recherche du point de calibration du plateau chauffant"
 
 #MSG_LANGUAGE_SELECT
 "Select language"
@@ -904,11 +998,23 @@
 "Set temperature:"
 "Regler temp.:"
 
+# c=20
+"Prusa i3 MK2.5 OK."
+"\x00"
+
+# c=20
+"Prusa i3 MK2.5S OK."
+"\x00"
+
+# c=20
+"Prusa i3 MK3 OK."
+"\x00"
+
 #MSG_SETTINGS
 "Settings"
 "Reglages"
 
-#MSG_SHOW_END_STOPS c=17 r=1
+#MSG_SHOW_END_STOPS c=18
 "Show end stops"
 "Afficher butees"
 
@@ -916,7 +1022,7 @@
 "Sensor state"
 "Etat capteur"
 
-#MSG_FILE_CNT c=20 r=4
+#MSG_FILE_CNT c=20 r=6
 "Some files will not be sorted. Max. No. of files in 1 folder for sorting is 100."
 "Certains fichiers ne seront pas tries. Max 100 fichiers tries par dossier."
 
@@ -956,6 +1062,10 @@
 "Sound"
 "Son"
 
+# c=7
+"Runouts"
+"\x00"
+
 #
 "Some problem encountered, Z-leveling enforced ..."
 "Probleme rencontre, cliquez sur le bouton pour niveller l'axe Z..."
@@ -963,6 +1073,7 @@
 #MSG_SOUND_ONCE
 "Once"
 "Une fois"
+
 #MSG_SPEED
 "Speed"
 "Vitesse"
@@ -999,7 +1110,7 @@
 "Select filament:"
 "Selectionnez le filament:"
 
-#MSG_TEMP_CALIBRATION c=12 r=1
+#MSG_TEMP_CALIBRATION c=14
 "Temp. cal."
 "Calib. Temp."
 
@@ -1019,6 +1130,10 @@
 "Temperature calibration is finished and active. Temp. calibration can be disabled in menu Settings->Temp. cal."
 "La calibration en temperature est terminee et activee. La calibration en temperature peut etre desactivee dans le menu Reglages-> Cal. Temp."
 
+# c=20 r=3
+"Sensor verified, remove the filament now."
+"Capteur verifie, retirez le filament maintenant."
+
 #MSG_TEMPERATURE
 "Temperature"
 "\x00"
@@ -1027,7 +1142,7 @@
 "Temperatures"
 "\x00"
 
-#MSG_FOLLOW_Z_CALIBRATION_FLOW c=20 r=4
+#MSG_FOLLOW_Z_CALIBRATION_FLOW c=20 r=9
 "There is still a need to make Z calibration. Please follow the manual, chapter First steps, section Calibration flow."
 "Il faut toujours effectuer la Calibration Z. Veuillez suivre le manuel, chapitre Premiers pas, section Processus de calibration."
 
@@ -1047,15 +1162,15 @@
 "Unload"
 "Decharger"
 
-#
+#MSG_TOTAL_FAILURES c=20
 "Total failures"
 "Total des echecs"
 
-#
+# c=20
 "to load filament"
 "pour charger le fil."
 
-#
+# c=20
 "to unload filament"
 "pour decharger fil."
 
@@ -1067,9 +1182,9 @@
 "Unloading filament"
 "Dechargement fil."
 
-#
+#MSG_TOTAL c=6
 "Total"
-"\x00"
+"Totale"
 
 #MSG_USED c=19 r=1
 "Used during print"
@@ -1089,7 +1204,7 @@
 
 #MSG_WAITING_TEMP c=20 r=3
 "Waiting for nozzle and bed cooling"
-"Attente du refroidissement des buse et plateau"
+"Attente du refroidissement des buse et plateau chauffant"
 
 #MSG_WAITING_TEMP_PINDA c=20 r=3
 "Waiting for PINDA probe cooling"
@@ -1123,7 +1238,7 @@
 "Wizard"
 "Assistant"
 
-#MSG_XYZ_DETAILS c=19 r=1
+#MSG_XYZ_DETAILS c=18
 "XYZ cal. details"
 "Details calib. XYZ"
 
@@ -1147,7 +1262,11 @@
 "XYZ calibration all right. X/Y axes are slightly skewed. Good job!"
 "Calibration XYZ OK. Les axes X/Y sont legerement non perpendiculaires. Bon boulot!"
 
-#
+#MSG_TIMEOUT c=12
+"Timeout"
+"\x00"
+
+#MSG_X_CORRECTION c=13
 "X-correct:"
 "Correct-X:"
 
@@ -1187,7 +1306,11 @@
 "The printer will start printing a zig-zag line. Rotate the knob until you reach the optimal height. Check the pictures in the handbook (Calibration chapter)."
 "L'imprimante commencera a  imprimer une ligne en zig-zag. Tournez le bouton jusqu'a atteindre la hauteur optimale. Consultez les photos dans le manuel (chapitre Calibration)."
 
-#
+# c=20 r=5
+"Verification failed, remove the filament and try again."
+"Verification en echec, retirez le filament et reessayez."
+
+#MSG_Y_CORRECTION c=13
 "Y-correct:"
 "Correct-Y:"
 
@@ -1227,7 +1350,7 @@
 "Warn"
 "Avert"
 
-#
+#MSG_HW_SETUP c=18
 "HW Setup"
 "Config HW"
 
@@ -1243,10 +1366,6 @@
 "Mesh"
 "\x00"
 
-#
-"Mesh bed leveling"
-"\x00"
-
 #
 "MK3S firmware detected on MK3 printer"
 "Firmware MK3S detecte sur imprimante MK3"
@@ -1269,17 +1388,17 @@
 
 #
 "G-code sliced for a different level. Continue?"
-"\x00"
+"Le G-code a ete prepare pour un niveau different. Continuer?"
 
 #
 "G-code sliced for a different level. Please re-slice the model again. Print cancelled."
-"\x00"
+"Le G-code a ete prepare pour un niveau different. Veuillez decouper le modele a nouveau. L'impression a ete annulee."
 
-#
+#MSG_GCODE_DIFF_PRINTER_CONTINUE c=20 r=5
 "G-code sliced for a different printer type. Continue?"
 "Le G-code a ete prepare pour une autre version de l'imprimante. Continuer?"
 
-#
+#MSG_GCODE_DIFF_PRINTER_CANCELLED c=20 r=6
 "G-code sliced for a different printer type. Please re-slice the model again. Print cancelled."
 "Le G-code a ete prepare pour une autre version de l'imprimante. Veuillez decouper le modele a nouveau. L'impression a ete annulee."
 
@@ -1295,11 +1414,11 @@
 "PINDA:"
 "PINDA:"
 
-# c=20 r=1
+# c=20
 "Preheating to cut"
 "Chauffe pour couper"
 
-# c=20 r=1
+# c=20
 "Preheating to eject"
 "Chauf. pour remonter"
 
@@ -1311,6 +1430,10 @@
 "Printer nozzle diameter differs from the G-code. Please check the value in settings. Print cancelled."
 "Diametre de la buse dans les reglages ne correspond pas a celui dans le G-Code. Merci de verifier le parametre dans les reglages. Impression annulee."
 
+# c=20
+"%s level expected"
+"\x00"
+
 #
 "Rename"
 "Renommer"
@@ -1323,7 +1446,7 @@
 "Sensor info"
 "Info capteur"
 
-#
+#MSG_SHEET c=10
 "Sheet"
 "Plaque"
 
@@ -1331,14 +1454,15 @@
 "Assist"
 "\x00"
 
-#
+#MSG_STEEL_SHEET c=18
 "Steel sheets"
 "Plaques en acier"
 
-#
+#MSG_Z_CORRECTION c=13
 "Z-correct:"
 "Correct-Z:"
 
 #MSG_Z_PROBE_NR
 "Z-probe nr."
 "Mesurer x-fois"
+

+ 226 - 104
lang/lang_en_it.txt

@@ -2,6 +2,26 @@
 "[%.7s]Live adj. Z\x0avalue set, continue\x0aor start from zero?\x0a%cContinue%cReset"
 "[%.7s]Set valori\x0aComp. Z, continuare\x0ao iniziare da zero?\x0a%cContinua%cReset"
 
+#MSG_03_OR_OLDER c=18
+" 0.3 or older"
+" 0.3 o inferiore"
+
+# c=18
+"FS v0.3 or older"
+"FS 0.3 o inferiore"
+
+#MSG_IR_04_OR_NEWER c=18
+" 0.4 or newer"
+" 0.4 o superiore"
+
+# c=18
+"FS v0.4 or newer"
+"FS 0.4 o superiore"
+
+#MSG_IR_UNKNOWN c=18
+"unknown state"
+"stato sconosciuto"
+
 #MSG_IMPROVE_BED_OFFSET_AND_SKEW_LINE2 c=14
 " of 4"
 " su 4"
@@ -42,7 +62,11 @@
 "Ambient"
 "Ambiente"
 
-#MSG_PRESS c=20
+#MSG_AUTO c=6
+"Auto"
+"\x00"
+
+#MSG_PRESS c=20 r=2
 "and press the knob"
 "e cliccare manopola"
 
@@ -52,13 +76,13 @@
 
 #MSG_AUTO_DEPLETE c=17 r=1
 "SpoolJoin"
-"\x00"
+""
 
 #MSG_AUTO_HOME
 "Auto home"
 "Trova origine"
 
-#MSG_AUTOLOAD_FILAMENT c=17
+#MSG_AUTOLOAD_FILAMENT c=18
 "AutoLoad filament"
 "Autocaric. filam."
 
@@ -80,7 +104,7 @@
 
 #MSG_SELFTEST_BEDHEATER
 "Bed / Heater"
-"Letto/Riscald."
+"Piano/Riscald."
 
 #MSG_BED_DONE
 "Bed done"
@@ -88,27 +112,39 @@
 
 #MSG_BED_HEATING
 "Bed Heating"
-"Riscald. letto"
+"Riscald. piano"
 
 #MSG_BED_CORRECTION_MENU
 "Bed level correct"
-"Correz. liv.letto"
+"Correz. liv.piano"
 
-#MSG_BED_LEVELING_FAILED_POINT_LOW c=20 r=4
+#MSG_BELTTEST c=17
+"Belt test        "
+"Test cinghie     "
+
+#MSG_BED_LEVELING_FAILED_POINT_LOW c=20 r=5
 "Bed leveling failed. Sensor didnt trigger. Debris on nozzle? Waiting for reset."
-"Livellamento letto fallito.NoRispSensore.Residui su ugello? In attesa di reset."
+"Livellamento piano fallito. Sensore KO? Residui su ugello? In attesa di reset."
+
+#MSG_BRIGHT c=6
+"Bright"
+"Chiaro"
+
+#MSG_BRIGHTNESS c=18
+"Brightness"
+"Luminosita'"
 
 #MSG_BED
 "Bed"
-"Letto"
+"Piano"
 
-#MSG_MENU_BELT_STATUS c=15 r=1
+#MSG_BELT_STATUS c=18
 "Belt status"
 "Stato cinghie"
 
 #MSG_RECOVER_PRINT c=20 r=2
 "Blackout occurred. Recover print?"
-"C'e stato un Blackout. Recuperare la stampa?"
+"Blackout rilevato. Recuperare la stampa?"
 
 #
 "Calibrating home"
@@ -166,7 +202,7 @@
 "Copy selected language?"
 "Copiare la lingua selezionata?"
 
-#MSG_CRASHDETECT
+#MSG_CRASHDETECT c=13
 "Crash det."
 "Rileva.crash"
 
@@ -182,7 +218,7 @@
 "Crash detected. Resume print?"
 "Scontro rilevato. Riprendere la stampa?"
 
-#
+#MSG_CRASH c=7
 "Crash"
 "Impatto"
 
@@ -200,27 +236,31 @@
 
 #MSG_BABYSTEP_Z_NOT_SET c=20 r=12
 "Distance between tip of the nozzle and the bed surface has not been set yet. Please follow the manual, chapter First steps, section First layer calibration."
-"Distanza tra la punta dell'ugello e la superficie del letto non ancora imposta. Si prega di seguire il manuale, capitolo Primi Passi, sezione Calibrazione primo layer."
+"Distanza tra la punta dell'ugello e la superficie del piano non ancora impostata. Si prega di seguire il manuale, capitolo Primi Passi, sezione Calibrazione primo strato."
+
+#MSG_FS_CONTINUE c=5
+"Cont."
+"\x00"
 
 #MSG_WIZARD_REPEAT_V2_CAL c=20 r=7
 "Do you want to repeat last step to readjust distance between nozzle and heatbed?"
 "Desideri ripetere l'ultimo passaggio per migliorare la distanza fra ugello e piatto?"
 
-#MSG_EXTRUDER_CORRECTION c=10
+#MSG_EXTRUDER_CORRECTION c=13
 "E-correct:"
 "Correzione-E:"
 
-#MSG_EJECT_FILAMENT c=17 r=1
+#MSG_EJECT_FILAMENT c=16
 "Eject filament"
-"Espelli filamento "
+"Espelli fil."
 
 #MSG_EJECTING_FILAMENT c=20 r=1
 "Ejecting filament"
-"Espellendo filamento "
+"Espellendo filamento"
 
-#MSG_SELFTEST_ENDSTOP_NOTHIT c=20 r=1
+#MSG_SELFTEST_ENDSTOP_NOTHIT c=20
 "Endstop not hit"
-"Finecorsa fuori portata"
+"Finec. fuori portata"
 
 #MSG_SELFTEST_ENDSTOP
 "Endstop"
@@ -232,12 +272,28 @@
 
 #MSG_STACK_ERROR c=20 r=4
 "Error - static memory has been overwritten"
-"Errore - la memoria statica e stata sovrascritta"
+"Errore - la memoria statica e' stata sovrascritta"
+
+#MSG_CUT_FILAMENT c=16
+"Cut filament"
+"Taglia filamento"
+
+#MSG_CUTTER c=9
+"Cutter"
+"Tagliatr."
+
+# c=18
+"Cutting filament"
+"Tagliando filam."
 
 #MSG_FSENS_NOT_RESPONDING c=20 r=4
 "ERROR: Filament sensor is not responding, please check connection."
 "ERRORE: il sensore filam. non risponde,Controllare conness."
 
+#MSG_DIM c=6
+"Dim"
+"Scuro"
+
 #MSG_ERROR
 "ERROR:"
 "ERRORE:"
@@ -246,11 +302,11 @@
 "Extruder fan:"
 "Ventola estr:"
 
-#MSG_INFO_EXTRUDER c=15 r=1
+#MSG_INFO_EXTRUDER c=18
 "Extruder info"
 "Info estrusore"
 
-#MSG_MOVE_E
+#MSG_EXTRUDER c=17
 "Extruder"
 "Estrusore"
 
@@ -258,7 +314,7 @@
 "Fail stats MMU"
 "Stat.fall. MMU"
 
-#MSG_FSENSOR_AUTOLOAD
+#MSG_FSENSOR_AUTOLOAD c=13
 "F. autoload"
 "Autocar.fil."
 
@@ -274,20 +330,21 @@
 "Fan test"
 "Test ventola"
 
-#MSG_FANS_CHECK
+#MSG_FANS_CHECK c=13
 "Fans check"
 "Control.vent"
 
 #MSG_FSENSOR
 "Fil. sensor"
 "Sensore fil."
-#
-"Filam. runouts"
-"Filam. esauriti"
+
+#MSG_FIL_RUNOUTS c=14
+"Fil. runouts  "
+"Fil. esauriti "
 
 #MSG_FILAMENT_CLEAN c=20 r=2
 "Filament extruding & with correct color?"
-"Filamento estruso & con il giusto colore?"
+"Filamento estruso e con colore corretto?"
 
 #MSG_NOT_LOADED c=19
 "Filament not loaded"
@@ -297,23 +354,27 @@
 "Filament sensor"
 "Sensore filam."
 
-#MSG_FILAMENT_USED c=19 r=1
+#MSG_FILAMENT_USED c=19
 "Filament used"
-"Filamento utilizzato"
+"Fil. utilizzato"
 
 #MSG_PRINT_TIME c=19 r=1
 "Print time"
 "Tempo di stampa"
 
-#MSG_FILE_INCOMPLETE c=20 r=2
+#MSG_FS_ACTION c=10
+"FS Action"
+"Azione FS"
+
+#MSG_FILE_INCOMPLETE c=20 r=3
 "File incomplete. Continue anyway?"
 "File incompleto. Continuare comunque?"
 
-#MSG_FINISHING_MOVEMENTS c=20 r=1
+#MSG_FINISHING_MOVEMENTS c=20
 "Finishing movements"
-"Finalizzando gli spostamenti"
+"Finaliz. spostamenti"
 
-#MSG_V2_CALIBRATION c=17 r=1
+#MSG_V2_CALIBRATION c=18
 "First layer cal."
 "Cal. primo strato"
 
@@ -323,7 +384,7 @@
 
 #
 "Fix the issue and then press button on MMU unit."
-"Risolvi il problema e quindi premi il bottone sull'unita MMU. "
+"Risolvere il problema e premere il bottone sull'unita MMU. "
 
 #MSG_FLOW
 "Flow"
@@ -379,7 +440,7 @@
 
 #MSG_CORRECTLY c=20
 "Changed correctly?"
-"Cambiato correttamente?"
+"Cambio corretto?"
 
 #MSG_SELFTEST_CHECK_BED c=20
 "Checking bed     "
@@ -397,16 +458,16 @@
 "Checking sensors "
 "Controllo sensori"
 
-#MSG_SELFTEST_CHECK_X c=20
-"Checking X axis  "
+#MSG_CHECKING_X c=20
+"Checking X axis"
 "Verifica asse X"
 
-#MSG_SELFTEST_CHECK_Y c=20
-"Checking Y axis  "
+#MSG_CHECKING_Y c=20
+"Checking Y axis"
 "Verifica asse Y"
 
 #MSG_SELFTEST_CHECK_Z c=20
-"Checking Z axis  "
+"Checking Z axis"
 "Verifica asse Z"
 
 #MSG_CHOOSE_EXTRUDER c=20 r=1
@@ -437,23 +498,23 @@
 "Insert filament"
 "Inserire filamento"
 
-#MSG_WIZARD_FILAMENT_LOADED c=20 r=2
+#MSG_FILAMENT_LOADED c=20 r=2
 "Is filament loaded?"
-"Il filamento e stato caricato?"
+"Il filamento e' stato caricato?"
 
 #MSG_STEEL_SHEET_CHECK c=20 r=2
 "Is steel sheet on heatbed?"
-"La piastra d'acciaio e sul piano riscaldato?"
+"Piastra d'acciaio su piano riscaldato?"
 
-#
+#MSG_LAST_PRINT_FAILURES c=20
 "Last print failures"
-"Fallimenti ultima stampa"
+"Errori ultima stampa"
 
 #
 "If you have additional steel sheets, calibrate their presets in Settings - HW Setup - Steel sheets."
 "Se hai piastre d'acciaio aggiuntive, calibra i preset in Impostazioni - Setup HW - Piastre in Acciaio."
 
-#
+#MSG_LAST_PRINT c=18
 "Last print"
 "Ultima stampa"
 
@@ -477,6 +538,10 @@
 "Live adjust Z"
 "Compensazione Z"
 
+# c=20 r=6
+"Insert the filament (do not load it) into the extruder and then press the knob."
+"Inserire filamento (senza caricarlo) nell'estrusore e premere la manopola."
+
 #MSG_LOAD_FILAMENT c=17
 "Load filament"
 "Carica filamento"
@@ -497,21 +562,29 @@
 "Load to nozzle"
 "Carica ugello"
 
-#MSG_M117_V2_CALIBRATION c=25 r=1
+#MSG_M117_V2_CALIBRATION c=25
 "M117 First layer cal."
-"M117 Calibrazione primo layer."
+"M117 Calibr. primo strato"
 
 #MSG_MAIN
 "Main"
 "Menu principale"
 
+#MSG_BL_HIGH c=12
+"Level Bright"
+"Liv. Chiaro"
+
+#MSG_BL_LOW c=12
+"Level Dimmed"
+"Liv. Scuro"
+
 #MSG_MEASURE_BED_REFERENCE_HEIGHT_LINE1 c=60
 "Measuring reference height of calibration point"
 "Misura altezza di rif. del punto di calib."
 
-#MSG_MESH_BED_LEVELING
+#MSG_MESH_BED_LEVELING c=18
 "Mesh Bed Leveling"
-"Livel. piatto"
+"Liv. grilia piano"
 
 #MSG_MMU_OK_RESUMING_POSITION c=20 r=4
 "MMU OK. Resuming position..."
@@ -525,7 +598,7 @@
 "Measured skew"
 "Deviazione mis"
 
-#
+#MSG_MMU_FAILS c=14
 "MMU fails"
 "Fallimenti MMU"
 
@@ -533,7 +606,7 @@
 "MMU load failed     "
 "Caricamento MMU fallito"
 
-#
+#MSG_MMU_LOAD_FAILS c=14
 "MMU load fails"
 "Caricamenti MMU falliti"
 
@@ -545,6 +618,10 @@
 "Mode"
 "Mod."
 
+# c=20 r=3
+"MK3 firmware detected on MK3S printer"
+"Firmware MK3 rilevato su stampante MK3S"
+
 #MSG_NORMAL
 "Normal"
 "Normale"
@@ -607,7 +684,7 @@
 
 #MSG_NA
 "N/A"
-"\x00"
+"N/D"
 
 #MSG_NO
 "No"
@@ -637,7 +714,7 @@
 "Nozzle"
 "Ugello"
 
-#MSG_DEFAULT_SETTINGS_LOADED c=20 r=4
+#MSG_DEFAULT_SETTINGS_LOADED c=20 r=5
 "Old settings found. Default PID, Esteps etc. will be set."
 "Sono state trovate impostazioni vecchie. Verranno impostati i valori predefiniti di PID, Esteps etc."
 
@@ -669,7 +746,7 @@
 "PINDA Heating"
 "Riscaldamento PINDA"
 
-#MSG_PAPER c=20 r=8
+#MSG_PAPER c=20 r=10
 "Place a sheet of paper under the nozzle during the calibration of first 4 points. If the nozzle catches the paper, power off the printer immediately."
 "Posizionare un foglio sotto l'ugello durante la calibrazione dei primi 4 punti. In caso l'ugello muova il foglio spegnere subito la stampante."
 
@@ -741,15 +818,23 @@
 "Preheating nozzle. Please wait."
 "Preriscaldando l'ugello. Attendere prego."
 
+# c=14
+"PINDA"
+"\x00"
+
 #
 "Please upgrade."
 "Prego aggiornare."
 
 #MSG_PRESS_TO_PREHEAT c=20 r=4
-"Press knob to preheat nozzle and continue."
+"Press the knob to preheat nozzle and continue."
 "Premete la manopola per preriscaldare l'ugello e continuare."
 
-#
+#MSG_FS_PAUSE c=5
+"Pause"
+"Pausa"
+
+#MSG_POWER_FAILURES c=14
 "Power failures"
 "Mancanza corrente"
 
@@ -757,13 +842,13 @@
 "Print aborted"
 "Stampa interrotta"
 
-#
+# c=20
 "Preheating to load"
-"Preriscaldamento per caricare"
+"Preriscald. carico"
 
-#
+# c=20
 "Preheating to unload"
-"Preriscaldamento per scaricare"
+"Preriscald. scarico"
 
 #MSG_SELFTEST_PRINT_FAN_SPEED c=18
 "Print fan:"
@@ -773,7 +858,7 @@
 "Print from SD"
 "Stampa da SD"
 
-#
+# c=20
 "Press the knob"
 "Premere la manopola"
 
@@ -813,15 +898,23 @@
 "Rear side [um]"
 "Retro [um]"
 
-#MSG_RECOVERING_PRINT c=20 r=1
+# c=20 r=4
+"Please unload the filament first, then repeat this action."
+"Scaricare prima il filamento, poi ripetere l'operazione."
+
+# c=20 r=4
+"Please check the IR sensor connection, unload filament if present."
+"Controllare il collegamento al sensore e rimuovere il filamento."
+
+#MSG_RECOVERING_PRINT c=20
 "Recovering print    "
-"Recupero stampa"
+"Recupero stampa     "
 
-#MSG_REMOVE_OLD_FILAMENT c=20 r=4
+#MSG_REMOVE_OLD_FILAMENT c=20 r=5
 "Remove old filament and press the knob to start loading new filament."
-"Rimuovi il filamento precedente e premi la manopola per caricare il nuovo filamento. "
+"Rimuovi il filamento precedente e premi la manopola per caricare il nuovo filamento."
 
-#
+# c=20
 "Prusa i3 MK3S OK."
 "\x00"
 
@@ -829,15 +922,15 @@
 "Reset XYZ calibr."
 "Reset calibrazione XYZ."
 
-#MSG_BED_CORRECTION_RESET
+#MSG_RESET c=14
 "Reset"
 "\x00"
 
-#MSG_RESUME_PRINT
+#MSG_RESUME_PRINT c=18
 "Resume print"
 "Riprendi stampa"
 
-#MSG_RESUMING_PRINT c=20 r=1
+#MSG_RESUMING_PRINT c=20
 "Resuming print"
 "Riprendi stampa"
 
@@ -883,7 +976,7 @@
 
 #MSG_SELFTEST
 "Selftest         "
-"Autotest"
+"Autotest         "
 
 #MSG_SELFTEST_ERROR
 "Selftest error !"
@@ -903,13 +996,25 @@
 
 #MSG_SET_TEMPERATURE c=19 r=1
 "Set temperature:"
-"Imposta temperatura:"
+"Imposta temperatura"
+
+# c=20
+"Prusa i3 MK2.5 OK."
+"\x00"
+
+# c=20
+"Prusa i3 MK2.5S OK."
+"\x00"
+
+# c=20
+"Prusa i3 MK3 OK."
+"\x00"
 
 #MSG_SETTINGS
 "Settings"
 "Impostazioni"
 
-#MSG_SHOW_END_STOPS c=17 r=1
+#MSG_SHOW_END_STOPS c=18
 "Show end stops"
 "Stato finecorsa"
 
@@ -917,7 +1022,7 @@
 "Sensor state"
 "Stato sensore"
 
-#MSG_FILE_CNT c=20 r=4
+#MSG_FILE_CNT c=20 r=6
 "Some files will not be sorted. Max. No. of files in 1 folder for sorting is 100."
 "Alcuni file non saranno ordinati. Il numero massimo di file in una cartella e 100 perche siano ordinati."
 
@@ -957,6 +1062,10 @@
 "Sound"
 "Suono"
 
+# c=7
+"Runouts"
+"Esaurim"
+
 #
 "Some problem encountered, Z-leveling enforced ..."
 "Sono stati rilevati problemi, avviato livellamento Z ..."
@@ -1001,7 +1110,7 @@
 "Select filament:"
 "Seleziona il filamento:"
 
-#MSG_TEMP_CALIBRATION c=12 r=1
+#MSG_TEMP_CALIBRATION c=14
 "Temp. cal."
 "Calib. temp."
 
@@ -1021,6 +1130,10 @@
 "Temperature calibration is finished and active. Temp. calibration can be disabled in menu Settings->Temp. cal."
 "Calibrazione temperatura completata e attiva. Puo essere disattivata dal menu Impostazioni ->Cal. Temp."
 
+# c=20 r=3
+"Sensor verified, remove the filament now."
+"Sensore verificato, rimuovere il filamento."
+
 #MSG_TEMPERATURE
 "Temperature"
 "\x00"
@@ -1029,7 +1142,7 @@
 "Temperatures"
 "Temperature"
 
-#MSG_FOLLOW_Z_CALIBRATION_FLOW c=20 r=4
+#MSG_FOLLOW_Z_CALIBRATION_FLOW c=20 r=9
 "There is still a need to make Z calibration. Please follow the manual, chapter First steps, section Calibration flow."
 "E ancora necessario effettuare la calibrazione Z. Segui il manuale, capitolo Primi Passi, sezione Sequenza di Calibrazione. "
 
@@ -1049,17 +1162,17 @@
 "Unload"
 "Scarica"
 
-#
+#MSG_TOTAL_FAILURES c=20
 "Total failures"
 "Totale fallimenti"
 
-#
+# c=20
 "to load filament"
-"per caricare il filamento"
+"per caricare il fil."
 
-#
+# c=20
 "to unload filament"
-"per scaricare il filamento"
+"per scaricare fil."
 
 #MSG_UNLOAD_FILAMENT c=17
 "Unload filament"
@@ -1069,7 +1182,7 @@
 "Unloading filament"
 "Scaricando filamento"
 
-#
+#MSG_TOTAL c=6
 "Total"
 "Totale"
 
@@ -1125,7 +1238,7 @@
 "Wizard"
 "\x00"
 
-#MSG_XYZ_DETAILS c=19 r=1
+#MSG_XYZ_DETAILS c=18
 "XYZ cal. details"
 "XYZ Cal. dettagli"
 
@@ -1149,7 +1262,11 @@
 "XYZ calibration all right. X/Y axes are slightly skewed. Good job!"
 "Calibrazion XYZ corretta. Assi X/Y leggermente storti. Ben fatto!"
 
-#
+#MSG_TIMEOUT c=12
+"Timeout"
+"\x00"
+
+#MSG_X_CORRECTION c=13
 "X-correct:"
 "Correzione-X:"
 
@@ -1171,7 +1288,7 @@
 
 #
 "XYZ calibration failed. Bed calibration point was not found."
-"Calibrazione XYZ fallita. Il punto di calibrazione sul letto non e' stato trovato."
+"Calibrazione XYZ fallita. Il punto di calibrazione sul piano non e' stato trovato."
 
 #
 "XYZ calibration failed. Front calibration points not reachable."
@@ -1189,7 +1306,11 @@
 "The printer will start printing a zig-zag line. Rotate the knob until you reach the optimal height. Check the pictures in the handbook (Calibration chapter)."
 "La stampante iniziera a stampare una linea a zig-zag. Gira la manopola fino a che non hai raggiungo l'altezza ottimale. Verifica con le immagini nel manuale (capitolo sulla calibrazione):"
 
-#
+# c=20 r=5
+"Verification failed, remove the filament and try again."
+"Verifica fallita, rimuovere il filamento e riprovare."
+
+#MSG_Y_CORRECTION c=13
 "Y-correct:"
 "Correzione-Y:"
 
@@ -1229,9 +1350,9 @@
 "Warn"
 "Avviso"
 
-#
+#MSG_HW_SETUP c=18
 "HW Setup"
-"Installazione HW"
+"Impostazioni HW"
 
 #
 "IR:"
@@ -1245,10 +1366,6 @@
 "Mesh"
 "Griglia"
 
-#
-"Mesh bed leveling"
-"Mesh livel. letto"
-
 #
 "MK3S firmware detected on MK3 printer"
 "Firmware MK3S rilevato su stampante MK3"
@@ -1277,11 +1394,11 @@
 "G-code sliced for a different level. Please re-slice the model again. Print cancelled."
 "G-code processato per un livello diverso. Per favore esegui nuovamente lo slice del modello. Stampa annullata."
 
-#
+#MSG_GCODE_DIFF_PRINTER_CONTINUE c=20 r=5
 "G-code sliced for a different printer type. Continue?"
 "G-code processato per una stampante diversa. Continuare?"
 
-#
+#MSG_GCODE_DIFF_PRINTER_CANCELLED c=20 r=6
 "G-code sliced for a different printer type. Please re-slice the model again. Print cancelled."
 "G-code processato per una stampante diversa. Per favore esegui nuovamente lo slice del modello. Stampa annullata."
 
@@ -1297,13 +1414,13 @@
 "PINDA:"
 "\x00"
 
-#
+# c=20
 "Preheating to cut"
-"Preriscaldamento per taglio"
+"Preriscalda. taglio"
 
-#
+# c=20
 "Preheating to eject"
-"Preriscaldamento per espulsione"
+"Preriscalda. espuls."
 
 #
 "Printer nozzle diameter differs from the G-code. Continue?"
@@ -1313,6 +1430,10 @@
 "Printer nozzle diameter differs from the G-code. Please check the value in settings. Print cancelled."
 "Diametro ugello diverso dal G-Code. Controlla il valore nelle impostazioni. Stampa annullata."
 
+# c=20
+"%s level expected"
+"atteso livello %s"
+
 #
 "Rename"
 "Rinomina"
@@ -1325,7 +1446,7 @@
 "Sensor info"
 "Info Sensore"
 
-#
+#MSG_SHEET c=10
 "Sheet"
 "Piano"
 
@@ -1333,14 +1454,15 @@
 "Assist"
 "Assist."
 
-#
+#MSG_STEEL_SHEET c=18
 "Steel sheets"
 "Piani d'acciaio"
 
-#
+#MSG_Z_CORRECTION c=13
 "Z-correct:"
 "Correzione-Z:"
 
 #MSG_Z_PROBE_NR
 "Z-probe nr."
-"\x00"
+"Nr. Z-test"
+

+ 0 - 0
lang/lang_en_pl.txt


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