From 15c598fd6aa37ba385c80ca824d6e7fcd83659f3 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Wed, 1 Aug 2018 19:38:05 +0200 Subject: [PATCH 001/141] Fix compiler warning: sketch/Dcodes.cpp: In function 'void print_eeprom(uint16_t, uint16_t, uint8_t)': sketch/Dcodes.cpp:37:12: warning: unused variable 'data' [-Wunused-variable] --- Firmware/Dcodes.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/Firmware/Dcodes.cpp b/Firmware/Dcodes.cpp index d1ddc61e..554ec48d 100644 --- a/Firmware/Dcodes.cpp +++ b/Firmware/Dcodes.cpp @@ -34,7 +34,6 @@ void print_eeprom(uint16_t address, uint16_t count, uint8_t countperline = 16) uint8_t count_line = countperline; while (count && count_line) { - uint8_t data = 0; putchar(' '); print_hex_byte(eeprom_read_byte((uint8_t*)address++)); count_line--; From d66da3084394985aa9d5bc54e3a344da85d13660 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Wed, 1 Aug 2018 19:40:41 +0200 Subject: [PATCH 002/141] Fix compiler warning: sketch/Dcodes.cpp: In function 'void dcode_3()': sketch/Dcodes.cpp:117:24: warning: comparison between signed and unsigned integer expressions [-Wsign-compare] for (int i = 0; i < count; i++) --- Firmware/Dcodes.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Firmware/Dcodes.cpp b/Firmware/Dcodes.cpp index 554ec48d..966e7af4 100644 --- a/Firmware/Dcodes.cpp +++ b/Firmware/Dcodes.cpp @@ -114,7 +114,7 @@ void dcode_3() count = parse_hex(strchr_pointer + 1, data, 16); if (count > 0) { - for (int i = 0; i < count; i++) + for (uint16_t i = 0; i < count; i++) eeprom_write_byte((uint8_t*)(address + i), data[i]); printf_P(_N("%d bytes written to EEPROM at address 0x%04x"), count, address); putchar('\n'); From 904fe7e8861d5051683304a741afd32b5c130bf9 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Wed, 1 Aug 2018 20:59:42 +0200 Subject: [PATCH 003/141] Fix compiler warning: In file included from sketch/Marlin_main.cpp:67:0: sketch/temperature.h: In function 'void M600_wait_for_user()': sketch/temperature.h:142:30: warning: array subscript is above array bounds [-Warray-bounds] target_temperature[extruder] = celsius; --- Firmware/Marlin_main.cpp | 5 +---- 1 file changed, 1 insertion(+), 4 deletions(-) diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index 699368ec..49f96c8a 100644 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -3092,7 +3092,6 @@ void gcode_M600(bool automatic, float x_position, float y_position, float z_shif //First backup current position and settings feedmultiplyBckp=feedmultiply; - float HotendTempBckp = degTargetHotend(active_extruder); int fanSpeedBckp = fanSpeed; lastpos[X_AXIS]=current_position[X_AXIS]; lastpos[Y_AXIS]=current_position[Y_AXIS]; @@ -9066,9 +9065,7 @@ void M600_wait_for_user() { 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 wait_for_user_state = 1; - setTargetHotend(0, 0); - setTargetHotend(0, 1); - setTargetHotend(0, 2); + setAllTargetHotends(0); st_synchronize(); disable_e0(); disable_e1(); From 25c00393ffa8527a395d470a79b3cd5a30cc37e0 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Wed, 1 Aug 2018 21:16:08 +0200 Subject: [PATCH 004/141] Fix compiler warning sketch/fsensor.cpp:221:10: warning: unused variable 'fsensor_autoload_c_old' [-Wunused-variable] --- Firmware/fsensor.cpp | 10 +++++++--- 1 file changed, 7 insertions(+), 3 deletions(-) diff --git a/Firmware/fsensor.cpp b/Firmware/fsensor.cpp index c4657293..c76ee157 100644 --- a/Firmware/fsensor.cpp +++ b/Firmware/fsensor.cpp @@ -218,7 +218,9 @@ bool fsensor_check_autoload(void) fsensor_autoload_check_start(); return false; } +#if 0 uint8_t fsensor_autoload_c_old = fsensor_autoload_c; +#endif if ((millis() - fsensor_autoload_last_millis) < 25) return false; fsensor_autoload_last_millis = millis(); if (!pat9125_update_y()) //update sensor @@ -243,9 +245,11 @@ bool fsensor_check_autoload(void) else if (fsensor_autoload_c > 0) fsensor_autoload_c--; if (fsensor_autoload_c == 0) fsensor_autoload_sum = 0; -// puts_P(_N("fsensor_check_autoload\n")); -// if (fsensor_autoload_c != fsensor_autoload_c_old) -// printf_P(PSTR("fsensor_check_autoload dy=%d c=%d sum=%d\n"), dy, fsensor_autoload_c, fsensor_autoload_sum); +#if 0 + puts_P(_N("fsensor_check_autoload\n")); + if (fsensor_autoload_c != fsensor_autoload_c_old) + printf_P(PSTR("fsensor_check_autoload dy=%d c=%d sum=%d\n"), dy, fsensor_autoload_c, fsensor_autoload_sum); +#endif // if ((fsensor_autoload_c >= 15) && (fsensor_autoload_sum > 30)) if ((fsensor_autoload_c >= 12) && (fsensor_autoload_sum > 20)) { From 1b299618c13249295f454f4f896ddc34fce6da9f Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Wed, 1 Aug 2018 21:49:23 +0200 Subject: [PATCH 005/141] Fix compiler warnings: sketch/fsensor.cpp: In function 'void __vector_11()': sketch/fsensor.cpp:370:50: warning: comparison between signed and unsigned integer expressions [-Wsign-compare] if (pat9125_y > 0) if (fsensor_oq_yd_min > pat9125_y) fsensor_oq_yd_min = (fsensor_oq_yd_min + pat9125_y) / 2; ^ sketch/fsensor.cpp:371:51: warning: comparison between signed and unsigned integer expressions [-Wsign-compare] if (pat9125_y >= 0) if (fsensor_oq_yd_max < pat9125_y) fsensor_oq_yd_max = (fsensor_oq_yd_max + pat9125_y) / 2; --- Firmware/fsensor.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Firmware/fsensor.cpp b/Firmware/fsensor.cpp index c76ee157..34fab48f 100644 --- a/Firmware/fsensor.cpp +++ b/Firmware/fsensor.cpp @@ -101,9 +101,9 @@ uint16_t fsensor_oq_er_sum; //max error counter value durring meassurement uint8_t fsensor_oq_er_max; //minimum delta value -uint16_t fsensor_oq_yd_min; +int16_t fsensor_oq_yd_min; //maximum delta value -uint16_t fsensor_oq_yd_max; +int16_t fsensor_oq_yd_max; //sum of shutter value uint16_t fsensor_oq_sh_sum; From 79057f070b80ef1d2867166212d0777fc85601f0 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Wed, 1 Aug 2018 21:56:39 +0200 Subject: [PATCH 006/141] Fix compiler warning sketch/lcd.cpp:509:1: warning: label 'end' defined but not used [-Wunused-label]. --- Firmware/lcd.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/Firmware/lcd.cpp b/Firmware/lcd.cpp index c14c55f1..806ef246 100644 --- a/Firmware/lcd.cpp +++ b/Firmware/lcd.cpp @@ -506,7 +506,6 @@ uint8_t lcd_escape_write(uint8_t chr) break; } escape_cnt = 0; // reset escape -end: return 1; // assume sucess } From 660a4c0d7567c47eca15ea69175be12134456e9b Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Thu, 2 Aug 2018 14:28:39 +0200 Subject: [PATCH 007/141] Fix compiler warnings: sketch/Marlin_main.cpp: In function 'void process_commands()': sketch/Marlin_main.cpp:6311:3: warning: 'filament' may be used uninitialized in this function [-Wmaybe-uninitialized] switch (filament) { sketch/Marlin_main.cpp:6310:44: warning: 'extruder' may be used uninitialized in this function [-Wmaybe-uninitialized] printf_P(PSTR("Extruder: %d; "), extruder); --- Firmware/Marlin_main.cpp | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index 49f96c8a..855c0823 100644 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -144,6 +144,7 @@ #define FILAMENT_DEFAULT 0 #define FILAMENT_FLEX 1 #define FILAMENT_PVA 2 +#define FILAMENT_UNDEFINED 255 // look here for descriptions of G-codes: http://linuxcnc.org/handbook/gcode/g-code.html // http://objects.reprap.org/wiki/Mendel_User_Manual:_RepRapGCodes @@ -6301,8 +6302,8 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) //add storing this information for different load/unload profiles etc. in the future //firmware does not wait for "ok" from mmu - uint8_t extruder; - uint8_t filament; + uint8_t extruder = 255; + uint8_t filament = FILAMENT_UNDEFINED; if(code_seen('E')) extruder = code_value(); if(code_seen('F')) filament = code_value(); From 5ac98afeec57191da18004e4a7c466502460ce4a Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Thu, 2 Aug 2018 14:55:38 +0200 Subject: [PATCH 008/141] Fix compiler warning sketch/optiboot_w25x20cl.cpp: In function 'void optiboot_w25x20cl_enter()': sketch/optiboot_w25x20cl.cpp:275:15: warning: variable 'desttype' set but not used [-Wunused-but-set-variable] --- Firmware/optiboot_w25x20cl.cpp | 5 ++--- 1 file changed, 2 insertions(+), 3 deletions(-) diff --git a/Firmware/optiboot_w25x20cl.cpp b/Firmware/optiboot_w25x20cl.cpp index cc6c66cd..d05ae59f 100644 --- a/Firmware/optiboot_w25x20cl.cpp +++ b/Firmware/optiboot_w25x20cl.cpp @@ -272,7 +272,6 @@ void optiboot_w25x20cl_enter() /* Read memory block mode, length is big endian. */ else if(ch == STK_READ_PAGE) { uint32_t addr = (((uint32_t)rampz) << 16) | address; - uint8_t desttype; register pagelen_t i; // Read the page length, with the length transferred each nibble separately to work around // the Prusa's USB to serial infamous semicolon issue. @@ -280,8 +279,8 @@ void optiboot_w25x20cl_enter() length |= ((pagelen_t)getch()) << 8; length |= getch(); length |= getch(); - // Read the destination type. It should always be 'F' as flash. - desttype = getch(); + // Read the destination type. It should always be 'F' as flash. It is not checked. + (void)getch(); verifySpace(); w25x20cl_wait_busy(); w25x20cl_rd_data(addr, buff, length); From aee31bdb8d56180ec9b69b83cbe4b8d9d1bf4eb7 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Thu, 2 Aug 2018 15:45:33 +0200 Subject: [PATCH 009/141] Fix compiler warnings sketch/stepper.cpp: In function 'void babystep(uint8_t, bool)': sketch/stepper.cpp:1429:20: warning: unused variable 'x' [-Wunused-variable] volatile float x=1./float(axis+1)/float(axis+2); //wait a tiny bit sketch/stepper.cpp:1455:20: warning: unused variable 'x' [-Wunused-variable] volatile float x=1./float(axis+1)/float(axis+2); //wait a tiny bit sketch/stepper.cpp:1485:20: warning: unused variable 'x' [-Wunused-variable] volatile float x=1./float(axis+1); //absolutely useless sketch/stepper.cpp: In function 'void microstep_init()': sketch/stepper.cpp:1571:17: warning: unused variable 'microstep_modes' [-Wunused-variable] const uint8_t microstep_modes[] = MICROSTEP_MODES; --- Firmware/stepper.cpp | 15 ++++----------- 1 file changed, 4 insertions(+), 11 deletions(-) diff --git a/Firmware/stepper.cpp b/Firmware/stepper.cpp index b2d71e2a..8f74ae6f 100644 --- a/Firmware/stepper.cpp +++ b/Firmware/stepper.cpp @@ -1425,9 +1425,7 @@ void babystep(const uint8_t axis,const bool direction) #ifdef DEBUG_XSTEP_DUP_PIN WRITE(DEBUG_XSTEP_DUP_PIN,!INVERT_X_STEP_PIN); #endif //DEBUG_XSTEP_DUP_PIN - { - volatile float x=1./float(axis+1)/float(axis+2); //wait a tiny bit - } + delayMicroseconds(1); WRITE(X_STEP_PIN, INVERT_X_STEP_PIN); #ifdef DEBUG_XSTEP_DUP_PIN WRITE(DEBUG_XSTEP_DUP_PIN,INVERT_X_STEP_PIN); @@ -1451,9 +1449,7 @@ void babystep(const uint8_t axis,const bool direction) #ifdef DEBUG_YSTEP_DUP_PIN WRITE(DEBUG_YSTEP_DUP_PIN,!INVERT_Y_STEP_PIN); #endif //DEBUG_YSTEP_DUP_PIN - { - volatile float x=1./float(axis+1)/float(axis+2); //wait a tiny bit - } + delayMicroseconds(1); WRITE(Y_STEP_PIN, INVERT_Y_STEP_PIN); #ifdef DEBUG_YSTEP_DUP_PIN WRITE(DEBUG_YSTEP_DUP_PIN,INVERT_Y_STEP_PIN); @@ -1480,10 +1476,7 @@ void babystep(const uint8_t axis,const bool direction) #ifdef Z_DUAL_STEPPER_DRIVERS WRITE(Z2_STEP_PIN, !INVERT_Z_STEP_PIN); #endif - //wait a tiny bit - { - volatile float x=1./float(axis+1); //absolutely useless - } + delayMicroseconds(1); WRITE(Z_STEP_PIN, INVERT_Z_STEP_PIN); #ifdef Z_DUAL_STEPPER_DRIVERS WRITE(Z2_STEP_PIN, INVERT_Z_STEP_PIN); @@ -1568,7 +1561,6 @@ void st_current_set(uint8_t driver, int current) void microstep_init() { - const uint8_t microstep_modes[] = MICROSTEP_MODES; #if defined(E1_MS1_PIN) && E1_MS1_PIN > -1 pinMode(E1_MS1_PIN,OUTPUT); @@ -1576,6 +1568,7 @@ void microstep_init() #endif #if defined(X_MS1_PIN) && X_MS1_PIN > -1 + const uint8_t microstep_modes[] = MICROSTEP_MODES; pinMode(X_MS1_PIN,OUTPUT); pinMode(X_MS2_PIN,OUTPUT); pinMode(Y_MS1_PIN,OUTPUT); From ea3d407aa7a950a4cbca3af9df88e89c4485c5ec Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Thu, 2 Aug 2018 15:52:28 +0200 Subject: [PATCH 010/141] Fix compiler warning: remove unused function float analog2tempPINDA(int raw). --- Firmware/temperature.cpp | 30 ------------------------------ 1 file changed, 30 deletions(-) diff --git a/Firmware/temperature.cpp b/Firmware/temperature.cpp index 6a21b825..34539483 100644 --- a/Firmware/temperature.cpp +++ b/Firmware/temperature.cpp @@ -183,7 +183,6 @@ static int bed_maxttemp_raw = HEATER_BED_RAW_HI_TEMP; static float analog2temp(int raw, uint8_t e); static float analog2tempBed(int raw); static float analog2tempAmbient(int raw); -static float analog2tempPINDA(int raw); static void updateTemperaturesFromRawValues(); enum TempRunawayStates @@ -936,35 +935,6 @@ static float analog2tempBed(int raw) { #endif } -#ifdef PINDA_THERMISTOR - -static float analog2tempPINDA(int raw) { - - float celsius = 0; - byte i; - - for (i = 1; i raw) - { - celsius = PGM_RD_W(BEDTEMPTABLE[i - 1][1]) + - (raw - PGM_RD_W(BEDTEMPTABLE[i - 1][0])) * - (float)(PGM_RD_W(BEDTEMPTABLE[i][1]) - PGM_RD_W(BEDTEMPTABLE[i - 1][1])) / - (float)(PGM_RD_W(BEDTEMPTABLE[i][0]) - PGM_RD_W(BEDTEMPTABLE[i - 1][0])); - break; - } - } - - // Overflow: Set to last value in the table - if (i == BEDTEMPTABLE_LEN) celsius = PGM_RD_W(BEDTEMPTABLE[i - 1][1]); - - return celsius; -} - - -#endif //PINDA_THERMISTOR - - #ifdef AMBIENT_THERMISTOR static float analog2tempAmbient(int raw) { From 9f68681a1bb94a9766a90dd30e3fcb3057a68357 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Thu, 2 Aug 2018 16:21:38 +0200 Subject: [PATCH 011/141] Fix compiler warnings: sketch/tmc2130.cpp: In function 'void tmc2130_goto_step(uint8_t, uint8_t, uint8_t, uint16_t, uint16_t)': sketch/tmc2130.cpp:795:94: warning: comparison between signed and unsigned integer expressions [-Wsign-compare] sketch/tmc2130.cpp:807:23: warning: comparison between signed and unsigned integer expressions [-Wsign-compare] sketch/tmc2130.cpp: In function 'void tmc2130_get_wave(uint8_t, uint8_t*, __file*)': sketch/tmc2130.cpp:839:17: warning: comparison between signed and unsigned integer expressions [-Wsign-compare] --- Firmware/tmc2130.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/Firmware/tmc2130.cpp b/Firmware/tmc2130.cpp index d4295701..c8af1a23 100644 --- a/Firmware/tmc2130.cpp +++ b/Firmware/tmc2130.cpp @@ -792,7 +792,7 @@ void tmc2130_do_steps(uint8_t axis, uint16_t steps, uint8_t dir, uint16_t delay_ void tmc2130_goto_step(uint8_t axis, uint8_t step, uint8_t dir, uint16_t delay_us, uint16_t microstep_resolution) { printf_P(PSTR("tmc2130_goto_step %d %d %d %d \n"), axis, step, dir, delay_us, microstep_resolution); - uint8_t shift; for (shift = 0; shift < 8; shift++) if (microstep_resolution == (256 >> shift)) break; + uint8_t shift; for (shift = 0; shift < 8; shift++) if (microstep_resolution == (256u >> shift)) break; uint16_t cnt = 4 * (1 << (8 - shift)); uint16_t mscnt = tmc2130_rd_MSCNT(axis); if (dir == 2) @@ -804,7 +804,7 @@ void tmc2130_goto_step(uint8_t axis, uint8_t step, uint8_t dir, uint16_t delay_u dir ^= 1; steps = -steps; } - if (steps > (cnt / 2)) + if (steps > static_cast(cnt / 2)) { dir ^= 1; steps = cnt - steps; @@ -829,7 +829,7 @@ void tmc2130_get_wave(uint8_t axis, uint8_t* data, FILE* stream) tmc2130_setup_chopper(axis, tmc2130_usteps2mres(256), tmc2130_current_h[axis], tmc2130_current_r[axis]); tmc2130_goto_step(axis, 0, 2, 100, 256); tmc2130_set_dir(axis, tmc2130_get_inv(axis)?0:1); - for (int i = 0; i <= 255; i++) + for (unsigned int i = 0; i <= 255; i++) { uint32_t val = tmc2130_rd_MSCURACT(axis); uint16_t mscnt = tmc2130_rd_MSCNT(axis); From 3248d219f28f18f2a5238ea82a6987c8b0f5f3a3 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Thu, 2 Aug 2018 16:23:30 +0200 Subject: [PATCH 012/141] Restore motor power, after it is disabled in tmc2130_get_wave(). This bug manifested itself as compiler warning: sketch/tmc2130.cpp:827:10: warning: unused variable 'pwr' [-Wunused-variable] --- Firmware/tmc2130.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/Firmware/tmc2130.cpp b/Firmware/tmc2130.cpp index c8af1a23..9548af37 100644 --- a/Firmware/tmc2130.cpp +++ b/Firmware/tmc2130.cpp @@ -846,6 +846,7 @@ void tmc2130_get_wave(uint8_t axis, uint8_t* data, FILE* stream) delayMicroseconds(100); } tmc2130_setup_chopper(axis, tmc2130_mres[axis], tmc2130_current_h[axis], tmc2130_current_r[axis]); + tmc2130_set_pwr(axis, pwr); } void tmc2130_set_wave(uint8_t axis, uint8_t amp, uint8_t fac1000) From bf8808ce22e3056480c5820e3367a5544e31f62e Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Thu, 2 Aug 2018 16:50:04 +0200 Subject: [PATCH 013/141] Fix compiler warning sketch/tmc2130.cpp: In function 'void tmc2130_set_wave(uint8_t, uint8_t, uint8_t)': sketch/tmc2130.cpp:921:32: warning: 'reg' may be used uninitialized in this function [-Wmaybe-uninitialized] This was completely innocent, as reg was zeroed inside for loop. --- Firmware/tmc2130.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Firmware/tmc2130.cpp b/Firmware/tmc2130.cpp index 9548af37..27600e92 100644 --- a/Firmware/tmc2130.cpp +++ b/Firmware/tmc2130.cpp @@ -869,7 +869,7 @@ void tmc2130_set_wave(uint8_t axis, uint8_t amp, uint8_t fac1000) int8_t b; //encoded bit value int8_t dA; //delta value int i; //microstep index - uint32_t reg; //tmc2130 register + uint32_t reg = 0; //tmc2130 register tmc2130_wr_MSLUTSTART(axis, 0, amp); for (i = 0; i < 256; i++) { From 1898ef9896bb5d8c634f6feb3da51a0f462dc6f0 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Thu, 2 Aug 2018 17:02:12 +0200 Subject: [PATCH 014/141] Fix compiler warning sketch/ultralcd.cpp:2533:7: warning: unused variable '_cm' [-Wunused-variable] --- Firmware/ultralcd.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index 4b20c9fb..7122b3b5 100644 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -2530,7 +2530,6 @@ void lcd_menu_statistics() if (IS_SD_PRINTING) { float _met = ((float)total_filament_used) / (100000.f); - int _cm = (total_filament_used - (_met * 100000)) / 10; int _t = (millis() - starttime) / 1000; int _h = _t / 3600; int _m = (_t - (_h * 3600)) / 60; From d85c36cc77fa9cd4402744c2f55864aee13e1992 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Thu, 2 Aug 2018 17:08:46 +0200 Subject: [PATCH 015/141] Fix compiler warning sketch/ultralcd.cpp:3588:9: warning: unused variable 'enc_dif' [-Wunused-variable] --- Firmware/ultralcd.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index 7122b3b5..d18c07fd 100644 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -3584,7 +3584,6 @@ static void menu_show_end_stops() { // Otherwise the Z calibration is not changed and false is returned. void lcd_diag_show_end_stops() { - int enc_dif = lcd_encoder_diff; lcd_clear(); for (;;) { manage_heater(); From 05d455fc3065a4f356ff9640f10360e8326e9e7b Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Thu, 2 Aug 2018 17:11:23 +0200 Subject: [PATCH 016/141] Fix compiler warning sketch/ultralcd.cpp:6301:7: warning: unused variable 'tempScrool' [-Wunused-variable]. --- Firmware/ultralcd.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index d18c07fd..767fafd7 100644 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -6296,7 +6296,7 @@ void lcd_sdcard_stop() void lcd_sdcard_menu() { uint8_t sdSort = eeprom_read_byte((uint8_t*)EEPROM_SD_SORT); - int tempScrool = 0; + if (presort_flag == true) { presort_flag = false; card.presort(); From 02f5a60065a651d1283ad21214d0599b817b3a8c Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Thu, 2 Aug 2018 17:23:11 +0200 Subject: [PATCH 017/141] Fix compiler warning: sketch/ultralcd.cpp:6540:23: warning: array subscript has type 'char' [-Wchar-subscripts] --- Firmware/ultralcd.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index 767fafd7..70e3a0db 100644 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -149,7 +149,7 @@ static void lcd_selftest_v(); static bool lcd_selfcheck_endstops(); #ifdef TMC2130 -static void reset_crash_det(char axis); +static void reset_crash_det(unsigned char axis); static bool lcd_selfcheck_axis_sg(char axis); static bool lcd_selfcheck_axis(int _axis, int _travel); #else @@ -6536,7 +6536,7 @@ bool lcd_selftest() #ifdef TMC2130 -static void reset_crash_det(char axis) { +static void reset_crash_det(unsigned char axis) { current_position[axis] += 10; plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[3], manual_feedrate[0] / 60, active_extruder); st_synchronize(); From 87a650f2cb853093e2772d5c375790feeaf7f725 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Thu, 2 Aug 2018 17:25:32 +0200 Subject: [PATCH 018/141] Fix compiler warning: sketch/ultralcd.cpp:6573:23: warning: array subscript has type 'char' [-Wchar-subscripts] --- Firmware/ultralcd.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index 70e3a0db..526df062 100644 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -150,7 +150,7 @@ static bool lcd_selfcheck_endstops(); #ifdef TMC2130 static void reset_crash_det(unsigned char axis); -static bool lcd_selfcheck_axis_sg(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(); @@ -6543,7 +6543,7 @@ static void reset_crash_det(unsigned char axis) { if (eeprom_read_byte((uint8_t*)EEPROM_CRASH_DET)) tmc2130_sg_stop_on_crash = true; } -static bool lcd_selfcheck_axis_sg(char axis) { +static bool lcd_selfcheck_axis_sg(unsigned char axis) { // each axis length is measured twice float axis_length, current_position_init, current_position_final; float measured_axis_length[2]; From 268c52207b59b434359f78c4af02cb4f0e855d75 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Thu, 2 Aug 2018 17:29:14 +0200 Subject: [PATCH 019/141] Fix compiler warning: sketch/ultralcd.cpp:7457:7: warning: unused variable 'pressed' [-Wunused-variable]. --- Firmware/ultralcd.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index 526df062..8dfee2f7 100644 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -7454,7 +7454,6 @@ static void lcd_connect_printer() { lcd_update_enable(false); lcd_clear(); - bool pressed = false; int i = 0; int t = 0; lcd_set_custom_characters_progress(); From fd70078606dfd1f97225597ab6d15f547a371109 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Thu, 2 Aug 2018 18:18:31 +0200 Subject: [PATCH 020/141] Remove or disable by preprocessor unused functions in ultralcd.cpp. --- Firmware/ultralcd.cpp | 102 +++++++++++------------------------------- 1 file changed, 27 insertions(+), 75 deletions(-) diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index 8dfee2f7..b9afa034 100644 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -118,19 +118,15 @@ static const char* lcd_display_message_fullscreen_nonBlocking_P(const char *msg, static void lcd_status_screen(); static void lcd_language_menu(); -extern bool powersupply; static void lcd_main_menu(); static void lcd_tune_menu(); -static void lcd_prepare_menu(); //static void lcd_move_menu(); static void lcd_settings_menu(); static void lcd_calibration_menu(); static void lcd_control_temperature_menu(); -static void lcd_control_temperature_preheat_pla_settings_menu(); -static void lcd_control_temperature_preheat_abs_settings_menu(); -static void lcd_control_motion_menu(); -static void lcd_control_volumetric_menu(); +#ifdef LINEARITY_CORRECTION static void lcd_settings_menu_back(); +#endif //LINEARITY_CORRECTION static void prusa_stat_printerstatus(int _status); static void prusa_stat_farm_number(); @@ -146,7 +142,6 @@ static void lcd_menu_fails_stats(); #endif //TMC2130 or FILAMENT_SENSOR static void lcd_selftest_v(); -static bool lcd_selfcheck_endstops(); #ifdef TMC2130 static void reset_crash_det(unsigned char axis); @@ -166,7 +161,10 @@ static bool lcd_selftest_fan_dialog(int _fan); static bool lcd_selftest_fsensor(); static void lcd_selftest_error(int _error_no, const char *_error_1, const char *_error_2); static void lcd_colorprint_change(); +#ifdef SNMM static int get_ext_nr(); +#endif //SNMM +#if defined (SNMM) || defined(SNMM_V2) static void extr_adj_0(); static void extr_adj_1(); static void extr_adj_2(); @@ -177,6 +175,7 @@ static void extr_unload_0(); static void extr_unload_1(); static void extr_unload_2(); static void extr_unload_3(); +#endif // SNMM || SNMM_V2 static void lcd_disable_farm_mode(); static void lcd_set_fan_check(); static char snmm_stop_print_menu(); @@ -186,11 +185,12 @@ static char snmm_stop_print_menu(); static float count_e(float layer_heigth, float extrusion_width, float extrusion_length); static void lcd_babystep_z(); static void lcd_send_status(); +#ifdef FARM_CONNECT_MESSAGE static void lcd_connect_printer(); +#endif //FARM_CONNECT_MESSAGE void lcd_finishstatus(); -static void lcd_control_retract_menu(); static void lcd_sdcard_menu(); #ifdef DELTA_CALIBRATION_MENU @@ -2853,12 +2853,6 @@ static void _lcd_babystep(int axis, const char *msg) if (LCD_CLICKED) menu_back(); } -static void lcd_babystep_x() { - _lcd_babystep(X_AXIS, (_i("Babystepping X")));////MSG_BABYSTEPPING_X c=0 r=0 -} -static void lcd_babystep_y() { - _lcd_babystep(Y_AXIS, (_i("Babystepping Y")));////MSG_BABYSTEPPING_Y c=0 r=0 -} static void lcd_babystep_z() { _lcd_babystep(Z_AXIS, (_i("Adjusting Z")));////MSG_BABYSTEPPING_Z c=20 r=0 } @@ -3574,10 +3568,12 @@ static void lcd_show_end_stops() { lcd_puts_P((READ(Z_MIN_PIN) ^ (bool)Z_MIN_ENDSTOP_INVERTING) ? (PSTR("Z1")) : (PSTR("Z0"))); } +#ifndef TMC2130 static void menu_show_end_stops() { lcd_show_end_stops(); if (LCD_CLICKED) menu_back(); } +#endif // not defined TMC2130 // Lets the user move the Z carriage up to the end stoppers. // When done, it sets the current Z to Z_MAX_POS and returns true. @@ -4534,7 +4530,7 @@ void lcd_wizard(int state) { lcd_return_to_status(); lcd_update(2); } -/* +#ifdef LINEARITY_CORRECTION void lcd_settings_linearity_correction_menu(void) { MENU_BEGIN(); @@ -4555,7 +4551,7 @@ void lcd_settings_linearity_correction_menu(void) MENU_ITEM_EDIT_int3_P(_i("E-correct"), &corr[E_AXIS], TMC2130_WAVE_FAC1000_MIN-TMC2130_WAVE_FAC1000_STP, TMC2130_WAVE_FAC1000_MAX);////MSG_EXTRUDER_CORRECTION c=9 r=0 MENU_END(); } -*/ +#endif //LINEARITY_CORRECTION static void lcd_settings_menu() { EEPROM_read(EEPROM_SILENT, (uint8_t*)&SilentModeMenu, sizeof(SilentModeMenu)); @@ -4625,8 +4621,9 @@ static void lcd_settings_menu() } else MENU_ITEM_SUBMENU_P(_T(MSG_CRASHDETECT_NA), lcd_crash_mode_info); } - -// MENU_ITEM_SUBMENU_P(_i("Lin. correction"), lcd_settings_linearity_correction_menu); +#ifdef LINEARITY_CORRECTION + MENU_ITEM_SUBMENU_P(_i("Lin. correction"), lcd_settings_linearity_correction_menu); +#endif //LINEARITY_CORRECTION #endif //TMC2130 if (temp_cal_active == false) @@ -4696,11 +4693,7 @@ switch(eSoundMode) MENU_END(); } -static void lcd_selftest_() -{ - lcd_selftest(); -} - +#ifdef LINEARITY_CORRECTION #ifdef TMC2130 static void lcd_ustep_linearity_menu_save() { @@ -4727,8 +4720,8 @@ static void lcd_settings_menu_back() if (changed) tmc2130_init(); #endif //TMC2130 menu_menu = lcd_main_menu; -// lcd_main_menu(); } +#endif //LINEARITY_CORRECTION static void lcd_calibration_menu() @@ -5186,6 +5179,7 @@ void change_extr(int extr) { //switches multiplexer for extruders #endif } +#ifdef SNMM static int get_ext_nr() { //reads multiplexer input pins and return current extruder number (counted from 0) #ifdef SNMM_V2 return(snmm_extruder); //update needed @@ -5193,6 +5187,7 @@ static int get_ext_nr() { //reads multiplexer input pins and return current extr return(2 * READ(E_MUX1_PIN) + READ(E_MUX0_PIN)); #endif } +#endif //SNMM void display_loading() { @@ -5835,6 +5830,7 @@ void lcd_confirm_print() #include "w25x20cl.h" +#ifdef LCD_TEST static void lcd_test_menu() { W25X20CL_SPI_ENTER(); @@ -5842,6 +5838,7 @@ static void lcd_test_menu() w25x20cl_chip_erase(); w25x20cl_disable_wr(); } +#endif //LCD_TEST static void lcd_main_menu() { @@ -6013,8 +6010,9 @@ static void lcd_main_menu() #endif MENU_ITEM_SUBMENU_P(_i("Support"), lcd_support_menu);////MSG_SUPPORT c=0 r=0 - -// MENU_ITEM_SUBMENU_P(_i("W25x20CL init"), lcd_test_menu);////MSG_SUPPORT c=0 r=0 +#ifdef LCD_TEST + MENU_ITEM_SUBMENU_P(_i("W25x20CL init"), lcd_test_menu);////MSG_SUPPORT c=0 r=0 +#endif //LCD_TEST MENU_END(); @@ -6051,34 +6049,6 @@ void stepper_timer_overflow() { } #endif /* DEBUG_STEPPER_TIMER_MISSED */ -#ifdef SDSUPPORT -static void lcd_autostart_sd() -{ - card.lastnr = 0; - card.setroot(); - card.checkautostart(true); -} -#endif - - - -static void lcd_silent_mode_set_tune() { - switch (SilentModeMenu) { -#ifdef TMC2130 - case SILENT_MODE_NORMAL: SilentModeMenu = SILENT_MODE_STEALTH; break; - case SILENT_MODE_STEALTH: SilentModeMenu = SILENT_MODE_NORMAL; break; - default: SilentModeMenu = SILENT_MODE_NORMAL; break; // (probably) not needed -#else - case SILENT_MODE_POWER: SilentModeMenu = SILENT_MODE_SILENT; break; - case SILENT_MODE_SILENT: SilentModeMenu = SILENT_MODE_AUTO; break; - case SILENT_MODE_AUTO: SilentModeMenu = SILENT_MODE_POWER; break; - default: SilentModeMenu = SILENT_MODE_POWER; break; // (probably) not needed -#endif //TMC2130 - } - eeprom_update_byte((unsigned char *)EEPROM_SILENT, SilentModeMenu); - st_current_init(); - menu_back(); -} static void lcd_colorprint_change() { @@ -6174,12 +6144,6 @@ static void lcd_tune_menu() MENU_END(); } -static void lcd_move_menu_01mm() -{ - move_menu_scale = 0.1; - lcd_move_menu_axis(); -} - static void lcd_control_temperature_menu() { #ifdef PIDTEMP @@ -6830,7 +6794,6 @@ static bool lcd_selfcheck_pulleys(int axis) } return(true); } -#endif //TMC2130 static bool lcd_selfcheck_endstops() @@ -6863,7 +6826,7 @@ static bool lcd_selfcheck_endstops() manage_inactivity(true); return _result; } -//#endif //not defined TMC2130 +#endif //not defined TMC2130 static bool lcd_selfcheck_check_heater(bool _isbed) { @@ -7450,6 +7413,7 @@ static void lcd_send_status() { } } +#ifdef FARM_CONNECT_MESSAGE static void lcd_connect_printer() { lcd_update_enable(false); lcd_clear(); @@ -7482,6 +7446,7 @@ static void lcd_connect_printer() { lcd_update_enable(true); lcd_update(2); } +#endif //FARM_CONNECT_MESSAGE void lcd_ping() { //chceck if printer is connected to monitoring when in farm mode if (farm_mode) { @@ -7545,19 +7510,6 @@ uint8_t get_message_level() } - - - - - - - - - - - - - void menu_lcd_longpress_func(void) { move_menu_scale = 1.0; From 63724c5f0e674bbf58527c5c2f54e388414a1365 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Thu, 2 Aug 2018 18:26:49 +0200 Subject: [PATCH 021/141] Comment out variable used only for commented out debug. --- Firmware/xyzcal.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Firmware/xyzcal.cpp b/Firmware/xyzcal.cpp index 027cfdfb..3984a83d 100644 --- a/Firmware/xyzcal.cpp +++ b/Firmware/xyzcal.cpp @@ -285,7 +285,7 @@ void xyzcal_scan_pixels_32x32(int16_t cx, int16_t cy, int16_t min_z, int16_t max xyzcal_lineXYZ_to(cx, cy, z, 2*delay_us, 0); for (uint8_t r = 0; r < 32; r++) { - int8_t _pinda = _PINDA; +// 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, 1); xyzcal_lineXYZ_to(_X, _Y, max_z, delay_us, -1); @@ -330,7 +330,7 @@ void xyzcal_scan_pixels_32x32(int16_t cx, int16_t cy, int16_t min_z, int16_t max } sm4_do_step(X_AXIS_MASK); delayMicroseconds(600); - _pinda = pinda; +// _pinda = pinda; } sum >>= 6; //div 64 if (z_sum < 0) From 2e61c0e28982e3562301a6d42fb19123e78ccc46 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Thu, 2 Aug 2018 20:47:03 +0200 Subject: [PATCH 022/141] Obey defined X and Y homing direction. Problem manifested itself as sketch/Marlin_main.cpp:2288:13: warning: unused variable 'axis_home_dir' [-Wunused-variable] --- Firmware/Marlin_main.cpp | 26 +++++++++++++------------- 1 file changed, 13 insertions(+), 13 deletions(-) diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index 1c8683cf..b29f23cd 100644 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -2296,43 +2296,43 @@ void homeaxis(int axis, uint8_t cnt, uint8_t* pstep) #endif //TMC2130 - // Move right a bit, so that the print head does not touch the left end position, - // and the following left movement has a chance to achieve the required velocity + // Move away a bit, so that the print head does not touch the end position, + // 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]); set_destination_to_current(); // destination[axis] = 11.f; - destination[axis] = 3.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); st_synchronize(); - // Move left away from the possible collision with the collision detection disabled. + // 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]); - destination[axis] = - 1.; + 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); st_synchronize(); // Now continue to move up to the left end stop with the collision detection enabled. enable_endstops(true); - destination[axis] = - 1.1 * max_length(axis); + 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); st_synchronize(); for (uint8_t i = 0; i < cnt; i++) { - // Move right from the collision to a known distance from the left end stop with the collision detection disabled. + // Move away from the collision to a known distance from the left end stop 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]); - destination[axis] = 10.f; + 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); st_synchronize(); endstops_hit_on_purpose(); // Now move left up to the collision, this time with a repeatable velocity. enable_endstops(true); - destination[axis] = - 11.f; + destination[axis] = 11.f * axis_home_dir; #ifdef TMC2130 feedrate = homing_feedrate[axis]; #else //TMC2130 @@ -2356,10 +2356,10 @@ void homeaxis(int axis, uint8_t cnt, uint8_t* pstep) { tmc2130_goto_step(axis, orig, 2, 1000, tmc2130_get_res(axis)); if (back > 0) - tmc2130_do_steps(axis, back, 1, 1000); + tmc2130_do_steps(axis, back, -axis_home_dir, 1000); } else - tmc2130_do_steps(axis, 8, 2, 1000); + tmc2130_do_steps(axis, 8, -axis_home_dir, 1000); tmc2130_home_exit(); #endif //TMC2130 @@ -2367,9 +2367,9 @@ void homeaxis(int axis, uint8_t cnt, uint8_t* pstep) axis_known_position[axis] = true; // Move from minimum #ifdef TMC2130 - float dist = 0.01f * tmc2130_home_fsteps[axis]; + float dist = - axis_home_dir * 0.01f * tmc2130_home_fsteps[axis]; #else //TMC2130 - float dist = 0.01f * 64; + 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]); From d3360c6868b36c87230f3fc8cda4aca29c95de45 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Thu, 2 Aug 2018 21:46:50 +0200 Subject: [PATCH 023/141] Fix compiler warning sketch/Marlin_main.cpp:9099:7: warning: unused variable 'response' [-Wunused-variable]. --- Firmware/Marlin_main.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index a39339e4..24237b64 100644 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -9096,7 +9096,6 @@ void M600_wait_for_user() { void mmu_M600_load_filament(bool automatic) { //load filament for mmu v2 - bool response = false; bool yes = false; if (!automatic) { From bd907aec867c576343fc7e3a4ab9fba6be5e5c37 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Fri, 3 Aug 2018 14:35:18 +0200 Subject: [PATCH 024/141] Fix 4 compiler warnings of type sketch/sm4.c:88:2: warning: 'register' is not at beginning of declaration [-Wold-style-declaration]. --- Firmware/sm4.c | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/Firmware/sm4.c b/Firmware/sm4.c index 509ac23f..34cf8a3c 100644 --- a/Firmware/sm4.c +++ b/Firmware/sm4.c @@ -85,8 +85,8 @@ void sm4_set_dir(uint8_t axis, uint8_t dir) uint8_t sm4_get_dir_bits(void) { - uint8_t register dir_bits = 0; - uint8_t register portL = PORTL; + register uint8_t dir_bits = 0; + register uint8_t portL = PORTL; //TODO -optimize in asm #if ((MOTHERBOARD == BOARD_RAMBO_MINI_1_0) || (MOTHERBOARD == BOARD_RAMBO_MINI_1_3)) if (portL & 2) dir_bits |= 1; @@ -106,7 +106,7 @@ uint8_t sm4_get_dir_bits(void) void sm4_set_dir_bits(uint8_t dir_bits) { - uint8_t register portL = PORTL; + register uint8_t portL = PORTL; portL &= 0xb8; //set direction bits to zero //TODO -optimize in asm #if ((MOTHERBOARD == BOARD_RAMBO_MINI_1_0) || (MOTHERBOARD == BOARD_RAMBO_MINI_1_3)) @@ -129,7 +129,7 @@ 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)) - uint8_t register portC = PORTC & 0xf0; + 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 From f7f4ba25128706ab450d4865e48323568f8fa760 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Fri, 3 Aug 2018 14:44:56 +0200 Subject: [PATCH 025/141] Make functions static, save 270B of flash. --- Firmware/ConfigurationStore.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Firmware/ConfigurationStore.cpp b/Firmware/ConfigurationStore.cpp index 264486b7..85e13e83 100644 --- a/Firmware/ConfigurationStore.cpp +++ b/Firmware/ConfigurationStore.cpp @@ -14,7 +14,7 @@ #else //DEBUG_EEPROM_WRITE #define EEPROM_WRITE_VAR(pos, value) _EEPROM_writeData(pos, (uint8_t*)&value, sizeof(value), 0) #endif //DEBUG_EEPROM_WRITE -void _EEPROM_writeData(int &pos, uint8_t* value, uint8_t size, char* name) +static void _EEPROM_writeData(int &pos, uint8_t* value, uint8_t size, char* name) { #ifdef DEBUG_EEPROM_WRITE printf_P(PSTR("EEPROM_WRITE_VAR addr=0x%04x size=0x%02hhx name=%s\n"), pos, size, name); @@ -42,7 +42,7 @@ void _EEPROM_writeData(int &pos, uint8_t* value, uint8_t size, char* name) #else //DEBUG_EEPROM_READ #define EEPROM_READ_VAR(pos, value) _EEPROM_readData(pos, (uint8_t*)&value, sizeof(value), 0) #endif //DEBUG_EEPROM_READ -void _EEPROM_readData(int &pos, uint8_t* value, uint8_t size, char* name) +static void _EEPROM_readData(int &pos, uint8_t* value, uint8_t size, char* name) { #ifdef DEBUG_EEPROM_READ printf_P(PSTR("EEPROM_READ_VAR addr=0x%04x size=0x%02hhx name=%s\n"), pos, size, name); From 0632f3b6d8d19cd45807b832ce1d23c66ca769e7 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Fri, 3 Aug 2018 14:50:51 +0200 Subject: [PATCH 026/141] Fix compiler warnings: sketch/ConfigurationStore.cpp:17:13: warning: unused parameter 'name' [-Wunused-parameter] static void _EEPROM_writeData(int &pos, uint8_t* value, uint8_t size, char* name) sketch/ConfigurationStore.cpp:45:13: warning: unused parameter 'name' [-Wunused-parameter] static void _EEPROM_readData(int &pos, uint8_t* value, uint8_t size, char* name) --- Firmware/ConfigurationStore.cpp | 14 ++++++++------ 1 file changed, 8 insertions(+), 6 deletions(-) diff --git a/Firmware/ConfigurationStore.cpp b/Firmware/ConfigurationStore.cpp index 85e13e83..388ded1a 100644 --- a/Firmware/ConfigurationStore.cpp +++ b/Firmware/ConfigurationStore.cpp @@ -11,10 +11,11 @@ #ifdef DEBUG_EEPROM_WRITE #define EEPROM_WRITE_VAR(pos, value) _EEPROM_writeData(pos, (uint8_t*)&value, sizeof(value), #value) -#else //DEBUG_EEPROM_WRITE -#define EEPROM_WRITE_VAR(pos, value) _EEPROM_writeData(pos, (uint8_t*)&value, sizeof(value), 0) -#endif //DEBUG_EEPROM_WRITE static void _EEPROM_writeData(int &pos, uint8_t* value, uint8_t size, char* name) +#else //DEBUG_EEPROM_WRITE +#define EEPROM_WRITE_VAR(pos, value) _EEPROM_writeData(pos, (uint8_t*)&value, sizeof(value)) +static void _EEPROM_writeData(int &pos, uint8_t* value, uint8_t size) +#endif //DEBUG_EEPROM_WRITE { #ifdef DEBUG_EEPROM_WRITE printf_P(PSTR("EEPROM_WRITE_VAR addr=0x%04x size=0x%02hhx name=%s\n"), pos, size, name); @@ -39,10 +40,11 @@ static void _EEPROM_writeData(int &pos, uint8_t* value, uint8_t size, char* name #ifdef DEBUG_EEPROM_READ #define EEPROM_READ_VAR(pos, value) _EEPROM_readData(pos, (uint8_t*)&value, sizeof(value), #value) -#else //DEBUG_EEPROM_READ -#define EEPROM_READ_VAR(pos, value) _EEPROM_readData(pos, (uint8_t*)&value, sizeof(value), 0) -#endif //DEBUG_EEPROM_READ static void _EEPROM_readData(int &pos, uint8_t* value, uint8_t size, char* name) +#else //DEBUG_EEPROM_READ +#define EEPROM_READ_VAR(pos, value) _EEPROM_readData(pos, (uint8_t*)&value, sizeof(value)) +static void _EEPROM_readData(int &pos, uint8_t* value, uint8_t size) +#endif //DEBUG_EEPROM_READ { #ifdef DEBUG_EEPROM_READ printf_P(PSTR("EEPROM_READ_VAR addr=0x%04x size=0x%02hhx name=%s\n"), pos, size, name); From 0638e490c10955800f0cecc52c18f2391b4c2ad4 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Fri, 3 Aug 2018 15:23:24 +0200 Subject: [PATCH 027/141] Fix compiler warnings: sketch/Marlin_main.cpp:923:19: warning: missing initializer for member '__file::unget' [-Wmissing-field-initializers] FILE _uartout = {0}; sketch/Marlin_main.cpp:923:19: warning: missing initializer for member '__file::flags' [-Wmissing-field-initializers] sketch/Marlin_main.cpp:923:19: warning: missing initializer for member '__file::size' [-Wmissing-field-initializers] sketch/Marlin_main.cpp:923:19: warning: missing initializer for member '__file::len' [-Wmissing-field-initializers] sketch/Marlin_main.cpp:923:19: warning: missing initializer for member '__file::put' [-Wmissing-field-initializers] sketch/Marlin_main.cpp:923:19: warning: missing initializer for member '__file::get' [-Wmissing-field-initializers] sketch/Marlin_main.cpp:923:19: warning: missing initializer for member '__file::udata' [-Wmissing-field-initializers] --- Firmware/Marlin_main.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index 24237b64..c10125f6 100644 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -920,7 +920,7 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) } -FILE _uartout = {0}; +FILE _uartout; //= {0}; Global variable is always zero initialized. No need to explicitly state this. int uart_putchar(char c, FILE *stream) { From 373b4a1ea978fda96457ab2ef16de2c2aca1b76b Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Fri, 3 Aug 2018 15:25:52 +0200 Subject: [PATCH 028/141] Fix compiler warnings sketch/lcd.cpp:59:18: warning: missing initializer for member '__file::unget' [-Wmissing-field-initializers] FILE _lcdout = {0}; sketch/lcd.cpp:59:18: warning: missing initializer for member '__file::flags' [-Wmissing-field-initializers] sketch/lcd.cpp:59:18: warning: missing initializer for member '__file::size' [-Wmissing-field-initializers] sketch/lcd.cpp:59:18: warning: missing initializer for member '__file::len' [-Wmissing-field-initializers] sketch/lcd.cpp:59:18: warning: missing initializer for member '__file::put' [-Wmissing-field-initializers] sketch/lcd.cpp:59:18: warning: missing initializer for member '__file::get' [-Wmissing-field-initializers] sketch/lcd.cpp:59:18: warning: missing initializer for member '__file::udata' [-Wmissing-field-initializers] --- Firmware/lcd.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Firmware/lcd.cpp b/Firmware/lcd.cpp index fa6556de..badb170d 100644 --- a/Firmware/lcd.cpp +++ b/Firmware/lcd.cpp @@ -56,7 +56,7 @@ #define LCD_5x8DOTS 0x00 -FILE _lcdout = {0}; +FILE _lcdout; // = {0}; Global variable is always zero initialized, no need to explicitly state that. uint8_t lcd_rs_pin; // LOW: command. HIGH: character. From a85d5948c3d68854005db562836d34bcbec9b134 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Fri, 3 Aug 2018 15:32:28 +0200 Subject: [PATCH 029/141] Make function static, save 38B flash. --- Firmware/lcd.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Firmware/lcd.cpp b/Firmware/lcd.cpp index badb170d..24eb28ae 100644 --- a/Firmware/lcd.cpp +++ b/Firmware/lcd.cpp @@ -157,7 +157,7 @@ uint8_t lcd_write(uint8_t value) return 1; // assume sucess } -void lcd_begin(uint8_t cols, uint8_t lines, uint8_t dotsize, uint8_t clear) +static void lcd_begin(uint8_t cols, uint8_t lines, uint8_t dotsize, uint8_t clear) { if (lines > 1) lcd_displayfunction |= LCD_2LINE; lcd_numlines = lines; From f6094a58f789abf2ebd626501264d8881c45d683 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Fri, 3 Aug 2018 15:37:40 +0200 Subject: [PATCH 030/141] Fix compiler warning sketch/lcd.cpp:160:6: warning: unused parameter 'cols' [-Wunused-parameter]. --- Firmware/lcd.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/Firmware/lcd.cpp b/Firmware/lcd.cpp index 24eb28ae..6def491e 100644 --- a/Firmware/lcd.cpp +++ b/Firmware/lcd.cpp @@ -157,7 +157,7 @@ uint8_t lcd_write(uint8_t value) return 1; // assume sucess } -static void lcd_begin(uint8_t cols, uint8_t lines, uint8_t dotsize, uint8_t clear) +static void lcd_begin(uint8_t lines, uint8_t dotsize, uint8_t clear) { if (lines > 1) lcd_displayfunction |= LCD_2LINE; lcd_numlines = lines; @@ -247,20 +247,20 @@ void lcd_init(void) pinMode(lcd_enable_pin, OUTPUT); if (fourbitmode) lcd_displayfunction = LCD_4BITMODE | LCD_1LINE | LCD_5x8DOTS; else lcd_displayfunction = LCD_8BITMODE | LCD_1LINE | LCD_5x8DOTS; - lcd_begin(LCD_WIDTH, LCD_HEIGHT, LCD_5x8DOTS, 1); + lcd_begin(LCD_HEIGHT, LCD_5x8DOTS, 1); //lcd_clear(); fdev_setup_stream(lcdout, lcd_putchar, NULL, _FDEV_SETUP_WRITE); //setup lcdout stream } void lcd_refresh(void) { - lcd_begin(LCD_WIDTH, LCD_HEIGHT, LCD_5x8DOTS, 1); + lcd_begin(LCD_HEIGHT, LCD_5x8DOTS, 1); lcd_set_custom_characters(); } void lcd_refresh_noclear(void) { - lcd_begin(LCD_WIDTH, LCD_HEIGHT, LCD_5x8DOTS, 0); + lcd_begin(LCD_HEIGHT, LCD_5x8DOTS, 0); lcd_set_custom_characters(); } From 5846707c5ad04de605ac23217c3564b8253cd882 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Fri, 3 Aug 2018 15:49:20 +0200 Subject: [PATCH 031/141] Remove local variable verbosity_level, which was masking function parameter of the same name. Remove duplicate code to derive verbosity level. Problem manifested itself as compiler warning: sketch/Marlin_main.cpp:2881:6: warning: unused parameter 'verbosity_level' [-Wunused-parameter] bool gcode_M45(bool onlyZ, int8_t verbosity_level) --- Firmware/Marlin_main.cpp | 9 --------- 1 file changed, 9 deletions(-) diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index c10125f6..5c6fb75b 100644 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -2965,15 +2965,6 @@ bool gcode_M45(bool onlyZ, int8_t verbosity_level) if (st_get_position_mm(Z_AXIS) == MESH_HOME_Z_SEARCH) { - - int8_t verbosity_level = 0; - if (code_seen('V')) - { - // Just 'V' without a number counts as V1. - char c = strchr_pointer[1]; - verbosity_level = (c == ' ' || c == '\t' || c == 0) ? 1 : code_value_short(); - } - if (onlyZ) { clean_up_after_endstop_move(); From 55a47d57daba1f6b9471cf92497ba5d96cb8605f Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Mon, 6 Aug 2018 16:57:45 +0200 Subject: [PATCH 032/141] Fix compiler warning: sketch/Marlin.h:151:25: warning: suggest braces around empty body in an 'if' statement [-Wempty-body] --- Firmware/Marlin.h | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/Firmware/Marlin.h b/Firmware/Marlin.h index 2bbab987..a883343d 100644 --- a/Firmware/Marlin.h +++ b/Firmware/Marlin.h @@ -148,7 +148,7 @@ void manage_inactivity(bool ignore_stepper_queue=false); #define disable_z() { WRITE(Z_ENABLE_PIN,!Z_ENABLE_ON); WRITE(Z2_ENABLE_PIN,!Z_ENABLE_ON); axis_known_position[Z_AXIS] = false; } #else #define enable_z() WRITE(Z_ENABLE_PIN, Z_ENABLE_ON) - #define disable_z() ; + #define disable_z() {} #endif #else #ifdef Z_DUAL_STEPPER_DRIVERS @@ -160,8 +160,8 @@ void manage_inactivity(bool ignore_stepper_queue=false); #endif #endif #else - #define enable_z() ; - #define disable_z() ; + #define enable_z() {} + #define disable_z() {} #endif @@ -475,4 +475,4 @@ void M600_load_filament(); void mmu_M600_load_filament(bool automatic); void M600_load_filament_movements(); void M600_wait_for_user(); -void M600_check_state(); \ No newline at end of file +void M600_check_state(); From 72cfa1b1243fb1f76dcebd8bc23c82e094b056cb Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Mon, 6 Aug 2018 17:02:48 +0200 Subject: [PATCH 033/141] Fix 4 compiler warnings of type: sketch/planner.cpp:872:59: warning: suggest braces around empty body in an 'if' statement [-Wempty-body] --- Firmware/planner.cpp | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/Firmware/planner.cpp b/Firmware/planner.cpp index e89cbef8..ddbee23e 100644 --- a/Firmware/planner.cpp +++ b/Firmware/planner.cpp @@ -869,22 +869,22 @@ block->steps_y.wide = labs((target[X_AXIS]-position[X_AXIS]) - (target[Y_AXIS]-p enable_e0(); g_uc_extruder_last_move[0] = BLOCK_BUFFER_SIZE*2; - if(g_uc_extruder_last_move[1] == 0) disable_e1(); - if(g_uc_extruder_last_move[2] == 0) disable_e2(); + if(g_uc_extruder_last_move[1] == 0) {disable_e1();} + if(g_uc_extruder_last_move[2] == 0) {disable_e2();} break; case 1: enable_e1(); g_uc_extruder_last_move[1] = BLOCK_BUFFER_SIZE*2; - if(g_uc_extruder_last_move[0] == 0) disable_e0(); - if(g_uc_extruder_last_move[2] == 0) disable_e2(); + if(g_uc_extruder_last_move[0] == 0) {disable_e0();} + if(g_uc_extruder_last_move[2] == 0) {disable_e2();} break; case 2: enable_e2(); g_uc_extruder_last_move[2] = BLOCK_BUFFER_SIZE*2; - if(g_uc_extruder_last_move[0] == 0) disable_e0(); - if(g_uc_extruder_last_move[1] == 0) disable_e1(); + if(g_uc_extruder_last_move[0] == 0) {disable_e0();} + if(g_uc_extruder_last_move[1] == 0) {disable_e1();} break; } } From 30438833c68be50d07a8b1e0736e99b7998e05a3 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Mon, 6 Aug 2018 17:07:04 +0200 Subject: [PATCH 034/141] Fix compiler warning sketch/Marlin_main.cpp:6584:19: warning: comparison is always true due to limited range of data type [-Wtype-limits] --- Firmware/Marlin_main.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index e69ce5a1..3bba1b6b 100644 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -6580,8 +6580,8 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) else if (code_seen('S')) { // Sxxx Iyyy - Set compensation ustep value S for compensation table index I int16_t usteps = code_value(); if (code_seen('I')) { - byte index = code_value(); - if ((index >= 0) && (index < 5)) { + uint8_t index = code_value(); + if (index < 5) { EEPROM_save_B(EEPROM_PROBE_TEMP_SHIFT + index * 2, &usteps); SERIAL_PROTOCOLLN("OK"); SERIAL_PROTOCOLLN("index, temp, ustep, um"); From 5f4380cafb81efb35de23d5cc6deb12db10fec11 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Mon, 6 Aug 2018 17:27:58 +0200 Subject: [PATCH 035/141] Remove unused function, fix compiler warning: sketch/Marlin_main.cpp:8994:6: warning: unused parameter 'extruder' [-Wunused-parameter] --- Firmware/Marlin_main.cpp | 4 ---- 1 file changed, 4 deletions(-) diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index 3bba1b6b..44dbfb76 100644 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -8991,10 +8991,6 @@ void mmu_load_to_nozzle() { if (!saved_e_relative_mode) axis_relative_modes[E_AXIS] = false; } -void mmu_switch_extruder(uint8_t extruder) { - -} - void M600_check_state() { //Wait for user to check the state lcd_change_fil_state = 0; From 7a6cbf75b9f43d582c24f61a1a058cefdf239992 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Mon, 6 Aug 2018 18:10:40 +0200 Subject: [PATCH 036/141] Fix compiler warnings: sketch/cardreader.cpp: In member function 'void CardReader::openFile(const char*, bool, bool)': sketch/cardreader.cpp:350:25: warning: ordered comparison of pointer with integer zero [-Wextra] sketch/cardreader.cpp:355:22: warning: ordered comparison of pointer with integer zero [-Wextra] --- Firmware/cardreader.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/Firmware/cardreader.cpp b/Firmware/cardreader.cpp index fe181362..6f61d23b 100644 --- a/Firmware/cardreader.cpp +++ b/Firmware/cardreader.cpp @@ -343,16 +343,16 @@ void CardReader::openFile(const char* name,bool read, bool replace_current/*=tru curDir=&root; const char *fname=name; - char *dirname_start,*dirname_end; + const char *dirname_start,*dirname_end; if(name[0]=='/') { - dirname_start=strchr(name,'/')+1; - while(dirname_start>0) + dirname_start = name + 1; + while(*dirname_start) { dirname_end=strchr(dirname_start,'/'); //SERIAL_ECHO("start:");SERIAL_ECHOLN((int)(dirname_start-name)); //SERIAL_ECHO("end :");SERIAL_ECHOLN((int)(dirname_end-name)); - if(dirname_end>0 && dirname_end>dirname_start) + if(dirname_end && dirname_end>dirname_start) { char subdirname[13]; strncpy(subdirname, dirname_start, dirname_end-dirname_start); From 2e719c788551f5b90f7c5d7e19f693cf40089828 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Mon, 6 Aug 2018 20:49:40 +0200 Subject: [PATCH 037/141] Fix stack corruption for folder name longer than 12 characters. Save 260B of flash memory. Move duplicate code to separate method. Fix compiler warnings: sketch/cardreader.cpp:448:25: warning: ordered comparison of pointer with integer zero [-Wextra] sketch/cardreader.cpp:453:22: warning: ordered comparison of pointer with integer zero [-Wextra] --- Firmware/cardreader.cpp | 180 ++++++++++++++++++---------------------- Firmware/cardreader.h | 2 + 2 files changed, 82 insertions(+), 100 deletions(-) diff --git a/Firmware/cardreader.cpp b/Firmware/cardreader.cpp index 6f61d23b..bea3fdec 100644 --- a/Firmware/cardreader.cpp +++ b/Firmware/cardreader.cpp @@ -288,6 +288,76 @@ void CardReader::getAbsFilename(char *t) else t[0]=0; } +/** + * @brief Dive into subfolder + * + * Method sets curDir to point to root, in case fileName is null. + * Method sets curDir to point to workDir, in case fileName path is relative + * (doesn't start with '/') + * Method sets curDir to point to dir, which is specified by absolute path + * specified by fileName. In such case fileName is updated so it points to + * file name without the path. + * + * @param[in,out] fileName + * expects file name including path + * in case of absolute path, file name without path is returned + * @param[in,out] dir SdFile object to operate with, + * in case of absolute path, curDir is modified to point to dir, + * so it is not possible to create on stack inside this function, + * as curDir would point to destroyed object. + */ +void CardReader::diveSubfolder (const char *fileName, SdFile& dir) +{ + curDir=&root; + if (!fileName) return; + + const char *dirname_start, *dirname_end; + if (fileName[0] == '/') // absolute path + { + dirname_start = fileName + 1; + while (*dirname_start) + { + dirname_end = strchr(dirname_start, '/'); + //SERIAL_ECHO("start:");SERIAL_ECHOLN((int)(dirname_start-name)); + //SERIAL_ECHO("end :");SERIAL_ECHOLN((int)(dirname_end-name)); + if (dirname_end && dirname_end > dirname_start) + { + const size_t maxLen = 12; + char subdirname[maxLen+1]; + subdirname[maxLen] = 0; + const size_t len = (dirname_end-dirname_start)>maxLen ? maxLen : dirname_end-dirname_start; + strncpy(subdirname, dirname_start, len); + SERIAL_ECHOLN(subdirname); + if (!dir.open(curDir, subdirname, O_READ)) + { + SERIAL_PROTOCOLRPGM(_T(MSG_SD_OPEN_FILE_FAIL)); + SERIAL_PROTOCOL(subdirname); + SERIAL_PROTOCOLLNPGM("."); + return; + } + else + { + //SERIAL_ECHOLN("dive ok"); + } + + curDir = &dir; + dirname_start = dirname_end + 1; + } + else // the reminder after all /fsa/fdsa/ is the filename + { + fileName = dirname_start; + //SERIAL_ECHOLN("remaider"); + //SERIAL_ECHOLN(fname); + break; + } + + } + } + else //relative path + { + curDir = &workDir; + } +} void CardReader::openFile(const char* name,bool read, bool replace_current/*=true*/) { @@ -340,53 +410,9 @@ void CardReader::openFile(const char* name,bool read, bool replace_current/*=tru SdFile myDir; - curDir=&root; const char *fname=name; - - const char *dirname_start,*dirname_end; - if(name[0]=='/') - { - dirname_start = name + 1; - while(*dirname_start) - { - dirname_end=strchr(dirname_start,'/'); - //SERIAL_ECHO("start:");SERIAL_ECHOLN((int)(dirname_start-name)); - //SERIAL_ECHO("end :");SERIAL_ECHOLN((int)(dirname_end-name)); - if(dirname_end && dirname_end>dirname_start) - { - char subdirname[13]; - strncpy(subdirname, dirname_start, dirname_end-dirname_start); - subdirname[dirname_end-dirname_start]=0; - SERIAL_ECHOLN(subdirname); - if(!myDir.open(curDir,subdirname,O_READ)) - { - SERIAL_PROTOCOLRPGM(_T(MSG_SD_OPEN_FILE_FAIL)); - SERIAL_PROTOCOL(subdirname); - SERIAL_PROTOCOLLNPGM("."); - return; - } - else - { - //SERIAL_ECHOLN("dive ok"); - } - - curDir=&myDir; - dirname_start=dirname_end+1; - } - else // the reminder after all /fsa/fdsa/ is the filename - { - fname=dirname_start; - //SERIAL_ECHOLN("remaider"); - //SERIAL_ECHOLN(fname); - break; - } - - } - } - else //relative path - { - curDir=&workDir; - } + diveSubfolder(fname,myDir); + if(read) { if (file.open(curDir, fname, O_READ)) @@ -431,60 +457,14 @@ void CardReader::openFile(const char* name,bool read, bool replace_current/*=tru void CardReader::removeFile(const char* name) { - if(!cardOK) - return; - file.close(); - sdprinting = false; - - - SdFile myDir; - curDir=&root; - const char *fname=name; - - char *dirname_start,*dirname_end; - if(name[0]=='/') - { - dirname_start=strchr(name,'/')+1; - while(dirname_start>0) - { - dirname_end=strchr(dirname_start,'/'); - //SERIAL_ECHO("start:");SERIAL_ECHOLN((int)(dirname_start-name)); - //SERIAL_ECHO("end :");SERIAL_ECHOLN((int)(dirname_end-name)); - if(dirname_end>0 && dirname_end>dirname_start) - { - char subdirname[13]; - strncpy(subdirname, dirname_start, dirname_end-dirname_start); - subdirname[dirname_end-dirname_start]=0; - SERIAL_ECHOLN(subdirname); - if(!myDir.open(curDir,subdirname,O_READ)) - { - SERIAL_PROTOCOLRPGM("open failed, File: "); - SERIAL_PROTOCOL(subdirname); - SERIAL_PROTOCOLLNPGM("."); - return; - } - else - { - //SERIAL_ECHOLN("dive ok"); - } - - curDir=&myDir; - dirname_start=dirname_end+1; - } - else // the reminder after all /fsa/fdsa/ is the filename - { - fname=dirname_start; - //SERIAL_ECHOLN("remaider"); - //SERIAL_ECHOLN(fname); - break; - } - - } - } - else //relative path - { - curDir=&workDir; - } + if(!cardOK) return; + file.close(); + sdprinting = false; + + SdFile myDir; + const char *fname=name; + diveSubfolder(fname,myDir); + if (file.remove(curDir, fname)) { SERIAL_PROTOCOLPGM("File deleted:"); diff --git a/Firmware/cardreader.h b/Firmware/cardreader.h index 4acc9376..f287a44f 100644 --- a/Firmware/cardreader.h +++ b/Firmware/cardreader.h @@ -154,6 +154,8 @@ private: LsAction lsAction; //stored for recursion. int16_t nrFiles; //counter for the files in the current directory and recycled as position counter for getting the nrFiles'th name in the directory. char* diveDirName; + + void diveSubfolder (const char *fileName, SdFile& dir); void lsDive(const char *prepend, SdFile parent, const char * const match=NULL); #ifdef SDCARD_SORT_ALPHA void flush_presort(); From 7364b6cf8088e44ed8161099cecc9c1c6882d9bb Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Mon, 6 Aug 2018 20:57:17 +0200 Subject: [PATCH 038/141] Do not compare signed value with unsigned, add parentheses. --- Firmware/cardreader.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Firmware/cardreader.cpp b/Firmware/cardreader.cpp index bea3fdec..44db2c19 100644 --- a/Firmware/cardreader.cpp +++ b/Firmware/cardreader.cpp @@ -325,7 +325,7 @@ void CardReader::diveSubfolder (const char *fileName, SdFile& dir) const size_t maxLen = 12; char subdirname[maxLen+1]; subdirname[maxLen] = 0; - const size_t len = (dirname_end-dirname_start)>maxLen ? maxLen : dirname_end-dirname_start; + const size_t len = ((static_cast(dirname_end-dirname_start))>maxLen) ? maxLen : (dirname_end-dirname_start); strncpy(subdirname, dirname_start, len); SERIAL_ECHOLN(subdirname); if (!dir.open(curDir, subdirname, O_READ)) From 95d13cbb59bfbe574400c657a719062415e26ff2 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Tue, 7 Aug 2018 12:51:03 +0200 Subject: [PATCH 039/141] Fix compiler warning: sketch/mesh_bed_calibration.cpp:135:20: warning: unused parameter 'i' [-Wunused-parameter] --- Firmware/mesh_bed_calibration.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Firmware/mesh_bed_calibration.cpp b/Firmware/mesh_bed_calibration.cpp index 48bb2071..f22f4d0d 100644 --- a/Firmware/mesh_bed_calibration.cpp +++ b/Firmware/mesh_bed_calibration.cpp @@ -132,7 +132,7 @@ const float bed_ref_points[] PROGMEM = { static inline float sqr(float x) { return x * x; } #ifdef HEATBED_V2 -static inline bool point_on_1st_row(const uint8_t i) +static inline bool point_on_1st_row(const uint8_t /*i*/) { return false; } From 523c9cd737e7bb38dec268a797d301dd8a551000 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Tue, 7 Aug 2018 12:58:15 +0200 Subject: [PATCH 040/141] Fix compiler warning: sketch/mesh_bed_calibration.cpp:205:34: warning: unused parameter 'verbosity_level' [-Wunused-parameter] --- Firmware/mesh_bed_calibration.cpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/Firmware/mesh_bed_calibration.cpp b/Firmware/mesh_bed_calibration.cpp index f22f4d0d..f4040551 100644 --- a/Firmware/mesh_bed_calibration.cpp +++ b/Firmware/mesh_bed_calibration.cpp @@ -209,7 +209,10 @@ BedSkewOffsetDetectionResultType calculate_machine_skew_and_offset_LS( float *vec_x, float *vec_y, float *cntr, - int8_t verbosity_level + int8_t +#ifdef SUPPORT_VERBOSITY + verbosity_level +#endif //SUPPORT_VERBOSITY ) { float angleDiff; From 0d35451544d990d193b6c7cc5bcb196da1549919 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Tue, 7 Aug 2018 13:00:22 +0200 Subject: [PATCH 041/141] Fix compiler warning: sketch/mesh_bed_calibration.cpp:966:13: warning: unused parameter 'verbosity_level' [-Wunused-parameter] --- Firmware/mesh_bed_calibration.cpp | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/Firmware/mesh_bed_calibration.cpp b/Firmware/mesh_bed_calibration.cpp index f4040551..c7d7dd46 100644 --- a/Firmware/mesh_bed_calibration.cpp +++ b/Firmware/mesh_bed_calibration.cpp @@ -963,7 +963,11 @@ static inline void update_current_position_z() } // At the current position, find the Z stop. -inline bool find_bed_induction_sensor_point_z(float minimum_z, uint8_t n_iter, int verbosity_level) +inline bool find_bed_induction_sensor_point_z(float minimum_z, uint8_t n_iter, int +#ifdef SUPPORT_VERBOSITY + verbosity_level +#endif //SUPPORT_VERBOSITY + ) { #ifdef TMC2130 FORCE_HIGH_POWER_START; From e9d8ed8599b74d3d170491586e82650d4122b051 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Tue, 7 Aug 2018 13:58:06 +0200 Subject: [PATCH 042/141] Fix compiler warning: sketch/mesh_bed_calibration.cpp:1057:13: warning: unused parameter 'verbosity_level' [-Wunused-parameter] --- Firmware/mesh_bed_calibration.cpp | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/Firmware/mesh_bed_calibration.cpp b/Firmware/mesh_bed_calibration.cpp index c7d7dd46..32ed0c04 100644 --- a/Firmware/mesh_bed_calibration.cpp +++ b/Firmware/mesh_bed_calibration.cpp @@ -1054,7 +1054,11 @@ extern bool xyzcal_find_bed_induction_sensor_point_xy(); #endif //HEATBED_V2 #ifdef HEATBED_V2 -inline bool find_bed_induction_sensor_point_xy(int verbosity_level) +inline bool find_bed_induction_sensor_point_xy(int +#if !defined (NEW_XYZCAL) && defined (SUPPORT_VERBOSITY) + verbosity_level +#endif + ) { #ifdef NEW_XYZCAL return xyzcal_find_bed_induction_sensor_point_xy(); From aa0f1fd80b948314034809a685de7db02cacf488 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Tue, 7 Aug 2018 14:20:51 +0200 Subject: [PATCH 043/141] Fix compiler warnings sketch/mesh_bed_calibration.cpp:150:21: warning: unused parameter 'npts' [-Wunused-parameter] sketch/mesh_bed_calibration.cpp:172:21: warning: unused parameter 'npts' [-Wunused-parameter] --- Firmware/mesh_bed_calibration.cpp | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/Firmware/mesh_bed_calibration.cpp b/Firmware/mesh_bed_calibration.cpp index 32ed0c04..82320c4c 100644 --- a/Firmware/mesh_bed_calibration.cpp +++ b/Firmware/mesh_bed_calibration.cpp @@ -147,7 +147,7 @@ static inline bool point_on_1st_row(const uint8_t i) // The first row of points may not be fully reachable // and the y values may be shortened a bit by the bed carriage // pulling the belt up. -static inline float point_weight_x(const uint8_t i, const uint8_t npts, const float &y) +static inline float point_weight_x(const uint8_t i, const float &y) { float w = 1.f; if (point_on_1st_row(i)) { @@ -169,7 +169,7 @@ static inline float point_weight_x(const uint8_t i, const uint8_t npts, const fl // The first row of points may not be fully reachable // and the y values may be shortened a bit by the bed carriage // pulling the belt up. -static inline float point_weight_y(const uint8_t i, const uint8_t npts, const float &y) +static inline float point_weight_y(const uint8_t i, const float &y) { float w = 1.f; if (point_on_1st_row(i)) { @@ -294,7 +294,7 @@ BedSkewOffsetDetectionResultType calculate_machine_skew_and_offset_LS( (c == 0) ? 1.f : ((c == 2) ? (-s1 * measured_pts[2 * i]) : (-c2 * measured_pts[2 * i + 1])); - float w = point_weight_x(i, npts, measured_pts[2 * i + 1]); + float w = point_weight_x(i, measured_pts[2 * i + 1]); acc += a * b * w; } // Second for the residuum in the y axis. @@ -309,7 +309,7 @@ BedSkewOffsetDetectionResultType calculate_machine_skew_and_offset_LS( (c == 1) ? 1.f : ((c == 2) ? ( c1 * measured_pts[2 * i]) : (-s2 * measured_pts[2 * i + 1])); - float w = point_weight_y(i, npts, measured_pts[2 * i + 1]); + float w = point_weight_y(i, measured_pts[2 * i + 1]); acc += a * b * w; } } @@ -325,7 +325,7 @@ BedSkewOffsetDetectionResultType calculate_machine_skew_and_offset_LS( ((r == 2) ? (-s1 * measured_pts[2 * i]) : (-c2 * measured_pts[2 * i + 1]))); float fx = c1 * measured_pts[2 * i] - s2 * measured_pts[2 * i + 1] + cntr[0] - pgm_read_float(true_pts + i * 2); - float w = point_weight_x(i, npts, measured_pts[2 * i + 1]); + float w = point_weight_x(i, measured_pts[2 * i + 1]); acc += j * fx * w; } { @@ -335,7 +335,7 @@ BedSkewOffsetDetectionResultType calculate_machine_skew_and_offset_LS( ((r == 2) ? ( c1 * measured_pts[2 * i]) : (-s2 * measured_pts[2 * i + 1]))); float fy = s1 * measured_pts[2 * i] + c2 * measured_pts[2 * i + 1] + cntr[1] - pgm_read_float(true_pts + i * 2 + 1); - float w = point_weight_y(i, npts, measured_pts[2 * i + 1]); + float w = point_weight_y(i, measured_pts[2 * i + 1]); acc += j * fy * w; } } @@ -456,7 +456,7 @@ BedSkewOffsetDetectionResultType calculate_machine_skew_and_offset_LS( #ifdef SUPPORT_VERBOSITY if(verbosity_level >= 20) SERIAL_ECHOPGM("Point on first row"); #endif // SUPPORT_VERBOSITY - float w = point_weight_y(i, npts, measured_pts[2 * i + 1]); + float w = point_weight_y(i, measured_pts[2 * i + 1]); if (sqrt(errX) > BED_CALIBRATION_POINT_OFFSET_MAX_1ST_ROW_X || (w != 0.f && sqrt(errY) > BED_CALIBRATION_POINT_OFFSET_MAX_1ST_ROW_Y)) { result = BED_SKEW_OFFSET_DETECTION_FITTING_FAILED; @@ -553,7 +553,7 @@ BedSkewOffsetDetectionResultType calculate_machine_skew_and_offset_LS( for (int8_t i = 0; i < npts; ++ i) { float x = vec_x[0] * measured_pts[i * 2] + vec_y[0] * measured_pts[i * 2 + 1]; float y = vec_x[1] * measured_pts[i * 2] + vec_y[1] * measured_pts[i * 2 + 1]; - float w = point_weight_x(i, npts, y); + float w = point_weight_x(i, y); cntr[0] += w * (pgm_read_float(true_pts + i * 2) - x); wx += w; #ifdef SUPPORT_VERBOSITY @@ -570,7 +570,7 @@ BedSkewOffsetDetectionResultType calculate_machine_skew_and_offset_LS( MYSERIAL.print(wx); } #endif // SUPPORT_VERBOSITY - w = point_weight_y(i, npts, y); + w = point_weight_y(i, y); cntr[1] += w * (pgm_read_float(true_pts + i * 2 + 1) - y); wy += w; #ifdef SUPPORT_VERBOSITY From 4c146a5b2cb95a2b8e941c931053e7b8f1735cc9 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Tue, 7 Aug 2018 14:44:53 +0200 Subject: [PATCH 044/141] Fix compiler warning: sketch/mesh_bed_leveling.cpp:24:6: warning: unused parameter 'use_default' [-Wunused-parameter]. --- Firmware/mesh_bed_leveling.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Firmware/mesh_bed_leveling.cpp b/Firmware/mesh_bed_leveling.cpp index 506d3746..746458ae 100644 --- a/Firmware/mesh_bed_leveling.cpp +++ b/Firmware/mesh_bed_leveling.cpp @@ -21,7 +21,7 @@ static inline bool vec_undef(const float v[2]) return vx[0] == 0x0FFFFFFFF || vx[1] == 0x0FFFFFFFF; } -void mesh_bed_leveling::get_meas_xy(int ix, int iy, float &x, float &y, bool use_default) +void mesh_bed_leveling::get_meas_xy(int ix, int iy, float &x, float &y, bool /*use_default*/) { #if 0 float cntr[2] = { From 548f4cb1fa51ebd6ce560547a729c2dc622bce0d Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Tue, 7 Aug 2018 15:01:49 +0200 Subject: [PATCH 045/141] Fix compiler warning sketch/mmu.cpp:32:6: warning: unused parameter 'extr' [-Wunused-parameter] --- Firmware/mmu.cpp | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/Firmware/mmu.cpp b/Firmware/mmu.cpp index 6afa8229..eedd8f33 100644 --- a/Firmware/mmu.cpp +++ b/Firmware/mmu.cpp @@ -29,7 +29,11 @@ void extr_mov(float shift, float feed_rate) } -void change_extr(int extr) { //switches multiplexer for extruders +void change_extr(int +#ifdef SNMM + extr +#endif //SNMM + ) { //switches multiplexer for extruders #ifdef SNMM st_synchronize(); delay(100); From 453b1990576d9991dfd50e7cc10fab6297b52bfb Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Tue, 7 Aug 2018 15:05:18 +0200 Subject: [PATCH 046/141] Save 8B flash, fix compiler warning sketch/sound.cpp:62:6: warning: unused parameter 'eSoundClass' [-Wunused-parameter] --- Firmware/lcd.cpp | 2 +- Firmware/sound.cpp | 2 +- Firmware/sound.h | 2 +- Firmware/ultralcd.cpp | 2 +- 4 files changed, 4 insertions(+), 4 deletions(-) diff --git a/Firmware/lcd.cpp b/Firmware/lcd.cpp index 6def491e..d6574d4b 100644 --- a/Firmware/lcd.cpp +++ b/Firmware/lcd.cpp @@ -691,7 +691,7 @@ void lcd_beeper_quick_feedback(void) { SET_OUTPUT(BEEPER); //-// -Sound_MakeSound(e_SOUND_CLASS_Echo,e_SOUND_TYPE_ButtonEcho); +Sound_MakeSound(e_SOUND_TYPE_ButtonEcho); /* for(int8_t i = 0; i < 10; i++) { diff --git a/Firmware/sound.cpp b/Firmware/sound.cpp index d808dfa8..6e41d252 100644 --- a/Firmware/sound.cpp +++ b/Firmware/sound.cpp @@ -59,7 +59,7 @@ switch(eSoundMode) Sound_SaveMode(); } -void Sound_MakeSound(eSOUND_CLASS eSoundClass,eSOUND_TYPE eSoundType) +void Sound_MakeSound(eSOUND_TYPE eSoundType) { switch(eSoundMode) { diff --git a/Firmware/sound.h b/Firmware/sound.h index 9415b763..479f113e 100644 --- a/Firmware/sound.h +++ b/Firmware/sound.h @@ -26,7 +26,7 @@ extern void Sound_Init(void); extern void Sound_Default(void); extern void Sound_Save(void); extern void Sound_CycleState(void); -extern void Sound_MakeSound(eSOUND_CLASS eSoundClass,eSOUND_TYPE eSoundType); +extern void Sound_MakeSound(eSOUND_TYPE eSoundType); //static void Sound_DoSound_Echo(void); //static void Sound_DoSound_Prompt(void); diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index 0ca7cf92..2f3db906 100644 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -5188,7 +5188,7 @@ void unload_filament() disable_e2(); delay(100); - Sound_MakeSound(e_SOUND_CLASS_Prompt, e_SOUND_TYPE_StandardPrompt); + Sound_MakeSound(e_SOUND_TYPE_StandardPrompt); uint8_t counterBeep = 0; while (!lcd_clicked() && (counterBeep < 50)) { delay_keep_alive(100); From cf069f3fc2f728348fde50ed27033301a4fd7fa8 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Tue, 7 Aug 2018 15:07:51 +0200 Subject: [PATCH 047/141] Fix compiler warning sketch/ultralcd.cpp:53:31: warning: missing initializer for member 'MenuData::BabyStep::babystepMem' [-Wmissing-field-initializers] --- Firmware/ultralcd.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index 2f3db906..0e9e67a9 100644 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -50,7 +50,7 @@ static void lcd_sd_updir(); // State of the currently active menu. // C Union manages sharing of the static memory by all the menus. -union MenuData menuData = { 0 }; +union MenuData menuData; int8_t ReInitLCD = 0; From c0f37efbad0f5fd27005588fe5d39160e0f6a6f1 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Tue, 7 Aug 2018 15:29:58 +0200 Subject: [PATCH 048/141] Save 278B of flash. Remove unused function parameters. Make functions static. Fix compiler warnings: sketch/ultralcd.cpp:292:6: warning: unused parameter 'pstr' [-Wunused-parameter] sketch/ultralcd.cpp:292:6: warning: unused parameter 'filename' [-Wunused-parameter] sketch/ultralcd.cpp:344:6: warning: unused parameter 'pstr' [-Wunused-parameter] sketch/ultralcd.cpp:364:6: warning: unused parameter 'pstr' [-Wunused-parameter] sketch/ultralcd.cpp:385:6: warning: unused parameter 'pstr' [-Wunused-parameter] sketch/ultralcd.cpp:6920:6: warning: unused parameter 'longFilename' [-Wunused-parameter] sketch/ultralcd.cpp:6965:6: warning: unused parameter 'longFilename' [-Wunused-parameter] --- Firmware/ultralcd.cpp | 40 ++++++++++++++++++++++------------------ 1 file changed, 22 insertions(+), 18 deletions(-) diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index 0e9e67a9..9c18586b 100644 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -187,8 +187,8 @@ static void lcd_delta_calibrate_menu(); /* Different types of actions that can be used in menu items. */ -void menu_action_sdfile(const char* filename, char* longFilename); -void menu_action_sddirectory(const char* filename, char* longFilename); +static void menu_action_sdfile(const char* filename); +static void menu_action_sddirectory(const char* filename); #define ENCODER_FEEDRATE_DEADZONE 10 @@ -289,7 +289,7 @@ static inline void lcd_print_time() { } -void lcd_implementation_drawmenu_sdfile_selected(uint8_t row, const char* pstr, const char* filename, char* longFilename) +static void lcd_implementation_drawmenu_sdfile_selected(uint8_t row, char* longFilename) { char c; int enc_dif = lcd_encoder_diff; @@ -341,7 +341,7 @@ void lcd_implementation_drawmenu_sdfile_selected(uint8_t row, const char* pstr, while(n--) lcd_print(' '); } -void lcd_implementation_drawmenu_sdfile(uint8_t row, const char* pstr, const char* filename, char* longFilename) +static void lcd_implementation_drawmenu_sdfile(uint8_t row, const char* filename, char* longFilename) { char c; uint8_t n = LCD_WIDTH - 1; @@ -361,7 +361,7 @@ void lcd_implementation_drawmenu_sdfile(uint8_t row, const char* pstr, const cha while(n--) lcd_print(' '); } -void lcd_implementation_drawmenu_sddirectory_selected(uint8_t row, const char* pstr, const char* filename, char* longFilename) +static void lcd_implementation_drawmenu_sddirectory_selected(uint8_t row, const char* filename, char* longFilename) { char c; uint8_t n = LCD_WIDTH - 2; @@ -382,7 +382,7 @@ void lcd_implementation_drawmenu_sddirectory_selected(uint8_t row, const char* p while(n--) lcd_print(' '); } -void lcd_implementation_drawmenu_sddirectory(uint8_t row, const char* pstr, const char* filename, char* longFilename) +static void lcd_implementation_drawmenu_sddirectory(uint8_t row, const char* filename, char* longFilename) { char c; uint8_t n = LCD_WIDTH - 2; @@ -406,7 +406,7 @@ void lcd_implementation_drawmenu_sddirectory(uint8_t row, const char* pstr, cons -#define MENU_ITEM_SDDIR(str, str_fn, str_fnl) do { if (menu_item_sddir(str, str_fn, str_fnl)) return; } while (0) +#define MENU_ITEM_SDDIR(str_fn, str_fnl) do { if (menu_item_sddir(str_fn, str_fnl)) return; } while (0) //#define MENU_ITEM_SDDIR(str, str_fn, str_fnl) MENU_ITEM(sddirectory, str, str_fn, str_fnl) //extern uint8_t menu_item_sddir(const char* str, const char* str_fn, char* str_fnl); @@ -415,7 +415,7 @@ void lcd_implementation_drawmenu_sddirectory(uint8_t row, const char* pstr, cons //extern uint8_t menu_item_sdfile(const char* str, const char* str_fn, char* str_fnl); -uint8_t menu_item_sddir(const char* str, const char* str_fn, char* str_fnl) +uint8_t menu_item_sddir(const char* str_fn, char* str_fnl) { #ifdef NEW_SD_MENU // str_fnl[18] = 0; @@ -446,15 +446,15 @@ uint8_t menu_item_sddir(const char* str, const char* str_fn, char* str_fnl) if (lcd_draw_update) { if (lcd_encoder == menu_item) - lcd_implementation_drawmenu_sddirectory_selected(menu_row, str, str_fn, str_fnl); + lcd_implementation_drawmenu_sddirectory_selected(menu_row, str_fn, str_fnl); else - lcd_implementation_drawmenu_sddirectory(menu_row, str, str_fn, str_fnl); + lcd_implementation_drawmenu_sddirectory(menu_row, str_fn, str_fnl); } if (menu_clicked && (lcd_encoder == menu_item)) { menu_clicked = false; lcd_update_enabled = 0; - menu_action_sddirectory(str_fn, str_fnl); + menu_action_sddirectory(str_fn); lcd_update_enabled = 1; return menu_item_ret(); } @@ -465,7 +465,11 @@ uint8_t menu_item_sddir(const char* str, const char* str_fn, char* str_fnl) #endif //NEW_SD_MENU } -uint8_t menu_item_sdfile(const char* str, const char* str_fn, char* str_fnl) +static uint8_t menu_item_sdfile(const char* +#ifdef NEW_SD_MENU + str +#endif //NEW_SD_MENU + ,const char* str_fn, char* str_fnl) { #ifdef NEW_SD_MENU // printf_P(PSTR("menu sdfile\n")); @@ -512,13 +516,13 @@ uint8_t menu_item_sdfile(const char* str, const char* str_fn, char* str_fnl) if (lcd_draw_update) { if (lcd_encoder == menu_item) - lcd_implementation_drawmenu_sdfile_selected(menu_row, str, str_fn, str_fnl); + lcd_implementation_drawmenu_sdfile_selected(menu_row, str_fnl); else - lcd_implementation_drawmenu_sdfile(menu_row, str, str_fn, str_fnl); + lcd_implementation_drawmenu_sdfile(menu_row, str_fn, str_fnl); } if (menu_clicked && (lcd_encoder == menu_item)) { - menu_action_sdfile(str_fn, str_fnl); + menu_action_sdfile(str_fn); return menu_item_ret(); } } @@ -5910,7 +5914,7 @@ void lcd_sdcard_menu() #endif if (card.filenameIsDir) - MENU_ITEM_SDDIR(_T(MSG_CARD_MENU), card.filename, card.longFilename); + MENU_ITEM_SDDIR(card.filename, card.longFilename); else MENU_ITEM_SDFILE(_T(MSG_CARD_MENU), card.filename, card.longFilename); } else { @@ -6917,7 +6921,7 @@ static bool check_file(const char* filename) { } -void menu_action_sdfile(const char* filename, char* longFilename) +static void menu_action_sdfile(const char* filename) { loading_flag = false; char cmd[30]; @@ -6962,7 +6966,7 @@ void menu_action_sdfile(const char* filename, char* longFilename) lcd_return_to_status(); } -void menu_action_sddirectory(const char* filename, char* longFilename) +void menu_action_sddirectory(const char* filename) { uint8_t depth = (uint8_t)card.getWorkDirDepth(); From e06e19edf59d823fe84fb108d3d9d57b8a610519 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Tue, 7 Aug 2018 15:46:23 +0200 Subject: [PATCH 049/141] Fix showing calibration results. Messages: _i("XYZ calibration failed. Bed calibration point was not found.") _T(MSG_BED_SKEW_OFFSET_DETECTION_FITTING_FAILED); _i("XYZ calibration failed. Front calibration points not reachable.") _i("XYZ calibration failed. Right front calibration point not reachable.") _i("XYZ calibration failed. Left front calibration point not reachable."); were never shown. Fix compiler warnings: sketch/ultralcd.cpp:3476:19: warning: comparison is always false due to limited range of data type [-Wtype-limits] sketch/ultralcd.cpp:3478:26: warning: comparison is always false due to limited range of data type [-Wtype-limits] --- Firmware/ultralcd.cpp | 2 +- Firmware/ultralcd.h | 3 ++- 2 files changed, 3 insertions(+), 2 deletions(-) diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index 9c18586b..5c66a0af 100644 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -3470,7 +3470,7 @@ int8_t lcd_show_fullscreen_message_yes_no_and_wait_P(const char *msg, bool allow } } -void lcd_bed_calibration_show_result(uint8_t result, uint8_t point_too_far_mask) +void lcd_bed_calibration_show_result(BedSkewOffsetDetectionResultType result, uint8_t point_too_far_mask) { const char *msg = NULL; if (result == BED_SKEW_OFFSET_DETECTION_POINT_NOT_FOUND) { diff --git a/Firmware/ultralcd.h b/Firmware/ultralcd.h index 77da5933..fb655ccb 100644 --- a/Firmware/ultralcd.h +++ b/Firmware/ultralcd.h @@ -5,6 +5,7 @@ #include "lcd.h" #include "conv2str.h" #include "menu.h" +#include "mesh_bed_calibration.h" extern int lcd_puts_P(const char* str); extern int lcd_printf_P(const char* format, ...); @@ -143,7 +144,7 @@ extern const char* lcd_display_message_fullscreen_P(const char *msg); #endif // Show the result of the calibration process on the LCD screen. - extern void lcd_bed_calibration_show_result(uint8_t result, uint8_t point_too_far_mask); + extern void lcd_bed_calibration_show_result(BedSkewOffsetDetectionResultType result, uint8_t point_too_far_mask); extern void lcd_diag_show_end_stops(); From 880ed6778530d23a894fd2b46e3ce22f89820787 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Tue, 7 Aug 2018 16:00:35 +0200 Subject: [PATCH 050/141] Fix compiler warning: sketch/stepper.cpp:1499:6: warning: unused parameter 'address' [-Wunused-parameter]. --- Firmware/stepper.cpp | 4 ++-- Firmware/stepper.h | 3 ++- 2 files changed, 4 insertions(+), 3 deletions(-) diff --git a/Firmware/stepper.cpp b/Firmware/stepper.cpp index 8f74ae6f..3bc3344b 100644 --- a/Firmware/stepper.cpp +++ b/Firmware/stepper.cpp @@ -1496,16 +1496,16 @@ void babystep(const uint8_t axis,const bool direction) } #endif //BABYSTEPPING +#if defined(DIGIPOTSS_PIN) && DIGIPOTSS_PIN > -1 void digitalPotWrite(int address, int value) // From Arduino DigitalPotControl example { - #if defined(DIGIPOTSS_PIN) && DIGIPOTSS_PIN > -1 digitalWrite(DIGIPOTSS_PIN,LOW); // take the SS pin low to select the chip SPI.transfer(address); // send in the address and value via SPI: SPI.transfer(value); digitalWrite(DIGIPOTSS_PIN,HIGH); // take the SS pin high to de-select the chip: //delay(10); - #endif } +#endif void EEPROM_read_st(int pos, uint8_t* value, uint8_t size) { diff --git a/Firmware/stepper.h b/Firmware/stepper.h index ac508944..d4199247 100644 --- a/Firmware/stepper.h +++ b/Firmware/stepper.h @@ -92,8 +92,9 @@ extern bool y_min_endstop; extern bool y_max_endstop; void quickStop(); - +#if defined(DIGIPOTSS_PIN) && DIGIPOTSS_PIN > -1 void digitalPotWrite(int address, int value); +#endif //defined(DIGIPOTSS_PIN) && DIGIPOTSS_PIN > -1 void microstep_ms(uint8_t driver, int8_t ms1, int8_t ms2); void microstep_mode(uint8_t driver, uint8_t stepping); void st_current_init(); From 5af489736084cad3060f7f5d78f3e27524abf9d4 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Tue, 7 Aug 2018 16:05:06 +0200 Subject: [PATCH 051/141] Fix compiler warning sketch/stepper.cpp:1553:6: warning: unused parameter 'driver' [-Wunused-parameter] --- Firmware/stepper.cpp | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/Firmware/stepper.cpp b/Firmware/stepper.cpp index 3bc3344b..cb4e680f 100644 --- a/Firmware/stepper.cpp +++ b/Firmware/stepper.cpp @@ -1549,15 +1549,16 @@ uint8_t SilentMode = eeprom_read_byte((uint8_t*)EEPROM_SILENT); - +#ifdef MOTOR_CURRENT_PWM_XY_PIN void st_current_set(uint8_t driver, int current) { - #ifdef MOTOR_CURRENT_PWM_XY_PIN if (driver == 0) analogWrite(MOTOR_CURRENT_PWM_XY_PIN, (long)current * 255L / (long)MOTOR_CURRENT_PWM_RANGE); if (driver == 1) analogWrite(MOTOR_CURRENT_PWM_Z_PIN, (long)current * 255L / (long)MOTOR_CURRENT_PWM_RANGE); if (driver == 2) analogWrite(MOTOR_CURRENT_PWM_E_PIN, (long)current * 255L / (long)MOTOR_CURRENT_PWM_RANGE); - #endif } +#else //MOTOR_CURRENT_PWM_XY_PIN +void st_current_set(uint8_t, int ){} +#endif //MOTOR_CURRENT_PWM_XY_PIN void microstep_init() { From 9271d12bf7ad316dfae40465db5876ef1580f022 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Tue, 7 Aug 2018 16:32:32 +0200 Subject: [PATCH 052/141] Save 32B of FLASH, fix compiler warning: sketch/tmc2130.cpp:238:6: warning: unused parameter 'last_step_mask' [-Wunused-parameter]. --- Firmware/stepper.cpp | 15 +-------------- Firmware/tmc2130.cpp | 2 +- Firmware/tmc2130.h | 2 +- 3 files changed, 3 insertions(+), 16 deletions(-) diff --git a/Firmware/stepper.cpp b/Firmware/stepper.cpp index cb4e680f..76a110f5 100644 --- a/Firmware/stepper.cpp +++ b/Firmware/stepper.cpp @@ -104,8 +104,6 @@ static bool z_endstop_invert = false; volatile long count_position[NUM_AXIS] = { 0, 0, 0, 0}; volatile signed char count_direction[NUM_AXIS] = { 1, 1, 1, 1}; -uint8_t LastStepMask = 0; - #ifdef LIN_ADVANCE static uint16_t nextMainISR = 0; @@ -714,7 +712,6 @@ FORCE_INLINE void stepper_tick_lowres() counter_x.lo += current_block->steps_x.lo; if (counter_x.lo > 0) { WRITE_NC(X_STEP_PIN, !INVERT_X_STEP_PIN); - LastStepMask |= X_AXIS_MASK; #ifdef DEBUG_XSTEP_DUP_PIN WRITE_NC(DEBUG_XSTEP_DUP_PIN,!INVERT_X_STEP_PIN); #endif //DEBUG_XSTEP_DUP_PIN @@ -729,7 +726,6 @@ FORCE_INLINE void stepper_tick_lowres() counter_y.lo += current_block->steps_y.lo; if (counter_y.lo > 0) { WRITE_NC(Y_STEP_PIN, !INVERT_Y_STEP_PIN); - LastStepMask |= Y_AXIS_MASK; #ifdef DEBUG_YSTEP_DUP_PIN WRITE_NC(DEBUG_YSTEP_DUP_PIN,!INVERT_Y_STEP_PIN); #endif //DEBUG_YSTEP_DUP_PIN @@ -744,7 +740,6 @@ FORCE_INLINE void stepper_tick_lowres() counter_z.lo += current_block->steps_z.lo; if (counter_z.lo > 0) { WRITE_NC(Z_STEP_PIN, !INVERT_Z_STEP_PIN); - LastStepMask |= Z_AXIS_MASK; 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); @@ -779,7 +774,6 @@ FORCE_INLINE void stepper_tick_highres() counter_x.wide += current_block->steps_x.wide; if (counter_x.wide > 0) { WRITE_NC(X_STEP_PIN, !INVERT_X_STEP_PIN); - LastStepMask |= X_AXIS_MASK; #ifdef DEBUG_XSTEP_DUP_PIN WRITE_NC(DEBUG_XSTEP_DUP_PIN,!INVERT_X_STEP_PIN); #endif //DEBUG_XSTEP_DUP_PIN @@ -794,7 +788,6 @@ FORCE_INLINE void stepper_tick_highres() counter_y.wide += current_block->steps_y.wide; if (counter_y.wide > 0) { WRITE_NC(Y_STEP_PIN, !INVERT_Y_STEP_PIN); - LastStepMask |= Y_AXIS_MASK; #ifdef DEBUG_YSTEP_DUP_PIN WRITE_NC(DEBUG_YSTEP_DUP_PIN,!INVERT_Y_STEP_PIN); #endif //DEBUG_YSTEP_DUP_PIN @@ -809,7 +802,6 @@ FORCE_INLINE void stepper_tick_highres() counter_z.wide += current_block->steps_z.wide; if (counter_z.wide > 0) { WRITE_NC(Z_STEP_PIN, !INVERT_Z_STEP_PIN); - LastStepMask |= Z_AXIS_MASK; 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); @@ -847,8 +839,6 @@ FORCE_INLINE void isr() { if (current_block == NULL) stepper_next_block(); - LastStepMask = 0; - if (current_block != NULL) { stepper_check_endstops(); @@ -1066,7 +1056,7 @@ FORCE_INLINE void isr() { } #ifdef TMC2130 - tmc2130_st_isr(LastStepMask); + tmc2130_st_isr(); #endif //TMC2130 //WRITE_NC(LOGIC_ANALYZER_CH0, false); @@ -1421,7 +1411,6 @@ void babystep(const uint8_t axis,const bool direction) //perform step WRITE(X_STEP_PIN, !INVERT_X_STEP_PIN); - LastStepMask |= X_AXIS_MASK; #ifdef DEBUG_XSTEP_DUP_PIN WRITE(DEBUG_XSTEP_DUP_PIN,!INVERT_X_STEP_PIN); #endif //DEBUG_XSTEP_DUP_PIN @@ -1445,7 +1434,6 @@ void babystep(const uint8_t axis,const bool direction) //perform step WRITE(Y_STEP_PIN, !INVERT_Y_STEP_PIN); - LastStepMask |= Y_AXIS_MASK; #ifdef DEBUG_YSTEP_DUP_PIN WRITE(DEBUG_YSTEP_DUP_PIN,!INVERT_Y_STEP_PIN); #endif //DEBUG_YSTEP_DUP_PIN @@ -1472,7 +1460,6 @@ void babystep(const uint8_t axis,const bool direction) #endif //perform step WRITE(Z_STEP_PIN, !INVERT_Z_STEP_PIN); - LastStepMask |= Z_AXIS_MASK; #ifdef Z_DUAL_STEPPER_DRIVERS WRITE(Z2_STEP_PIN, !INVERT_Z_STEP_PIN); #endif diff --git a/Firmware/tmc2130.cpp b/Firmware/tmc2130.cpp index 27600e92..ddef5dd8 100644 --- a/Firmware/tmc2130.cpp +++ b/Firmware/tmc2130.cpp @@ -235,7 +235,7 @@ uint8_t tmc2130_sample_diag() extern bool is_usb_printing; -void tmc2130_st_isr(uint8_t last_step_mask) +void tmc2130_st_isr() { if (tmc2130_mode == TMC2130_MODE_SILENT || tmc2130_sg_stop_on_crash == false) return; uint8_t crash = 0; diff --git a/Firmware/tmc2130.h b/Firmware/tmc2130.h index 28ecb7be..66c2b92b 100644 --- a/Firmware/tmc2130.h +++ b/Firmware/tmc2130.h @@ -53,7 +53,7 @@ extern tmc2130_chopper_config_t tmc2130_chopper_config[4]; //initialize tmc2130 extern void tmc2130_init(); //check diag pins (called from stepper isr) -extern void tmc2130_st_isr(uint8_t last_step_mask); +extern void tmc2130_st_isr(); //update stall guard (called from st_synchronize inside the loop) extern bool tmc2130_update_sg(); //temperature watching (called from ) From 78f1a7914fe48c0ffdc928f9648d43c48f689ac2 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Tue, 7 Aug 2018 16:45:19 +0200 Subject: [PATCH 053/141] Fix compiler warning: sketch/xyzcal.cpp:90:6: warning: unused parameter 'de' [-Wunused-parameter]. --- Firmware/xyzcal.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Firmware/xyzcal.cpp b/Firmware/xyzcal.cpp index 3984a83d..1551a69a 100644 --- a/Firmware/xyzcal.cpp +++ b/Firmware/xyzcal.cpp @@ -87,7 +87,7 @@ uint8_t check_pinda_1() uint8_t xyzcal_dm = 0; -void xyzcal_update_pos(uint16_t dx, uint16_t dy, uint16_t dz, uint16_t de) +void xyzcal_update_pos(uint16_t dx, uint16_t dy, uint16_t dz, uint16_t) { // DBG(_n("xyzcal_update_pos dx=%d dy=%d dz=%d dir=%02x\n"), dx, dy, dz, xyzcal_dm); if (xyzcal_dm&1) count_position[0] -= dx; else count_position[0] += dx; From 4395ec207ec7eabd48a0577a0457775c3f757d3a Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Tue, 7 Aug 2018 17:32:27 +0200 Subject: [PATCH 054/141] Fix compiler warnings: sketch/xyzcal.cpp:111:10: warning: unused parameter 'nd' [-Wunused-parameter] sketch/xyzcal.cpp:111:10: warning: unused parameter 'dd' [-Wunused-parameter] --- Firmware/xyzcal.cpp | 12 +++++++----- 1 file changed, 7 insertions(+), 5 deletions(-) diff --git a/Firmware/xyzcal.cpp b/Firmware/xyzcal.cpp index 1551a69a..e1142c1e 100644 --- a/Firmware/xyzcal.cpp +++ b/Firmware/xyzcal.cpp @@ -108,11 +108,9 @@ uint16_t xyzcal_sm4_ac2 = (uint32_t)xyzcal_sm4_ac * 1024 / 10000; //float xyzcal_sm4_vm = 10000; #endif //SM4_ACCEL_TEST +#ifdef SM4_ACCEL_TEST uint16_t xyzcal_calc_delay(uint16_t nd, uint16_t dd) { - return xyzcal_sm4_delay; -#ifdef SM4_ACCEL_TEST - uint16_t del_us = 0; if (xyzcal_sm4_v & 0xf000) //>=4096 { @@ -138,9 +136,13 @@ uint16_t xyzcal_calc_delay(uint16_t nd, uint16_t dd) // return xyzcal_sm4_delay; // DBG(_n("xyzcal_calc_delay nd=%d dd=%d v=%d del_us=%d\n"), nd, dd, xyzcal_sm4_v, del_us); return 0; -#endif //SM4_ACCEL_TEST } - +#else //SM4_ACCEL_TEST +uint16_t xyzcal_calc_delay(uint16_t, uint16_t) +{ + return xyzcal_sm4_delay; +} +#endif //SM4_ACCEL_TEST bool xyzcal_lineXYZ_to(int16_t x, int16_t y, int16_t z, uint16_t delay_us, int8_t check_pinda) { From 791b5683393ae04ac2fc9ce3af47665cdb2090d5 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Tue, 7 Aug 2018 17:51:30 +0200 Subject: [PATCH 055/141] Fix compiler warnings: sketch/uart2.c:19:33: warning: unused parameter 'stream' [-Wunused-parameter] sketch/uart2.c:28:25: warning: unused parameter 'stream' [-Wunused-parameter] sketch/Marlin_main.cpp:925:5: warning: unused parameter 'stream' [-Wunused-parameter] sketch/lcd.cpp:224:5: warning: unused parameter 'stream' [-Wunused-parameter] --- Firmware/Marlin_main.cpp | 2 +- Firmware/lcd.cpp | 2 +- Firmware/uart2.c | 4 ++-- 3 files changed, 4 insertions(+), 4 deletions(-) diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index 44dbfb76..2056ad65 100644 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -922,7 +922,7 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) FILE _uartout; //= {0}; Global variable is always zero initialized. No need to explicitly state this. -int uart_putchar(char c, FILE *stream) +int uart_putchar(char c, FILE *) { MYSERIAL.write(c); return 0; diff --git a/Firmware/lcd.cpp b/Firmware/lcd.cpp index d6574d4b..b4d969ce 100644 --- a/Firmware/lcd.cpp +++ b/Firmware/lcd.cpp @@ -221,7 +221,7 @@ static void lcd_begin(uint8_t lines, uint8_t dotsize, uint8_t clear) lcd_escape[0] = 0; } -int lcd_putchar(char c, FILE *stream) +int lcd_putchar(char c, FILE *) { lcd_write(c); return 0; diff --git a/Firmware/uart2.c b/Firmware/uart2.c index e6d5c3f8..f62ed1f0 100644 --- a/Firmware/uart2.c +++ b/Firmware/uart2.c @@ -16,7 +16,7 @@ uint8_t uart2_ibuf[10] = {0, 0}; FILE _uart2io = {0}; -int uart2_putchar(char c, FILE *stream) +int uart2_putchar(char c, FILE *stream __attribute__((unused))) { while (!uart2_txready); UDR2 = c; // transmit byte @@ -25,7 +25,7 @@ int uart2_putchar(char c, FILE *stream) return 0; } -int uart2_getchar(FILE *stream) +int uart2_getchar(FILE *stream __attribute__((unused))) { if (rbuf_empty(uart2_ibuf)) return -1; return rbuf_get(uart2_ibuf); From 814d31d70d59237a96e831026476cf1804e892fe Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Tue, 7 Aug 2018 18:50:11 +0200 Subject: [PATCH 056/141] Remove factory_reset() unused quiet parameter and make it static. It was tested, that both calls of factory reset (from menu and via PRUSA FR command) works somehow. Fix compiler warning: sketch/Marlin_main.cpp:808:6: warning: unused parameter 'quiet' [-Wunused-parameter] --- Firmware/Marlin_main.cpp | 7 +++---- 1 file changed, 3 insertions(+), 4 deletions(-) diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index 2056ad65..c4f5833b 100644 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -803,9 +803,8 @@ void failstats_reset_print() // Factory reset function // This function is used to erase parts or whole EEPROM memory which is used for storing calibration and and so on. // Level input parameter sets depth of reset -// Quiet parameter masks all waitings for user interact. int er_progress = 0; -void factory_reset(char level, bool quiet) +static void factory_reset(char level) { lcd_clear(); switch (level) { @@ -967,7 +966,7 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) _delay_ms(2000); char level = reset_menu(); - factory_reset(level, false); + factory_reset(level); switch (level) { case 0: _delay_ms(0); break; @@ -3525,7 +3524,7 @@ void process_commands() } else if(code_seen("FR")) { // Factory full reset - factory_reset(0,true); + factory_reset(0); } //else if (code_seen('Cal')) { // lcd_calibration(); From 7e19b4adc1f55768cd9c0445026e0566c253baaa Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Tue, 7 Aug 2018 19:17:29 +0200 Subject: [PATCH 057/141] Supress compiler warning sketch/Marlin_main.cpp:3079:6: warning: unused parameter 'e_shift_late' [-Wunused-parameter]. Make function static. Fix indentation. --- Firmware/Marlin_main.cpp | 182 ++++++++++++++++++++------------------- 1 file changed, 94 insertions(+), 88 deletions(-) diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index c4f5833b..8809a611 100644 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -3076,106 +3076,112 @@ void gcode_M114() SERIAL_PROTOCOLLN(""); } -void gcode_M600(bool automatic, float x_position, float y_position, float z_shift, float e_shift, float e_shift_late) { - st_synchronize(); - float lastpos[4]; +static void gcode_M600(bool automatic, float x_position, float y_position, float z_shift, float e_shift, float /*e_shift_late*/) +{ + st_synchronize(); + float lastpos[4]; - if (farm_mode) - { - prusa_statistics(22); - } + if (farm_mode) + { + prusa_statistics(22); + } - //First backup current position and settings - feedmultiplyBckp=feedmultiply; - HotendTempBckp = degTargetHotend(active_extruder); - fanSpeedBckp = fanSpeed; + //First backup current position and settings + feedmultiplyBckp = feedmultiply; + HotendTempBckp = degTargetHotend(active_extruder); + fanSpeedBckp = fanSpeed; - lastpos[X_AXIS]=current_position[X_AXIS]; - lastpos[Y_AXIS]=current_position[Y_AXIS]; - lastpos[Z_AXIS]=current_position[Z_AXIS]; - lastpos[E_AXIS]=current_position[E_AXIS]; + lastpos[X_AXIS] = current_position[X_AXIS]; + lastpos[Y_AXIS] = current_position[Y_AXIS]; + lastpos[Z_AXIS] = current_position[Z_AXIS]; + lastpos[E_AXIS] = current_position[E_AXIS]; - //Retract E - current_position[E_AXIS]+= e_shift; - plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], FILAMENTCHANGE_RFEED, active_extruder); - st_synchronize(); + //Retract E + current_position[E_AXIS] += e_shift; + plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], + current_position[E_AXIS], FILAMENTCHANGE_RFEED, active_extruder); + st_synchronize(); - //Lift Z - current_position[Z_AXIS]+= z_shift; - plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], FILAMENTCHANGE_ZFEED, active_extruder); - st_synchronize(); - - //Move XY to side - current_position[X_AXIS]= x_position; - current_position[Y_AXIS]= y_position; - plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], FILAMENTCHANGE_XYFEED, active_extruder); - st_synchronize(); - - //Beep, manage nozzle heater and wait for user to start unload filament - if(!automatic) M600_wait_for_user(); - - lcd_change_fil_state = 0; - - // Unload filament - if (mmu_enabled) - extr_unload(); //unload just current filament for multimaterial printers (used also in M702) - else - unload_filament(); //unload filament for single material (used also in M702) - //finish moves - st_synchronize(); + //Lift Z + current_position[Z_AXIS] += z_shift; + plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], + current_position[E_AXIS], FILAMENTCHANGE_ZFEED, active_extruder); + st_synchronize(); - if (!mmu_enabled) - { - KEEPALIVE_STATE(PAUSED_FOR_USER); - lcd_change_fil_state = lcd_show_fullscreen_message_yes_no_and_wait_P(_i("Was filament unload successful?"), false, true);////MSG_UNLOAD_SUCCESSFUL c=20 r=2 - if (lcd_change_fil_state == 0) lcd_show_fullscreen_message_and_wait_P(_i("Please open idler and remove filament manually."));////MSG_CHECK_IDLER c=20 r=4 - lcd_update_enable(true); - } + //Move XY to side + current_position[X_AXIS] = x_position; + current_position[Y_AXIS] = y_position; + plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], + current_position[E_AXIS], FILAMENTCHANGE_XYFEED, active_extruder); + st_synchronize(); - if (mmu_enabled) - mmu_M600_load_filament(automatic); - else - M600_load_filament(); + //Beep, manage nozzle heater and wait for user to start unload filament + if (!automatic) M600_wait_for_user(); - if(!automatic) M600_check_state(); + lcd_change_fil_state = 0; - //Not let's go back to print - fanSpeed = fanSpeedBckp; + // Unload filament + if (mmu_enabled) extr_unload(); //unload just current filament for multimaterial printers (used also in M702) + else unload_filament(); //unload filament for single material (used also in M702) + //finish moves + st_synchronize(); - //Feed a little of filament to stabilize pressure - if (!automatic) { - current_position[E_AXIS] += FILAMENTCHANGE_RECFEED; - plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], FILAMENTCHANGE_EXFEED, active_extruder); - } - - //Move XY back - plan_buffer_line(lastpos[X_AXIS], lastpos[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], FILAMENTCHANGE_XYFEED, active_extruder); - st_synchronize(); - //Move Z back - plan_buffer_line(lastpos[X_AXIS], lastpos[Y_AXIS], lastpos[Z_AXIS], current_position[E_AXIS], FILAMENTCHANGE_ZFEED, active_extruder); - st_synchronize(); - - //Unretract - current_position[E_AXIS]= current_position[E_AXIS] - e_shift; - plan_buffer_line(lastpos[X_AXIS], lastpos[Y_AXIS], lastpos[Z_AXIS], current_position[E_AXIS], FILAMENTCHANGE_RFEED, active_extruder); - st_synchronize(); + if (!mmu_enabled) + { + KEEPALIVE_STATE(PAUSED_FOR_USER); + lcd_change_fil_state = lcd_show_fullscreen_message_yes_no_and_wait_P(_i("Was filament unload successful?"), + false, true); ////MSG_UNLOAD_SUCCESSFUL c=20 r=2 + if (lcd_change_fil_state == 0) + lcd_show_fullscreen_message_and_wait_P(_i("Please open idler and remove filament manually."));////MSG_CHECK_IDLER c=20 r=4 + lcd_update_enable(true); + } - //Set E position to original - plan_set_e_position(lastpos[E_AXIS]); + if (mmu_enabled) mmu_M600_load_filament(automatic); + else M600_load_filament(); - memcpy(current_position, lastpos, sizeof(lastpos)); - memcpy(destination, current_position, sizeof(current_position)); - - //Recover feed rate - feedmultiply=feedmultiplyBckp; - char cmd[9]; - sprintf_P(cmd, PSTR("M220 S%i"), feedmultiplyBckp); - enquecommand(cmd); - - lcd_setstatuspgm(_T(WELCOME_MSG)); - custom_message = false; - custom_message_type = 0; - + if (!automatic) M600_check_state(); + + //Not let's go back to print + fanSpeed = fanSpeedBckp; + + //Feed a little of filament to stabilize pressure + if (!automatic) + { + current_position[E_AXIS] += FILAMENTCHANGE_RECFEED; + plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], + current_position[E_AXIS], FILAMENTCHANGE_EXFEED, active_extruder); + } + + //Move XY back + plan_buffer_line(lastpos[X_AXIS], lastpos[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], + FILAMENTCHANGE_XYFEED, active_extruder); + st_synchronize(); + //Move Z back + plan_buffer_line(lastpos[X_AXIS], lastpos[Y_AXIS], lastpos[Z_AXIS], current_position[E_AXIS], + FILAMENTCHANGE_ZFEED, active_extruder); + st_synchronize(); + + //Unretract + current_position[E_AXIS] = current_position[E_AXIS] - e_shift; + plan_buffer_line(lastpos[X_AXIS], lastpos[Y_AXIS], lastpos[Z_AXIS], current_position[E_AXIS], + FILAMENTCHANGE_RFEED, active_extruder); + st_synchronize(); + + //Set E position to original + plan_set_e_position(lastpos[E_AXIS]); + + memcpy(current_position, lastpos, sizeof(lastpos)); + memcpy(destination, current_position, sizeof(current_position)); + + //Recover feed rate + feedmultiply = feedmultiplyBckp; + char cmd[9]; + sprintf_P(cmd, PSTR("M220 S%i"), feedmultiplyBckp); + enquecommand(cmd); + + lcd_setstatuspgm(_T(WELCOME_MSG)); + custom_message = false; + custom_message_type = 0; } From 10ba3e7ffde4229e46cd819fdd551bd55027a1ca Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Tue, 7 Aug 2018 19:59:32 +0200 Subject: [PATCH 058/141] Move global variable count_position declaration to stepper.h header file. --- Firmware/stepper.h | 1 + Firmware/xyzcal.cpp | 2 -- 2 files changed, 1 insertion(+), 2 deletions(-) diff --git a/Firmware/stepper.h b/Firmware/stepper.h index ac508944..ab48c644 100644 --- a/Firmware/stepper.h +++ b/Firmware/stepper.h @@ -90,6 +90,7 @@ extern bool x_min_endstop; extern bool x_max_endstop; extern bool y_min_endstop; extern bool y_max_endstop; +extern volatile long count_position[NUM_AXIS]; void quickStop(); diff --git a/Firmware/xyzcal.cpp b/Firmware/xyzcal.cpp index 1ecc86cf..164ec79c 100644 --- a/Firmware/xyzcal.cpp +++ b/Firmware/xyzcal.cpp @@ -32,8 +32,6 @@ #define _PI 3.14159265F -extern volatile long count_position[NUM_AXIS]; - 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); From 5493ac57f9759e1c1b556605f06084bdec857109 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Tue, 7 Aug 2018 20:15:04 +0200 Subject: [PATCH 059/141] Fix declaration and definition type mismatch of lcd_change_fil_state. Move declaration to Marlin.h. --- Firmware/Marlin.h | 1 + Firmware/ultralcd.cpp | 1 - 2 files changed, 1 insertion(+), 1 deletion(-) diff --git a/Firmware/Marlin.h b/Firmware/Marlin.h index 2bbab987..8f0ca477 100644 --- a/Firmware/Marlin.h +++ b/Firmware/Marlin.h @@ -282,6 +282,7 @@ extern bool axis_known_position[3]; extern float zprobe_zoffset; extern int fanSpeed; extern void homeaxis(int axis, uint8_t cnt = 1, uint8_t* pstep = 0); +extern int8_t lcd_change_fil_state; #ifdef FAN_SOFT_PWM diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index 0ca7cf92..3fb19449 100644 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -37,7 +37,6 @@ #include "mmu.h" -extern int lcd_change_fil_state; extern bool fans_check_enabled; From 59882e4c0b8daa58c6ba8603bc64e4c467448dfa Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Fri, 10 Aug 2018 00:18:37 +0200 Subject: [PATCH 060/141] Update README.md. --- README.md | 7 ++++--- README_cz.md | 7 +++++-- 2 files changed, 9 insertions(+), 5 deletions(-) diff --git a/README.md b/README.md index 72598ee0..53eda62c 100644 --- a/README.md +++ b/README.md @@ -2,8 +2,7 @@ 1. install `"Arduino Software IDE"` for your preferred operating system `https://www.arduino.cc -> Software->Downloads` -it is strongly recommended to use older version `"1.6.9"`, by which we can assure correct compilation results -_note: in versions `1.7.x` and `1.8.x` there are known some C/C++ compilator disasters, which disallow correct source code compilation (you can obtain `"... internal compiler error: in extract_insn, at ..."` error message, for example); we are not able to affect this situation afraid_ +it is recommended to use older version `"1.6.9"`, as it is used on out build server to produce offitial builds. _note: in the case of persistent compilation problems, check the version of the currently used C/C++ compiler (GCC) - should be `4.8.1`; version can be verified by entering the command `avr-gcc --version` 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_ @@ -27,7 +26,9 @@ _note: select this item for any variant of board used in printers `'Prusa i3 MKx _(after installation, the item is labeled as `"INSTALLED"` and can then be used for target board selection)_ 3. modify platform.txt to enable float printf support: - `"compiler.c.elf.flags=-w -Os -Wl,-u,vfprintf -lprintf_flt -lm -Wl,--gc-sections"` +add "-Wl,-u,vfprintf -lprintf_flt -lm" to "compiler.c.elf.flags=" +example: +`"compiler.c.elf.flags=-w -Os -Wl,-u,vfprintf -lprintf_flt -lm -Wl,--gc-sections"` # 2. Source code compilation diff --git a/README_cz.md b/README_cz.md index 5c649963..24df12fa 100644 --- a/README_cz.md +++ b/README_cz.md @@ -2,8 +2,7 @@ 1. nainstalujte vývojové prostředí `"Arduino Software IDE"` pro operační prostředí, které jste zvyklí používat `https://www.arduino.cc -> Software->Downloads` -důrazně doporučujeme použít starší verzi `"1.6.8"`, u které jsme schopni garantovat bezproblémový překlad a správné výsledky -_pozn.: ve verzích `1.7.x` a `1.8.x` jsou k datu vydání tohoto dokumentu evidovány chyby v překladači jazyka C/C++, které znemožňují překlad zdrojového kódu (můžete např. obdržet chybové hlášení `"... internal compiler error: in extract_insn, at ..."`); tuto nepříjemnou situaci bohužel nedokážeme nijak ovlivnit_ +doporučujeme použít starší verzi `"1.6.9"`, kterou používáme na našem build serveru pro překlad oficiálních buildů _pozn.: v případě přetrvávajících potíží s překladem zkontrolujte verzi aktuálně použitého překladače jazyka C/C++ (GCC) - měla by být `4.8.1`; verzi ověříte zadáním příkazu `avr-gcc --version` pokud si nejste jisti umístěním souboru (závisí na způsobu, jakým bylo `"Arduino Software IDE"` nainstalováno), použijte funkci vyhledání v rámci systému souborů_ @@ -26,6 +25,10 @@ _pozn.: tuto položku zvolte pro všechny varianty desek použitých v tiskárn 'kliknutím' na položku se zobrazí tlačítko pro instalaci; ve výběrovém seznamu zvolte verzi `"1.0.1"` (poslední známá verze k datu vydání tohoto dokumentu) _(po provedení instalace je položka označena poznámkou `"INSTALLED"` a lze ji následně použít při výběru cílové desky)_ + 3. modify platform.txt to enable float printf support: +add "-Wl,-u,vfprintf -lprintf_flt -lm" to "compiler.c.elf.flags=" +example: +`"compiler.c.elf.flags=-w -Os -Wl,-u,vfprintf -lprintf_flt -lm -Wl,--gc-sections"` # 2. Překlad zdrojoveho kódu From 4f190c010e1a446b27936e14b62868825ff175d8 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Fri, 10 Aug 2018 00:34:17 +0200 Subject: [PATCH 061/141] Update README.md. --- README.md | 4 +++- README_cz.md | 4 +++- 2 files changed, 6 insertions(+), 2 deletions(-) diff --git a/README.md b/README.md index 53eda62c..cdc8f06d 100644 --- a/README.md +++ b/README.md @@ -26,7 +26,9 @@ _note: select this item for any variant of board used in printers `'Prusa i3 MKx _(after installation, the item is labeled as `"INSTALLED"` and can then be used for target board selection)_ 3. modify platform.txt to enable float printf support: -add "-Wl,-u,vfprintf -lprintf_flt -lm" to "compiler.c.elf.flags=" + +add "-Wl,-u,vfprintf -lprintf_flt -lm" to "compiler.c.elf.flags=" before existing flag "-Wl,--gc-sections" + example: `"compiler.c.elf.flags=-w -Os -Wl,-u,vfprintf -lprintf_flt -lm -Wl,--gc-sections"` diff --git a/README_cz.md b/README_cz.md index 24df12fa..80216325 100644 --- a/README_cz.md +++ b/README_cz.md @@ -26,7 +26,9 @@ _pozn.: tuto položku zvolte pro všechny varianty desek použitých v tiskárn _(po provedení instalace je položka označena poznámkou `"INSTALLED"` a lze ji následně použít při výběru cílové desky)_ 3. modify platform.txt to enable float printf support: -add "-Wl,-u,vfprintf -lprintf_flt -lm" to "compiler.c.elf.flags=" + +add "-Wl,-u,vfprintf -lprintf_flt -lm" to "compiler.c.elf.flags=" before existing flag "-Wl,--gc-sections" + example: `"compiler.c.elf.flags=-w -Os -Wl,-u,vfprintf -lprintf_flt -lm -Wl,--gc-sections"` From ecb2a6e02cc4c501ea85fe67d0224e668518c599 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Fri, 10 Aug 2018 01:00:02 +0200 Subject: [PATCH 062/141] Update README.md. --- README.md | 8 +++----- README_cz.md | 8 +++----- 2 files changed, 6 insertions(+), 10 deletions(-) diff --git a/README.md b/README.md index cdc8f06d..e8e9e7c1 100644 --- a/README.md +++ b/README.md @@ -25,11 +25,9 @@ _note: select this item for any variant of board used in printers `'Prusa i3 MKx 'clicking' the item will display the installation button; select choice `"1.0.1"` from the list(last known version as of the date of issue of this document) _(after installation, the item is labeled as `"INSTALLED"` and can then be used for target board selection)_ - 3. modify platform.txt to enable float printf support: - -add "-Wl,-u,vfprintf -lprintf_flt -lm" to "compiler.c.elf.flags=" before existing flag "-Wl,--gc-sections" - -example: + 3. modify platform.txt to enable float printf support: +add "-Wl,-u,vfprintf -lprintf_flt -lm" to "compiler.c.elf.flags=" before existing flag "-Wl,--gc-sections" +example: `"compiler.c.elf.flags=-w -Os -Wl,-u,vfprintf -lprintf_flt -lm -Wl,--gc-sections"` # 2. Source code compilation diff --git a/README_cz.md b/README_cz.md index 80216325..282babdc 100644 --- a/README_cz.md +++ b/README_cz.md @@ -25,11 +25,9 @@ _pozn.: tuto položku zvolte pro všechny varianty desek použitých v tiskárn 'kliknutím' na položku se zobrazí tlačítko pro instalaci; ve výběrovém seznamu zvolte verzi `"1.0.1"` (poslední známá verze k datu vydání tohoto dokumentu) _(po provedení instalace je položka označena poznámkou `"INSTALLED"` a lze ji následně použít při výběru cílové desky)_ - 3. modify platform.txt to enable float printf support: - -add "-Wl,-u,vfprintf -lprintf_flt -lm" to "compiler.c.elf.flags=" before existing flag "-Wl,--gc-sections" - -example: + 3. modify platform.txt to enable float printf support: +add "-Wl,-u,vfprintf -lprintf_flt -lm" to "compiler.c.elf.flags=" before existing flag "-Wl,--gc-sections" +example: `"compiler.c.elf.flags=-w -Os -Wl,-u,vfprintf -lprintf_flt -lm -Wl,--gc-sections"` # 2. Překlad zdrojoveho kódu From 95e7536955540c96a710b173b8465ad32d3843b2 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Fri, 10 Aug 2018 15:19:35 +0200 Subject: [PATCH 063/141] Split settings menu into separate functions. --- Firmware/ultralcd.cpp | 203 +++++++++++++++++++++++------------------- 1 file changed, 109 insertions(+), 94 deletions(-) diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index 7c3078f7..51b89d2b 100644 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -4546,6 +4546,106 @@ void lcd_settings_linearity_correction_menu(void) MENU_END(); } #endif //LINEARITY_CORRECTION + +static void settings_silent_mode() +{ + if(!farm_mode) + { +#ifdef TMC2130 + + if (SilentModeMenu == SILENT_MODE_NORMAL) { MENU_ITEM_FUNCTION_P(_T(MSG_STEALTH_MODE_OFF), lcd_silent_mode_set); } + else MENU_ITEM_FUNCTION_P(_T(MSG_STEALTH_MODE_ON), lcd_silent_mode_set); + if (SilentModeMenu == SILENT_MODE_NORMAL) + { + if (CrashDetectMenu == 0) { MENU_ITEM_FUNCTION_P(_T(MSG_CRASHDETECT_OFF), lcd_crash_mode_set); } + else MENU_ITEM_FUNCTION_P(_T(MSG_CRASHDETECT_ON), lcd_crash_mode_set); + } + else MENU_ITEM_SUBMENU_P(_T(MSG_CRASHDETECT_NA), lcd_crash_mode_info); +#else //TMC2130 + + switch (SilentModeMenu) + { + case SILENT_MODE_POWER: MENU_ITEM_FUNCTION_P(_T(MSG_SILENT_MODE_OFF), lcd_silent_mode_set); break; + case SILENT_MODE_SILENT: MENU_ITEM_FUNCTION_P(_T(MSG_SILENT_MODE_ON), lcd_silent_mode_set); break; + case SILENT_MODE_AUTO: MENU_ITEM_FUNCTION_P(_T(MSG_AUTO_MODE_ON), lcd_silent_mode_set); break; + default: MENU_ITEM_FUNCTION_P(_T(MSG_SILENT_MODE_OFF), lcd_silent_mode_set); break; // (probably) not needed + } +#endif //TMC2130 + } +} + +static void settings_filament_sensor() +{ +#ifdef FILAMENT_SENSOR + if (FSensorStateMenu == 0) + { + if (fsensor_not_responding) + { + // Filament sensor not working + MENU_ITEM_FUNCTION_P(_i("Fil. sensor [N/A]"), lcd_fsensor_state_set);////MSG_FSENSOR_NA c=0 r=0 + MENU_ITEM_SUBMENU_P(_T(MSG_FSENS_AUTOLOAD_NA), lcd_fsensor_fail); + } + else + { + // Filament sensor turned off, working, no problems + MENU_ITEM_FUNCTION_P(_T(MSG_FSENSOR_OFF), lcd_fsensor_state_set); + MENU_ITEM_SUBMENU_P(_T(MSG_FSENS_AUTOLOAD_NA), lcd_filament_autoload_info); + } + } + else + { + // Filament sensor turned on, working, no problems + MENU_ITEM_FUNCTION_P(_T(MSG_FSENSOR_ON), lcd_fsensor_state_set); + if (fsensor_autoload_enabled) + MENU_ITEM_FUNCTION_P(_i("F. autoload [on]"), lcd_set_filament_autoload);////MSG_FSENS_AUTOLOAD_ON c=17 r=1 + else + MENU_ITEM_FUNCTION_P(_i("F. autoload [off]"), lcd_set_filament_autoload);////MSG_FSENS_AUTOLOAD_OFF c=17 r=1 + } +#endif //FILAMENT_SENSOR +} + +static void settings_sd() +{ + if (card.ToshibaFlashAir_isEnabled()) + MENU_ITEM_FUNCTION_P(_i("SD card [flshAir]"), lcd_toshiba_flash_air_compatibility_toggle);////MSG_TOSHIBA_FLASH_AIR_COMPATIBILITY_ON c=19 r=1 + else + MENU_ITEM_FUNCTION_P(_i("SD card [normal]"), lcd_toshiba_flash_air_compatibility_toggle);////MSG_TOSHIBA_FLASH_AIR_COMPATIBILITY_OFF c=19 r=1 +#ifdef SDCARD_SORT_ALPHA + if (!farm_mode) + { + uint8_t sdSort; + EEPROM_read(EEPROM_SD_SORT, (uint8_t*)&sdSort, sizeof(sdSort)); + switch (sdSort) + { + case SD_SORT_TIME: MENU_ITEM_FUNCTION_P(_i("Sort: [time]"), lcd_sort_type_set); break;////MSG_SORT_TIME c=17 r=1 + case SD_SORT_ALPHA: MENU_ITEM_FUNCTION_P(_i("Sort: [alphabet]"), lcd_sort_type_set); break;////MSG_SORT_ALPHA c=17 r=1 + default: MENU_ITEM_FUNCTION_P(_i("Sort: [none]"), lcd_sort_type_set);////MSG_SORT_NONE c=17 r=1 + } + } +#endif // SDCARD_SORT_ALPHA +} + +static void settings_sound() +{ + switch(eSoundMode) + { + case e_SOUND_MODE_LOUD: + MENU_ITEM_FUNCTION_P(_i(MSG_SOUND_MODE_LOUD),lcd_sound_state_set); + break; + case e_SOUND_MODE_ONCE: + MENU_ITEM_FUNCTION_P(_i(MSG_SOUND_MODE_ONCE),lcd_sound_state_set); + break; + case e_SOUND_MODE_SILENT: + MENU_ITEM_FUNCTION_P(_i(MSG_SOUND_MODE_SILENT),lcd_sound_state_set); + break; + case e_SOUND_MODE_MUTE: + MENU_ITEM_FUNCTION_P(_i(MSG_SOUND_MODE_MUTE),lcd_sound_state_set); + break; + default: + MENU_ITEM_FUNCTION_P(_i(MSG_SOUND_MODE_LOUD),lcd_sound_state_set); + } +} + static void lcd_settings_menu() { EEPROM_read(EEPROM_SILENT, (uint8_t*)&SilentModeMenu, sizeof(SilentModeMenu)); @@ -4554,71 +4654,22 @@ static void lcd_settings_menu() MENU_ITEM_SUBMENU_P(_i("Temperature"), lcd_control_temperature_menu);////MSG_TEMPERATURE c=0 r=0 if (!homing_flag) - MENU_ITEM_SUBMENU_P(_i("Move axis"), lcd_move_menu_1mm);////MSG_MOVE_AXIS c=0 r=0 + MENU_ITEM_SUBMENU_P(_i("Move axis"), lcd_move_menu_1mm);////MSG_MOVE_AXIS c=0 r=0 if (!isPrintPaused) - MENU_ITEM_GCODE_P(_i("Disable steppers"), PSTR("M84"));////MSG_DISABLE_STEPPERS c=0 r=0 + MENU_ITEM_GCODE_P(_i("Disable steppers"), PSTR("M84"));////MSG_DISABLE_STEPPERS c=0 r=0 -#ifndef TMC2130 - if (!farm_mode) - { //dont show in menu if we are in farm mode - switch (SilentModeMenu) - { - case SILENT_MODE_POWER: MENU_ITEM_FUNCTION_P(_T(MSG_SILENT_MODE_OFF), lcd_silent_mode_set); break; - case SILENT_MODE_SILENT: MENU_ITEM_FUNCTION_P(_T(MSG_SILENT_MODE_ON), lcd_silent_mode_set); break; - case SILENT_MODE_AUTO: MENU_ITEM_FUNCTION_P(_T(MSG_AUTO_MODE_ON), lcd_silent_mode_set); break; - default: MENU_ITEM_FUNCTION_P(_T(MSG_SILENT_MODE_OFF), lcd_silent_mode_set); break; // (probably) not needed - } - } -#endif //TMC2130 - -#ifdef FILAMENT_SENSOR - if (FSensorStateMenu == 0) - { - if (fsensor_not_responding) - { - // Filament sensor not working - MENU_ITEM_FUNCTION_P(_i("Fil. sensor [N/A]"), lcd_fsensor_state_set);////MSG_FSENSOR_NA c=0 r=0 - MENU_ITEM_SUBMENU_P(_T(MSG_FSENS_AUTOLOAD_NA), lcd_fsensor_fail); - } - else - { - // Filament sensor turned off, working, no problems - MENU_ITEM_FUNCTION_P(_T(MSG_FSENSOR_OFF), lcd_fsensor_state_set); - MENU_ITEM_SUBMENU_P(_T(MSG_FSENS_AUTOLOAD_NA), lcd_filament_autoload_info); - } - } - else - { - // Filament sensor turned on, working, no problems - MENU_ITEM_FUNCTION_P(_T(MSG_FSENSOR_ON), lcd_fsensor_state_set); - if (fsensor_autoload_enabled) - MENU_ITEM_FUNCTION_P(_i("F. autoload [on]"), lcd_set_filament_autoload);////MSG_FSENS_AUTOLOAD_ON c=17 r=1 - else - MENU_ITEM_FUNCTION_P(_i("F. autoload [off]"), lcd_set_filament_autoload);////MSG_FSENS_AUTOLOAD_OFF c=17 r=1 - } -#endif //FILAMENT_SENSOR + settings_filament_sensor(); if (fans_check_enabled == true) MENU_ITEM_FUNCTION_P(_i("Fans check [on]"), lcd_set_fan_check);////MSG_FANS_CHECK_ON c=17 r=1 else MENU_ITEM_FUNCTION_P(_i("Fans check [off]"), lcd_set_fan_check);////MSG_FANS_CHECK_OFF c=17 r=1 -#ifdef TMC2130 - if(!farm_mode) - { - if (SilentModeMenu == SILENT_MODE_NORMAL) { MENU_ITEM_FUNCTION_P(_T(MSG_STEALTH_MODE_OFF), lcd_silent_mode_set); } - else MENU_ITEM_FUNCTION_P(_T(MSG_STEALTH_MODE_ON), lcd_silent_mode_set); - if (SilentModeMenu == SILENT_MODE_NORMAL) - { - if (CrashDetectMenu == 0) { MENU_ITEM_FUNCTION_P(_T(MSG_CRASHDETECT_OFF), lcd_crash_mode_set); } - else MENU_ITEM_FUNCTION_P(_T(MSG_CRASHDETECT_ON), lcd_crash_mode_set); - } - else MENU_ITEM_SUBMENU_P(_T(MSG_CRASHDETECT_NA), lcd_crash_mode_info); - } -#ifdef LINEARITY_CORRECTION + settings_silent_mode(); + +#if defined (TMC2130) && defined (LINEARITY_CORRECTION) MENU_ITEM_SUBMENU_P(_i("Lin. correction"), lcd_settings_linearity_correction_menu); -#endif //LINEARITY_CORRECTION -#endif //TMC2130 +#endif //LINEARITY_CORRECTION && TMC2130 if (temp_cal_active == false) MENU_ITEM_FUNCTION_P(_i("Temp. cal. [off]"), lcd_temp_calibration_set);////MSG_TEMP_CALIBRATION_OFF c=20 r=1 @@ -4639,45 +4690,9 @@ static void lcd_settings_menu() MENU_ITEM_SUBMENU_P(_i("Select language"), lcd_language_menu);////MSG_LANGUAGE_SELECT c=0 r=0 #endif //(LANG_MODE != 0) - if (card.ToshibaFlashAir_isEnabled()) - MENU_ITEM_FUNCTION_P(_i("SD card [flshAir]"), lcd_toshiba_flash_air_compatibility_toggle);////MSG_TOSHIBA_FLASH_AIR_COMPATIBILITY_ON c=19 r=1 - else - MENU_ITEM_FUNCTION_P(_i("SD card [normal]"), lcd_toshiba_flash_air_compatibility_toggle);////MSG_TOSHIBA_FLASH_AIR_COMPATIBILITY_OFF c=19 r=1 + settings_sd(); + settings_sound(); -#ifdef SDCARD_SORT_ALPHA - if (!farm_mode) - { - uint8_t sdSort; - EEPROM_read(EEPROM_SD_SORT, (uint8_t*)&sdSort, sizeof(sdSort)); - switch (sdSort) - { - case SD_SORT_TIME: MENU_ITEM_FUNCTION_P(_i("Sort: [time]"), lcd_sort_type_set); break;////MSG_SORT_TIME c=17 r=1 - case SD_SORT_ALPHA: MENU_ITEM_FUNCTION_P(_i("Sort: [alphabet]"), lcd_sort_type_set); break;////MSG_SORT_ALPHA c=17 r=1 - default: MENU_ITEM_FUNCTION_P(_i("Sort: [none]"), lcd_sort_type_set);////MSG_SORT_NONE c=17 r=1 - } - } -#endif // SDCARD_SORT_ALPHA - - -//-// -switch(eSoundMode) - { - case e_SOUND_MODE_LOUD: - MENU_ITEM_FUNCTION_P(_i(MSG_SOUND_MODE_LOUD),lcd_sound_state_set); - break; - case e_SOUND_MODE_ONCE: - MENU_ITEM_FUNCTION_P(_i(MSG_SOUND_MODE_ONCE),lcd_sound_state_set); - break; - case e_SOUND_MODE_SILENT: - MENU_ITEM_FUNCTION_P(_i(MSG_SOUND_MODE_SILENT),lcd_sound_state_set); - break; - case e_SOUND_MODE_MUTE: - MENU_ITEM_FUNCTION_P(_i(MSG_SOUND_MODE_MUTE),lcd_sound_state_set); - break; - default: - MENU_ITEM_FUNCTION_P(_i(MSG_SOUND_MODE_LOUD),lcd_sound_state_set); - } -//-// if (farm_mode) { MENU_ITEM_SUBMENU_P(PSTR("Farm number"), lcd_farm_no); From ac62117d6b8d166ef015c5b6f92406ccc75e557f Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Mon, 13 Aug 2018 19:38:55 +0200 Subject: [PATCH 064/141] Merge remote-tracking branch 'prusa3d/MK3' into MK3_dev --- Firmware/Configuration.h | 4 +- Firmware/Marlin.h | 14 +- Firmware/Marlin_main.cpp | 242 +++--------------------- Firmware/Timer.cpp | 2 +- Firmware/lcd.cpp | 2 + Firmware/menu.cpp | 33 +++- Firmware/menu.h | 11 +- Firmware/mesh_bed_calibration.cpp | 7 +- Firmware/mesh_bed_calibration.h | 1 + Firmware/mmu.cpp | 274 +++++++++++++++++++++++---- Firmware/mmu.h | 23 ++- Firmware/tmc2130.cpp | 33 ++-- Firmware/uart2.c | 2 + Firmware/ultralcd.cpp | 295 ++++++++++++++++++++---------- Firmware/ultralcd.h | 88 --------- Firmware/xyzcal.cpp | 16 +- 16 files changed, 547 insertions(+), 500 deletions(-) diff --git a/Firmware/Configuration.h b/Firmware/Configuration.h index 3fa648f7..6e08fe28 100644 --- a/Firmware/Configuration.h +++ b/Firmware/Configuration.h @@ -7,8 +7,8 @@ #define STR(x) STR_HELPER(x) // Firmware version -#define FW_VERSION "3.3.1" -#define FW_COMMIT_NR 845 +#define FW_VERSION "3.4.0-RC1" +#define FW_COMMIT_NR 1170 // 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 diff --git a/Firmware/Marlin.h b/Firmware/Marlin.h index d97236a3..3912c9a2 100644 --- a/Firmware/Marlin.h +++ b/Firmware/Marlin.h @@ -360,11 +360,11 @@ extern bool mmu_print_saved; //estimated time to end of the print extern uint8_t print_percent_done_normal; -extern uint16_t print_time_remaining_normal; +extern uint32_t print_time_remaining_normal; extern uint8_t print_percent_done_silent; -extern uint16_t print_time_remaining_silent; -#define PRINT_TIME_REMAINING_INIT 65535 -#define PRINT_PERCENT_DONE_INIT 255 +extern uint32_t print_time_remaining_silent; +#define PRINT_TIME_REMAINING_INIT 0xffffffff +#define PRINT_PERCENT_DONE_INIT 0xff #define PRINTER_ACTIVE (IS_SD_PRINTING || is_usb_printing || isPrintPaused || (custom_message_type == 4) || saved_printing || (lcd_commands_type == LCD_COMMAND_V2_CAL) || card.paused || mmu_print_saved) extern void calculate_extruder_multipliers(); @@ -468,12 +468,8 @@ void gcode_M701(); void proc_commands(); -void manage_response(bool move_axes, bool turn_off_nozzle); -bool mmu_get_response(bool timeout); -void mmu_not_responding(); -void mmu_load_to_nozzle(); + void M600_load_filament(); -void mmu_M600_load_filament(bool automatic); void M600_load_filament_movements(); void M600_wait_for_user(); void M600_check_state(); diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index f2ea1428..061d9352 100644 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -337,8 +337,8 @@ float pause_lastpos[4]; unsigned long pause_time = 0; unsigned long start_pause_print = millis(); unsigned long t_fan_rising_edge = millis(); -static LongTimer safetyTimer; -static LongTimer crashDetTimer; +LongTimer safetyTimer; +LongTimer crashDetTimer; //unsigned long load_filament_time; @@ -476,9 +476,9 @@ bool mmu_print_saved = false; // storing estimated time to end of print counted by slicer uint8_t print_percent_done_normal = PRINT_PERCENT_DONE_INIT; -uint16_t print_time_remaining_normal = PRINT_TIME_REMAINING_INIT; //estimated remaining print time in minutes +uint32_t print_time_remaining_normal = PRINT_TIME_REMAINING_INIT; //estimated remaining print time in minutes 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 print_time_remaining_silent = PRINT_TIME_REMAINING_INIT; //estimated remaining print time in minutes //=========================================================================== //=============================Private Variables============================= @@ -509,7 +509,6 @@ unsigned long starttime=0; unsigned long stoptime=0; unsigned long _usb_timer = 0; -static uint8_t tmp_extruder; bool extruder_under_pressure = true; @@ -973,42 +972,9 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) case 2: _delay_ms(0); break; case 3: _delay_ms(0); break; } - // _delay_ms(100); - /* - #ifdef MESH_BED_LEVELING - _delay_ms(2000); - - if (!READ(BTN_ENC)) - { - WRITE(BEEPER, HIGH); - _delay_ms(100); - WRITE(BEEPER, LOW); - _delay_ms(200); - WRITE(BEEPER, HIGH); - _delay_ms(100); - WRITE(BEEPER, LOW); - - int _z = 0; - calibration_status_store(CALIBRATION_STATUS_CALIBRATED); - EEPROM_save_B(EEPROM_BABYSTEP_X, &_z); - EEPROM_save_B(EEPROM_BABYSTEP_Y, &_z); - EEPROM_save_B(EEPROM_BABYSTEP_Z, &_z); - } - else - { - - WRITE(BEEPER, HIGH); - _delay_ms(100); - WRITE(BEEPER, LOW); - } - #endif // mesh */ } } - else - { - //_delay_ms(1000); // wait 1sec to display the splash screen // what's this and why do we need it?? - andre - } KEEPALIVE_STATE(IN_HANDLER); } @@ -1158,7 +1124,9 @@ void list_sec_lang_from_external_flash() // are initialized by the main() routine provided by the Arduino framework. void setup() { - ultralcd_init(); + mmu_init(); + + ultralcd_init(); spi_init(); @@ -1778,11 +1746,6 @@ void setup() wdt_enable(WDTO_4S); #endif //WATCHDOG - puts_P(_N("Checking MMU unit...")); - if (mmu_init()) - printf_P(_N("MMU ENABLED, finda=%hhd, version=%d\n"), mmu_finda, mmu_version); - else - puts_P(_N("MMU DISABLED")); } @@ -2016,7 +1979,7 @@ void loop() } } #endif //TMC2130 - + mmu_loop(); } #define DEFINE_PGM_READ_ANY(type, reader) \ @@ -3476,14 +3439,6 @@ void process_commands() { mmu_reset(); } - else if (code_seen("MMUFIN")) - { - mmu_read_finda(); - } - else if (code_seen("MMUVER")) - { - mmu_read_version(); - } else if (code_seen("RESET")) { // careful! if (farm_mode) { @@ -6333,21 +6288,14 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) //currently three different materials are needed (default, flex and PVA) //add storing this information for different load/unload profiles etc. in the future //firmware does not wait for "ok" from mmu - - uint8_t extruder = 255; - uint8_t filament = FILAMENT_UNDEFINED; - - if(code_seen('E')) extruder = code_value(); - if(code_seen('F')) filament = code_value(); - - printf_P(PSTR("Extruder: %d; "), extruder); - switch (filament) { - case FILAMENT_FLEX: printf_P(PSTR("Flex\n")); break; - case FILAMENT_PVA: printf_P(PSTR("PVA\n")); break; - default: printf_P(PSTR("Default\n")); break; + if (mmu_enabled) + { + uint8_t extruder = 255; + uint8_t filament = FILAMENT_UNDEFINED; + if(code_seen('E')) extruder = code_value(); + if(code_seen('F')) filament = code_value(); + mmu_set_filament_type(extruder, filament); } - printf_P(PSTR("F%d%d\n"), extruder, filament); - mmu_printf_P(PSTR("F%d%d\n"), extruder, filament); } break; @@ -7748,7 +7696,8 @@ void wait_for_heater(long codenum) { } } -void check_babystep() { +void check_babystep() +{ int babystep_z; EEPROM_read_B(EEPROM_BABYSTEP_Z, &babystep_z); if ((babystep_z < Z_BABYSTEP_MIN) || (babystep_z > Z_BABYSTEP_MAX)) { @@ -8869,7 +8818,8 @@ uint16_t print_time_remaining() { return print_t; } -uint8_t print_percent_done() { +uint8_t print_percent_done() +{ //in case that we have information from M73 gcode return percentage counted by slicer, else return percentage counted as byte_printed/filesize uint8_t percent_done = 0; if (SilentModeMenu == SILENT_MODE_OFF && print_percent_done_normal <= 100) { @@ -8884,131 +8834,16 @@ uint8_t print_percent_done() { return percent_done; } -static void print_time_remaining_init() { +static void print_time_remaining_init() +{ print_time_remaining_normal = PRINT_TIME_REMAINING_INIT; print_time_remaining_silent = PRINT_TIME_REMAINING_INIT; print_percent_done_normal = PRINT_PERCENT_DONE_INIT; print_percent_done_silent = PRINT_PERCENT_DONE_INIT; } -bool mmu_get_response(bool timeout) { - //waits for "ok" from mmu - //function returns true if "ok" was received - //if timeout is set to true function return false if there is no "ok" received before timeout - bool response = true; - LongTimer mmu_get_reponse_timeout; - KEEPALIVE_STATE(IN_PROCESS); - mmu_get_reponse_timeout.start(); - while (mmu_rx_ok() <= 0) - { - delay_keep_alive(100); - if (timeout && mmu_get_reponse_timeout.expired(5 * 60 * 1000ul)) { //5 minutes timeout - response = false; - break; - } - } - return response; -} - - -void manage_response(bool move_axes, bool turn_off_nozzle) { - - bool response = false; - mmu_print_saved = false; - bool lcd_update_was_enabled = false; - float hotend_temp_bckp = degTargetHotend(active_extruder); - float z_position_bckp = current_position[Z_AXIS]; - float x_position_bckp = current_position[X_AXIS]; - float y_position_bckp = current_position[Y_AXIS]; - while(!response) { - response = mmu_get_response(true); //wait for "ok" from mmu - if (!response) { //no "ok" was received in reserved time frame, user will fix the issue on mmu unit - if (!mmu_print_saved) { //first occurence, we are saving current position, park print head in certain position and disable nozzle heater - if (lcd_update_enabled) { - lcd_update_was_enabled = true; - lcd_update_enable(false); - } - st_synchronize(); - mmu_print_saved = true; - - hotend_temp_bckp = degTargetHotend(active_extruder); - if (move_axes) { - z_position_bckp = current_position[Z_AXIS]; - x_position_bckp = current_position[X_AXIS]; - y_position_bckp = current_position[Y_AXIS]; - - //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(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 15, active_extruder); - st_synchronize(); - - //Move XY to side - current_position[X_AXIS] = X_PAUSE_POS; - current_position[Y_AXIS] = Y_PAUSE_POS; - plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 50, active_extruder); - st_synchronize(); - } - if (turn_off_nozzle) { - //set nozzle target temperature to 0 - setAllTargetHotends(0); - printf_P(PSTR("MMU not responding\n")); - lcd_show_fullscreen_message_and_wait_P(_i("MMU needs user attention. Please press knob to resume nozzle target temperature.")); - setTargetHotend(hotend_temp_bckp, active_extruder); - while ((degTargetHotend(active_extruder) - degHotend(active_extruder)) > 5) { - delay_keep_alive(1000); - lcd_wait_for_heater(); - } - } - } - lcd_display_message_fullscreen_P(_i("Check MMU. Fix the issue and then press button on MMU unit.")); - } - else if (mmu_print_saved) { - printf_P(PSTR("MMU start responding\n")); - lcd_clear(); - lcd_display_message_fullscreen_P(_i("MMU OK. Resuming...")); - if (move_axes) { - current_position[X_AXIS] = x_position_bckp; - current_position[Y_AXIS] = y_position_bckp; - plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 50, active_extruder); - st_synchronize(); - current_position[Z_AXIS] = z_position_bckp; - plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 15, active_extruder); - st_synchronize(); - } - else { - delay_keep_alive(1000); //delay just for showing MMU OK message for a while in case that there are no xyz movements - } - } - } - if (lcd_update_was_enabled) lcd_update_enable(true); -} - -void mmu_load_to_nozzle() { - st_synchronize(); - - bool saved_e_relative_mode = axis_relative_modes[E_AXIS]; - if (!saved_e_relative_mode) axis_relative_modes[E_AXIS] = true; - current_position[E_AXIS] += 7.2f; - float feedrate = 562; - plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], feedrate / 60, active_extruder); - st_synchronize(); - current_position[E_AXIS] += 14.4f; - feedrate = 871; - plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], feedrate / 60, active_extruder); - st_synchronize(); - current_position[E_AXIS] += 36.0f; - feedrate = 1393; - plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], feedrate / 60, active_extruder); - st_synchronize(); - current_position[E_AXIS] += 14.4f; - feedrate = 871; - plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], feedrate / 60, active_extruder); - st_synchronize(); - if (!saved_e_relative_mode) axis_relative_modes[E_AXIS] = false; -} - -void M600_check_state() { +void M600_check_state() +{ //Wait for user to check the state lcd_change_fil_state = 0; @@ -9120,37 +8955,6 @@ void M600_wait_for_user() { WRITE(BEEPER, LOW); } -void mmu_M600_load_filament(bool automatic) -{ - //load filament for mmu v2 - bool yes = false; - if (!automatic) - { - yes = lcd_show_fullscreen_message_yes_no_and_wait_P(_i("Do you want to switch extruder?"), false); - if (yes) tmp_extruder = choose_extruder_menu(); - else tmp_extruder = mmu_extruder; - } - else - { - tmp_extruder = (tmp_extruder+1)%5; - } - lcd_update_enable(false); - lcd_clear(); - lcd_set_cursor(0, 1); lcd_puts_P(_T(MSG_LOADING_FILAMENT)); - lcd_print(" "); - lcd_print(tmp_extruder + 1); - snmm_filaments_used |= (1 << tmp_extruder); //for stop print - printf_P(PSTR("T code: %d \n"), tmp_extruder); - mmu_printf_P(PSTR("T%d\n"), tmp_extruder); - manage_response(false, true); - mmu_extruder = tmp_extruder; //filament change is finished - mmu_load_to_nozzle(); - - st_synchronize(); - current_position[E_AXIS]+= FILAMENTCHANGE_FINALFEED ; - plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 2, active_extruder); -} - void M600_load_filament_movements() { #ifdef SNMM diff --git a/Firmware/Timer.cpp b/Firmware/Timer.cpp index ecf9b9b9..e81abcc1 100644 --- a/Firmware/Timer.cpp +++ b/Firmware/Timer.cpp @@ -10,7 +10,7 @@ * @brief construct Timer * * It is guaranteed, that construction is equivalent with zeroing all members. - * This property can be exploited in MenuData union. + * This property can be exploited in menu_data. */ template Timer::Timer() : m_isRunning(false), m_started() diff --git a/Firmware/lcd.cpp b/Firmware/lcd.cpp index b4d969ce..e2a5d47a 100644 --- a/Firmware/lcd.cpp +++ b/Firmware/lcd.cpp @@ -754,6 +754,7 @@ void lcd_update_enable(uint8_t enabled) } } +extern LongTimer safetyTimer; void lcd_buttons_update(void) { static bool _lock = false; @@ -769,6 +770,7 @@ void lcd_buttons_update(void) lcd_timeoutToStatus.start(); if (!buttonBlanking.running() || buttonBlanking.expired(BUTTON_BLANKING_TIME)) { buttonBlanking.start(); + safetyTimer.start(); if ((lcd_button_pressed == 0) && (lcd_long_press_active == 0)) { longPressTimer.start(); diff --git a/Firmware/menu.cpp b/Firmware/menu.cpp index 33e6184c..1e4b77fa 100644 --- a/Firmware/menu.cpp +++ b/Firmware/menu.cpp @@ -116,7 +116,7 @@ uint8_t menu_item_ret(void) } /* -int menu_item_printf_P(char type_char, const char* format, ...) +int menu_draw_item_printf_P(char type_char, const char* format, ...) { va_list args; va_start(args, format); @@ -134,12 +134,14 @@ int menu_item_printf_P(char type_char, const char* format, ...) return ret; } */ + int menu_draw_item_puts_P(char type_char, const char* str) { lcd_set_cursor(0, menu_row); int cnt = lcd_printf_P(PSTR("%c%-18S%c"), (lcd_encoder == menu_item)?'>':' ', str, type_char); return cnt; } + /* int menu_draw_item_puts_P_int16(char type_char, const char* str, int16_t val, ) { @@ -148,6 +150,7 @@ int menu_draw_item_puts_P_int16(char type_char, const char* str, int16_t val, ) return cnt; } */ + void menu_item_dummy(void) { menu_item++; @@ -270,25 +273,35 @@ void menu_draw_float13(char chr, const char* str, float val) lcd_printf_P(menu_fmt_float13, chr, str, spaces, val); } -#define _menu_data menuData.edit_menu +typedef struct +{ + //Variables used when editing values. + const char* editLabel; + void* editValue; + int32_t minEditValue; + int32_t maxEditValue; +} menu_data_edit_t; + void _menu_edit_int3(void) { + menu_data_edit_t* _md = (menu_data_edit_t*)&(menu_data[0]); if (lcd_draw_update) { - if (lcd_encoder < _menu_data.minEditValue) lcd_encoder = _menu_data.minEditValue; - if (lcd_encoder > _menu_data.maxEditValue) lcd_encoder = _menu_data.maxEditValue; + if (lcd_encoder < _md->minEditValue) lcd_encoder = _md->minEditValue; + if (lcd_encoder > _md->maxEditValue) lcd_encoder = _md->maxEditValue; lcd_set_cursor(0, 1); - menu_draw_int3(' ', _menu_data.editLabel, (int)lcd_encoder); + menu_draw_int3(' ', _md->editLabel, (int)lcd_encoder); } if (LCD_CLICKED) { - *((int*)(_menu_data.editValue)) = (int)lcd_encoder; + *((int*)(_md->editValue)) = (int)lcd_encoder; menu_back(); } } uint8_t menu_item_edit_int3(const char* str, int16_t* pval, int16_t min_val, int16_t max_val) { + menu_data_edit_t* _md = (menu_data_edit_t*)&(menu_data[0]); if (menu_item == menu_line) { if (lcd_draw_update) @@ -299,10 +312,10 @@ uint8_t menu_item_edit_int3(const char* str, int16_t* pval, int16_t min_val, int if (menu_clicked && (lcd_encoder == menu_item)) { menu_submenu(_menu_edit_int3); - _menu_data.editLabel = str; - _menu_data.editValue = pval; - _menu_data.minEditValue = min_val; - _menu_data.maxEditValue = max_val; + _md->editLabel = str; + _md->editValue = pval; + _md->minEditValue = min_val; + _md->maxEditValue = max_val; lcd_encoder = *pval; return menu_item_ret(); } diff --git a/Firmware/menu.h b/Firmware/menu.h index 27548657..70a6151b 100644 --- a/Firmware/menu.h +++ b/Firmware/menu.h @@ -16,15 +16,6 @@ typedef struct uint8_t position; } menu_record_t; -typedef struct -{ - //Variables used when editing values. - const char* editLabel; - void* editValue; - int32_t minEditValue; - int32_t maxEditValue; -} menu_data_edit_t; - extern menu_record_t menu_stack[MENU_DEPTH_MAX]; extern uint8_t menu_data[MENU_DATA_SIZE]; @@ -63,7 +54,7 @@ extern void menu_submenu(menu_func_t submenu); extern uint8_t menu_item_ret(void); -//int menu_item_printf_P(char type_char, const char* format, ...); +//extern int menu_draw_item_printf_P(char type_char, const char* format, ...); extern int menu_draw_item_puts_P(char type_char, const char* str); diff --git a/Firmware/mesh_bed_calibration.cpp b/Firmware/mesh_bed_calibration.cpp index 82320c4c..1a62ed3b 100644 --- a/Firmware/mesh_bed_calibration.cpp +++ b/Firmware/mesh_bed_calibration.cpp @@ -2995,13 +2995,14 @@ static int babystepLoadZ = 0; void babystep_load() { + babystepLoadZ = 0; // Apply Z height correction aka baby stepping before mesh bed leveling gets activated. - if(calibration_status() < CALIBRATION_STATUS_LIVE_ADJUST) + if (calibration_status() < CALIBRATION_STATUS_LIVE_ADJUST) { check_babystep(); //checking if babystep is in allowed range, otherwise setting babystep to 0 // End of G80: Apply the baby stepping value. - EEPROM_read_B(EEPROM_BABYSTEP_Z,&babystepLoadZ); + EEPROM_read_B(EEPROM_BABYSTEP_Z, &babystepLoadZ); #if 0 SERIAL_ECHO("Z baby step: "); @@ -3037,7 +3038,7 @@ void babystep_undo() void babystep_reset() { - babystepLoadZ = 0; + babystepLoadZ = 0; } void count_xyz_details(float (&distanceMin)[2]) { diff --git a/Firmware/mesh_bed_calibration.h b/Firmware/mesh_bed_calibration.h index 6d020f8c..d928f1d1 100644 --- a/Firmware/mesh_bed_calibration.h +++ b/Firmware/mesh_bed_calibration.h @@ -176,6 +176,7 @@ extern void babystep_undo(); // Reset the current babystep counter without moving the axes. extern void babystep_reset(); + extern void count_xyz_details(float (&distanceMin)[2]); extern bool sample_z(); diff --git a/Firmware/mmu.cpp b/Firmware/mmu.cpp index 1a6680e9..1e1afc78 100644 --- a/Firmware/mmu.cpp +++ b/Firmware/mmu.cpp @@ -10,18 +10,34 @@ extern const char* lcd_display_message_fullscreen_P(const char *msg); +extern void lcd_show_fullscreen_message_and_wait_P(const char *msg); +extern int8_t lcd_show_fullscreen_message_yes_no_and_wait_P(const char *msg, bool allow_timeouting = true, bool default_yes = false); extern void lcd_return_to_status(); +extern void lcd_wait_for_heater(); +extern char choose_extruder_menu(); + + +#define MMU_TODELAY 100 +#define MMU_TIMEOUT 10 + +#define MMU_HWRESET +#define MMU_RST_PIN 76 -#define MMU_TIMEOUT 100 bool mmu_enabled = false; +int8_t mmu_state = 0; + uint8_t mmu_extruder = 0; +uint8_t tmp_extruder = 0; + int8_t mmu_finda = -1; int16_t mmu_version = -1; +int16_t mmu_buildnr = -1; + //clear rx buffer void mmu_clr_rx_buf(void) @@ -59,53 +75,249 @@ int8_t mmu_rx_start(void) return uart2_rx_str_P(PSTR("start\n")); } -//initialize mmu_unit -bool mmu_init(void) +//initialize mmu2 unit - first part - should be done at begining of startup process +void mmu_init(void) { + digitalWrite(MMU_RST_PIN, HIGH); + pinMode(MMU_RST_PIN, OUTPUT); //setup reset pin uart2_init(); //init uart2 _delay_ms(10); //wait 10ms for sure - if (mmu_reset()) //reset mmu + mmu_reset(); //reset mmu (HW or SW), do not wait for response + mmu_state = -1; +} + +//mmu main loop - state machine processing +void mmu_loop(void) +{ +// printf_P(PSTR("MMU loop, state=%d\n"), mmu_state); + switch (mmu_state) { - mmu_read_finda(); - mmu_read_version(); - return true; + case 0: + return; + case -1: + if (mmu_rx_start() > 0) + { + puts_P(PSTR("MMU => 'start'")); + puts_P(PSTR("MMU <= 'S1'")); + mmu_puts_P(PSTR("S1\n")); //send 'read version' request + mmu_state = -2; + } + else if (millis() > 30000) //30sec after reset disable mmu + { + puts_P(PSTR("MMU not responding - DISABLED")); + mmu_state = 0; + } + return; + case -2: + if (mmu_rx_ok() > 0) + { + fscanf_P(uart2io, PSTR("%u"), &mmu_version); //scan version from buffer + printf_P(PSTR("MMU => '%dok'\n"), mmu_version); + puts_P(PSTR("MMU <= 'S2'")); + mmu_puts_P(PSTR("S2\n")); //send 'read buildnr' request + mmu_state = -3; + } + return; + case -3: + if (mmu_rx_ok() > 0) + { + fscanf_P(uart2io, PSTR("%u"), &mmu_buildnr); //scan buildnr from buffer + printf_P(PSTR("MMU => '%dok'\n"), mmu_buildnr); + puts_P(PSTR("MMU <= 'P0'")); + mmu_puts_P(PSTR("P0\n")); //send 'read finda' request + mmu_state = -4; + } + return; + case -4: + if (mmu_rx_ok() > 0) + { + fscanf_P(uart2io, PSTR("%hhu"), &mmu_finda); //scan finda from buffer + printf_P(PSTR("MMU => '%dok'\n"), mmu_finda); + puts_P(PSTR("MMU - ENABLED")); + mmu_enabled = true; + mmu_state = 1; + } + return; } - return false; } -bool mmu_reset(void) +void mmu_reset(void) { - mmu_puts_P(PSTR("X0\n")); //send command - unsigned char timeout = 10; //timeout = 10x100ms - while ((mmu_rx_start() <= 0) && (--timeout)) - delay_keep_alive(MMU_TIMEOUT); - mmu_enabled = timeout?true:false; - return mmu_enabled; +#ifdef MMU_HWRESET //HW - pulse reset pin + digitalWrite(MMU_RST_PIN, LOW); + _delay_us(100); + digitalWrite(MMU_RST_PIN, HIGH); +#else //SW - send X0 command + mmu_puts_P(PSTR("X0\n")); +#endif } -int8_t mmu_read_finda(void) +int8_t mmu_set_filament_type(uint8_t extruder, uint8_t filament) { - mmu_puts_P(PSTR("P0\n")); - unsigned char timeout = 10; //10x100ms + printf_P(PSTR("MMU <= 'F%d %d'\n"), extruder, filament); + mmu_printf_P(PSTR("F%d %d\n"), extruder, filament); + unsigned char timeout = MMU_TIMEOUT; //10x100ms while ((mmu_rx_ok() <= 0) && (--timeout)) - delay_keep_alive(MMU_TIMEOUT); - mmu_finda = -1; - if (timeout) - fscanf_P(uart2io, PSTR("%hhu"), &mmu_finda); - return mmu_finda; + delay_keep_alive(MMU_TODELAY); + return timeout?1:0; } -int16_t mmu_read_version(void) +bool mmu_get_response(bool timeout) { - mmu_puts_P(PSTR("S1\n")); - unsigned char timeout = 10; //10x100ms - while ((mmu_rx_ok() <= 0) && (--timeout)) - delay_keep_alive(MMU_TIMEOUT); - if (timeout) - fscanf_P(uart2io, PSTR("%u"), &mmu_version); - return mmu_version; + printf_P(PSTR("mmu_get_response - begin\n")); + //waits for "ok" from mmu + //function returns true if "ok" was received + //if timeout is set to true function return false if there is no "ok" received before timeout + bool response = true; + LongTimer mmu_get_reponse_timeout; + KEEPALIVE_STATE(IN_PROCESS); + mmu_get_reponse_timeout.start(); + while (mmu_rx_ok() <= 0) + { + delay_keep_alive(100); + if (timeout && mmu_get_reponse_timeout.expired(5 * 60 * 1000ul)) + { //5 minutes timeout + response = false; + break; + } + } + printf_P(PSTR("mmu_get_response - end %d\n"), response?1:0); + return response; } + +void manage_response(bool move_axes, bool turn_off_nozzle) +{ + bool response = false; + mmu_print_saved = false; + bool lcd_update_was_enabled = false; + float hotend_temp_bckp = degTargetHotend(active_extruder); + float z_position_bckp = current_position[Z_AXIS]; + float x_position_bckp = current_position[X_AXIS]; + float y_position_bckp = current_position[Y_AXIS]; + while(!response) + { + response = mmu_get_response(true); //wait for "ok" from mmu + if (!response) { //no "ok" was received in reserved time frame, user will fix the issue on mmu unit + if (!mmu_print_saved) { //first occurence, we are saving current position, park print head in certain position and disable nozzle heater + if (lcd_update_enabled) { + lcd_update_was_enabled = true; + lcd_update_enable(false); + } + st_synchronize(); + mmu_print_saved = true; + + hotend_temp_bckp = degTargetHotend(active_extruder); + if (move_axes) { + z_position_bckp = current_position[Z_AXIS]; + x_position_bckp = current_position[X_AXIS]; + y_position_bckp = current_position[Y_AXIS]; + + //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(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 15, active_extruder); + st_synchronize(); + + //Move XY to side + current_position[X_AXIS] = X_PAUSE_POS; + current_position[Y_AXIS] = Y_PAUSE_POS; + plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 50, active_extruder); + st_synchronize(); + } + if (turn_off_nozzle) { + //set nozzle target temperature to 0 + setAllTargetHotends(0); + printf_P(PSTR("MMU not responding\n")); + lcd_show_fullscreen_message_and_wait_P(_i("MMU needs user attention. Please press knob to resume nozzle target temperature.")); + setTargetHotend(hotend_temp_bckp, active_extruder); + while ((degTargetHotend(active_extruder) - degHotend(active_extruder)) > 5) { + delay_keep_alive(1000); + lcd_wait_for_heater(); + } + } + } + lcd_display_message_fullscreen_P(_i("Check MMU. Fix the issue and then press button on MMU unit.")); + } + else if (mmu_print_saved) { + printf_P(PSTR("MMU start responding\n")); + lcd_clear(); + lcd_display_message_fullscreen_P(_i("MMU OK. Resuming...")); + if (move_axes) { + current_position[X_AXIS] = x_position_bckp; + current_position[Y_AXIS] = y_position_bckp; + plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 50, active_extruder); + st_synchronize(); + current_position[Z_AXIS] = z_position_bckp; + plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 15, active_extruder); + st_synchronize(); + } + else { + delay_keep_alive(1000); //delay just for showing MMU OK message for a while in case that there are no xyz movements + } + } + } + if (lcd_update_was_enabled) lcd_update_enable(true); +} + +void mmu_load_to_nozzle() +{ + st_synchronize(); + + bool saved_e_relative_mode = axis_relative_modes[E_AXIS]; + if (!saved_e_relative_mode) axis_relative_modes[E_AXIS] = true; + current_position[E_AXIS] += 7.2f; + float feedrate = 562; + plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], feedrate / 60, active_extruder); + st_synchronize(); + current_position[E_AXIS] += 14.4f; + feedrate = 871; + plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], feedrate / 60, active_extruder); + st_synchronize(); + current_position[E_AXIS] += 36.0f; + feedrate = 1393; + plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], feedrate / 60, active_extruder); + st_synchronize(); + current_position[E_AXIS] += 14.4f; + feedrate = 871; + plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], feedrate / 60, active_extruder); + st_synchronize(); + if (!saved_e_relative_mode) axis_relative_modes[E_AXIS] = false; +} + +void mmu_M600_load_filament(bool automatic) +{ + //load filament for mmu v2 + bool yes = false; + if (!automatic) { + yes = lcd_show_fullscreen_message_yes_no_and_wait_P(_i("Do you want to switch extruder?"), false); + if(yes) tmp_extruder = choose_extruder_menu(); + else tmp_extruder = mmu_extruder; + + } + else { + tmp_extruder = (tmp_extruder+1)%5; + } + lcd_update_enable(false); + lcd_clear(); + lcd_set_cursor(0, 1); lcd_puts_P(_T(MSG_LOADING_FILAMENT)); + lcd_print(" "); + lcd_print(tmp_extruder + 1); + snmm_filaments_used |= (1 << tmp_extruder); //for stop print + printf_P(PSTR("T code: %d \n"), tmp_extruder); + mmu_printf_P(PSTR("T%d\n"), tmp_extruder); + + manage_response(false, true); + mmu_extruder = tmp_extruder; //filament change is finished + + mmu_load_to_nozzle(); + + st_synchronize(); + current_position[E_AXIS]+= FILAMENTCHANGE_FINALFEED ; + plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 2, active_extruder); +} + + void extr_mov(float shift, float feed_rate) { //move extruder no matter what the current heater temperature is set_extrude_min_temp(.0); diff --git a/Firmware/mmu.h b/Firmware/mmu.h index 91a1f511..9411ec37 100644 --- a/Firmware/mmu.h +++ b/Firmware/mmu.h @@ -5,11 +5,16 @@ extern bool mmu_enabled; +extern int8_t mmu_state; + extern uint8_t mmu_extruder; +extern uint8_t tmp_extruder; + extern int8_t mmu_finda; extern int16_t mmu_version; +extern int16_t mmu_buildnr; extern int mmu_puts_P(const char* str); @@ -19,13 +24,23 @@ extern int mmu_printf_P(const char* format, ...); extern int8_t mmu_rx_ok(void); -extern bool mmu_init(void); +extern void mmu_init(void); -extern bool mmu_reset(void); +extern void mmu_loop(void); -extern int8_t mmu_read_finda(void); -extern int16_t mmu_read_version(void); +extern void mmu_reset(void); + +extern int8_t mmu_set_filament_type(uint8_t extruder, uint8_t filament); + + +extern bool mmu_get_response(bool timeout); + +extern void manage_response(bool move_axes, bool turn_off_nozzle); + +extern void mmu_load_to_nozzle(); + +extern void mmu_M600_load_filament(bool automatic); extern void extr_mov(float shift, float feed_rate); diff --git a/Firmware/tmc2130.cpp b/Firmware/tmc2130.cpp index ddef5dd8..1d1495fe 100644 --- a/Firmware/tmc2130.cpp +++ b/Firmware/tmc2130.cpp @@ -77,7 +77,8 @@ bool tmc2130_sg_change = false; bool skip_debug_msg = false; -#define DBG(args...) printf_P(args) +#define DBG(args...) +//printf_P(args) #ifndef _n #define _n PSTR #endif //_n @@ -150,7 +151,7 @@ uint16_t __tcoolthrs(uint8_t axis) void tmc2130_init() { - DBG(_n("tmc2130_init(), mode=%S\n"), tmc2130_mode?_n("STEALTH"):_n("NORMAL")); +// DBG(_n("tmc2130_init(), mode=%S\n"), tmc2130_mode?_n("STEALTH"):_n("NORMAL")); WRITE(X_TMC2130_CS, HIGH); WRITE(Y_TMC2130_CS, HIGH); WRITE(Z_TMC2130_CS, HIGH); @@ -442,8 +443,8 @@ void tmc2130_setup_chopper(uint8_t axis, uint8_t mres, uint8_t current_h, uint8_ // toff = TMC2130_TOFF_E; // toff = 3-5 // rndtf = 1; } - 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); +// 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); @@ -458,31 +459,31 @@ void tmc2130_setup_chopper(uint8_t axis, uint8_t mres, uint8_t current_h, uint8_ void tmc2130_set_current_h(uint8_t axis, uint8_t current) { - DBG(_n("tmc2130_set_current_h(axis=%d, current=%d\n"), axis, current); +// DBG(_n("tmc2130_set_current_h(axis=%d, current=%d\n"), axis, current); tmc2130_current_h[axis] = current; tmc2130_setup_chopper(axis, tmc2130_mres[axis], tmc2130_current_h[axis], tmc2130_current_r[axis]); } void tmc2130_set_current_r(uint8_t axis, uint8_t current) { - DBG(_n("tmc2130_set_current_r(axis=%d, current=%d\n"), axis, current); +// DBG(_n("tmc2130_set_current_r(axis=%d, current=%d\n"), axis, current); tmc2130_current_r[axis] = current; tmc2130_setup_chopper(axis, tmc2130_mres[axis], tmc2130_current_h[axis], tmc2130_current_r[axis]); } void tmc2130_print_currents() { - DBG(_n("tmc2130_print_currents()\n\tH\tR\nX\t%d\t%d\nY\t%d\t%d\nZ\t%d\t%d\nE\t%d\t%d\n"), - tmc2130_current_h[0], tmc2130_current_r[0], - tmc2130_current_h[1], tmc2130_current_r[1], - tmc2130_current_h[2], tmc2130_current_r[2], - tmc2130_current_h[3], tmc2130_current_r[3] - ); +// DBG(_n("tmc2130_print_currents()\n\tH\tR\nX\t%d\t%d\nY\t%d\t%d\nZ\t%d\t%d\nE\t%d\t%d\n"), +// tmc2130_current_h[0], tmc2130_current_r[0], +// tmc2130_current_h[1], tmc2130_current_r[1], +// tmc2130_current_h[2], tmc2130_current_r[2], +// tmc2130_current_h[3], tmc2130_current_r[3] +// ); } void tmc2130_set_pwm_ampl(uint8_t axis, uint8_t pwm_ampl) { - DBG(_n("tmc2130_set_pwm_ampl(axis=%hhd, pwm_ampl=%hhd\n"), axis, pwm_ampl); +// DBG(_n("tmc2130_set_pwm_ampl(axis=%hhd, pwm_ampl=%hhd\n"), axis, pwm_ampl); tmc2130_pwm_ampl[axis] = pwm_ampl; if (((axis == 0) || (axis == 1)) && (tmc2130_mode == TMC2130_MODE_SILENT)) tmc2130_wr_PWMCONF(axis, tmc2130_pwm_ampl[axis], tmc2130_pwm_grad[axis], tmc2130_pwm_freq[axis], tmc2130_pwm_auto[axis], 0, 0); @@ -490,7 +491,7 @@ void tmc2130_set_pwm_ampl(uint8_t axis, uint8_t pwm_ampl) void tmc2130_set_pwm_grad(uint8_t axis, uint8_t pwm_grad) { - DBG(_n("tmc2130_set_pwm_grad(axis=%hhd, pwm_grad=%hhd\n"), axis, pwm_grad); +// DBG(_n("tmc2130_set_pwm_grad(axis=%hhd, pwm_grad=%hhd\n"), axis, pwm_grad); tmc2130_pwm_grad[axis] = pwm_grad; if (((axis == 0) || (axis == 1)) && (tmc2130_mode == TMC2130_MODE_SILENT)) tmc2130_wr_PWMCONF(axis, tmc2130_pwm_ampl[axis], tmc2130_pwm_grad[axis], tmc2130_pwm_freq[axis], tmc2130_pwm_auto[axis], 0, 0); @@ -853,12 +854,12 @@ void tmc2130_set_wave(uint8_t axis, uint8_t amp, uint8_t fac1000) { // TMC2130 wave compression algorithm // optimized for minimal memory requirements - printf_P(PSTR("tmc2130_set_wave %hhd %hhd\n"), axis, fac1000); +// printf_P(PSTR("tmc2130_set_wave %hhd %hhd\n"), axis, fac1000); if (fac1000 < TMC2130_WAVE_FAC1000_MIN) fac1000 = 0; if (fac1000 > TMC2130_WAVE_FAC1000_MAX) fac1000 = TMC2130_WAVE_FAC1000_MAX; float fac = 0; if (fac1000) fac = ((float)((uint16_t)fac1000 + 1000) / 1000); //correction factor - printf_P(PSTR(" factor: %s\n"), ftostr43(fac)); +// printf_P(PSTR(" factor: %s\n"), ftostr43(fac)); uint8_t vA = 0; //value of currentA uint8_t va = 0; //previous vA int8_t d0 = 0; //delta0 diff --git a/Firmware/uart2.c b/Firmware/uart2.c index 894d9587..47238999 100644 --- a/Firmware/uart2.c +++ b/Firmware/uart2.c @@ -34,6 +34,8 @@ int uart2_getchar(FILE *stream __attribute__((unused))) //uart init (io + FILE stream) void uart2_init(void) { + DDRH &= ~0x01; + PORTH |= 0x01; rbuf_ini(uart2_ibuf, sizeof(uart2_ibuf) - 4); UCSR2A |= (1 << U2X2); // baudrate multiplier UBRR2L = UART_BAUD_SELECT(UART2_BAUD, F_CPU); // select baudrate diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index 7c3078f7..b278eccc 100644 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -44,12 +44,6 @@ char longFilenameOLD[LONG_FILENAME_LENGTH]; static void lcd_sd_updir(); - -// State of the currently active menu. -// C Union manages sharing of the static memory by all the menus. -union MenuData menuData; - - int8_t ReInitLCD = 0; @@ -116,11 +110,14 @@ static void lcd_tune_menu(); //static void lcd_move_menu(); static void lcd_settings_menu(); static void lcd_calibration_menu(); -static void lcd_control_temperature_menu(); #ifdef LINEARITY_CORRECTION static void lcd_settings_menu_back(); #endif //LINEARITY_CORRECTION - +static void lcd_control_temperature_menu(); +static void lcd_control_temperature_preheat_pla_settings_menu(); +static void lcd_control_temperature_preheat_abs_settings_menu(); +static void lcd_control_motion_menu(); +static void lcd_control_volumetric_menu(); static void prusa_stat_printerstatus(int _status); static void prusa_stat_farm_number(); static void prusa_stat_temperatures(); @@ -225,9 +222,7 @@ bool wait_for_unclick; - - - +const char STR_SEPARATOR[] PROGMEM = "------------"; @@ -608,12 +603,13 @@ static void lcd_implementation_status_screen() //Print Feedrate lcd_set_cursor(LCD_WIDTH - 8-2, 1); lcd_puts_P(PSTR(" ")); +/* if (maxlimit_status) { maxlimit_status = 0; lcd_print('!'); } - else + else*/ lcd_print(LCD_STR_FEEDRATE[0]); lcd_print(itostr3(feedmultiply)); lcd_puts_P(PSTR("% ")); @@ -1958,6 +1954,9 @@ static void lcd_menu_extruder_info() // Display Nozzle fan RPM fan_speed_RPM[0] = 60*fan_speed[0]; fan_speed_RPM[1] = 60*fan_speed[1]; + + lcd_timeoutToStatus.stop(); //infinite timeout + lcd_printf_P(_N( ESC_H(0,0) "Nozzle FAN: %4d RPM\n" @@ -2005,6 +2004,7 @@ static void lcd_menu_fails_stats_total() // Filam. runouts 000 // Crash X 000 Y 000 ////////////////////// + lcd_timeoutToStatus.stop(); //infinite timeout uint16_t power = eeprom_read_word((uint16_t*)EEPROM_POWER_COUNT_TOT); uint16_t filam = eeprom_read_word((uint16_t*)EEPROM_FERROR_COUNT_TOT); uint16_t crashX = eeprom_read_word((uint16_t*)EEPROM_CRASH_COUNT_X_TOT); @@ -2021,6 +2021,7 @@ static void lcd_menu_fails_stats_print() // Filam. runouts 000 // Crash X 000 Y 000 ////////////////////// + lcd_timeoutToStatus.stop(); //infinite timeout uint8_t power = eeprom_read_byte((uint8_t*)EEPROM_POWER_COUNT); uint8_t filam = eeprom_read_byte((uint8_t*)EEPROM_FERROR_COUNT); uint8_t crashX = eeprom_read_byte((uint8_t*)EEPROM_CRASH_COUNT_X); @@ -2061,6 +2062,7 @@ static void lcd_menu_fails_stats() */ static void lcd_menu_fails_stats() { + lcd_timeoutToStatus.stop(); //infinite timeout uint8_t filamentLast = eeprom_read_byte((uint8_t*)EEPROM_FERROR_COUNT); uint16_t filamentTotal = eeprom_read_word((uint16_t*)EEPROM_FERROR_COUNT_TOT); lcd_printf_P(PSTR(ESC_H(0,0) "Last print failures" ESC_H(1,1) "Filam. runouts %-3d" ESC_H(0,2) "Total failures" ESC_H(1,3) "Filam. runouts %-3d"), filamentLast, filamentTotal); @@ -2069,6 +2071,7 @@ static void lcd_menu_fails_stats() #else static void lcd_menu_fails_stats() { + lcd_timeoutToStatus.stop(); //infinite timeout MENU_BEGIN(); MENU_ITEM_BACK_P(_T(MSG_MAIN)); MENU_END(); @@ -2095,6 +2098,8 @@ static void lcd_menu_debug() static void lcd_menu_temperatures() { + lcd_timeoutToStatus.stop(); //infinite timeout + lcd_printf_P(PSTR(ESC_H(1,0) "Nozzle: %d%c" ESC_H(1,1) "Bed: %d%c"), (int)current_temperature[0], '\x01', (int)current_temperature_bed, '\x01'); #ifdef AMBIENT_THERMISTOR lcd_printf_P(PSTR(ESC_H(1,2) "Ambient: %d%c" ESC_H(1,3) "PINDA: %d%c"), (int)current_temperature_ambient, '\x01', (int)current_temperature_pinda, '\x01'); @@ -2112,6 +2117,7 @@ static void lcd_menu_temperatures() #define VOLT_DIV_REF 5 static void lcd_menu_voltages() { + lcd_timeoutToStatus.stop(); //infinite timeout float volt_pwr = VOLT_DIV_REF * ((float)current_voltage_raw_pwr / (1023 * OVERSAMPLENR)) / VOLT_DIV_FAC; // float volt_bed = VOLT_DIV_REF * ((float)current_voltage_raw_bed / (1023 * OVERSAMPLENR)) / VOLT_DIV_FAC; // lcd_printf_P(PSTR(ESC_H(1,1)"PWR: %d.%01dV" ESC_H(1,2)"BED: %d.%01dV"), (int)volt_pwr, (int)(10*fabs(volt_pwr - (int)volt_pwr)), (int)volt_bed, (int)(10*fabs(volt_bed - (int)volt_bed))); @@ -2170,21 +2176,34 @@ static void lcd_preheat_menu() static void lcd_support_menu() { - if (menuData.supportMenu.status == 0 || lcd_draw_update == 2) { + typedef struct + { // 22bytes total + int8_t status; // 1byte + bool is_flash_air; // 1byte + uint8_t ip[4]; // 4bytes + char ip_str[3*4+3+1]; // 16bytes + } _menu_data_t; +#if (22 > MENU_DATA_SIZE) +#error "check MENU_DATA_SIZE definition!" +#endif + _menu_data_t* _md = (_menu_data_t*)&(menu_data[0]); + if (_md->status == 0 || lcd_draw_update == 2) + { // Menu was entered or SD card status has changed (plugged in or removed). // Initialize its status. - menuData.supportMenu.status = 1; - menuData.supportMenu.is_flash_air = card.ToshibaFlashAir_isEnabled() && card.ToshibaFlashAir_GetIP(menuData.supportMenu.ip); - if (menuData.supportMenu.is_flash_air) - sprintf_P(menuData.supportMenu.ip_str, PSTR("%d.%d.%d.%d"), - menuData.supportMenu.ip[0], menuData.supportMenu.ip[1], - menuData.supportMenu.ip[2], menuData.supportMenu.ip[3]); - } else if (menuData.supportMenu.is_flash_air && - menuData.supportMenu.ip[0] == 0 && menuData.supportMenu.ip[1] == 0 && - menuData.supportMenu.ip[2] == 0 && menuData.supportMenu.ip[3] == 0 && - ++ menuData.supportMenu.status == 16) { + _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) + { // Waiting for the FlashAir card to get an IP address from a router. Force an update. - menuData.supportMenu.status = 0; + _md->status = 0; } MENU_BEGIN(); @@ -2207,22 +2226,41 @@ static void lcd_support_menu() MENU_ITEM_BACK_P(_i("prusa3d.com"));////MSG_PRUSA3D c=0 r=0 MENU_ITEM_BACK_P(_i("forum.prusa3d.com"));////MSG_PRUSA3D_FORUM c=0 r=0 MENU_ITEM_BACK_P(_i("howto.prusa3d.com"));////MSG_PRUSA3D_HOWTO c=0 r=0 - MENU_ITEM_BACK_P(PSTR("------------")); + MENU_ITEM_BACK_P(STR_SEPARATOR); MENU_ITEM_BACK_P(PSTR(FILAMENT_SIZE)); MENU_ITEM_BACK_P(PSTR(ELECTRONICS)); MENU_ITEM_BACK_P(PSTR(NOZZLE_TYPE)); - MENU_ITEM_BACK_P(PSTR("------------")); + MENU_ITEM_BACK_P(STR_SEPARATOR); MENU_ITEM_BACK_P(_i("Date:"));////MSG_DATE c=17 r=1 MENU_ITEM_BACK_P(PSTR(__DATE__)); + MENU_ITEM_BACK_P(STR_SEPARATOR); + if (mmu_enabled) + { + MENU_ITEM_BACK_P(PSTR("MMU2 connected")); + MENU_ITEM_BACK_P(PSTR(" FW:")); + if (((menu_item - 1) == menu_line) && lcd_draw_update) + { + lcd_set_cursor(6, menu_row); + if ((mmu_version > 0) && (mmu_buildnr > 0)) + lcd_printf_P(PSTR("%d.%d.%d-%d"), mmu_version/100, mmu_version%100/10, mmu_version%10, mmu_buildnr); + else + lcd_puts_P(PSTR("unknown")); + } + } + else + MENU_ITEM_BACK_P(PSTR("MMU2 N/A")); + + // Show the FlashAir IP address, if the card is available. - if (menuData.supportMenu.is_flash_air) { - MENU_ITEM_BACK_P(PSTR("------------")); + if (_md->is_flash_air) { + MENU_ITEM_BACK_P(STR_SEPARATOR); MENU_ITEM_BACK_P(PSTR("FlashAir IP Addr:")); -///! MENU_ITEM(back_RAM, menuData.supportMenu.ip_str, 0); +///! MENU_ITEM(back_RAM, _md->ip_str, 0); } + #ifndef MK1BP - MENU_ITEM_BACK_P(PSTR("------------")); + 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=15 r=1 @@ -2476,7 +2514,7 @@ static void lcd_menu_AutoLoadFilament() } else { - ShortTimer* ptimer = (ShortTimer*)&(menuData.autoLoadFilamentMenu.dummy); + ShortTimer* ptimer = (ShortTimer*)&(menu_data[0]); if (!ptimer->running()) ptimer->start(); lcd_set_cursor(0, 0); lcd_puts_P(_T(MSG_ERROR)); @@ -2586,10 +2624,19 @@ void lcd_menu_statistics() static void _lcd_move(const char *name, int axis, int min, int max) { - if (!menuData._lcd_moveMenu.initialized) + typedef struct + { // 2bytes total + bool initialized; // 1byte + bool endstopsEnabledPrevious; // 1byte + } _menu_data_t; +#if (2 > MENU_DATA_SIZE) +#error "check MENU_DATA_SIZE definition!" +#endif + _menu_data_t* _md = (_menu_data_t*)&(menu_data[0]); + if (!_md->initialized) { - menuData._lcd_moveMenu.endstopsEnabledPrevious = enable_endstops(false); - menuData._lcd_moveMenu.initialized = true; + _md->endstopsEnabledPrevious = enable_endstops(false); + _md->initialized = true; } if (lcd_encoder != 0) { @@ -2610,7 +2657,7 @@ static void _lcd_move(const char *name, int axis, int min, int max) lcd_set_cursor(0, 1); menu_draw_float31(' ', name, current_position[axis]); } - if (menuExiting || LCD_CLICKED) (void)enable_endstops(menuData._lcd_moveMenu.endstopsEnabledPrevious); + if (menuExiting || LCD_CLICKED) (void)enable_endstops(_md->endstopsEnabledPrevious); if (LCD_CLICKED) menu_back(); } @@ -2782,23 +2829,37 @@ static void lcd_move_z() { */ static void _lcd_babystep(int axis, const char *msg) { - if (menuData.babyStep.status == 0) + typedef struct + { // 19bytes total + int8_t status; // 1byte + int babystepMem[3]; // 6bytes + float babystepMemMM[3]; // 12bytes + } _menu_data_t; +#if (19 > MENU_DATA_SIZE) +#error "check MENU_DATA_SIZE definition!" +#endif + _menu_data_t* _md = (_menu_data_t*)&(menu_data[0]); + if (_md->status == 0) { // Menu was entered. // Initialize its status. - menuData.babyStep.status = 1; + _md->status = 1; check_babystep(); - EEPROM_read_B(EEPROM_BABYSTEP_X, &menuData.babyStep.babystepMem[0]); - EEPROM_read_B(EEPROM_BABYSTEP_Y, &menuData.babyStep.babystepMem[1]); - EEPROM_read_B(EEPROM_BABYSTEP_Z, &menuData.babyStep.babystepMem[2]); + EEPROM_read_B(EEPROM_BABYSTEP_X, &_md->babystepMem[0]); + EEPROM_read_B(EEPROM_BABYSTEP_Y, &_md->babystepMem[1]); + EEPROM_read_B(EEPROM_BABYSTEP_Z, &_md->babystepMem[2]); - menuData.babyStep.babystepMemMM[0] = menuData.babyStep.babystepMem[0]/axis_steps_per_unit[X_AXIS]; - menuData.babyStep.babystepMemMM[1] = menuData.babyStep.babystepMem[1]/axis_steps_per_unit[Y_AXIS]; - menuData.babyStep.babystepMemMM[2] = menuData.babyStep.babystepMem[2]/axis_steps_per_unit[Z_AXIS]; + // same logic as in babystep_load + if (calibration_status() >= CALIBRATION_STATUS_LIVE_ADJUST) + _md->babystepMem[2] = 0; + + _md->babystepMemMM[0] = _md->babystepMem[0]/axis_steps_per_unit[X_AXIS]; + _md->babystepMemMM[1] = _md->babystepMem[1]/axis_steps_per_unit[Y_AXIS]; + _md->babystepMemMM[2] = _md->babystepMem[2]/axis_steps_per_unit[Z_AXIS]; lcd_draw_update = 1; //SERIAL_ECHO("Z baby step: "); - //SERIAL_ECHO(menuData.babyStep.babystepMem[2]); + //SERIAL_ECHO(_md->babystepMem[2]); // Wait 90 seconds before closing the live adjust dialog. lcd_timeoutToStatus.start(); } @@ -2806,11 +2867,11 @@ static void _lcd_babystep(int axis, const char *msg) if (lcd_encoder != 0) { if (homing_flag) lcd_encoder = 0; - menuData.babyStep.babystepMem[axis] += (int)lcd_encoder; + _md->babystepMem[axis] += (int)lcd_encoder; if (axis == 2) { - if (menuData.babyStep.babystepMem[axis] < Z_BABYSTEP_MIN) menuData.babyStep.babystepMem[axis] = Z_BABYSTEP_MIN; //-3999 -> -9.99 mm - else if (menuData.babyStep.babystepMem[axis] > Z_BABYSTEP_MAX) menuData.babyStep.babystepMem[axis] = Z_BABYSTEP_MAX; //0 + if (_md->babystepMem[axis] < Z_BABYSTEP_MIN) _md->babystepMem[axis] = Z_BABYSTEP_MIN; //-3999 -> -9.99 mm + else if (_md->babystepMem[axis] > Z_BABYSTEP_MAX) _md->babystepMem[axis] = Z_BABYSTEP_MAX; //0 else { CRITICAL_SECTION_START @@ -2818,7 +2879,7 @@ static void _lcd_babystep(int axis, const char *msg) CRITICAL_SECTION_END } } - menuData.babyStep.babystepMemMM[axis] = menuData.babyStep.babystepMem[axis]/axis_steps_per_unit[axis]; + _md->babystepMemMM[axis] = _md->babystepMem[axis]/axis_steps_per_unit[axis]; delay(50); lcd_encoder = 0; lcd_draw_update = 1; @@ -2826,14 +2887,14 @@ static void _lcd_babystep(int axis, const char *msg) if (lcd_draw_update) { lcd_set_cursor(0, 1); - menu_draw_float13(' ', msg, menuData.babyStep.babystepMemMM[axis]); + menu_draw_float13(' ', msg, _md->babystepMemMM[axis]); } if (LCD_CLICKED || menuExiting) { // Only update the EEPROM when leaving the menu. EEPROM_save_B( (axis == X_AXIS) ? EEPROM_BABYSTEP_X : ((axis == Y_AXIS) ? EEPROM_BABYSTEP_Y : EEPROM_BABYSTEP_Z), - &menuData.babyStep.babystepMem[axis]); + &_md->babystepMem[axis]); if(Z_AXIS == axis) calibration_status_store(CALIBRATION_STATUS_CALIBRATED); } if (LCD_CLICKED) menu_back(); @@ -2845,72 +2906,94 @@ static void lcd_babystep_z() { static void lcd_adjust_bed(); +typedef struct +{ // 13bytes total + int8_t status; // 1byte + int8_t left; // 1byte + int8_t right; // 1byte + int8_t front; // 1byte + int8_t rear; // 1byte + int left2; // 2byte + int right2; // 2byte + int front2; // 2byte + int rear2; // 2byte +} _menu_data_adjust_bed_t; +#if (13 > MENU_DATA_SIZE) +#error "check MENU_DATA_SIZE definition!" +#endif + static void lcd_adjust_bed_reset() { - eeprom_update_byte((unsigned char*)EEPROM_BED_CORRECTION_VALID, 1); - eeprom_update_byte((unsigned char*)EEPROM_BED_CORRECTION_LEFT , 0); - eeprom_update_byte((unsigned char*)EEPROM_BED_CORRECTION_RIGHT, 0); - eeprom_update_byte((unsigned char*)EEPROM_BED_CORRECTION_FRONT, 0); - eeprom_update_byte((unsigned char*)EEPROM_BED_CORRECTION_REAR , 0); - menuData.adjustBed.status = 0; + eeprom_update_byte((unsigned char*)EEPROM_BED_CORRECTION_VALID, 1); + eeprom_update_byte((unsigned char*)EEPROM_BED_CORRECTION_LEFT , 0); + eeprom_update_byte((unsigned char*)EEPROM_BED_CORRECTION_RIGHT, 0); + eeprom_update_byte((unsigned char*)EEPROM_BED_CORRECTION_FRONT, 0); + eeprom_update_byte((unsigned char*)EEPROM_BED_CORRECTION_REAR , 0); + _menu_data_adjust_bed_t* _md = (_menu_data_adjust_bed_t*)&(menu_data[0]); + _md->status = 0; } -void adjust_bed_reset() { +void adjust_bed_reset() +{ + _menu_data_adjust_bed_t* _md = (_menu_data_adjust_bed_t*)&(menu_data[0]); eeprom_update_byte((unsigned char*)EEPROM_BED_CORRECTION_VALID, 1); eeprom_update_byte((unsigned char*)EEPROM_BED_CORRECTION_LEFT, 0); eeprom_update_byte((unsigned char*)EEPROM_BED_CORRECTION_RIGHT, 0); eeprom_update_byte((unsigned char*)EEPROM_BED_CORRECTION_FRONT, 0); eeprom_update_byte((unsigned char*)EEPROM_BED_CORRECTION_REAR, 0); - menuData.adjustBed.left = menuData.adjustBed.left2 = 0; - menuData.adjustBed.right = menuData.adjustBed.right2 = 0; - menuData.adjustBed.front = menuData.adjustBed.front2 = 0; - menuData.adjustBed.rear = menuData.adjustBed.rear2 = 0; + _md->left = _md->left2 = 0; + _md->right = _md->right2 = 0; + _md->front = _md->front2 = 0; + _md->rear = _md->rear2 = 0; } + #define BED_ADJUSTMENT_UM_MAX 50 static void lcd_adjust_bed() { - if (menuData.adjustBed.status == 0) { + _menu_data_adjust_bed_t* _md = (_menu_data_adjust_bed_t*)&(menu_data[0]); + if (_md->status == 0) + { // Menu was entered. // Initialize its status. - menuData.adjustBed.status = 1; + _md->status = 1; bool valid = false; - menuData.adjustBed.left = menuData.adjustBed.left2 = eeprom_read_int8((unsigned char*)EEPROM_BED_CORRECTION_LEFT); - menuData.adjustBed.right = menuData.adjustBed.right2 = eeprom_read_int8((unsigned char*)EEPROM_BED_CORRECTION_RIGHT); - menuData.adjustBed.front = menuData.adjustBed.front2 = eeprom_read_int8((unsigned char*)EEPROM_BED_CORRECTION_FRONT); - menuData.adjustBed.rear = menuData.adjustBed.rear2 = eeprom_read_int8((unsigned char*)EEPROM_BED_CORRECTION_REAR); + _md->left = _md->left2 = eeprom_read_int8((unsigned char*)EEPROM_BED_CORRECTION_LEFT); + _md->right = _md->right2 = eeprom_read_int8((unsigned char*)EEPROM_BED_CORRECTION_RIGHT); + _md->front = _md->front2 = eeprom_read_int8((unsigned char*)EEPROM_BED_CORRECTION_FRONT); + _md->rear = _md->rear2 = eeprom_read_int8((unsigned char*)EEPROM_BED_CORRECTION_REAR); if (eeprom_read_byte((unsigned char*)EEPROM_BED_CORRECTION_VALID) == 1 && - menuData.adjustBed.left >= -BED_ADJUSTMENT_UM_MAX && menuData.adjustBed.left <= BED_ADJUSTMENT_UM_MAX && - menuData.adjustBed.right >= -BED_ADJUSTMENT_UM_MAX && menuData.adjustBed.right <= BED_ADJUSTMENT_UM_MAX && - menuData.adjustBed.front >= -BED_ADJUSTMENT_UM_MAX && menuData.adjustBed.front <= BED_ADJUSTMENT_UM_MAX && - menuData.adjustBed.rear >= -BED_ADJUSTMENT_UM_MAX && menuData.adjustBed.rear <= BED_ADJUSTMENT_UM_MAX) + _md->left >= -BED_ADJUSTMENT_UM_MAX && _md->left <= BED_ADJUSTMENT_UM_MAX && + _md->right >= -BED_ADJUSTMENT_UM_MAX && _md->right <= BED_ADJUSTMENT_UM_MAX && + _md->front >= -BED_ADJUSTMENT_UM_MAX && _md->front <= BED_ADJUSTMENT_UM_MAX && + _md->rear >= -BED_ADJUSTMENT_UM_MAX && _md->rear <= BED_ADJUSTMENT_UM_MAX) valid = true; if (! valid) { // Reset the values: simulate an edit. - menuData.adjustBed.left2 = 0; - menuData.adjustBed.right2 = 0; - menuData.adjustBed.front2 = 0; - menuData.adjustBed.rear2 = 0; + _md->left2 = 0; + _md->right2 = 0; + _md->front2 = 0; + _md->rear2 = 0; } lcd_draw_update = 1; eeprom_update_byte((unsigned char*)EEPROM_BED_CORRECTION_VALID, 1); } - if (menuData.adjustBed.left != menuData.adjustBed.left2) - eeprom_update_int8((unsigned char*)EEPROM_BED_CORRECTION_LEFT, menuData.adjustBed.left = menuData.adjustBed.left2); - if (menuData.adjustBed.right != menuData.adjustBed.right2) - eeprom_update_int8((unsigned char*)EEPROM_BED_CORRECTION_RIGHT, menuData.adjustBed.right = menuData.adjustBed.right2); - if (menuData.adjustBed.front != menuData.adjustBed.front2) - eeprom_update_int8((unsigned char*)EEPROM_BED_CORRECTION_FRONT, menuData.adjustBed.front = menuData.adjustBed.front2); - if (menuData.adjustBed.rear != menuData.adjustBed.rear2) - eeprom_update_int8((unsigned char*)EEPROM_BED_CORRECTION_REAR, menuData.adjustBed.rear = menuData.adjustBed.rear2); + if (_md->left != _md->left2) + eeprom_update_int8((unsigned char*)EEPROM_BED_CORRECTION_LEFT, _md->left = _md->left2); + if (_md->right != _md->right2) + eeprom_update_int8((unsigned char*)EEPROM_BED_CORRECTION_RIGHT, _md->right = _md->right2); + if (_md->front != _md->front2) + eeprom_update_int8((unsigned char*)EEPROM_BED_CORRECTION_FRONT, _md->front = _md->front2); + if (_md->rear != _md->rear2) + eeprom_update_int8((unsigned char*)EEPROM_BED_CORRECTION_REAR, _md->rear = _md->rear2); MENU_BEGIN(); MENU_ITEM_BACK_P(_T(MSG_SETTINGS)); - MENU_ITEM_EDIT_int3_P(_i("Left side [um]"), &menuData.adjustBed.left2, -BED_ADJUSTMENT_UM_MAX, BED_ADJUSTMENT_UM_MAX);////MSG_BED_CORRECTION_LEFT c=14 r=1 - MENU_ITEM_EDIT_int3_P(_i("Right side[um]"), &menuData.adjustBed.right2, -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]"), &menuData.adjustBed.front2, -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]"), &menuData.adjustBed.rear2, -BED_ADJUSTMENT_UM_MAX, BED_ADJUSTMENT_UM_MAX);////MSG_BED_CORRECTION_REAR c=14 r=1 + MENU_ITEM_EDIT_int3_P(_i("Left side [um]"), &_md->left2, -BED_ADJUSTMENT_UM_MAX, BED_ADJUSTMENT_UM_MAX);////MSG_BED_CORRECTION_LEFT c=14 r=1 + MENU_ITEM_EDIT_int3_P(_i("Right side[um]"), &_md->right2, -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->front2, -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->rear2, -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 c=0 r=0 MENU_END(); } @@ -2933,7 +3016,7 @@ void pid_extruder() { } } - +/* void lcd_adjust_z() { int enc_dif = 0; int cursor_pos = 1; @@ -3016,7 +3099,7 @@ void lcd_adjust_z() { lcd_clear(); lcd_return_to_status(); -} +}*/ bool lcd_wait_for_pinda(float temp) { lcd_set_custom_characters_degree(); @@ -4717,7 +4800,6 @@ static void lcd_settings_menu_back() } #endif //LINEARITY_CORRECTION - static void lcd_calibration_menu() { MENU_BEGIN(); @@ -5672,15 +5754,30 @@ static void lcd_colorprint_change() { static void lcd_tune_menu() { - if (menuData.tuneMenu.status == 0) { - // Menu was entered. Mark the menu as entered and save the current extrudemultiply value. - menuData.tuneMenu.status = 1; - menuData.tuneMenu.extrudemultiply = extrudemultiply; - } else if (menuData.tuneMenu.extrudemultiply != extrudemultiply) { - // extrudemultiply has been changed from the child menu. Apply the new value. - menuData.tuneMenu.extrudemultiply = extrudemultiply; - calculate_extruder_multipliers(); - } + typedef struct + { // 3bytes total + // To recognize, whether the menu has been just initialized. + int8_t status; // 1byte + // Backup of extrudemultiply, to recognize, that the value has been changed and + // it needs to be applied. + int16_t extrudemultiply; // 2byte + } _menu_data_t; +#if (3 > MENU_DATA_SIZE) +#error "check MENU_DATA_SIZE definition!" +#endif + _menu_data_t* _md = (_menu_data_t*)&(menu_data[0]); + if (_md->status == 0) + { + // Menu was entered. Mark the menu as entered and save the current extrudemultiply value. + _md->status = 1; + _md->extrudemultiply = extrudemultiply; + } + else if (_md->extrudemultiply != extrudemultiply) + { + // extrudemultiply has been changed from the child menu. Apply the new value. + _md->extrudemultiply = extrudemultiply; + calculate_extruder_multipliers(); + } EEPROM_read(EEPROM_SILENT, (uint8_t*)&SilentModeMenu, sizeof(SilentModeMenu)); diff --git a/Firmware/ultralcd.h b/Firmware/ultralcd.h index fb655ccb..4b02388a 100644 --- a/Firmware/ultralcd.h +++ b/Firmware/ultralcd.h @@ -14,92 +14,6 @@ extern void menu_lcd_longpress_func(void); extern void menu_lcd_charsetup_func(void); extern void menu_lcd_lcdupdate_func(void); -struct EditMenuParentState -{ - //prevMenu and prevEncoderPosition are used to store the previous menu location when editing settings. - menu_func_t prevMenu; - uint16_t prevEncoderPosition; - //Variables used when editing values. - const char* editLabel; - void* editValue; - int32_t minEditValue, maxEditValue; - // menu_func_t callbackFunc; -}; - -union MenuData -{ - struct BabyStep - { - // 29B total - int8_t status; - int babystepMem[3]; - float babystepMemMM[3]; - } babyStep; - - struct SupportMenu - { - // 6B+16B=22B total - int8_t status; - bool is_flash_air; - uint8_t ip[4]; - char ip_str[3*4+3+1]; - } supportMenu; - - struct AdjustBed - { - // 6+13+16=35B - // editMenuParentState is used when an edit menu is entered, so it knows - // the return menu and encoder state. - struct EditMenuParentState editMenuParentState; - int8_t status; - int8_t left; - int8_t right; - int8_t front; - int8_t rear; - int left2; - int right2; - int front2; - int rear2; - } adjustBed; - - struct TuneMenu - { - // editMenuParentState is used when an edit menu is entered, so it knows - // the return menu and encoder state. - struct EditMenuParentState editMenuParentState; - // To recognize, whether the menu has been just initialized. - int8_t status; - // Backup of extrudemultiply, to recognize, that the value has been changed and - // it needs to be applied. - int16_t extrudemultiply; - } tuneMenu; - - // editMenuParentState is used when an edit menu is entered, so it knows - // the return menu and encoder state. - struct EditMenuParentState editMenuParentState; - - struct AutoLoadFilamentMenu - { - //ShortTimer timer; - char dummy; - } autoLoadFilamentMenu; - struct _Lcd_moveMenu - { - bool initialized; - bool endstopsEnabledPrevious; - } _lcd_moveMenu; - struct sdcard_menu_t - { - uint8_t viewState; - } sdcard_menu; - menu_data_edit_t edit_menu; -}; - -// State of the currently active menu. -// C Union manages sharing of the static memory by all the menus. -extern union MenuData menuData; - - // Call with a false parameter to suppress the LCD update from various places like the planner or the temp control. void ultralcd_init(); void lcd_setstatus(const char* message); @@ -226,8 +140,6 @@ void lcd_temp_cal_show_result(bool result); bool lcd_wait_for_pinda(float temp); -union MenuData; - void bowden_menu(); char reset_menu(); char choose_extruder_menu(); diff --git a/Firmware/xyzcal.cpp b/Firmware/xyzcal.cpp index 18d124b3..3b9c0a4f 100644 --- a/Firmware/xyzcal.cpp +++ b/Firmware/xyzcal.cpp @@ -686,17 +686,17 @@ uint8_t xyzcal_xycoords2point(int16_t x, int16_t y) //MK3 #if ((MOTHERBOARD == BOARD_EINSY_1_0a)) -const int16_t PROGMEM xyzcal_point_xcoords[4] = {1200, 22000, 22000, 1200}; -const int16_t PROGMEM xyzcal_point_ycoords[4] = {600, 600, 19800, 19800}; +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)) //MK2.5 #if ((MOTHERBOARD == BOARD_RAMBO_MINI_1_0) || (MOTHERBOARD == BOARD_RAMBO_MINI_1_3)) -const int16_t PROGMEM xyzcal_point_xcoords[4] = {1200, 22000, 22000, 1200}; -const int16_t PROGMEM xyzcal_point_ycoords[4] = {700, 700, 19800, 19800}; +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)) -const uint16_t PROGMEM xyzcal_point_pattern[12] = {0x000, 0x0f0, 0x1f8, 0x3fc, 0x7fe, 0x7fe, 0x7fe, 0x7fe, 0x3fc, 0x1f8, 0x0f0, 0x000}; +const uint16_t xyzcal_point_pattern[12] PROGMEM = {0x000, 0x0f0, 0x1f8, 0x3fc, 0x7fe, 0x7fe, 0x7fe, 0x7fe, 0x3fc, 0x1f8, 0x0f0, 0x000}; bool xyzcal_searchZ(void) { @@ -747,7 +747,7 @@ bool xyzcal_scan_and_process(void) uint16_t* pattern = (uint16_t*)(histo + 2*16); for (uint8_t i = 0; i < 12; i++) { - pattern[i] = pgm_read_word_far((uint16_t*)(xyzcal_point_pattern + 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; @@ -777,8 +777,8 @@ bool xyzcal_find_bed_induction_sensor_point_xy(void) int16_t y = _Y; int16_t z = _Z; uint8_t point = xyzcal_xycoords2point(x, y); - x = pgm_read_word_far((uint16_t*)(xyzcal_point_xcoords + point)); - y = pgm_read_word_far((uint16_t*)(xyzcal_point_ycoords + point)); + 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); xyzcal_meassure_enter(); xyzcal_lineXYZ_to(x, y, z, 200, 0); From 6c387384c7ba7417827fd21249ddb129018770aa Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Mon, 13 Aug 2018 19:43:37 +0200 Subject: [PATCH 065/141] Fix compiler warnings: sketch/Marlin.h:366:35: warning: large integer implicitly truncated to unsigned type [-Woverflow] #define PRINT_TIME_REMAINING_INIT 0xffffffff sketch/Marlin_main.cpp:8814:21: note: in expansion of macro 'PRINT_TIME_REMAINING_INIT' uint16_t print_t = PRINT_TIME_REMAINING_INIT; sketch/Marlin_main.cpp:8817:15: warning: comparison is always true due to limited range of data type [-Wtype-limits] if ((print_t != PRINT_TIME_REMAINING_INIT) && (feedmultiply != 0)) print_t = 100 * print_t / feedmultiply; --- Firmware/Marlin.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Firmware/Marlin.h b/Firmware/Marlin.h index 3912c9a2..4af4af49 100644 --- a/Firmware/Marlin.h +++ b/Firmware/Marlin.h @@ -363,7 +363,7 @@ extern uint8_t print_percent_done_normal; extern uint32_t print_time_remaining_normal; extern uint8_t print_percent_done_silent; extern uint32_t print_time_remaining_silent; -#define PRINT_TIME_REMAINING_INIT 0xffffffff +#define PRINT_TIME_REMAINING_INIT 0xffff #define PRINT_PERCENT_DONE_INIT 0xff #define PRINTER_ACTIVE (IS_SD_PRINTING || is_usb_printing || isPrintPaused || (custom_message_type == 4) || saved_printing || (lcd_commands_type == LCD_COMMAND_V2_CAL) || card.paused || mmu_print_saved) From 34a4443170a02bb047724afd564e6ad4d8ef6c51 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Wed, 15 Aug 2018 17:34:29 +0200 Subject: [PATCH 066/141] Fix typo. --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index e8e9e7c1..4de43b93 100644 --- a/README.md +++ b/README.md @@ -2,7 +2,7 @@ 1. install `"Arduino Software IDE"` for your preferred operating system `https://www.arduino.cc -> Software->Downloads` -it is recommended to use older version `"1.6.9"`, as it is used on out build server to produce offitial builds. +it is recommended to use older version `"1.6.9"`, as it is used on out build server to produce official builds. _note: in the case of persistent compilation problems, check the version of the currently used C/C++ compiler (GCC) - should be `4.8.1`; version can be verified by entering the command `avr-gcc --version` 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_ From cc0249126a89cff7b48010133c23d554756c5261 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Wed, 15 Aug 2018 21:36:23 +0200 Subject: [PATCH 067/141] Document fsensor_update, remove disabled code. --- Firmware/fsensor.cpp | 18 +++++------------- Firmware/fsensor.h | 1 - 2 files changed, 5 insertions(+), 14 deletions(-) diff --git a/Firmware/fsensor.cpp b/Firmware/fsensor.cpp index 34fab48f..8800dbb0 100644 --- a/Firmware/fsensor.cpp +++ b/Firmware/fsensor.cpp @@ -430,6 +430,11 @@ void fsensor_st_block_chunk(block_t* bl, int cnt) } } +//! update (perform M600 on filament runout) +//! +//! Works only if filament sensor is enabled. +//! When the filament sensor error count is larger then FSENSOR_ERR_MAX, pauses print, tries to move filament back and forth. +//! If there is still no plausible signal from filament sensor plans M600 (Filament change). void fsensor_update(void) { if (fsensor_enabled) @@ -452,19 +457,6 @@ void fsensor_update(void) fsensor_err_cnt = 0; fsensor_oq_meassure_start(0); -// st_synchronize(); -// for (int axis = X_AXIS; axis <= E_AXIS; axis++) -// current_position[axis] = st_get_position_mm(axis); -/* - current_position[E_AXIS] -= 3; - plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 200 / 60, active_extruder); - st_synchronize(); - - current_position[E_AXIS] += 3; - plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 200 / 60, active_extruder); - st_synchronize(); -*/ - enquecommand_front_P((PSTR("G1 E-3 F200"))); process_commands(); cmdqueue_pop_front(); diff --git a/Firmware/fsensor.h b/Firmware/fsensor.h index df58def2..0b262a51 100644 --- a/Firmware/fsensor.h +++ b/Firmware/fsensor.h @@ -27,7 +27,6 @@ extern void fsensor_disable(void); extern bool fsensor_autoload_enabled; extern void fsensor_autoload_set(bool State); -//update (perform M600 on filament runout) extern void fsensor_update(void); //setup pin-change interrupt From 54138407ddadca134f8a64db59215a4367bef9ce Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Thu, 23 Aug 2018 23:16:39 +0200 Subject: [PATCH 068/141] Encapsulate MMU internal state. --- Firmware/mmu.cpp | 2 +- Firmware/mmu.h | 2 -- 2 files changed, 1 insertion(+), 3 deletions(-) diff --git a/Firmware/mmu.cpp b/Firmware/mmu.cpp index a48ca36a..4db861de 100644 --- a/Firmware/mmu.cpp +++ b/Firmware/mmu.cpp @@ -28,7 +28,7 @@ bool mmu_enabled = false; bool mmu_ready = false; -int8_t mmu_state = 0; +static int8_t mmu_state = 0; uint8_t mmu_cmd = 0; diff --git a/Firmware/mmu.h b/Firmware/mmu.h index 763c15ea..63835ca8 100644 --- a/Firmware/mmu.h +++ b/Firmware/mmu.h @@ -5,8 +5,6 @@ extern bool mmu_enabled; -extern int8_t mmu_state; - extern uint8_t mmu_extruder; extern uint8_t tmp_extruder; From 3c9047c9cd683d45f1fa96cb3ad83e5addc74ff4 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Thu, 23 Aug 2018 15:41:47 +0200 Subject: [PATCH 069/141] Remove usage of global variable tmp_extruder in mmu_M600_load_filament. For automatic load filament, use mmu_extruder value as filament previously selected. --- Firmware/mmu.cpp | 23 +++++++++++------------ 1 file changed, 11 insertions(+), 12 deletions(-) diff --git a/Firmware/mmu.cpp b/Firmware/mmu.cpp index 4db861de..963f3da3 100644 --- a/Firmware/mmu.cpp +++ b/Firmware/mmu.cpp @@ -34,6 +34,7 @@ uint8_t mmu_cmd = 0; uint8_t mmu_extruder = 0; +//! This variable probably has no meaning and is planed to be removed uint8_t tmp_extruder = 0; int8_t mmu_finda = -1; @@ -363,29 +364,27 @@ void mmu_load_to_nozzle() void mmu_M600_load_filament(bool automatic) { //load filament for mmu v2 - bool yes = false; + uint8_t filament = mmu_extruder; if (!automatic) { - yes = lcd_show_fullscreen_message_yes_no_and_wait_P(_i("Do you want to switch extruder?"), false); - if(yes) tmp_extruder = choose_extruder_menu(); - else tmp_extruder = mmu_extruder; - + bool yes = lcd_show_fullscreen_message_yes_no_and_wait_P(_i("Do you want to switch extruder?"), false); + if(yes) filament = choose_extruder_menu(); } else { - tmp_extruder = (tmp_extruder+1)%5; + filament = (filament+1)%5; } lcd_update_enable(false); lcd_clear(); lcd_set_cursor(0, 1); lcd_puts_P(_T(MSG_LOADING_FILAMENT)); lcd_print(" "); - lcd_print(tmp_extruder + 1); - snmm_filaments_used |= (1 << tmp_extruder); //for stop print + lcd_print(filament + 1); + snmm_filaments_used |= (1 << filament); //for stop print -// printf_P(PSTR("T code: %d \n"), tmp_extruder); -// mmu_printf_P(PSTR("T%d\n"), tmp_extruder); - mmu_command(MMU_CMD_T0 + tmp_extruder); +// printf_P(PSTR("T code: %d \n"), filament); +// mmu_printf_P(PSTR("T%d\n"), filament); + mmu_command(MMU_CMD_T0 + filament); manage_response(false, true); - mmu_extruder = tmp_extruder; //filament change is finished + mmu_extruder = filament; //filament change is finished mmu_load_to_nozzle(); From 0de7668bacea596eee8e8a910bcffe3dfa579648 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Thu, 23 Aug 2018 15:58:08 +0200 Subject: [PATCH 070/141] Remove usage of global variable tmp_extruder in M200. --- Firmware/Marlin_main.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index 30a4258e..276d1c7b 100644 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -5808,10 +5808,10 @@ Sigma_Exit: case 200: // M200 D set filament diameter and set E axis units to cubic millimeters (use S0 to set back to millimeters). { - tmp_extruder = active_extruder; + uint8_t extruder = active_extruder; if(code_seen('T')) { - tmp_extruder = code_value(); - if(tmp_extruder >= EXTRUDERS) { + extruder = code_value(); + if(extruder >= EXTRUDERS) { SERIAL_ECHO_START; SERIAL_ECHO(_i("M200 Invalid extruder "));////MSG_M200_INVALID_EXTRUDER c=0 r=0 break; @@ -5825,7 +5825,7 @@ Sigma_Exit: // for all extruders volumetric_enabled = false; } else { - filament_size[tmp_extruder] = (float)code_value(); + filament_size[extruder] = (float)code_value(); // make sure all extruders have some sane value for the filament size filament_size[0] = (filament_size[0] == 0.0 ? DEFAULT_NOMINAL_FILAMENT_DIA : filament_size[0]); #if EXTRUDERS > 1 From 9a14daab069fb259906a5a6583028ff8819288ff Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Tue, 28 Aug 2018 16:03:07 +0200 Subject: [PATCH 071/141] Revert "Split settings menu into separate functions." Original commit wont work, as intended as MENU_ITEM_* macros contain return statement. --- Firmware/ultralcd.cpp | 203 +++++++++++++++++++----------------------- 1 file changed, 94 insertions(+), 109 deletions(-) diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index ef3f2d83..386e7b22 100644 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -4512,106 +4512,6 @@ void lcd_settings_linearity_correction_menu(void) MENU_END(); } #endif //LINEARITY_CORRECTION - -static void settings_silent_mode() -{ - if(!farm_mode) - { -#ifdef TMC2130 - - if (SilentModeMenu == SILENT_MODE_NORMAL) { MENU_ITEM_FUNCTION_P(_T(MSG_STEALTH_MODE_OFF), lcd_silent_mode_set); } - else MENU_ITEM_FUNCTION_P(_T(MSG_STEALTH_MODE_ON), lcd_silent_mode_set); - if (SilentModeMenu == SILENT_MODE_NORMAL) - { - if (CrashDetectMenu == 0) { MENU_ITEM_FUNCTION_P(_T(MSG_CRASHDETECT_OFF), lcd_crash_mode_set); } - else MENU_ITEM_FUNCTION_P(_T(MSG_CRASHDETECT_ON), lcd_crash_mode_set); - } - else MENU_ITEM_SUBMENU_P(_T(MSG_CRASHDETECT_NA), lcd_crash_mode_info); -#else //TMC2130 - - switch (SilentModeMenu) - { - case SILENT_MODE_POWER: MENU_ITEM_FUNCTION_P(_T(MSG_SILENT_MODE_OFF), lcd_silent_mode_set); break; - case SILENT_MODE_SILENT: MENU_ITEM_FUNCTION_P(_T(MSG_SILENT_MODE_ON), lcd_silent_mode_set); break; - case SILENT_MODE_AUTO: MENU_ITEM_FUNCTION_P(_T(MSG_AUTO_MODE_ON), lcd_silent_mode_set); break; - default: MENU_ITEM_FUNCTION_P(_T(MSG_SILENT_MODE_OFF), lcd_silent_mode_set); break; // (probably) not needed - } -#endif //TMC2130 - } -} - -static void settings_filament_sensor() -{ -#ifdef FILAMENT_SENSOR - if (FSensorStateMenu == 0) - { - if (fsensor_not_responding) - { - // Filament sensor not working - MENU_ITEM_FUNCTION_P(_i("Fil. sensor [N/A]"), lcd_fsensor_state_set);////MSG_FSENSOR_NA c=0 r=0 - MENU_ITEM_SUBMENU_P(_T(MSG_FSENS_AUTOLOAD_NA), lcd_fsensor_fail); - } - else - { - // Filament sensor turned off, working, no problems - MENU_ITEM_FUNCTION_P(_T(MSG_FSENSOR_OFF), lcd_fsensor_state_set); - MENU_ITEM_SUBMENU_P(_T(MSG_FSENS_AUTOLOAD_NA), lcd_filament_autoload_info); - } - } - else - { - // Filament sensor turned on, working, no problems - MENU_ITEM_FUNCTION_P(_T(MSG_FSENSOR_ON), lcd_fsensor_state_set); - if (fsensor_autoload_enabled) - MENU_ITEM_FUNCTION_P(_i("F. autoload [on]"), lcd_set_filament_autoload);////MSG_FSENS_AUTOLOAD_ON c=17 r=1 - else - MENU_ITEM_FUNCTION_P(_i("F. autoload [off]"), lcd_set_filament_autoload);////MSG_FSENS_AUTOLOAD_OFF c=17 r=1 - } -#endif //FILAMENT_SENSOR -} - -static void settings_sd() -{ - if (card.ToshibaFlashAir_isEnabled()) - MENU_ITEM_FUNCTION_P(_i("SD card [flshAir]"), lcd_toshiba_flash_air_compatibility_toggle);////MSG_TOSHIBA_FLASH_AIR_COMPATIBILITY_ON c=19 r=1 - else - MENU_ITEM_FUNCTION_P(_i("SD card [normal]"), lcd_toshiba_flash_air_compatibility_toggle);////MSG_TOSHIBA_FLASH_AIR_COMPATIBILITY_OFF c=19 r=1 -#ifdef SDCARD_SORT_ALPHA - if (!farm_mode) - { - uint8_t sdSort; - EEPROM_read(EEPROM_SD_SORT, (uint8_t*)&sdSort, sizeof(sdSort)); - switch (sdSort) - { - case SD_SORT_TIME: MENU_ITEM_FUNCTION_P(_i("Sort: [time]"), lcd_sort_type_set); break;////MSG_SORT_TIME c=17 r=1 - case SD_SORT_ALPHA: MENU_ITEM_FUNCTION_P(_i("Sort: [alphabet]"), lcd_sort_type_set); break;////MSG_SORT_ALPHA c=17 r=1 - default: MENU_ITEM_FUNCTION_P(_i("Sort: [none]"), lcd_sort_type_set);////MSG_SORT_NONE c=17 r=1 - } - } -#endif // SDCARD_SORT_ALPHA -} - -static void settings_sound() -{ - switch(eSoundMode) - { - case e_SOUND_MODE_LOUD: - MENU_ITEM_FUNCTION_P(_i(MSG_SOUND_MODE_LOUD),lcd_sound_state_set); - break; - case e_SOUND_MODE_ONCE: - MENU_ITEM_FUNCTION_P(_i(MSG_SOUND_MODE_ONCE),lcd_sound_state_set); - break; - case e_SOUND_MODE_SILENT: - MENU_ITEM_FUNCTION_P(_i(MSG_SOUND_MODE_SILENT),lcd_sound_state_set); - break; - case e_SOUND_MODE_MUTE: - MENU_ITEM_FUNCTION_P(_i(MSG_SOUND_MODE_MUTE),lcd_sound_state_set); - break; - default: - MENU_ITEM_FUNCTION_P(_i(MSG_SOUND_MODE_LOUD),lcd_sound_state_set); - } -} - static void lcd_settings_menu() { EEPROM_read(EEPROM_SILENT, (uint8_t*)&SilentModeMenu, sizeof(SilentModeMenu)); @@ -4620,22 +4520,71 @@ static void lcd_settings_menu() MENU_ITEM_SUBMENU_P(_i("Temperature"), lcd_control_temperature_menu);////MSG_TEMPERATURE c=0 r=0 if (!homing_flag) - MENU_ITEM_SUBMENU_P(_i("Move axis"), lcd_move_menu_1mm);////MSG_MOVE_AXIS c=0 r=0 + MENU_ITEM_SUBMENU_P(_i("Move axis"), lcd_move_menu_1mm);////MSG_MOVE_AXIS c=0 r=0 if (!isPrintPaused) - MENU_ITEM_GCODE_P(_i("Disable steppers"), PSTR("M84"));////MSG_DISABLE_STEPPERS c=0 r=0 + MENU_ITEM_GCODE_P(_i("Disable steppers"), PSTR("M84"));////MSG_DISABLE_STEPPERS c=0 r=0 - settings_filament_sensor(); +#ifndef TMC2130 + if (!farm_mode) + { //dont show in menu if we are in farm mode + switch (SilentModeMenu) + { + case SILENT_MODE_POWER: MENU_ITEM_FUNCTION_P(_T(MSG_SILENT_MODE_OFF), lcd_silent_mode_set); break; + case SILENT_MODE_SILENT: MENU_ITEM_FUNCTION_P(_T(MSG_SILENT_MODE_ON), lcd_silent_mode_set); break; + case SILENT_MODE_AUTO: MENU_ITEM_FUNCTION_P(_T(MSG_AUTO_MODE_ON), lcd_silent_mode_set); break; + default: MENU_ITEM_FUNCTION_P(_T(MSG_SILENT_MODE_OFF), lcd_silent_mode_set); break; // (probably) not needed + } + } +#endif //TMC2130 + +#ifdef FILAMENT_SENSOR + if (FSensorStateMenu == 0) + { + if (fsensor_not_responding) + { + // Filament sensor not working + MENU_ITEM_FUNCTION_P(_i("Fil. sensor [N/A]"), lcd_fsensor_state_set);////MSG_FSENSOR_NA c=0 r=0 + MENU_ITEM_SUBMENU_P(_T(MSG_FSENS_AUTOLOAD_NA), lcd_fsensor_fail); + } + else + { + // Filament sensor turned off, working, no problems + MENU_ITEM_FUNCTION_P(_T(MSG_FSENSOR_OFF), lcd_fsensor_state_set); + MENU_ITEM_SUBMENU_P(_T(MSG_FSENS_AUTOLOAD_NA), lcd_filament_autoload_info); + } + } + else + { + // Filament sensor turned on, working, no problems + MENU_ITEM_FUNCTION_P(_T(MSG_FSENSOR_ON), lcd_fsensor_state_set); + if (fsensor_autoload_enabled) + MENU_ITEM_FUNCTION_P(_i("F. autoload [on]"), lcd_set_filament_autoload);////MSG_FSENS_AUTOLOAD_ON c=17 r=1 + else + MENU_ITEM_FUNCTION_P(_i("F. autoload [off]"), lcd_set_filament_autoload);////MSG_FSENS_AUTOLOAD_OFF c=17 r=1 + } +#endif //FILAMENT_SENSOR if (fans_check_enabled == true) MENU_ITEM_FUNCTION_P(_i("Fans check [on]"), lcd_set_fan_check);////MSG_FANS_CHECK_ON c=17 r=1 else MENU_ITEM_FUNCTION_P(_i("Fans check [off]"), lcd_set_fan_check);////MSG_FANS_CHECK_OFF c=17 r=1 - settings_silent_mode(); - -#if defined (TMC2130) && defined (LINEARITY_CORRECTION) +#ifdef TMC2130 + if(!farm_mode) + { + if (SilentModeMenu == SILENT_MODE_NORMAL) { MENU_ITEM_FUNCTION_P(_T(MSG_STEALTH_MODE_OFF), lcd_silent_mode_set); } + else MENU_ITEM_FUNCTION_P(_T(MSG_STEALTH_MODE_ON), lcd_silent_mode_set); + if (SilentModeMenu == SILENT_MODE_NORMAL) + { + if (CrashDetectMenu == 0) { MENU_ITEM_FUNCTION_P(_T(MSG_CRASHDETECT_OFF), lcd_crash_mode_set); } + else MENU_ITEM_FUNCTION_P(_T(MSG_CRASHDETECT_ON), lcd_crash_mode_set); + } + else MENU_ITEM_SUBMENU_P(_T(MSG_CRASHDETECT_NA), lcd_crash_mode_info); + } +#ifdef LINEARITY_CORRECTION MENU_ITEM_SUBMENU_P(_i("Lin. correction"), lcd_settings_linearity_correction_menu); -#endif //LINEARITY_CORRECTION && TMC2130 +#endif //LINEARITY_CORRECTION +#endif //TMC2130 if (temp_cal_active == false) MENU_ITEM_FUNCTION_P(_i("Temp. cal. [off]"), lcd_temp_calibration_set);////MSG_TEMP_CALIBRATION_OFF c=20 r=1 @@ -4656,9 +4605,45 @@ static void lcd_settings_menu() MENU_ITEM_SUBMENU_P(_i("Select language"), lcd_language_menu);////MSG_LANGUAGE_SELECT c=0 r=0 #endif //(LANG_MODE != 0) - settings_sd(); - settings_sound(); + if (card.ToshibaFlashAir_isEnabled()) + MENU_ITEM_FUNCTION_P(_i("SD card [flshAir]"), lcd_toshiba_flash_air_compatibility_toggle);////MSG_TOSHIBA_FLASH_AIR_COMPATIBILITY_ON c=19 r=1 + else + MENU_ITEM_FUNCTION_P(_i("SD card [normal]"), lcd_toshiba_flash_air_compatibility_toggle);////MSG_TOSHIBA_FLASH_AIR_COMPATIBILITY_OFF c=19 r=1 +#ifdef SDCARD_SORT_ALPHA + if (!farm_mode) + { + uint8_t sdSort; + EEPROM_read(EEPROM_SD_SORT, (uint8_t*)&sdSort, sizeof(sdSort)); + switch (sdSort) + { + case SD_SORT_TIME: MENU_ITEM_FUNCTION_P(_i("Sort: [time]"), lcd_sort_type_set); break;////MSG_SORT_TIME c=17 r=1 + case SD_SORT_ALPHA: MENU_ITEM_FUNCTION_P(_i("Sort: [alphabet]"), lcd_sort_type_set); break;////MSG_SORT_ALPHA c=17 r=1 + default: MENU_ITEM_FUNCTION_P(_i("Sort: [none]"), lcd_sort_type_set);////MSG_SORT_NONE c=17 r=1 + } + } +#endif // SDCARD_SORT_ALPHA + + +//-// +switch(eSoundMode) + { + case e_SOUND_MODE_LOUD: + MENU_ITEM_FUNCTION_P(_i(MSG_SOUND_MODE_LOUD),lcd_sound_state_set); + break; + case e_SOUND_MODE_ONCE: + MENU_ITEM_FUNCTION_P(_i(MSG_SOUND_MODE_ONCE),lcd_sound_state_set); + break; + case e_SOUND_MODE_SILENT: + MENU_ITEM_FUNCTION_P(_i(MSG_SOUND_MODE_SILENT),lcd_sound_state_set); + break; + case e_SOUND_MODE_MUTE: + MENU_ITEM_FUNCTION_P(_i(MSG_SOUND_MODE_MUTE),lcd_sound_state_set); + break; + default: + MENU_ITEM_FUNCTION_P(_i(MSG_SOUND_MODE_LOUD),lcd_sound_state_set); + } +//-// if (farm_mode) { MENU_ITEM_SUBMENU_P(PSTR("Farm number"), lcd_farm_no); From d796df3f1430cff91619fbb973c07f92ae718afe Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Mon, 3 Sep 2018 17:32:42 +0200 Subject: [PATCH 072/141] PFW-543 Add filament ramming when unloading filament with MMU. --- Firmware/mmu.cpp | 61 ++++++++++++++++++++++++++++++++++++++++++++---- 1 file changed, 57 insertions(+), 4 deletions(-) diff --git a/Firmware/mmu.cpp b/Firmware/mmu.cpp index 78b9d93a..251fcde4 100644 --- a/Firmware/mmu.cpp +++ b/Firmware/mmu.cpp @@ -645,6 +645,61 @@ void extr_adj(int extruder) //loading filament for SNMM #endif } +//! @brief Unload sequence to optimize shape of the tip of the unloaded filament +//! +//! Ideas to minimize flash consumption of this code: +//! +//! Create const array of extrude and feed_rate on stack, call increment current_position, plan_buffer_line() and st_synchronize() +//! in loop iterating over array. +//! +//! Same as previous, but create array in PROGMEM and call PGM_read instructions in a loop. +//! +static void filament_ramming() +{ + current_position[E_AXIS] += 1; + plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 1000 / 60, active_extruder); + st_synchronize(); + + current_position[E_AXIS] += 1; + plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 1500 / 60, active_extruder); + st_synchronize(); + + current_position[E_AXIS] += 2; + plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 2000 / 60, active_extruder); + st_synchronize(); + + current_position[E_AXIS] += 1.5; + plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 3000 / 60, active_extruder); + st_synchronize(); + + current_position[E_AXIS] += 2.5; + plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 4000 / 60, active_extruder); + st_synchronize(); + + current_position[E_AXIS] -= 15; + plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 5000 / 60, active_extruder); + st_synchronize(); + + current_position[E_AXIS] -= 14; + plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 1200 / 60, active_extruder); + st_synchronize(); + + current_position[E_AXIS] -= 6; + plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 600 / 60, active_extruder); + st_synchronize(); + + current_position[E_AXIS] += 10; + plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 700 / 60, active_extruder); + st_synchronize(); + + current_position[E_AXIS] -= 10; + plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 400 / 60, active_extruder); + st_synchronize(); + + current_position[E_AXIS] -= 50; + plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 2000 / 60, active_extruder); + st_synchronize(); +} void extr_unload() { //unload just current filament for multimaterial printers @@ -666,9 +721,7 @@ void extr_unload() lcd_print(" "); lcd_print(mmu_extruder + 1); - current_position[E_AXIS] -= 80; - plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 2500 / 60, active_extruder); - st_synchronize(); + filament_ramming(); mmu_command(MMU_CMD_U0); // get response @@ -989,4 +1042,4 @@ void mmu_eject_filament(uint8_t filament, bool recover) { puts_P(PSTR("Filament nr out of range!")); } -} \ No newline at end of file +} From 517fbb66bfc3a5460f02b1d24a7f49f2a0b0eecb Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Mon, 3 Sep 2018 20:00:46 +0200 Subject: [PATCH 073/141] Save 1K flash memory. --- Firmware/mmu.cpp | 79 +++++++++++++++++------------------------------- 1 file changed, 28 insertions(+), 51 deletions(-) diff --git a/Firmware/mmu.cpp b/Firmware/mmu.cpp index 251fcde4..7d2ef3c3 100644 --- a/Firmware/mmu.cpp +++ b/Firmware/mmu.cpp @@ -11,6 +11,7 @@ #include "cardreader.h" #include "ultralcd.h" #include "sound.h" +#include #define CHECK_FINDA ((IS_SD_PRINTING || is_usb_printing) && (mcode_in_progress != 600) && !saved_printing && e_active()) @@ -645,60 +646,36 @@ void extr_adj(int extruder) //loading filament for SNMM #endif } +struct E_step +{ + float extrude; //!< extrude distance in mm + float feed_rate; //!< feed rate in mm/s +}; +static const E_step ramming_sequence[] PROGMEM = +{ + {1.0, 1000.0/60}, + {1.0, 1500.0/60}, + {2.0, 2000.0/60}, + {1.5, 3000.0/60}, + {2.5, 4000.0/60}, + {-15.0, 5000.0/60}, + {-14.0, 1200.0/60}, + {-6.0, 600.0/60}, + {10.0, 700.0/60}, + {-10.0, 400.0/60}, + {-50.0, 2000.0/60}, +}; + //! @brief Unload sequence to optimize shape of the tip of the unloaded filament -//! -//! Ideas to minimize flash consumption of this code: -//! -//! Create const array of extrude and feed_rate on stack, call increment current_position, plan_buffer_line() and st_synchronize() -//! in loop iterating over array. -//! -//! Same as previous, but create array in PROGMEM and call PGM_read instructions in a loop. -//! static void filament_ramming() { - current_position[E_AXIS] += 1; - plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 1000 / 60, active_extruder); - st_synchronize(); - - current_position[E_AXIS] += 1; - plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 1500 / 60, active_extruder); - st_synchronize(); - - current_position[E_AXIS] += 2; - plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 2000 / 60, active_extruder); - st_synchronize(); - - current_position[E_AXIS] += 1.5; - plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 3000 / 60, active_extruder); - st_synchronize(); - - current_position[E_AXIS] += 2.5; - plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 4000 / 60, active_extruder); - st_synchronize(); - - current_position[E_AXIS] -= 15; - plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 5000 / 60, active_extruder); - st_synchronize(); - - current_position[E_AXIS] -= 14; - plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 1200 / 60, active_extruder); - st_synchronize(); - - current_position[E_AXIS] -= 6; - plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 600 / 60, active_extruder); - st_synchronize(); - - current_position[E_AXIS] += 10; - plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 700 / 60, active_extruder); - st_synchronize(); - - current_position[E_AXIS] -= 10; - plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 400 / 60, active_extruder); - st_synchronize(); - - current_position[E_AXIS] -= 50; - plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 2000 / 60, active_extruder); - st_synchronize(); + 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(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], + current_position[E_AXIS], pgm_read_float(&(ramming_sequence[i].feed_rate)), active_extruder); + st_synchronize(); + } } void extr_unload() From c95b463e0bee3aab8591cf4228cc53ab4ae74e26 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Mon, 3 Sep 2018 20:44:40 +0200 Subject: [PATCH 074/141] Remove unused variable yes. Remove redundant tmp_extruder assignment. --- Firmware/mmu.cpp | 6 ++---- 1 file changed, 2 insertions(+), 4 deletions(-) diff --git a/Firmware/mmu.cpp b/Firmware/mmu.cpp index 78b9d93a..0f25b30e 100644 --- a/Firmware/mmu.cpp +++ b/Firmware/mmu.cpp @@ -466,13 +466,11 @@ void mmu_M600_wait_and_beep() { void mmu_M600_load_filament(bool automatic) { //load filament for mmu v2 - bool yes = false; tmp_extruder = mmu_extruder; if (!automatic) { #ifdef MMU_M600_SWITCH_EXTRUDER - yes = lcd_show_fullscreen_message_yes_no_and_wait_P(_i("Do you want to switch extruder?"), false); + bool yes = lcd_show_fullscreen_message_yes_no_and_wait_P(_i("Do you want to switch extruder?"), false); if(yes) tmp_extruder = choose_extruder_menu(); - else tmp_extruder = mmu_extruder; #endif //MMU_M600_SWITCH_EXTRUDER } else { @@ -989,4 +987,4 @@ void mmu_eject_filament(uint8_t filament, bool recover) { puts_P(PSTR("Filament nr out of range!")); } -} \ No newline at end of file +} From cbf633cfd42fd43ea04ddb0dc1453c4d8d87c05d Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Mon, 3 Sep 2018 20:47:12 +0200 Subject: [PATCH 075/141] Remove unused variable chars. --- Firmware/ultralcd.cpp | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index f10aa6eb..8ed4b519 100644 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -482,12 +482,10 @@ void lcdui_print_temp(char type, int val_current, int val_target) // Print Z-coordinate (8 chars total) void lcdui_print_Z_coord(void) { - int chars = 8; if (custom_message_type == CUSTOM_MSG_TYPE_MESHBL) lcd_puts_P(_N("Z --- ")); else - chars = lcd_printf_P(_N("Z%6.2f "), current_position[Z_AXIS]); -// lcd_space(8 - chars); + lcd_printf_P(_N("Z%6.2f "), current_position[Z_AXIS]); } #ifdef PLANNER_DIAGNOSTICS From 63a215b0c3c87ed44d033deee9281858a0330391 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Mon, 3 Sep 2018 20:48:03 +0200 Subject: [PATCH 076/141] Remove unused variable chars. --- Firmware/ultralcd.cpp | 3 +-- 1 file changed, 1 insertion(+), 2 deletions(-) diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index 8ed4b519..f4076867 100644 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -525,8 +525,7 @@ void lcdui_print_percent_done(void) char per[4]; bool num = IS_SD_PRINTING || (PRINTER_ACTIVE && (print_percent_done_normal != PRINT_PERCENT_DONE_INIT)); sprintf_P(per, num?_N("%3hhd"):_N("---"), calc_percent_done()); - int chars = lcd_printf_P(_N("%3S%3s%%"), src, per); -// lcd_space(7 - chars); + lcd_printf_P(_N("%3S%3s%%"), src, per); } // Print extruder status (5 chars total) From af08e164266d37b778c00668dff96a35d754e140 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Tue, 4 Sep 2018 08:06:03 +0200 Subject: [PATCH 077/141] Use stop_and_save_print_to_ram() and restore_print_from_ram_and_continue() pair to pause print from menu. Move declaration of those functions to marlin.h. Move declaration of FSensorStateMenu to ultralcd.h. Known limitations: Filament is not retracted, extruder is not lifted in Z and moved to rear left corner in XY. Nozzle heating is not turned off nor restored. Unused code is not removed. --- Firmware/Marlin.h | 3 +++ Firmware/Marlin_main.cpp | 3 --- Firmware/fsensor.cpp | 5 +---- Firmware/ultralcd.cpp | 13 +++++++++++-- Firmware/ultralcd.h | 1 + 5 files changed, 16 insertions(+), 9 deletions(-) diff --git a/Firmware/Marlin.h b/Firmware/Marlin.h index dbb611f4..5367a41e 100644 --- a/Firmware/Marlin.h +++ b/Firmware/Marlin.h @@ -419,6 +419,9 @@ extern void print_world_coordinates(); extern void print_physical_coordinates(); extern void print_mesh_bed_leveling_table(); +extern void stop_and_save_print_to_ram(float z_move, float e_move); +extern void restore_print_from_ram_and_continue(float e_move); + //estimated time to end of the print extern uint16_t print_time_remaining(); diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index 6ac5298e..f30abc71 100644 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -649,9 +649,6 @@ void servo_init() } -void stop_and_save_print_to_ram(float z_move, float e_move); -void restore_print_from_ram_and_continue(float e_move); - bool fans_check_enabled = true; diff --git a/Firmware/fsensor.cpp b/Firmware/fsensor.cpp index 8800dbb0..a035683c 100644 --- a/Firmware/fsensor.cpp +++ b/Firmware/fsensor.cpp @@ -7,6 +7,7 @@ #include "planner.h" #include "fastio.h" #include "cmdqueue.h" +#include "ultralcd.h" //Basic params #define FSENSOR_CHUNK_LEN 0.64F //filament sensor chunk length 0.64mm @@ -27,10 +28,6 @@ const char ERRMSG_PAT9125_NOT_RESP[] PROGMEM = "PAT9125 not responding (%d)!\n"; #define FSENSOR_INT_PIN 63 //filament sensor interrupt pin PK1 #define FSENSOR_INT_PIN_MSK 0x02 //filament sensor interrupt pin mask (bit1) -extern void stop_and_save_print_to_ram(float z_move, float e_move); -extern void restore_print_from_ram_and_continue(float e_move); -extern int8_t FSensorStateMenu; - void fsensor_stop_and_save_print(void) { printf_P(PSTR("fsensor_stop_and_save_print\n")); diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index f10aa6eb..95cc170a 100644 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -5520,6 +5520,15 @@ static void lcd_test_menu() } #endif //LCD_TEST +static void pause_print() +{ + stop_and_save_print_to_ram(0.0,0.0); +} +static void resume_print() +{ + restore_print_from_ram_and_continue(0.0); +} + static void lcd_main_menu() { @@ -5613,11 +5622,11 @@ static void lcd_main_menu() if (mesh_bed_leveling_flag == false && homing_flag == false) { if (card.sdprinting) { - MENU_ITEM_FUNCTION_P(_i("Pause print"), lcd_sdcard_pause);////MSG_PAUSE_PRINT c=0 r=0 + MENU_ITEM_FUNCTION_P(_i("Pause print"), pause_print);////MSG_PAUSE_PRINT c=0 r=0 } else { - MENU_ITEM_FUNCTION_P(_i("Resume print"), lcd_sdcard_resume);////MSG_RESUME_PRINT c=0 r=0 + MENU_ITEM_FUNCTION_P(_i("Resume print"), resume_print);////MSG_RESUME_PRINT c=0 r=0 } MENU_ITEM_SUBMENU_P(_T(MSG_STOP_PRINT), lcd_sdcard_stop); } diff --git a/Firmware/ultralcd.h b/Firmware/ultralcd.h index c6bbb900..d7f8d00d 100644 --- a/Firmware/ultralcd.h +++ b/Firmware/ultralcd.h @@ -82,6 +82,7 @@ extern void lcd_diag_show_end_stops(); #define LCD_COMMAND_V2_CAL 8 extern int lcd_commands_type; +extern int8_t FSensorStateMenu; #define CUSTOM_MSG_TYPE_STATUS 0 // status message from lcd_status_message variable #define CUSTOM_MSG_TYPE_MESHBL 1 // Mesh bed leveling in progress From d54e629950ef58b676a179a4b7bceba0c37096d2 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Tue, 4 Sep 2018 08:53:27 +0200 Subject: [PATCH 078/141] Retract, lift Z, move away in XY, disable fan and nozzle heating. Resume nozzle heating. Known limitations: Doesn't wait for nozzle temperature reaching set temperature before moving to print area. Doesn't resume print fan. Unused code not removed. --- Firmware/ultralcd.cpp | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index 95cc170a..c8e625c0 100644 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -5523,9 +5523,17 @@ static void lcd_test_menu() static void pause_print() { stop_and_save_print_to_ram(0.0,0.0); + long_pause(); } static void resume_print() { + char cmd1[30]; + strcpy(cmd1, "M104 S"); + strcat(cmd1, ftostr3(HotendTempBckp)); + enquecommand(cmd1); + strcpy(cmd1, "M109 S"); + strcat(cmd1, ftostr3(HotendTempBckp)); + enquecommand(cmd1); restore_print_from_ram_and_continue(0.0); } From acef0578a5bb53b68426c5133b0d26ca662247b8 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Tue, 4 Sep 2018 10:07:52 +0200 Subject: [PATCH 079/141] Don't move before reaching nozzle temperature when resuming the print. Known limitations: Doesn't resume print fan. Unused code not removed. Unload filament moves extruder to print position. --- Firmware/ultralcd.cpp | 29 ++++++++++++++++++++--------- 1 file changed, 20 insertions(+), 9 deletions(-) diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index c8e625c0..3a13fdae 100644 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -5527,14 +5527,25 @@ static void pause_print() } static void resume_print() { - char cmd1[30]; - strcpy(cmd1, "M104 S"); - strcat(cmd1, ftostr3(HotendTempBckp)); - enquecommand(cmd1); - strcpy(cmd1, "M109 S"); - strcat(cmd1, ftostr3(HotendTempBckp)); - enquecommand(cmd1); - restore_print_from_ram_and_continue(0.0); + lcd_set_cursor(0, 0); + lcdui_print_temp(LCD_STR_THERMOMETER[0], (int)(degHotend(0) + 0.5), (int)(degTargetHotend(0) + 0.5)); + lcd_space(3); + lcd_puts_P(_T(MSG_HEATING)); + if (!blocks_queued()) + { + if ((0 == menu_data[0])) + { + char cmd1[30]; + strcpy(cmd1, "M109 S"); + strcat(cmd1, ftostr3(HotendTempBckp)); + enquecommand(cmd1); + menu_data[0] = 1; + } else if (1 != heating_status) + { + restore_print_from_ram_and_continue(0.0); + menu_back(); + } + } } static void lcd_main_menu() @@ -5634,7 +5645,7 @@ static void lcd_main_menu() } else { - MENU_ITEM_FUNCTION_P(_i("Resume print"), resume_print);////MSG_RESUME_PRINT c=0 r=0 + MENU_ITEM_SUBMENU_P(_i("Resume print"), resume_print);////MSG_RESUME_PRINT c=0 r=0 } MENU_ITEM_SUBMENU_P(_T(MSG_STOP_PRINT), lcd_sdcard_stop); } From 2abd2a6cabed9543df421a81f375bb5a27146280 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Tue, 4 Sep 2018 11:13:51 +0200 Subject: [PATCH 080/141] Resume print fan. Known limitations: Unused code not removed. Unload filament moves extruder to print position. --- Firmware/Marlin_main.cpp | 3 +++ 1 file changed, 3 insertions(+) diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index f30abc71..80d14f3f 100644 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -538,6 +538,7 @@ static float saved_feedrate2 = 0; static uint8_t saved_active_extruder = 0; static bool saved_extruder_under_pressure = false; static bool saved_extruder_relative_mode = false; +static int saved_fanSpeed = 0; //=========================================================================== //=============================Routines====================================== @@ -8745,6 +8746,7 @@ void stop_and_save_print_to_ram(float z_move, float e_move) saved_extruder_under_pressure = extruder_under_pressure; //extruder under pressure flag - currently unused saved_extruder_relative_mode = axis_relative_modes[E_AXIS]; + saved_fanSpeed = fanSpeed; cmdqueue_reset(); //empty cmdqueue card.sdprinting = false; // card.closefile(); @@ -8797,6 +8799,7 @@ void restore_print_from_ram_and_continue(float e_move) active_extruder = saved_active_extruder; //restore active_extruder feedrate = saved_feedrate2; //restore feedrate axis_relative_modes[E_AXIS] = saved_extruder_relative_mode; + fanSpeed = saved_fanSpeed; float e = saved_pos[E_AXIS] - e_move; plan_set_e_position(e); //first move print head in XY to the saved position: From a5db084b705f24cc11e699b4ef0e083a56792374 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Tue, 4 Sep 2018 14:56:20 +0200 Subject: [PATCH 081/141] Move resuming nozzle temperature to restore_print_from_ram_and_continue(). Known limitations: Unused code not removed. Unload filament moves extruder to print position. --- Firmware/Marlin_main.cpp | 6 ++++++ Firmware/ultralcd.cpp | 27 +++++++-------------------- 2 files changed, 13 insertions(+), 20 deletions(-) diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index 80d14f3f..0e7d8e91 100644 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -536,6 +536,7 @@ static float saved_pos[4] = { 0, 0, 0, 0 }; // Feedrate hopefully derived from an active block of the planner at the time the print has been canceled, in mm/min. static float saved_feedrate2 = 0; static uint8_t saved_active_extruder = 0; +static float saved_extruder_temperature = 0.0; static bool saved_extruder_under_pressure = false; static bool saved_extruder_relative_mode = false; static int saved_fanSpeed = 0; @@ -8743,6 +8744,7 @@ void stop_and_save_print_to_ram(float z_move, float e_move) planner_abort_hard(); //abort printing memcpy(saved_pos, current_position, sizeof(saved_pos)); saved_active_extruder = active_extruder; //save active_extruder + saved_extruder_temperature = degTargetHotend(active_extruder); saved_extruder_under_pressure = extruder_under_pressure; //extruder under pressure flag - currently unused saved_extruder_relative_mode = axis_relative_modes[E_AXIS]; @@ -8797,6 +8799,10 @@ void restore_print_from_ram_and_continue(float e_move) // for (int axis = X_AXIS; axis <= E_AXIS; axis++) // current_position[axis] = st_get_position_mm(axis); active_extruder = saved_active_extruder; //restore active_extruder + setTargetHotendSafe(saved_extruder_temperature,saved_active_extruder); + heating_status = 1; + wait_for_heater(millis(),saved_active_extruder); + heating_status = 2; feedrate = saved_feedrate2; //restore feedrate axis_relative_modes[E_AXIS] = saved_extruder_relative_mode; fanSpeed = saved_fanSpeed; diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index 3a13fdae..a583f94b 100644 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -5522,30 +5522,17 @@ static void lcd_test_menu() static void pause_print() { + lcd_clear(); + lcd_puts_P(_i("Pausing")); + lcd_setstatuspgm(_i("Print paused")); stop_and_save_print_to_ram(0.0,0.0); long_pause(); + lcd_return_to_status(); } static void resume_print() { - lcd_set_cursor(0, 0); - lcdui_print_temp(LCD_STR_THERMOMETER[0], (int)(degHotend(0) + 0.5), (int)(degTargetHotend(0) + 0.5)); - lcd_space(3); - lcd_puts_P(_T(MSG_HEATING)); - if (!blocks_queued()) - { - if ((0 == menu_data[0])) - { - char cmd1[30]; - strcpy(cmd1, "M109 S"); - strcat(cmd1, ftostr3(HotendTempBckp)); - enquecommand(cmd1); - menu_data[0] = 1; - } else if (1 != heating_status) - { - restore_print_from_ram_and_continue(0.0); - menu_back(); - } - } + lcd_return_to_status(); + restore_print_from_ram_and_continue(0.0); } static void lcd_main_menu() @@ -5645,7 +5632,7 @@ static void lcd_main_menu() } else { - MENU_ITEM_SUBMENU_P(_i("Resume print"), resume_print);////MSG_RESUME_PRINT c=0 r=0 + MENU_ITEM_SUBMENU_P(_i("Resume print"), resume_print);////MSG_RESUME_PRINT c=0 r=0 } MENU_ITEM_SUBMENU_P(_T(MSG_STOP_PRINT), lcd_sdcard_stop); } From 4b47a74d1d03a2b78340ef1a40b70a181b2f814b Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Wed, 5 Sep 2018 18:14:32 +0200 Subject: [PATCH 082/141] Remove unused declarations from tmc2130.cpp. Move used declaration to Marlin.h. --- Firmware/Marlin.h | 1 + Firmware/tmc2130.cpp | 6 ------ 2 files changed, 1 insertion(+), 6 deletions(-) diff --git a/Firmware/Marlin.h b/Firmware/Marlin.h index 5367a41e..767fac3e 100644 --- a/Firmware/Marlin.h +++ b/Firmware/Marlin.h @@ -379,6 +379,7 @@ extern void delay_keep_alive(unsigned int ms); extern void check_babystep(); extern void long_pause(); +extern void crashdet_stop_and_save_print(); #ifdef DIS diff --git a/Firmware/tmc2130.cpp b/Firmware/tmc2130.cpp index 1d1495fe..732f290d 100644 --- a/Firmware/tmc2130.cpp +++ b/Firmware/tmc2130.cpp @@ -13,12 +13,6 @@ #define TMC2130_GCONF_SGSENS 0x00003180 // spreadCycle with stallguard (stall activates DIAG0 and DIAG1 [pushpull]) #define TMC2130_GCONF_SILENT 0x00000004 // stealthChop -//externals for debuging -extern float current_position[4]; -extern void st_get_position_xy(long &x, long &y); -extern long st_get_position(uint8_t axis); -extern void crashdet_stop_and_save_print(); -extern void crashdet_stop_and_save_print2(); //mode uint8_t tmc2130_mode = TMC2130_MODE_NORMAL; From 74be7677cfa0befa981858ea352fe3a134566ee0 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Wed, 5 Sep 2018 21:10:05 +0200 Subject: [PATCH 083/141] Fix problem, that current_position is rewritten after long_pause() call. --- Firmware/ultralcd.cpp | 25 ++++++++----------------- 1 file changed, 8 insertions(+), 17 deletions(-) diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index a583f94b..6f3652eb 100644 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -967,18 +967,8 @@ void lcd_commands() { if (lcd_commands_type == LCD_COMMAND_LONG_PAUSE) { - if(lcd_commands_step == 0) { - if (card.sdprinting) { - card.pauseSDPrint(); - lcd_setstatuspgm(_T(MSG_FINISHING_MOVEMENTS)); - lcd_draw_update = 3; - lcd_commands_step = 1; - } - else { - lcd_commands_type = 0; - } - } - if (lcd_commands_step == 1 && !blocks_queued() && !homing_flag) { + if (!blocks_queued() && !homing_flag) + { lcd_setstatuspgm(_i("Print paused"));////MSG_PRINT_PAUSED c=20 r=1 isPrintPaused = true; long_pause(); @@ -5522,12 +5512,13 @@ static void lcd_test_menu() static void pause_print() { - lcd_clear(); lcd_puts_P(_i("Pausing")); - lcd_setstatuspgm(_i("Print paused")); stop_and_save_print_to_ram(0.0,0.0); - long_pause(); - lcd_return_to_status(); + if (LCD_COMMAND_IDLE == lcd_commands_type) + { + lcd_commands_type = LCD_COMMAND_LONG_PAUSE; + lcd_return_to_status(); + } } static void resume_print() { @@ -5628,7 +5619,7 @@ static void lcd_main_menu() if (mesh_bed_leveling_flag == false && homing_flag == false) { if (card.sdprinting) { - MENU_ITEM_FUNCTION_P(_i("Pause print"), pause_print);////MSG_PAUSE_PRINT c=0 r=0 + MENU_ITEM_SUBMENU_P(_i("Pause print"), pause_print);////MSG_PAUSE_PRINT c=0 r=0 } else { From 920d828833b50bab775adb8ee4f1338fb0d3c7d9 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Thu, 6 Sep 2018 08:32:50 +0200 Subject: [PATCH 084/141] Rename lcd_sdcard_pause() to lcd_pause_print() to reflect, that also USB printing could be possible to pause. Unite it with pause_print() and use new (immediate) pause mechanism in all places where old mechanism was used. Rename resume_print() to lcd_resume_print() and make it global, unite it with lcd_sdcard_resume() and use it also in place, where lcd_commands_type = LCD_COMMAND_LONG_PAUSE_RESUME was used. Remove LCD_COMMAND_LONG_PAUSE_RESUME lcd_command_type. Remove unused pause_lastpos[]. --- Firmware/Marlin.h | 1 - Firmware/Marlin_main.cpp | 15 ++----- Firmware/temperature.cpp | 2 +- Firmware/ultralcd.cpp | 94 ++++++---------------------------------- Firmware/ultralcd.h | 4 +- 5 files changed, 20 insertions(+), 96 deletions(-) diff --git a/Firmware/Marlin.h b/Firmware/Marlin.h index 767fac3e..5292334f 100644 --- a/Firmware/Marlin.h +++ b/Firmware/Marlin.h @@ -337,7 +337,6 @@ extern uint8_t active_extruder; extern int saved_feedmultiply; extern float HotendTempBckp; extern int fanSpeedBckp; -extern float pause_lastpos[4]; extern unsigned long pause_time; extern unsigned long start_pause_print; extern unsigned long t_fan_rising_edge; diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index 0e7d8e91..2cf5d337 100644 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -333,7 +333,6 @@ int8_t lcd_change_fil_state = 0; int feedmultiplyBckp = 100; float HotendTempBckp = 0; int fanSpeedBckp = 0; -float pause_lastpos[4]; unsigned long pause_time = 0; unsigned long start_pause_print = millis(); unsigned long t_fan_rising_edge = millis(); @@ -6479,13 +6478,14 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) } break; #endif //FILAMENTCHANGEENABLE - case 601: { - if(lcd_commands_type == 0) lcd_commands_type = LCD_COMMAND_LONG_PAUSE; + case 601: + { + lcd_pause_print(); } break; case 602: { - if(lcd_commands_type == 0) lcd_commands_type = LCD_COMMAND_LONG_PAUSE_RESUME; + lcd_resume_print(); } break; @@ -8124,13 +8124,6 @@ void long_pause() //long pause print HotendTempBckp = degTargetHotend(active_extruder); fanSpeedBckp = fanSpeed; start_pause_print = millis(); - - - //save position - pause_lastpos[X_AXIS] = current_position[X_AXIS]; - pause_lastpos[Y_AXIS] = current_position[Y_AXIS]; - pause_lastpos[Z_AXIS] = current_position[Z_AXIS]; - pause_lastpos[E_AXIS] = current_position[E_AXIS]; //retract current_position[E_AXIS] -= default_retraction; diff --git a/Firmware/temperature.cpp b/Firmware/temperature.cpp index 34539483..ec05de2b 100644 --- a/Firmware/temperature.cpp +++ b/Firmware/temperature.cpp @@ -512,7 +512,7 @@ void fanSpeedError(unsigned char _fan) { } else { isPrintPaused = true; - lcd_sdcard_pause(); + lcd_pause_print(); } } else { diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index 6f3652eb..4feb2299 100644 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -975,68 +975,8 @@ void lcd_commands() lcd_commands_type = 0; lcd_commands_step = 0; } - } - if (lcd_commands_type == LCD_COMMAND_LONG_PAUSE_RESUME) { - char cmd1[30]; - if (lcd_commands_step == 0) { - - lcd_draw_update = 3; - lcd_commands_step = 4; - } - if (lcd_commands_step == 1 && !blocks_queued() && cmd_buffer_empty()) { //recover feedmultiply; cmd_buffer_empty() ensures that card.sdprinting is synchronized with buffered commands and thus print cant be paused until resume is finished - - sprintf_P(cmd1, PSTR("M220 S%d"), saved_feedmultiply); - enquecommand(cmd1); - isPrintPaused = false; - pause_time += (millis() - start_pause_print); //accumulate time when print is paused for correct statistics calculation - card.startFileprint(); - lcd_commands_step = 0; - lcd_commands_type = 0; - } - if (lcd_commands_step == 2 && !blocks_queued()) { //turn on fan, move Z and unretract - - sprintf_P(cmd1, PSTR("M106 S%d"), fanSpeedBckp); - enquecommand(cmd1); - strcpy(cmd1, "G1 Z"); - strcat(cmd1, ftostr32(pause_lastpos[Z_AXIS])); - enquecommand(cmd1); - - if (axis_relative_modes[3] == false) { - enquecommand_P(PSTR("M83")); // set extruder to relative mode - enquecommand_P(PSTR("G1 E" STRINGIFY(default_retraction))); //unretract - enquecommand_P(PSTR("M82")); // set extruder to absolute mode - } - else { - enquecommand_P(PSTR("G1 E" STRINGIFY(default_retraction))); //unretract - } - - lcd_commands_step = 1; - } - if (lcd_commands_step == 3 && !blocks_queued()) { //wait for nozzle to reach target temp - - strcpy(cmd1, "M109 S"); - strcat(cmd1, ftostr3(HotendTempBckp)); - enquecommand(cmd1); - lcd_commands_step = 2; - } - if (lcd_commands_step == 4 && !blocks_queued()) { //set temperature back and move xy - - strcpy(cmd1, "M104 S"); - strcat(cmd1, ftostr3(HotendTempBckp)); - enquecommand(cmd1); - enquecommand_P(PSTR("G90")); //absolute positioning - strcpy(cmd1, "G1 X"); - strcat(cmd1, ftostr32(pause_lastpos[X_AXIS])); - strcat(cmd1, " Y"); - strcat(cmd1, ftostr32(pause_lastpos[Y_AXIS])); - enquecommand(cmd1); - - lcd_setstatuspgm(_T(MSG_RESUMING_PRINT)); - lcd_commands_step = 3; - } - } #ifdef SNMM if (lcd_commands_type == LCD_COMMAND_V2_CAL) @@ -1744,17 +1684,15 @@ void lcd_return_to_status() } -void lcd_sdcard_pause() { +void lcd_pause_print() { lcd_return_to_status(); - lcd_commands_type = LCD_COMMAND_LONG_PAUSE; - + stop_and_save_print_to_ram(0.0,0.0); + if (LCD_COMMAND_IDLE == lcd_commands_type) + { + lcd_commands_type = LCD_COMMAND_LONG_PAUSE; + } } -static void lcd_sdcard_resume() { - lcd_return_to_status(); - lcd_reset_alert_level(); //for fan speed error - lcd_commands_type = LCD_COMMAND_LONG_PAUSE_RESUME; -} float move_menu_scale; static void lcd_move_menu_axis(); @@ -5510,20 +5448,14 @@ static void lcd_test_menu() } #endif //LCD_TEST -static void pause_print() -{ - lcd_puts_P(_i("Pausing")); - stop_and_save_print_to_ram(0.0,0.0); - if (LCD_COMMAND_IDLE == lcd_commands_type) - { - lcd_commands_type = LCD_COMMAND_LONG_PAUSE; - lcd_return_to_status(); - } -} -static void resume_print() +void lcd_resume_print() { lcd_return_to_status(); + lcd_setstatuspgm(_T(MSG_RESUMING_PRINT)); + lcd_reset_alert_level(); //for fan speed error restore_print_from_ram_and_continue(0.0); + pause_time += (millis() - start_pause_print); //accumulate time when print is paused for correct statistics calculation + isPrintPaused = false; } static void lcd_main_menu() @@ -5619,11 +5551,11 @@ static void lcd_main_menu() if (mesh_bed_leveling_flag == false && homing_flag == false) { if (card.sdprinting) { - MENU_ITEM_SUBMENU_P(_i("Pause print"), pause_print);////MSG_PAUSE_PRINT c=0 r=0 + MENU_ITEM_FUNCTION_P(_i("Pause print"), lcd_pause_print);////MSG_PAUSE_PRINT c=0 r=0 } else { - MENU_ITEM_SUBMENU_P(_i("Resume print"), resume_print);////MSG_RESUME_PRINT c=0 r=0 + MENU_ITEM_SUBMENU_P(_i("Resume print"), lcd_resume_print);////MSG_RESUME_PRINT c=0 r=0 } MENU_ITEM_SUBMENU_P(_T(MSG_STOP_PRINT), lcd_sdcard_stop); } diff --git a/Firmware/ultralcd.h b/Firmware/ultralcd.h index d7f8d00d..113f6f70 100644 --- a/Firmware/ultralcd.h +++ b/Firmware/ultralcd.h @@ -32,7 +32,8 @@ void lcd_loading_filament(); void lcd_change_success(); void lcd_loading_color(); void lcd_sdcard_stop(); -void lcd_sdcard_pause(); +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(); @@ -77,7 +78,6 @@ extern void lcd_diag_show_end_stops(); #define LCD_COMMAND_STOP_PRINT 2 #define LCD_COMMAND_FARM_MODE_CONFIRM 4 #define LCD_COMMAND_LONG_PAUSE 5 -#define LCD_COMMAND_LONG_PAUSE_RESUME 6 #define LCD_COMMAND_PID_EXTRUDER 7 #define LCD_COMMAND_V2_CAL 8 From d71311f13ff2cefa8cd9fd633df248f09890bd70 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Thu, 6 Sep 2018 09:41:37 +0200 Subject: [PATCH 085/141] Remove redundant HotendTempBckp from crash detection recover. --- Firmware/Marlin_main.cpp | 5 ----- 1 file changed, 5 deletions(-) diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index 2cf5d337..351ddc02 100644 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -745,16 +745,11 @@ void crashdet_detected(uint8_t mask) if (automatic_recovery_after_crash) { enquecommand_P(PSTR("CRASH_RECOVER")); }else{ - HotendTempBckp = degTargetHotend(active_extruder); setTargetHotend(0, active_extruder); bool yesno = lcd_show_fullscreen_message_yes_no_and_wait_P(_i("Crash detected. Resume print?"), false); lcd_update_enable(true); if (yesno) { - char cmd1[10]; - strcpy(cmd1, "M109 S"); - strcat(cmd1, ftostr3(HotendTempBckp)); - enquecommand(cmd1); enquecommand_P(PSTR("CRASH_RECOVER")); } else From b43c8dad746bf743cbfaabffd9cd728699aa941b Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Thu, 6 Sep 2018 10:05:59 +0200 Subject: [PATCH 086/141] Remove HotendTempBckp global variable. --- Firmware/Marlin.h | 3 +-- Firmware/Marlin_main.cpp | 8 +++----- 2 files changed, 4 insertions(+), 7 deletions(-) diff --git a/Firmware/Marlin.h b/Firmware/Marlin.h index 5292334f..88d9a3bf 100644 --- a/Firmware/Marlin.h +++ b/Firmware/Marlin.h @@ -335,7 +335,6 @@ extern uint8_t active_extruder; //Long pause extern int saved_feedmultiply; -extern float HotendTempBckp; extern int fanSpeedBckp; extern unsigned long pause_time; extern unsigned long start_pause_print; @@ -476,5 +475,5 @@ void proc_commands(); void M600_load_filament(); void M600_load_filament_movements(); -void M600_wait_for_user(); +void M600_wait_for_user(float HotendTempBckp); void M600_check_state(); diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index 351ddc02..68982587 100644 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -331,7 +331,6 @@ unsigned int usb_printing_counter; int8_t lcd_change_fil_state = 0; int feedmultiplyBckp = 100; -float HotendTempBckp = 0; int fanSpeedBckp = 0; unsigned long pause_time = 0; unsigned long start_pause_print = millis(); @@ -3059,7 +3058,7 @@ static void gcode_M600(bool automatic, float x_position, float y_position, float //First backup current position and settings feedmultiplyBckp = feedmultiply; - HotendTempBckp = degTargetHotend(active_extruder); + float HotendTempBckp = degTargetHotend(active_extruder); fanSpeedBckp = fanSpeed; lastpos[X_AXIS] = current_position[X_AXIS]; @@ -3087,7 +3086,7 @@ static void gcode_M600(bool automatic, float x_position, float y_position, float st_synchronize(); //Beep, manage nozzle heater and wait for user to start unload filament - if(!mmu_enabled) M600_wait_for_user(); + if(!mmu_enabled) M600_wait_for_user(HotendTempBckp); lcd_change_fil_state = 0; @@ -8116,7 +8115,6 @@ void long_pause() //long pause print //save currently set parameters to global variables saved_feedmultiply = feedmultiply; - HotendTempBckp = degTargetHotend(active_extruder); fanSpeedBckp = fanSpeed; start_pause_print = millis(); @@ -8912,7 +8910,7 @@ void M600_check_state() } } -void M600_wait_for_user() { +void M600_wait_for_user(float HotendTempBckp) { //Beep, manage nozzle heater and wait for user to start unload filament KEEPALIVE_STATE(PAUSED_FOR_USER); From 40990c4deb25f9d5b87f6a177d82b23383fe4dfb Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Thu, 6 Sep 2018 11:30:06 +0200 Subject: [PATCH 087/141] Remove saved_feedmultiply global variable. --- Firmware/Marlin_main.cpp | 65 ++++++++++++++++++++-------------------- 1 file changed, 32 insertions(+), 33 deletions(-) diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index 68982587..47ac08de 100644 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -306,7 +306,6 @@ float homing_feedrate[] = HOMING_FEEDRATE; // Other axes are always absolute or relative based on the common relative_mode flag. bool axis_relative_modes[] = AXIS_RELATIVE_MODES; int feedmultiply=100; //100->1 200->2 -int saved_feedmultiply; int extrudemultiply=100; //100->1 200->2 int extruder_multiply[EXTRUDERS] = {100 #if EXTRUDERS > 1 @@ -2009,23 +2008,24 @@ static void axis_is_at_home(int axis) { inline void set_current_to_destination() { memcpy(current_position, destination, sizeof(current_position)); } inline void set_destination_to_current() { memcpy(destination, current_position, sizeof(destination)); } - -static void setup_for_endstop_move(bool enable_endstops_now = true) { +//! @return original feedmultiply +static int setup_for_endstop_move(bool enable_endstops_now = true) { saved_feedrate = feedrate; - saved_feedmultiply = feedmultiply; + int l_feedmultiply = feedmultiply; feedmultiply = 100; previous_millis_cmd = millis(); enable_endstops(enable_endstops_now); + return l_feedmultiply; } -static void clean_up_after_endstop_move() { +static void clean_up_after_endstop_move(int original_feedmultiply) { #ifdef ENDSTOPS_ONLY_FOR_HOMING enable_endstops(false); #endif feedrate = saved_feedrate; - feedmultiply = saved_feedmultiply; + feedmultiply = original_feedmultiply; previous_millis_cmd = millis(); } @@ -2610,7 +2610,7 @@ void gcode_G28(bool home_x_axis, long home_x_value, bool home_y_axis, long home_ babystep_undo(); saved_feedrate = feedrate; - saved_feedmultiply = feedmultiply; + int l_feedmultiply = feedmultiply; feedmultiply = 100; previous_millis_cmd = millis(); @@ -2796,7 +2796,7 @@ void gcode_G28(bool home_x_axis, long home_x_value, bool home_y_axis, long home_ #endif feedrate = saved_feedrate; - feedmultiply = saved_feedmultiply; + feedmultiply = l_feedmultiply; previous_millis_cmd = millis(); endstops_hit_on_purpose(); #ifndef MESH_BED_LEVELING @@ -2876,7 +2876,7 @@ bool gcode_M45(bool onlyZ, int8_t verbosity_level) // Home in the XY plane. //set_destination_to_current(); - setup_for_endstop_move(); + int l_feedmultiply = setup_for_endstop_move(); lcd_display_message_fullscreen_P(_T(MSG_AUTO_HOME)); home_xy(); @@ -2936,7 +2936,7 @@ bool gcode_M45(bool onlyZ, int8_t verbosity_level) { if (onlyZ) { - clean_up_after_endstop_move(); + clean_up_after_endstop_move(l_feedmultiply); // Z only calibration. // Load the machine correction matrix world2machine_initialize(); @@ -2961,7 +2961,7 @@ bool gcode_M45(bool onlyZ, int8_t verbosity_level) // Complete XYZ calibration. uint8_t point_too_far_mask = 0; BedSkewOffsetDetectionResultType result = find_bed_offset_and_skew(verbosity_level, point_too_far_mask); - clean_up_after_endstop_move(); + clean_up_after_endstop_move(l_feedmultiply); // Print head up. current_position[Z_AXIS] = MESH_HOME_Z_SEARCH; plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], homing_feedrate[Z_AXIS] / 40, active_extruder); @@ -2978,10 +2978,10 @@ bool gcode_M45(bool onlyZ, int8_t verbosity_level) mbl.reset(); world2machine_reset(); // Home in the XY plane. - setup_for_endstop_move(); + int l_feedmultiply = setup_for_endstop_move(); home_xy(); result = improve_bed_offset_and_skew(1, verbosity_level, point_too_far_mask); - clean_up_after_endstop_move(); + clean_up_after_endstop_move(l_feedmultiply); // Print head up. current_position[Z_AXIS] = MESH_HOME_Z_SEARCH; plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], homing_feedrate[Z_AXIS] / 40, active_extruder); @@ -3824,7 +3824,7 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) 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]); - setup_for_endstop_move(); + int l_feedmultiply = setup_for_endstop_move(); feedrate = homing_feedrate[Z_AXIS]; #ifdef AUTO_BED_LEVELING_GRID @@ -3890,7 +3890,7 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) xProbe += xInc; } } - clean_up_after_endstop_move(); + clean_up_after_endstop_move(l_feedmultiply); // solve lsq problem double *plane_equation_coefficients = qr_solve(AUTO_BED_LEVELING_GRID_POINTS*AUTO_BED_LEVELING_GRID_POINTS, 3, eqnAMatrix, eqnBVector); @@ -3919,7 +3919,7 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) // probe 3 float z_at_pt_3 = probe_pt(ABL_PROBE_PT_3_X, ABL_PROBE_PT_3_Y, current_position[Z_AXIS] + Z_RAISE_BETWEEN_PROBINGS); - clean_up_after_endstop_move(); + clean_up_after_endstop_move(l_feedmultiply); set_bed_level_equation_3pts(z_at_pt_1, z_at_pt_2, z_at_pt_3); @@ -3945,7 +3945,7 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) { st_synchronize(); // TODO: make sure the bed_level_rotation_matrix is identity or the planner will get set incorectly - setup_for_endstop_move(); + int l_feedmultiply = setup_for_endstop_move(); feedrate = homing_feedrate[Z_AXIS]; @@ -3959,7 +3959,7 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) SERIAL_PROTOCOL(current_position[Z_AXIS]); SERIAL_PROTOCOLPGM("\n"); - clean_up_after_endstop_move(); + clean_up_after_endstop_move(l_feedmultiply); } break; #else @@ -3977,7 +3977,7 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) { st_synchronize(); // TODO: make sure the bed_level_rotation_matrix is identity or the planner will get set incorectly - setup_for_endstop_move(); + int l_feedmultiply = setup_for_endstop_move(); feedrate = homing_feedrate[Z_AXIS]; @@ -3985,7 +3985,7 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) printf_P(_N("%S X: %.5f Y: %.5f Z: %.5f\n"), _T(MSG_BED), _x, _y, _z); - clean_up_after_endstop_move(); + clean_up_after_endstop_move(l_feedmultiply); } break; @@ -4410,7 +4410,7 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) has_z ? SERIAL_PROTOCOLPGM("Z jitter data from Z cal. valid.\n") : SERIAL_PROTOCOLPGM("Z jitter data from Z cal. not valid.\n"); } #endif // SUPPORT_VERBOSITY - setup_for_endstop_move(false); //save feedrate and feedmultiply, sets feedmultiply to 100 + int l_feedmultiply = setup_for_endstop_move(false); //save feedrate and feedmultiply, sets feedmultiply to 100 const char *kill_message = NULL; while (mesh_point != MESH_MEAS_NUM_X_POINTS * MESH_MEAS_NUM_Y_POINTS) { // Get coords of a measuring point. @@ -4517,7 +4517,7 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) kill(kill_message); SERIAL_ECHOLNPGM("killed"); } - clean_up_after_endstop_move(); + clean_up_after_endstop_move(l_feedmultiply); // SERIAL_ECHOLNPGM("clean up finished "); bool apply_temp_comp = true; @@ -4641,9 +4641,9 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) */ case 82: SERIAL_PROTOCOLLNPGM("Finding bed "); - setup_for_endstop_move(); + int l_feedmultiply = setup_for_endstop_move(); find_bed_induction_sensor_point_z(); - clean_up_after_endstop_move(); + clean_up_after_endstop_move(l_feedmultiply); SERIAL_PROTOCOLPGM("Bed found at: "); SERIAL_PROTOCOL_F(current_position[Z_AXIS], 5); SERIAL_PROTOCOLPGM("\n"); @@ -5070,7 +5070,7 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) st_synchronize(); // Home in the XY plane. set_destination_to_current(); - setup_for_endstop_move(); + int l_feedmultiply = setup_for_endstop_move(); home_xy(); int8_t verbosity_level = 0; if (code_seen('V')) { @@ -5079,7 +5079,7 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) verbosity_level = (c == ' ' || c == '\t' || c == 0) ? 1 : code_value_short(); } bool success = scan_bed_induction_points(verbosity_level); - clean_up_after_endstop_move(); + clean_up_after_endstop_move(l_feedmultiply); // Print head up. current_position[Z_AXIS] = MESH_HOME_Z_SEARCH; plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS],current_position[Z_AXIS] , current_position[E_AXIS], homing_feedrate[Z_AXIS]/40, active_extruder); @@ -5209,7 +5209,7 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) // Then retrace the right amount and use that in subsequent probes // - setup_for_endstop_move(); + int l_feedmultiply = setup_for_endstop_move(); run_z_probe(); current_position[Z_AXIS] = Z_current = st_get_position_mm(Z_AXIS); @@ -5273,7 +5273,7 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) do_blocking_move_to( X_probe_location, Y_probe_location, Z_start_location); // Go back to the probe location } - setup_for_endstop_move(); + int l_feedmultiply = setup_for_endstop_move(); run_z_probe(); sample_set[n] = current_position[Z_AXIS]; @@ -5324,9 +5324,9 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) delay(1000); - clean_up_after_endstop_move(); + clean_up_after_endstop_move(l_feedmultiply); -// enable_endstops(true); +// enable_endstops(true); if (verbose_level > 0) { SERIAL_PROTOCOLPGM("Mean: "); @@ -7850,7 +7850,7 @@ void bed_analysis(float x_dimension, float y_dimension, int x_points_num, int y_ int XY_AXIS_FEEDRATE = homing_feedrate[X_AXIS] / 20; int Z_LIFT_FEEDRATE = homing_feedrate[Z_AXIS] / 40; - setup_for_endstop_move(false); + int l_feedmultiply = setup_for_endstop_move(false); SERIAL_PROTOCOLPGM("Num X,Y: "); SERIAL_PROTOCOL(x_points_num); @@ -7979,7 +7979,7 @@ void bed_analysis(float x_dimension, float y_dimension, int x_points_num, int y_ } card.closefile(); - + clean_up_after_endstop_move(l_feedmultiply); } #endif @@ -8114,7 +8114,6 @@ void long_pause() //long pause print st_synchronize(); //save currently set parameters to global variables - saved_feedmultiply = feedmultiply; fanSpeedBckp = fanSpeed; start_pause_print = millis(); From 05a0b9c93928a07274fe966732cead706b58dd20 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Thu, 6 Sep 2018 11:36:23 +0200 Subject: [PATCH 088/141] Remove fanSpeedBckp global variable. --- Firmware/Marlin_main.cpp | 5 +---- 1 file changed, 1 insertion(+), 4 deletions(-) diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index 47ac08de..6fbdf3ac 100644 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -330,7 +330,6 @@ unsigned int usb_printing_counter; int8_t lcd_change_fil_state = 0; int feedmultiplyBckp = 100; -int fanSpeedBckp = 0; unsigned long pause_time = 0; unsigned long start_pause_print = millis(); unsigned long t_fan_rising_edge = millis(); @@ -3059,7 +3058,7 @@ static void gcode_M600(bool automatic, float x_position, float y_position, float //First backup current position and settings feedmultiplyBckp = feedmultiply; float HotendTempBckp = degTargetHotend(active_extruder); - fanSpeedBckp = fanSpeed; + int fanSpeedBckp = fanSpeed; lastpos[X_AXIS] = current_position[X_AXIS]; lastpos[Y_AXIS] = current_position[Y_AXIS]; @@ -8113,8 +8112,6 @@ void long_pause() //long pause print { st_synchronize(); - //save currently set parameters to global variables - fanSpeedBckp = fanSpeed; start_pause_print = millis(); //retract From 0fe48de4aff8de61de44cfdc1a3477ad65d03137 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Thu, 6 Sep 2018 12:23:21 +0200 Subject: [PATCH 089/141] Remove feedmultiplyBckp global variable. Remove redundant isPrintPaused = true assignment, as it is already done in lcd_pause_print(). Remove unused saved_feedmultiply and fanSpeedBckp prototypes. Move isPrintPaused = true assignment to safer location, as LCD_COMMAND_LONG_PAUSE is not reached if lcd_commands_type is not LCD_COMMAND_IDLE. --- Firmware/Marlin.h | 2 -- Firmware/Marlin_main.cpp | 5 ++--- Firmware/temperature.cpp | 4 ---- Firmware/ultralcd.cpp | 2 +- 4 files changed, 3 insertions(+), 10 deletions(-) diff --git a/Firmware/Marlin.h b/Firmware/Marlin.h index 88d9a3bf..4c8440aa 100644 --- a/Firmware/Marlin.h +++ b/Firmware/Marlin.h @@ -334,8 +334,6 @@ extern uint8_t active_extruder; #endif //Long pause -extern int saved_feedmultiply; -extern int fanSpeedBckp; extern unsigned long pause_time; extern unsigned long start_pause_print; extern unsigned long t_fan_rising_edge; diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index 6fbdf3ac..767ab8d5 100644 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -329,7 +329,6 @@ unsigned int usb_printing_counter; int8_t lcd_change_fil_state = 0; -int feedmultiplyBckp = 100; unsigned long pause_time = 0; unsigned long start_pause_print = millis(); unsigned long t_fan_rising_edge = millis(); @@ -3056,7 +3055,7 @@ static void gcode_M600(bool automatic, float x_position, float y_position, float } //First backup current position and settings - feedmultiplyBckp = feedmultiply; + int feedmultiplyBckp = feedmultiply; float HotendTempBckp = degTargetHotend(active_extruder); int fanSpeedBckp = fanSpeed; @@ -3541,7 +3540,7 @@ void process_commands() if(READ(FR_SENS)){ - feedmultiplyBckp=feedmultiply; + int feedmultiplyBckp=feedmultiply; float target[4]; float lastpos[4]; target[X_AXIS]=current_position[X_AXIS]; diff --git a/Firmware/temperature.cpp b/Firmware/temperature.cpp index ec05de2b..03f59693 100644 --- a/Firmware/temperature.cpp +++ b/Firmware/temperature.cpp @@ -500,9 +500,6 @@ void checkFanSpeed() } } -extern void stop_and_save_print_to_ram(float z_move, float e_move); -extern void restore_print_from_ram_and_continue(float e_move); - void fanSpeedError(unsigned char _fan) { if (get_message_level() != 0 && isPrintPaused) return; //to ensure that target temp. is not set to zero in case taht we are resuming print @@ -511,7 +508,6 @@ void fanSpeedError(unsigned char _fan) { lcd_print_stop(); } else { - isPrintPaused = true; lcd_pause_print(); } } diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index 4feb2299..c699a19f 100644 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -970,7 +970,6 @@ void lcd_commands() if (!blocks_queued() && !homing_flag) { lcd_setstatuspgm(_i("Print paused"));////MSG_PRINT_PAUSED c=20 r=1 - isPrintPaused = true; long_pause(); lcd_commands_type = 0; lcd_commands_step = 0; @@ -1687,6 +1686,7 @@ void lcd_return_to_status() void lcd_pause_print() { lcd_return_to_status(); stop_and_save_print_to_ram(0.0,0.0); + isPrintPaused = true; if (LCD_COMMAND_IDLE == lcd_commands_type) { lcd_commands_type = LCD_COMMAND_LONG_PAUSE; From 5d1e59cec3d79093e8bc6d69e2e5f77b609d3b84 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Thu, 6 Sep 2018 13:20:24 +0200 Subject: [PATCH 090/141] Fix problem that nozzle temperature stays 0 if resume print is invoked from menu earlier than pause movements are finished. --- Firmware/Marlin_main.cpp | 3 --- Firmware/ultralcd.cpp | 18 ++++++++++-------- 2 files changed, 10 insertions(+), 11 deletions(-) diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index 767ab8d5..6f9a6a0e 100644 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -8122,9 +8122,6 @@ void long_pause() //long pause print if (current_position[Z_AXIS] > Z_MAX_POS) current_position[Z_AXIS] = Z_MAX_POS; plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 15, active_extruder); - //set nozzle target temperature to 0 - setAllTargetHotends(0); - //Move XY to side current_position[X_AXIS] = X_PAUSE_POS; current_position[Y_AXIS] = Y_PAUSE_POS; diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index c699a19f..3043dbe0 100644 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -1683,14 +1683,16 @@ void lcd_return_to_status() } -void lcd_pause_print() { - lcd_return_to_status(); - stop_and_save_print_to_ram(0.0,0.0); - isPrintPaused = true; - if (LCD_COMMAND_IDLE == lcd_commands_type) - { - lcd_commands_type = LCD_COMMAND_LONG_PAUSE; - } +void lcd_pause_print() +{ + lcd_return_to_status(); + stop_and_save_print_to_ram(0.0,0.0); + setAllTargetHotends(0); + isPrintPaused = true; + if (LCD_COMMAND_IDLE == lcd_commands_type) + { + lcd_commands_type = LCD_COMMAND_LONG_PAUSE; + } } From cc08d660f7c88fa133a7d6470595aaf2bcc2c90e Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Mon, 10 Sep 2018 20:55:50 +0200 Subject: [PATCH 091/141] Always use filament 1 for first layer calibration when MMU is present. Lift Z when moving from intro line to meander. For MMU, print longer intro line to allow load to nozzle. --- Firmware/ultralcd.cpp | 59 ++++++++++++++++++++++++++++++++++--------- 1 file changed, 47 insertions(+), 12 deletions(-) diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index 3fb0f7c4..41b7f28e 100644 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -1257,9 +1257,9 @@ void lcd_commands() if(lcd_commands_step>1) lcd_timeoutToStatus.start(); //if user dont confirm live adjust Z value by pressing the knob, we are saving last value by timeout to status screen if (lcd_commands_step == 0) { - lcd_commands_step = 9; + lcd_commands_step = 10; } - if (lcd_commands_step == 9 && !blocks_queued() && cmd_buffer_empty()) + if (lcd_commands_step == 10 && !blocks_queued() && cmd_buffer_empty()) { enquecommand_P(PSTR("M107")); enquecommand_P(PSTR("M104 S" STRINGIFY(PLA_PREHEAT_HOTEND_TEMP))); @@ -1267,26 +1267,54 @@ void lcd_commands() enquecommand_P(PSTR("M190 S" STRINGIFY(PLA_PREHEAT_HPB_TEMP))); enquecommand_P(PSTR("M109 S" STRINGIFY(PLA_PREHEAT_HOTEND_TEMP))); enquecommand_P(_T(MSG_M117_V2_CALIBRATION)); - if (mmu_enabled) - enquecommand_P(PSTR("T?")); enquecommand_P(PSTR("G28")); enquecommand_P(PSTR("G92 E0.0")); - lcd_commands_step = 8; + + lcd_commands_step = 9; } + if (lcd_commands_step == 9 && !blocks_queued() && cmd_buffer_empty()) + { + lcd_clear(); + menu_depth = 0; + menu_submenu(lcd_babystep_z); + + if (mmu_enabled) + { + const uint8_t filament = 0; + strcpy(cmd1, "T"); + strcat(cmd1, itostr3left(filament)); + enquecommand(cmd1); + enquecommand_P(PSTR("M83")); //intro line + enquecommand_P(PSTR("G1 Y-3.0 F1000.0")); //intro line + enquecommand_P(PSTR("G1 Z0.4 F1000.0")); //intro line + enquecommand_P(PSTR("G1 X55.0 E32.0 F1073.0")); //intro line + enquecommand_P(PSTR("G1 X5.0 E32.0 F1800.0")); //intro line + enquecommand_P(PSTR("G1 X55.0 E8.0 F2000.0")); //intro line + enquecommand_P(PSTR("G1 Z0.3 F1000.0")); //intro line + enquecommand_P(PSTR("G92 E0.0")); //intro line + enquecommand_P(PSTR("G1 X240.0 E25.0 F2200.0")); //intro line + enquecommand_P(PSTR("G1 Y-2.0 F1000.0")); //intro line + enquecommand_P(PSTR("G1 X55.0 E25 F1400.0")); //intro line + enquecommand_P(PSTR("G1 Z0.20 F1000.0")); //intro line + enquecommand_P(PSTR("G1 X5.0 E4.0 F1000.0")); //intro line + + } else + { + enquecommand_P(PSTR("G1 X60.0 E9.0 F1000.0")); //intro line + enquecommand_P(PSTR("G1 X100.0 E12.5 F1000.0")); //intro line + } + + lcd_commands_step = 8; + } if (lcd_commands_step == 8 && !blocks_queued() && cmd_buffer_empty()) { - lcd_clear(); - menu_depth = 0; - menu_submenu(lcd_babystep_z); - enquecommand_P(PSTR("G1 X60.0 E9.0 F1000.0")); //intro line - enquecommand_P(PSTR("G1 X100.0 E12.5 F1000.0")); //intro line enquecommand_P(PSTR("G92 E0.0")); enquecommand_P(PSTR("G21")); //set units to millimeters enquecommand_P(PSTR("G90")); //use absolute coordinates enquecommand_P(PSTR("M83")); //use relative distances for extrusion enquecommand_P(PSTR("G1 E-1.50000 F2100.00000")); - enquecommand_P(PSTR("G1 Z0.150 F7200.000")); + enquecommand_P(PSTR("G1 Z5 F7200.000")); enquecommand_P(PSTR("M204 S1000")); //set acceleration enquecommand_P(PSTR("G1 F4000")); lcd_commands_step = 7; @@ -1316,6 +1344,7 @@ void lcd_commands() enquecommand_P(PSTR("G1 X50 Y155")); + enquecommand_P(PSTR("G1 Z0.150 F7200.000")); enquecommand_P(PSTR("G1 F1080")); enquecommand_P(PSTR("G1 X75 Y155 E2.5")); enquecommand_P(PSTR("G1 X100 Y155 E2")); @@ -4335,7 +4364,13 @@ void lcd_wizard(int state) { lcd_commands_type = LCD_COMMAND_V2_CAL; setTargetHotend(PLA_PREHEAT_HOTEND_TEMP, 0); setTargetBed(PLA_PREHEAT_HPB_TEMP); - wizard_event = lcd_show_fullscreen_message_yes_no_and_wait_P(_i("Is filament loaded?"), false);////MSG_WIZARD_FILAMENT_LOADED c=20 r=2 + if (mmu_enabled) + { + wizard_event = lcd_show_fullscreen_message_yes_no_and_wait_P(_i("Is filament 1 loaded?"), false);////c=20 r=2 + } else + { + wizard_event = lcd_show_fullscreen_message_yes_no_and_wait_P(_i("Is filament loaded?"), false);////MSG_WIZARD_FILAMENT_LOADED c=20 r=2 + } if (wizard_event) state = 8; else state = 6; From 6c6354b2cb0298a54dbb505804ca812af93e9fc4 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Tue, 11 Sep 2018 16:03:46 +0200 Subject: [PATCH 092/141] Do not preheat nozzle before loading filament to MMU in first layer calibration wizard. Show insert PLA filament to the first tube of MMU instead of "to the extruder". First layer calibration wizard with MMU is now functional. But there is no option to unload filament from wizard. --- Firmware/ultralcd.cpp | 15 ++++++++++++--- 1 file changed, 12 insertions(+), 3 deletions(-) diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index adfd0014..60dfbca3 100644 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -4373,8 +4373,11 @@ void lcd_wizard(int state) { wizard_event = lcd_show_fullscreen_message_yes_no_and_wait_P(_i("Is filament loaded?"), false);////MSG_WIZARD_FILAMENT_LOADED c=20 r=2 } if (wizard_event) state = 8; - else state = 6; - + else + { + if(mmu_enabled) state = 7; + else state = 6; + } break; case 6: //waiting for preheat nozzle for PLA; #ifndef SNMM @@ -4399,7 +4402,13 @@ void lcd_wizard(int state) { state = 7; break; case 7: //load filament - lcd_show_fullscreen_message_and_wait_P(_i("Please insert PLA filament to the extruder, then press knob to load it."));////MSG_WIZARD_LOAD_FILAMENT c=20 r=8 + if (mmu_enabled) + { + lcd_show_fullscreen_message_and_wait_P(_i("Please insert PLA filament to the first tube of MMU, then press the knob to load it."));////c=20 r=8 + } else + { + lcd_show_fullscreen_message_and_wait_P(_i("Please insert PLA filament to the extruder, then press knob to load it."));////MSG_WIZARD_LOAD_FILAMENT c=20 r=8 + } lcd_update_enable(false); lcd_clear(); lcd_puts_at_P(0, 2, _T(MSG_LOADING_FILAMENT)); From 19a1ccdc768fb295901597b6c27bb62fa66e3059 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Tue, 11 Sep 2018 16:51:00 +0200 Subject: [PATCH 093/141] Rename choose_extruder_menu() to choose_menu_P(), add parameters to make it reusable. --- Firmware/Marlin_main.cpp | 2 +- Firmware/ultralcd.cpp | 16 ++++++++-------- Firmware/ultralcd.h | 2 +- 3 files changed, 10 insertions(+), 10 deletions(-) diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index 9d641c67..33074b71 100644 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -6816,7 +6816,7 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) } else { if (*(strchr_pointer + index) == '?') { - tmp_extruder = choose_extruder_menu(); + tmp_extruder = choose_menu_P(_T(MSG_CHOOSE_EXTRUDER), _T(MSG_EXTRUDER)); } else { tmp_extruder = code_value(); diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index 60dfbca3..3f05a628 100644 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -4969,7 +4969,7 @@ static char snmm_stop_print_menu() { //menu for choosing which filaments will be } -char choose_extruder_menu() +char choose_menu_P(const char *header, const char *item) { int items_no = mmu_enabled?5:4; int first = 0; @@ -4979,17 +4979,17 @@ char choose_extruder_menu() enc_dif = lcd_encoder_diff; lcd_clear(); - lcd_puts_P(_T(MSG_CHOOSE_EXTRUDER)); + lcd_puts_P(header); lcd_set_cursor(0, 1); lcd_print(">"); for (int i = 0; i < 3; i++) { - lcd_puts_at_P(1, i + 1, _T(MSG_EXTRUDER)); + lcd_puts_at_P(1, i + 1, item); } KEEPALIVE_STATE(PAUSED_FOR_USER); while (1) { for (int i = 0; i < 3; i++) { - lcd_set_cursor(2 + strlen_P(_T(MSG_EXTRUDER)), i+1); + lcd_set_cursor(2 + strlen_P(item), i+1); lcd_print(first + i + 1); } @@ -5012,9 +5012,9 @@ char choose_extruder_menu() if (first < items_no - 3) { first++; lcd_clear(); - lcd_puts_P(_T(MSG_CHOOSE_EXTRUDER)); + lcd_puts_P(header); for (int i = 0; i < 3; i++) { - lcd_puts_at_P(1, i + 1, _T(MSG_EXTRUDER)); + lcd_puts_at_P(1, i + 1, item); } } } @@ -5024,9 +5024,9 @@ char choose_extruder_menu() if (first > 0) { first--; lcd_clear(); - lcd_puts_P(_T(MSG_CHOOSE_EXTRUDER)); + lcd_puts_P(header); for (int i = 0; i < 3; i++) { - lcd_puts_at_P(1, i + 1, _T(MSG_EXTRUDER)); + lcd_puts_at_P(1, i + 1, item); } } } diff --git a/Firmware/ultralcd.h b/Firmware/ultralcd.h index 113f6f70..20c1707a 100644 --- a/Firmware/ultralcd.h +++ b/Firmware/ultralcd.h @@ -152,7 +152,7 @@ bool lcd_wait_for_pinda(float temp); void bowden_menu(); char reset_menu(); -char choose_extruder_menu(); +char choose_menu_P(const char *header, const char *item); void lcd_pinda_calibration_menu(); void lcd_calibrate_pinda(); From 46df46f48268ac0bd5dfff9808f72869e52c7df2 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Tue, 11 Sep 2018 17:03:20 +0200 Subject: [PATCH 094/141] Add possibility to use other filaments in LCD_COMMAND_V2_CAL. --- Firmware/ultralcd.cpp | 28 +++++++++++++++++++++++++++- 1 file changed, 27 insertions(+), 1 deletion(-) diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index 3f05a628..9bd966a5 100644 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -1250,6 +1250,7 @@ void lcd_commands() if (lcd_commands_type == LCD_COMMAND_V2_CAL) { char cmd1[30]; + uint8_t filament = 0; float width = 0.4; float length = 20 - width; float extr = count_e(0.2, width, length); @@ -1259,6 +1260,32 @@ void lcd_commands() { lcd_commands_step = 10; } + if (lcd_commands_step == 20 && !blocks_queued() && cmd_buffer_empty()) + { + filament = 0; + lcd_commands_step = 10; + } + if (lcd_commands_step == 21 && !blocks_queued() && cmd_buffer_empty()) + { + filament = 1; + lcd_commands_step = 10; + } + if (lcd_commands_step == 22 && !blocks_queued() && cmd_buffer_empty()) + { + filament = 2; + lcd_commands_step = 10; + } + if (lcd_commands_step == 23 && !blocks_queued() && cmd_buffer_empty()) + { + filament = 3; + lcd_commands_step = 10; + } + if (lcd_commands_step == 24 && !blocks_queued() && cmd_buffer_empty()) + { + filament = 4; + lcd_commands_step = 10; + } + if (lcd_commands_step == 10 && !blocks_queued() && cmd_buffer_empty()) { enquecommand_P(PSTR("M107")); @@ -1280,7 +1307,6 @@ void lcd_commands() if (mmu_enabled) { - const uint8_t filament = 0; strcpy(cmd1, "T"); strcat(cmd1, itostr3left(filament)); enquecommand(cmd1); From 98264808dcfed971fd137c5ce29d0617ba9fed6c Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Tue, 11 Sep 2018 17:16:13 +0200 Subject: [PATCH 095/141] Change gcode "T?" question from "Choose extruder:" to "Choose filament" and answers from "Extruder 1" .. "Extruder 5" to "Filament 1" .. "Filament 5". --- Firmware/Marlin_main.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index 33074b71..589ab814 100644 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -6816,7 +6816,7 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) } else { if (*(strchr_pointer + index) == '?') { - tmp_extruder = choose_menu_P(_T(MSG_CHOOSE_EXTRUDER), _T(MSG_EXTRUDER)); + tmp_extruder = choose_menu_P(_i("Choose filament:"), _i("Filament")); ////c=20 r=1 ////c=17 r=1 } else { tmp_extruder = code_value(); From 5649d6c3c0007b3797e0cd0d5be8945c784ee68f Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Tue, 11 Sep 2018 17:27:10 +0200 Subject: [PATCH 096/141] Precede active filament on status screen with letter F. --- Firmware/ultralcd.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index 9bd966a5..0b26cec2 100644 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -533,7 +533,7 @@ void lcdui_print_extruder(void) { int chars = 0; if (mmu_extruder == tmp_extruder) - chars = lcd_printf_P(_N(" T%u"), mmu_extruder+1); + chars = lcd_printf_P(_N(" F%u"), mmu_extruder+1); else chars = lcd_printf_P(_N(" %u>%u"), mmu_extruder+1, tmp_extruder+1); lcd_space(5 - chars); From ada7cffd32e28ae51bf8cbb572bdbab172245e90 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Tue, 11 Sep 2018 19:53:29 +0200 Subject: [PATCH 097/141] Open menu to select filament before first layer calibration if MMU unit is present. --- Firmware/ultralcd.cpp | 40 +++++++++++++++++++++++++--------------- 1 file changed, 25 insertions(+), 15 deletions(-) diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index 0b26cec2..830a35d6 100644 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -1256,7 +1256,8 @@ void lcd_commands() float extr = count_e(0.2, width, length); float extr_short_segment = count_e(0.2, width, width); if(lcd_commands_step>1) lcd_timeoutToStatus.start(); //if user dont confirm live adjust Z value by pressing the knob, we are saving last value by timeout to status screen - if (lcd_commands_step == 0) + + if (lcd_commands_step == 0 && !blocks_queued() && cmd_buffer_empty()) { lcd_commands_step = 10; } @@ -1286,11 +1287,17 @@ void lcd_commands() lcd_commands_step = 10; } - if (lcd_commands_step == 10 && !blocks_queued() && cmd_buffer_empty()) + if (lcd_commands_step == 10) { enquecommand_P(PSTR("M107")); enquecommand_P(PSTR("M104 S" STRINGIFY(PLA_PREHEAT_HOTEND_TEMP))); enquecommand_P(PSTR("M140 S" STRINGIFY(PLA_PREHEAT_HPB_TEMP))); + if (mmu_enabled) + { + strcpy(cmd1, "T"); + strcat(cmd1, itostr3left(filament)); + enquecommand(cmd1); + } enquecommand_P(PSTR("M190 S" STRINGIFY(PLA_PREHEAT_HPB_TEMP))); enquecommand_P(PSTR("M109 S" STRINGIFY(PLA_PREHEAT_HOTEND_TEMP))); enquecommand_P(_T(MSG_M117_V2_CALIBRATION)); @@ -1307,9 +1314,6 @@ void lcd_commands() if (mmu_enabled) { - strcpy(cmd1, "T"); - strcat(cmd1, itostr3left(filament)); - enquecommand(cmd1); enquecommand_P(PSTR("M83")); //intro line enquecommand_P(PSTR("G1 Y-3.0 F1000.0")); //intro line enquecommand_P(PSTR("G1 Z0.4 F1000.0")); //intro line @@ -4274,7 +4278,10 @@ void lcd_toshiba_flash_air_compatibility_toggle() void lcd_v2_calibration() { if (mmu_enabled) + { + lcd_commands_step = 20 + choose_menu_P(_i("Select PLA filament:"),_i("Filament")); ////c=20 r=1 ////c=17 r=1 lcd_commands_type = LCD_COMMAND_V2_CAL; + } else { bool loaded = lcd_show_fullscreen_message_yes_no_and_wait_P(_i("Is PLA filament loaded?"), false, true);////MSG_PLA_FILAMENT_LOADED c=20 r=2 @@ -4995,6 +5002,16 @@ static char snmm_stop_print_menu() { //menu for choosing which filaments will be } +//! @brief Select one of numbered items +//! +//! Create list of items with header. Header can not be selected. +//! Each item has text description passed by function parameter and +//! number. There are 5 items, if mmu_enabled, 4 otherwise. +//! Items are numbered from 1 to 4 or 5. But index returned starts at 0. +//! +//! @param header Header text +//! @param item Item text +//! @return selected item index, first item index is 0 char choose_menu_P(const char *header, const char *item) { int items_no = mmu_enabled?5:4; @@ -5067,21 +5084,14 @@ char choose_menu_P(const char *header, const char *item) enc_dif = lcd_encoder_diff; delay(100); } - } - if (lcd_clicked()) { - lcd_update(2); - while (lcd_clicked()); - delay(10); - while (lcd_clicked()); - KEEPALIVE_STATE(IN_HANDLER); + if (lcd_clicked()) + { + KEEPALIVE_STATE(IN_HANDLER); return(cursor_pos + first - 1); - } - } - } //#endif From 13b67f0e0a67862a053dbc7f59ae65725a2435a4 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Tue, 11 Sep 2018 22:33:13 +0200 Subject: [PATCH 098/141] Add Cancel item into PLA filament selection menu initiated by first layer calibration with MMU. --- Firmware/ultralcd.cpp | 146 +++++++++++++++++++++++------------------- Firmware/ultralcd.h | 2 +- 2 files changed, 81 insertions(+), 67 deletions(-) diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index 830a35d6..21836c38 100644 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -4279,8 +4279,12 @@ void lcd_v2_calibration() { if (mmu_enabled) { - lcd_commands_step = 20 + choose_menu_P(_i("Select PLA filament:"),_i("Filament")); ////c=20 r=1 ////c=17 r=1 - lcd_commands_type = LCD_COMMAND_V2_CAL; + const uint8_t filament = choose_menu_P(_i("Select PLA filament:"),_i("Filament"),_i("Cancel")); ////c=20 r=1 ////c=17 r=1 ////c=19 r=1 + if (filament < 5) + { + lcd_commands_step = 20 + filament; + lcd_commands_type = LCD_COMMAND_V2_CAL; + } } else { @@ -5006,86 +5010,96 @@ static char snmm_stop_print_menu() { //menu for choosing which filaments will be //! //! Create list of items with header. Header can not be selected. //! Each item has text description passed by function parameter and -//! number. There are 5 items, if mmu_enabled, 4 otherwise. +//! number. There are 5 numbered items, if mmu_enabled, 4 otherwise. //! Items are numbered from 1 to 4 or 5. But index returned starts at 0. +//! There can be last item with different text and no number. //! //! @param header Header text //! @param item Item text +//! @param last_item Last item text, or nullptr if there is no Last item //! @return selected item index, first item index is 0 -char choose_menu_P(const char *header, const char *item) +uint8_t choose_menu_P(const char *header, const char *item, const char *last_item) { - int items_no = mmu_enabled?5:4; - int first = 0; - int enc_dif = 0; - char cursor_pos = 1; + //following code should handle 3 to 127 number of items well + const int8_t items_no = last_item?(mmu_enabled?6:5):(mmu_enabled?5:4); + const uint8_t item_len = item?strlen_P(item):0; + int8_t first = 0; + int8_t enc_dif = lcd_encoder_diff; + int8_t cursor_pos = 1; - enc_dif = lcd_encoder_diff; lcd_clear(); - lcd_puts_P(header); - lcd_set_cursor(0, 1); - lcd_print(">"); - for (int i = 0; i < 3; i++) { - lcd_puts_at_P(1, i + 1, item); - } + KEEPALIVE_STATE(PAUSED_FOR_USER); - while (1) { - - for (int i = 0; i < 3; i++) { - lcd_set_cursor(2 + strlen_P(item), i+1); - lcd_print(first + i + 1); - } - + while (1) + { manage_heater(); manage_inactivity(true); - if (abs((enc_dif - lcd_encoder_diff)) > 4) { + if (abs((enc_dif - lcd_encoder_diff)) > 4) + { + if (enc_dif > lcd_encoder_diff) + { + cursor_pos--; + } - if ((abs(enc_dif - lcd_encoder_diff)) > 1) { - if (enc_dif > lcd_encoder_diff) { - cursor_pos--; - } - - if (enc_dif < lcd_encoder_diff) { - cursor_pos++; - } - - if (cursor_pos > 3) { - cursor_pos = 3; - if (first < items_no - 3) { - first++; - lcd_clear(); - lcd_puts_P(header); - for (int i = 0; i < 3; i++) { - lcd_puts_at_P(1, i + 1, item); - } - } - } - - if (cursor_pos < 1) { - cursor_pos = 1; - if (first > 0) { - first--; - lcd_clear(); - lcd_puts_P(header); - for (int i = 0; i < 3; i++) { - lcd_puts_at_P(1, i + 1, 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(">"); - enc_dif = lcd_encoder_diff; - delay(100); - } + if (enc_dif < lcd_encoder_diff) + { + cursor_pos++; + } + enc_dif = lcd_encoder_diff; } + if (cursor_pos > 3) + { + cursor_pos = 3; + if (first < items_no - 3) + { + first++; + lcd_clear(); + } + } + + if (cursor_pos < 1) + { + cursor_pos = 1; + if (first > 0) + { + first--; + lcd_clear(); + } + } + + if (header) lcd_puts_at_P(0,0,header); + + const bool last_visible = (first == items_no - 3); + const int8_t ordinary_items = (last_item&&last_visible)?2:3; + + for (int i = 0; i < ordinary_items; i++) + { + if (item) lcd_puts_at_P(1, i + 1, item); + } + + for (int i = 0; i < ordinary_items; i++) + { + lcd_set_cursor(2 + item_len, i+1); + lcd_print(first + i + 1); + } + + 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(">"); + + delay(100); + if (lcd_clicked()) { KEEPALIVE_STATE(IN_HANDLER); diff --git a/Firmware/ultralcd.h b/Firmware/ultralcd.h index 20c1707a..34eded1e 100644 --- a/Firmware/ultralcd.h +++ b/Firmware/ultralcd.h @@ -152,7 +152,7 @@ bool lcd_wait_for_pinda(float temp); void bowden_menu(); char reset_menu(); -char choose_menu_P(const char *header, const char *item); +uint8_t choose_menu_P(const char *header, const char *item, const char *last_item = nullptr); void lcd_pinda_calibration_menu(); void lcd_calibrate_pinda(); From 7bc46323e27b6a3a8807bf700e6b9925d888ddcc Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Wed, 12 Sep 2018 18:35:26 +0200 Subject: [PATCH 099/141] Update pause print documentation. --- Firmware/Marlin_main.cpp | 42 +++++++++++++++++++++++++++++----------- Firmware/doxyfile | 2 +- Firmware/ultralcd.cpp | 5 ++++- 3 files changed, 36 insertions(+), 13 deletions(-) diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index 9d641c67..b09f398c 100644 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -464,8 +464,6 @@ bool no_response = false; uint8_t important_status; uint8_t saved_filament_type; -// save/restore printing -bool saved_printing = false; // save/restore printing in case that mmu was not responding bool mmu_print_saved = false; @@ -526,17 +524,20 @@ unsigned long chdkHigh = 0; boolean chdkActive = false; #endif -// save/restore printing -static uint32_t saved_sdpos = 0; +//! @name RAM save/restore printing +//! @{ +bool saved_printing = false; //!< Print is paused and saved in RAM +static uint32_t saved_sdpos = 0; //!< SD card position, or line number in case of USB printing static uint8_t saved_printing_type = PRINTING_TYPE_SD; static float saved_pos[4] = { 0, 0, 0, 0 }; -// Feedrate hopefully derived from an active block of the planner at the time the print has been canceled, in mm/min. +//! Feedrate hopefully derived from an active block of the planner at the time the print has been canceled, in mm/min. static float saved_feedrate2 = 0; static uint8_t saved_active_extruder = 0; -static float saved_extruder_temperature = 0.0; +static float saved_extruder_temperature = 0.0; //!< Active extruder temperature static bool saved_extruder_under_pressure = false; static bool saved_extruder_relative_mode = false; -static int saved_fanSpeed = 0; +static int saved_fanSpeed = 0; //!< Print fan speed +//! @} //=========================================================================== //=============================Routines====================================== @@ -2019,6 +2020,7 @@ static int setup_for_endstop_move(bool enable_endstops_now = true) { return l_feedmultiply; } +//! @param original_feedmultiply feedmultiply to restore static void clean_up_after_endstop_move(int original_feedmultiply) { #ifdef ENDSTOPS_ONLY_FOR_HOMING enable_endstops(false); @@ -8586,9 +8588,14 @@ void restore_print_from_eeprom() { #endif //UVLO_SUPPORT -//////////////////////////////////////////////////////////////////////////////// -// save/restore printing - +//! @brief Immediately stop print moves +//! +//! Immediately stop print moves, save current extruder temperature and position to RAM. +//! If printing from sd card, position in file is saved. +//! If printing from USB, line number is saved. +//! +//! @param z_move +//! @param e_move void stop_and_save_print_to_ram(float z_move, float e_move) { if (saved_printing) return; @@ -8773,6 +8780,14 @@ void stop_and_save_print_to_ram(float z_move, float e_move) } } +//! @brief Restore print from ram +//! +//! Restore print saved by stop_and_save_print_to_ram(). Is blocking, +//! waits for extruder temperature restore, then restores position and continues +//! print moves. +//! Internaly lcd_update() is called by wait_for_heater(). +//! +//! @param e_move void restore_print_from_ram_and_continue(float e_move) { if (!saved_printing) return; @@ -8914,8 +8929,13 @@ void M600_check_state() } } +//! @brief Wait for user action +//! +//! Beep, manage nozzle heater and wait for user to start unload filament +//! If times out, active extruder temperature is set to 0. +//! +//! @param HotendTempBckp Temperature to be restored for active extruder, after user resolves MMU problem. void M600_wait_for_user(float HotendTempBckp) { - //Beep, manage nozzle heater and wait for user to start unload filament KEEPALIVE_STATE(PAUSED_FOR_USER); diff --git a/Firmware/doxyfile b/Firmware/doxyfile index 6fa1ef4f..f3805302 100644 --- a/Firmware/doxyfile +++ b/Firmware/doxyfile @@ -453,7 +453,7 @@ EXTRACT_PACKAGE = NO # included in the documentation. # The default value is: NO. -EXTRACT_STATIC = NO +EXTRACT_STATIC = YES # If the EXTRACT_LOCAL_CLASSES tag is set to YES, classes (and structs) defined # locally in source files will be included in the documentation. If set to NO, diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index 7037d2f5..8b84cc4f 100644 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -1684,7 +1684,7 @@ void lcd_return_to_status() menu_depth = 0; } - +//! @brief Pause print, disable nozzle heater, move to park position void lcd_pause_print() { lcd_return_to_status(); @@ -5458,6 +5458,9 @@ static void lcd_test_menu() } #endif //LCD_TEST +//! @brief Resume paused print +//! @todo It is not good to call restore_print_from_ram_and_continue() from function called by lcd_update(), +//! as restore_print_from_ram_and_continue() calls lcd_update() internally. void lcd_resume_print() { lcd_return_to_status(); From d14822b22f77af223e403c08ae973e13cfedd7db Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Thu, 13 Sep 2018 16:07:19 +0200 Subject: [PATCH 100/141] Give wizard states human readable names. Use uint8_t as underlying type - saves 20B of FLASH memory. --- Firmware/Marlin_main.cpp | 7 +++- Firmware/ultralcd.cpp | 87 ++++++++++++++++++++-------------------- Firmware/ultralcd.h | 20 ++++++++- 3 files changed, 69 insertions(+), 45 deletions(-) diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index 93b0989a..198f6160 100644 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -1635,7 +1635,7 @@ void setup() erase_eeprom_section(EEPROM_OFFSET, 156); //erase M500 part of eeprom } if (eeprom_read_byte((uint8_t*)EEPROM_WIZARD_ACTIVE) == 1) { - lcd_wizard(0); + lcd_wizard(WizState::Run); } if (eeprom_read_byte((uint8_t*)EEPROM_WIZARD_ACTIVE) == 0) { //dont show calibration status messages if wizard is currently active if (calibration_status() == CALIBRATION_STATUS_ASSEMBLED || @@ -2849,6 +2849,11 @@ void adjust_bed_reset() eeprom_update_byte((unsigned char*)EEPROM_BED_CORRECTION_REAR, 0); } +//! @brief Calibrate XYZ +//! @param onlyZ if true, calibrate only Z axis +//! @param verbosity_level +//! @retval true Succeeded +//! @retval false Failed bool gcode_M45(bool onlyZ, int8_t verbosity_level) { bool final_result = false; diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index cd73912e..e9b98ebb 100644 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -1239,7 +1239,7 @@ void lcd_commands() lcd_commands_step = 0; lcd_commands_type = 0; if (eeprom_read_byte((uint8_t*)EEPROM_WIZARD_ACTIVE) == 1) { - lcd_wizard(10); + lcd_wizard(WizState::RepeatLay1Cal); } } @@ -1535,7 +1535,7 @@ void lcd_commands() lcd_commands_step = 0; lcd_commands_type = 0; if (eeprom_read_byte((uint8_t*)EEPROM_WIZARD_ACTIVE) == 1) { - lcd_wizard(10); + lcd_wizard(WizState::RepeatLay1Cal); } } @@ -4316,7 +4316,7 @@ void lcd_wizard() { } if (result) { calibration_status_store(CALIBRATION_STATUS_ASSEMBLED); - lcd_wizard(0); + lcd_wizard(WizState::Run); } else { lcd_return_to_status(); @@ -4345,19 +4345,20 @@ void lcd_language() lang_select(LANG_ID_PRI); } -void lcd_wizard(int state) { - +void lcd_wizard(WizState state) +{ + using S = WizState; bool end = false; int wizard_event; const char *msg = NULL; while (!end) { printf_P(PSTR("Wizard state: %d"), state); switch (state) { - case 0: // run wizard? + case S::Run: //Run wizard? wizard_active = true; wizard_event = lcd_show_multiscreen_message_yes_no_and_wait_P(_i("Hi, I am your Original Prusa i3 printer. Would you like me to guide you through the setup process?"), false, true);////MSG_WIZARD_WELCOME c=20 r=7 if (wizard_event) { - state = 1; + state = S::Restore; eeprom_write_byte((uint8_t*)EEPROM_WIZARD_ACTIVE, 1); } else { @@ -4365,40 +4366,40 @@ void lcd_wizard(int state) { end = true; } break; - case 1: // restore calibration status + case S::Restore: // restore calibration status switch (calibration_status()) { - case CALIBRATION_STATUS_ASSEMBLED: state = 2; break; //run selftest - case CALIBRATION_STATUS_XYZ_CALIBRATION: state = 3; break; //run xyz cal. - case CALIBRATION_STATUS_Z_CALIBRATION: state = 4; break; //run z cal. - case CALIBRATION_STATUS_LIVE_ADJUST: state = 5; break; //run live adjust + case CALIBRATION_STATUS_ASSEMBLED: state = S::Selftest; break; //run selftest + case CALIBRATION_STATUS_XYZ_CALIBRATION: state = S::Xyz; break; //run xyz cal. + case CALIBRATION_STATUS_Z_CALIBRATION: state = S::Z; break; //run z cal. + case CALIBRATION_STATUS_LIVE_ADJUST: state = S::IsFil; break; //run live adjust case CALIBRATION_STATUS_CALIBRATED: end = true; eeprom_write_byte((uint8_t*)EEPROM_WIZARD_ACTIVE, 0); break; - default: state = 2; break; //if calibration status is unknown, run wizard from the beginning + default: state = S::Selftest; break; //if calibration status is unknown, run wizard from the beginning } break; - case 2: //selftest + case S::Selftest: lcd_show_fullscreen_message_and_wait_P(_i("First, I will run the selftest to check most common assembly problems."));////MSG_WIZARD_SELFTEST c=20 r=8 wizard_event = lcd_selftest(); if (wizard_event) { calibration_status_store(CALIBRATION_STATUS_XYZ_CALIBRATION); - state = 3; + state = S::Xyz; } else end = true; break; - case 3: //xyz cal. + case S::Xyz: //xyz calibration lcd_show_fullscreen_message_and_wait_P(_i("I will run xyz calibration now. It will take approx. 12 mins."));////MSG_WIZARD_XYZ_CAL c=20 r=8 wizard_event = gcode_M45(false, 0); - if (wizard_event) state = 5; + if (wizard_event) state = S::IsFil; else end = true; break; - case 4: //z cal. + case S::Z: //z calibration lcd_show_fullscreen_message_and_wait_P(_i("I will run z calibration now."));////MSG_WIZARD_Z_CAL c=20 r=8 wizard_event = lcd_show_fullscreen_message_yes_no_and_wait_P(_T(MSG_STEEL_SHEET_CHECK), false, false); if (!wizard_event) lcd_show_fullscreen_message_and_wait_P(_T(MSG_PLACE_STEEL_SHEET)); wizard_event = gcode_M45(true, 0); - if (wizard_event) state = 11; //shipped, no need to set first layer, go to final message directly + if (wizard_event) state = S::Finish; //shipped, no need to set first layer, go to final message directly else end = true; break; - case 5: //is filament loaded? + case S::IsFil: //is filament loaded? //start to preheat nozzle and bed to save some time later setTargetHotend(PLA_PREHEAT_HOTEND_TEMP, 0); setTargetBed(PLA_PREHEAT_HPB_TEMP); @@ -4409,14 +4410,14 @@ void lcd_wizard(int state) { { wizard_event = lcd_show_fullscreen_message_yes_no_and_wait_P(_i("Is filament loaded?"), false);////MSG_WIZARD_FILAMENT_LOADED c=20 r=2 } - if (wizard_event) state = 8; + if (wizard_event) state = S::IsPla; else { - if(mmu_enabled) state = 7; - else state = 6; + if(mmu_enabled) state = S::LoadFil; + else state = S::Preheat; } break; - case 6: //waiting for preheat nozzle for PLA; + case S::Preheat: #ifndef SNMM lcd_display_message_fullscreen_P(_i("Now I will preheat nozzle for PLA."));////MSG_WIZARD_WILL_PREHEAT c=20 r=4 current_position[Z_AXIS] = 100; //move in z axis to make space for loading filament @@ -4436,9 +4437,9 @@ void lcd_wizard(int state) { delay_keep_alive(1000); } #endif //not SNMM - state = 7; + state = S::LoadFil; break; - case 7: //load filament + case S::LoadFil: //load filament if (mmu_enabled) { lcd_show_fullscreen_message_and_wait_P(_i("Please insert PLA filament to the first tube of MMU, then press the knob to load it."));////c=20 r=8 @@ -4454,30 +4455,30 @@ void lcd_wizard(int state) { #endif loading_flag = true; gcode_M701(); - state = 9; + state = S::Lay1Cal; break; - case 8: + case S::IsPla: wizard_event = lcd_show_fullscreen_message_yes_no_and_wait_P(_i("Is it PLA filament?"), false, true);////MSG_WIZARD_PLA_FILAMENT c=20 r=2 - if (wizard_event) state = 9; + if (wizard_event) state = S::Lay1Cal; else end = true; break; - case 9: + case S::Lay1Cal: lcd_show_fullscreen_message_and_wait_P(_i("Now I will calibrate distance between tip of the nozzle and heatbed surface."));////MSG_WIZARD_V2_CAL c=20 r=8 lcd_show_fullscreen_message_and_wait_P(_i("I will start to print line and you will gradually lower the nozzle by rotating the knob, until you reach optimal height. Check the pictures in our handbook in chapter Calibration."));////MSG_WIZARD_V2_CAL_2 c=20 r=12 lcd_commands_type = LCD_COMMAND_V2_CAL; end = true; break; - case 10: //repeat first layer cal.? + case S::RepeatLay1Cal: //repeat first layer cal.? wizard_event = lcd_show_multiscreen_message_yes_no_and_wait_P(_i("Do you want to repeat last step to readjust distance between nozzle and heatbed?"), false);////MSG_WIZARD_REPEAT_V2_CAL c=20 r=7 if (wizard_event) { lcd_show_fullscreen_message_and_wait_P(_i("Please clean heatbed and then press the knob."));////MSG_WIZARD_CLEAN_HEATBED c=20 r=8 - state = 9; + state = S::Lay1Cal; } else { - state = 11; + state = S::Finish; } break; - case 11: //we are finished + case S::Finish: //we are finished eeprom_write_byte((uint8_t*)EEPROM_WIZARD_ACTIVE, 0); end = true; break; @@ -4488,27 +4489,27 @@ void lcd_wizard(int state) { printf_P(_N("Wizard end state: %d\n"), state); switch (state) { //final message - case 0: //user dont want to use wizard + case S::Run: //user dont want to use wizard msg = _T(MSG_WIZARD_QUIT); break; - case 1: //printer was already calibrated + case S::Restore: //printer was already calibrated msg = _T(MSG_WIZARD_DONE); break; - case 2: //selftest + case S::Selftest: //selftest msg = _T(MSG_WIZARD_CALIBRATION_FAILED); break; - case 3: //xyz cal. + case S::Xyz: //xyz cal. msg = _T(MSG_WIZARD_CALIBRATION_FAILED); break; - case 4: //z cal. + case S::Z: //z cal. msg = _T(MSG_WIZARD_CALIBRATION_FAILED); break; - case 8: + case S::IsPla: msg = _i("Please load PLA filament and then resume Wizard by rebooting the printer.");////MSG_WIZARD_INSERT_CORRECT_FILAMENT c=20 r=8 break; - case 9: break; //exit wizard for v2 calibration, which is implemted in lcd_commands (we need lcd_update running) - case 11: //we are finished + case S::Lay1Cal: break; //exit wizard for v2 calibration, which is implemted in lcd_commands (we need lcd_update running) + case S::Finish: //we are finished msg = _T(MSG_WIZARD_DONE); lcd_reset_alert_level(); @@ -4520,7 +4521,7 @@ void lcd_wizard(int state) { break; } - if (state != 9) { + if (state != S::Lay1Cal) { lcd_show_fullscreen_message_and_wait_P(msg); wizard_active = false; } diff --git a/Firmware/ultralcd.h b/Firmware/ultralcd.h index 34eded1e..a0d218cb 100644 --- a/Firmware/ultralcd.h +++ b/Firmware/ultralcd.h @@ -168,6 +168,24 @@ void lcd_set_progress(); void lcd_language(); void lcd_wizard(); -void lcd_wizard(int state); + +//! @brief Wizard state +enum class WizState : uint8_t +{ + Run, //!< run wizard? Entry point. + Restore, //!< restore calibration status + Selftest, + Xyz, //!< xyz calibration + Z, //!< z calibration + IsFil, //!< Is filament loaded? Entry point for 1st layer calibration + Preheat, //!< waiting for preheat nozzle for PLA + LoadFil, //!< Load filament + IsPla, //!< Is PLA filament? + Lay1Cal, //!< First layer calibration + RepeatLay1Cal, //!< Repeat first layer calibration? + Finish, //!< Deactivate wizard +}; + +void lcd_wizard(WizState state); #endif //ULTRALCD_H From fe30e58fb555f4b780b5e9d11bb670367db3ce65 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Fri, 14 Sep 2018 16:06:25 +0200 Subject: [PATCH 101/141] Add possibility to unload filament from wizard before first layer calibration, if it is not PLA. Known limitations: Preheat temperature other than PLA can not be selected. During filament eject, menu is shown for some moment. --- Firmware/doxyfile | 2 +- Firmware/ultralcd.cpp | 127 ++++++++++++++++++++++++++++++++++-------- Firmware/ultralcd.h | 3 + 3 files changed, 107 insertions(+), 25 deletions(-) diff --git a/Firmware/doxyfile b/Firmware/doxyfile index f3805302..9c2d550c 100644 --- a/Firmware/doxyfile +++ b/Firmware/doxyfile @@ -2421,7 +2421,7 @@ DIAFILE_DIRS = # generate a warning when it encounters a \startuml command in this case and # will not generate output for the diagram. -PLANTUML_JAR_PATH = +PLANTUML_JAR_PATH = /usr/share/plantuml/ # When using plantuml, the PLANTUML_CFG_FILE tag can be used to specify a # configuration file for plantuml. diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index e9b98ebb..d2a4ccfb 100644 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -1,3 +1,5 @@ +//! @file + #include "temperature.h" #include "ultralcd.h" #include "fsensor.h" @@ -3296,11 +3298,32 @@ void lcd_wait_for_click() } } +//! @brief Show multiple screen message with yes and no possible choices and wait with possible timeout +//! @param msg Message to show +//! @param allow_timeouting if true, allows time outing of the screen +//! @param default_yes if true, yes choice is selected by default, otherwise no choice is preselected +//! @retval 1 yes choice selected by user +//! @retval 0 no choice selected by user +//! @retval -1 screen timed out int8_t lcd_show_multiscreen_message_yes_no_and_wait_P(const char *msg, bool allow_timeouting, bool default_yes) //currently just max. n*4 + 3 lines supported (set in language header files) +{ + return lcd_show_multiscreen_message_two_choices_and_wait_P(msg, allow_timeouting, default_yes, _T(MSG_YES), _T(MSG_NO)); +} +//! @brief Show multiple screen message with two possible choices and wait with possible timeout +//! @param msg Message to show +//! @param allow_timeouting if true, allows time outing of the screen +//! @param default_first if true, fist choice is selected by default, otherwise second choice is preselected +//! @param first_choice text caption of first possible choice +//! @param second_choice text caption of second possible choice +//! @retval 1 first choice selected by user +//! @retval 0 second choice selected by user +//! @retval -1 screen timed out +int8_t lcd_show_multiscreen_message_two_choices_and_wait_P(const char *msg, bool allow_timeouting, bool default_first, + const char *first_choice, const char *second_choice) { const char *msg_next = lcd_display_message_fullscreen_P(msg); bool multi_screen = msg_next != NULL; - bool yes = default_yes ? true : false; + bool yes = default_first ? true : false; // Wait for user confirmation or a timeout. unsigned long previous_millis_cmd = millis(); @@ -3357,15 +3380,22 @@ int8_t lcd_show_multiscreen_message_yes_no_and_wait_P(const char *msg, bool allo lcd_set_cursor(0, 3); if (yes) lcd_puts_P(PSTR(">")); lcd_set_cursor(1, 3); - lcd_puts_P(_T(MSG_YES)); + lcd_puts_P(first_choice); lcd_set_cursor(7, 3); if (!yes) lcd_puts_P(PSTR(">")); lcd_set_cursor(8, 3); - lcd_puts_P(_T(MSG_NO)); + lcd_puts_P(second_choice); } } } +//! @brief Show single screen message with yes and no possible choices and wait with possible timeout +//! @param msg Message to show +//! @param allow_timeouting if true, allows time outing of the screen +//! @param default_yes if true, yes choice is selected by default, otherwise no choice is preselected +//! @retval 1 yes choice selected by user +//! @retval 0 no choice selected by user +//! @retval -1 screen timed out int8_t lcd_show_fullscreen_message_yes_no_and_wait_P(const char *msg, bool allow_timeouting, bool default_yes) { @@ -4345,6 +4375,54 @@ void lcd_language() lang_select(LANG_ID_PRI); } +static void pla_preheat() +{ + lcd_display_message_fullscreen_P(_i("Now I will preheat nozzle for PLA."));////MSG_WIZARD_WILL_PREHEAT c=20 r=4 + current_position[Z_AXIS] = 100; //move in z axis to make space for loading filament + plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], homing_feedrate[Z_AXIS] / 60, active_extruder); + delay_keep_alive(2000); + lcd_display_message_fullscreen_P(_T(MSG_WIZARD_HEATING)); + while (abs(degHotend(0) - PLA_PREHEAT_HOTEND_TEMP) > 3) { + lcd_display_message_fullscreen_P(_T(MSG_WIZARD_HEATING)); + + lcd_set_cursor(0, 4); + lcd_print(LCD_STR_THERMOMETER[0]); + lcd_print(ftostr3(degHotend(0))); + lcd_print("/"); + lcd_print(PLA_PREHEAT_HOTEND_TEMP); + lcd_print(LCD_STR_DEGREE); + lcd_set_custom_characters(); + delay_keep_alive(1000); + } +} + +//! @brief Printer first run wizard (Selftest and calibration) +//! +//! +//! First layer calibration with MMU state diagram +//! +//! @startuml +//! [*] --> IsFil +//! IsFil : Is filament 1 loaded? +//! isPLA : Is filament 1 PLA? +//! unload : Eject or Unload? +//! load : Push the button to start loading PLA Filament 1 +//! +//! IsFil --> isPLA : yes +//! IsFil --> load : no +//! isPLA --> unload : no +//! unload --> load : eject +//! unload --> load : unload +//! load --> calibration : click +//! isPLA --> calibration : yes +//! @enduml +//! +//! @param state Entry point of the wizard +//! +//! state | description +//! ---------------------- | ---------------- +//! WizState::Run | Main entry point +//! WizState::RepeatLay1Cal | Entry point after passing 1st layer calibration void lcd_wizard(WizState state) { using S = WizState; @@ -4419,26 +4497,30 @@ void lcd_wizard(WizState state) break; case S::Preheat: #ifndef SNMM - lcd_display_message_fullscreen_P(_i("Now I will preheat nozzle for PLA."));////MSG_WIZARD_WILL_PREHEAT c=20 r=4 - current_position[Z_AXIS] = 100; //move in z axis to make space for loading filament - plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], homing_feedrate[Z_AXIS] / 60, active_extruder); - delay_keep_alive(2000); - lcd_display_message_fullscreen_P(_T(MSG_WIZARD_HEATING)); - while (abs(degHotend(0) - PLA_PREHEAT_HOTEND_TEMP) > 3) { - lcd_display_message_fullscreen_P(_T(MSG_WIZARD_HEATING)); - - lcd_set_cursor(0, 4); - lcd_print(LCD_STR_THERMOMETER[0]); - lcd_print(ftostr3(degHotend(0))); - lcd_print("/"); - lcd_print(PLA_PREHEAT_HOTEND_TEMP); - lcd_print(LCD_STR_DEGREE); - lcd_set_custom_characters(); - delay_keep_alive(1000); - } + pla_preheat(); #endif //not SNMM state = S::LoadFil; break; + case S::Unload: + pla_preheat(); + if(mmu_enabled) + { + int8_t unload = lcd_show_multiscreen_message_two_choices_and_wait_P( + _i("Use unload to remove filament 1 if it protrudes outside of the rear MMU tube. Use eject if it is hidden in tube.") + ,false, true, _i("Unload"), _i("Eject")); + if (unload) + { + extr_unload_0(); + } else + { + mmu_eject_fil_0(); + } + } else + { + unload_filament(); + } + state = S::LoadFil; + break; case S::LoadFil: //load filament if (mmu_enabled) { @@ -4460,7 +4542,7 @@ void lcd_wizard(WizState state) case S::IsPla: wizard_event = lcd_show_fullscreen_message_yes_no_and_wait_P(_i("Is it PLA filament?"), false, true);////MSG_WIZARD_PLA_FILAMENT c=20 r=2 if (wizard_event) state = S::Lay1Cal; - else end = true; + else state = S::Unload; break; case S::Lay1Cal: lcd_show_fullscreen_message_and_wait_P(_i("Now I will calibrate distance between tip of the nozzle and heatbed surface."));////MSG_WIZARD_V2_CAL c=20 r=8 @@ -4505,9 +4587,6 @@ void lcd_wizard(WizState state) case S::Z: //z cal. msg = _T(MSG_WIZARD_CALIBRATION_FAILED); break; - case S::IsPla: - msg = _i("Please load PLA filament and then resume Wizard by rebooting the printer.");////MSG_WIZARD_INSERT_CORRECT_FILAMENT c=20 r=8 - break; case S::Lay1Cal: break; //exit wizard for v2 calibration, which is implemted in lcd_commands (we need lcd_update running) case S::Finish: //we are finished diff --git a/Firmware/ultralcd.h b/Firmware/ultralcd.h index a0d218cb..71bb89cf 100644 --- a/Firmware/ultralcd.h +++ b/Firmware/ultralcd.h @@ -52,6 +52,8 @@ extern void lcd_wait_for_click(); extern void lcd_show_fullscreen_message_and_wait_P(const char *msg); // 0: no, 1: yes, -1: timeouted extern int8_t lcd_show_fullscreen_message_yes_no_and_wait_P(const char *msg, bool allow_timeouting = true, bool default_yes = false); +extern int8_t lcd_show_multiscreen_message_two_choices_and_wait_P(const char *msg, bool allow_timeouting, bool default_yes, + const char *first_choice, const char *second_choice); extern int8_t lcd_show_multiscreen_message_yes_no_and_wait_P(const char *msg, bool allow_timeouting = true, bool default_yes = false); // Ask the user to move the Z axis up to the end stoppers and let // the user confirm that it has been done. @@ -179,6 +181,7 @@ enum class WizState : uint8_t Z, //!< z calibration IsFil, //!< Is filament loaded? Entry point for 1st layer calibration Preheat, //!< waiting for preheat nozzle for PLA + Unload, //!< Unload filament LoadFil, //!< Load filament IsPla, //!< Is PLA filament? Lay1Cal, //!< First layer calibration From 635a1b4cd84bf13de54a67cf3f9d8511d2ebf6a8 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Fri, 14 Sep 2018 18:29:14 +0200 Subject: [PATCH 102/141] Add possibility to to select preheat temperature when unloading filament in first layer calibration wizard. Known limitations: During filament eject, menu is shown for some moment. --- Firmware/ultralcd.cpp | 49 ++++++++++++++++++++++++++----------------- Firmware/ultralcd.h | 3 ++- 2 files changed, 32 insertions(+), 20 deletions(-) diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index d2a4ccfb..5b9bed4d 100644 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -1787,55 +1787,61 @@ void lcd_preheat_farm_nozzle() void lcd_preheat_pla() { setTargetHotend0(PLA_PREHEAT_HOTEND_TEMP); - setTargetBed(PLA_PREHEAT_HPB_TEMP); + if (!wizard_active) setTargetBed(PLA_PREHEAT_HPB_TEMP); fanSpeed = 0; lcd_return_to_status(); setWatch(); // heater sanity check timer + if (wizard_active) lcd_wizard(WizState::Unload); } void lcd_preheat_abs() { setTargetHotend0(ABS_PREHEAT_HOTEND_TEMP); - setTargetBed(ABS_PREHEAT_HPB_TEMP); + if (!wizard_active) setTargetBed(ABS_PREHEAT_HPB_TEMP); fanSpeed = 0; lcd_return_to_status(); setWatch(); // heater sanity check timer + if (wizard_active) lcd_wizard(WizState::Unload); } void lcd_preheat_pp() { setTargetHotend0(PP_PREHEAT_HOTEND_TEMP); - setTargetBed(PP_PREHEAT_HPB_TEMP); + if (!wizard_active) setTargetBed(PP_PREHEAT_HPB_TEMP); fanSpeed = 0; lcd_return_to_status(); setWatch(); // heater sanity check timer + if (wizard_active) lcd_wizard(WizState::Unload); } void lcd_preheat_pet() { setTargetHotend0(PET_PREHEAT_HOTEND_TEMP); - setTargetBed(PET_PREHEAT_HPB_TEMP); + if (!wizard_active) setTargetBed(PET_PREHEAT_HPB_TEMP); fanSpeed = 0; lcd_return_to_status(); setWatch(); // heater sanity check timer + if (wizard_active) lcd_wizard(WizState::Unload); } void lcd_preheat_hips() { setTargetHotend0(HIPS_PREHEAT_HOTEND_TEMP); - setTargetBed(HIPS_PREHEAT_HPB_TEMP); + if (!wizard_active) setTargetBed(HIPS_PREHEAT_HPB_TEMP); fanSpeed = 0; lcd_return_to_status(); setWatch(); // heater sanity check timer + if (wizard_active) lcd_wizard(WizState::Unload); } void lcd_preheat_flex() { setTargetHotend0(FLEX_PREHEAT_HOTEND_TEMP); - setTargetBed(FLEX_PREHEAT_HPB_TEMP); + if (!wizard_active) setTargetBed(FLEX_PREHEAT_HPB_TEMP); fanSpeed = 0; lcd_return_to_status(); setWatch(); // heater sanity check timer + if (wizard_active) lcd_wizard(WizState::Unload); } @@ -2061,7 +2067,7 @@ static void lcd_preheat_menu() { MENU_BEGIN(); - MENU_ITEM_BACK_P(_T(MSG_MAIN)); + if (!wizard_active) MENU_ITEM_BACK_P(_T(MSG_MAIN)); if (farm_mode) { MENU_ITEM_FUNCTION_P(PSTR("farm - " STRINGIFY(FARM_PREHEAT_HOTEND_TEMP) "/" STRINGIFY(FARM_PREHEAT_HPB_TEMP)), lcd_preheat_farm); @@ -2075,7 +2081,7 @@ static void lcd_preheat_menu() MENU_ITEM_FUNCTION_P(PSTR("HIPS - " STRINGIFY(HIPS_PREHEAT_HOTEND_TEMP) "/" STRINGIFY(HIPS_PREHEAT_HPB_TEMP)), lcd_preheat_hips); MENU_ITEM_FUNCTION_P(PSTR("PP - " STRINGIFY(PP_PREHEAT_HOTEND_TEMP) "/" STRINGIFY(PP_PREHEAT_HPB_TEMP)), lcd_preheat_pp); MENU_ITEM_FUNCTION_P(PSTR("FLEX - " STRINGIFY(FLEX_PREHEAT_HOTEND_TEMP) "/" STRINGIFY(FLEX_PREHEAT_HPB_TEMP)), lcd_preheat_flex); - MENU_ITEM_FUNCTION_P(_T(MSG_COOLDOWN), lcd_cooldown); + if (!wizard_active) MENU_ITEM_FUNCTION_P(_T(MSG_COOLDOWN), lcd_cooldown); } @@ -4375,21 +4381,20 @@ void lcd_language() lang_select(LANG_ID_PRI); } -static void pla_preheat() +static void wait_preheat() { - lcd_display_message_fullscreen_P(_i("Now I will preheat nozzle for PLA."));////MSG_WIZARD_WILL_PREHEAT c=20 r=4 current_position[Z_AXIS] = 100; //move in z axis to make space for loading filament plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], homing_feedrate[Z_AXIS] / 60, active_extruder); delay_keep_alive(2000); lcd_display_message_fullscreen_P(_T(MSG_WIZARD_HEATING)); - while (abs(degHotend(0) - PLA_PREHEAT_HOTEND_TEMP) > 3) { + while (abs(degHotend(0) - degTargetHotend(0)) > 3) { lcd_display_message_fullscreen_P(_T(MSG_WIZARD_HEATING)); lcd_set_cursor(0, 4); lcd_print(LCD_STR_THERMOMETER[0]); lcd_print(ftostr3(degHotend(0))); lcd_print("/"); - lcd_print(PLA_PREHEAT_HOTEND_TEMP); + lcd_print(degTargetHotend(0)); lcd_print(LCD_STR_DEGREE); lcd_set_custom_characters(); delay_keep_alive(1000); @@ -4492,17 +4497,23 @@ void lcd_wizard(WizState state) else { if(mmu_enabled) state = S::LoadFil; - else state = S::Preheat; + else state = S::PreheatPla; } break; - case S::Preheat: + case S::PreheatPla: #ifndef SNMM - pla_preheat(); + lcd_display_message_fullscreen_P(_i("Now I will preheat nozzle for PLA."));////MSG_WIZARD_WILL_PREHEAT c=20 r=4 + wait_preheat(); #endif //not SNMM state = S::LoadFil; break; + case S::Preheat: + menu_goto(lcd_preheat_menu,0,false,true); + lcd_show_fullscreen_message_and_wait_P(_i("Select nozzle preheat temperature which matches your material.")); + end = true; // Leave wizard temporarily for lcd_preheat_menu + break; case S::Unload: - pla_preheat(); + wait_preheat(); if(mmu_enabled) { int8_t unload = lcd_show_multiscreen_message_two_choices_and_wait_P( @@ -4542,12 +4553,13 @@ void lcd_wizard(WizState state) case S::IsPla: wizard_event = lcd_show_fullscreen_message_yes_no_and_wait_P(_i("Is it PLA filament?"), false, true);////MSG_WIZARD_PLA_FILAMENT c=20 r=2 if (wizard_event) state = S::Lay1Cal; - else state = S::Unload; + else state = S::Preheat; break; case S::Lay1Cal: lcd_show_fullscreen_message_and_wait_P(_i("Now I will calibrate distance between tip of the nozzle and heatbed surface."));////MSG_WIZARD_V2_CAL c=20 r=8 lcd_show_fullscreen_message_and_wait_P(_i("I will start to print line and you will gradually lower the nozzle by rotating the knob, until you reach optimal height. Check the pictures in our handbook in chapter Calibration."));////MSG_WIZARD_V2_CAL_2 c=20 r=12 lcd_commands_type = LCD_COMMAND_V2_CAL; + lcd_return_to_status(); end = true; break; case S::RepeatLay1Cal: //repeat first layer cal.? @@ -4600,12 +4612,11 @@ void lcd_wizard(WizState state) break; } - if (state != S::Lay1Cal) { + if (!((S::Lay1Cal == state) || (S::Preheat == state))) { lcd_show_fullscreen_message_and_wait_P(msg); wizard_active = false; } lcd_update_enable(true); - lcd_return_to_status(); lcd_update(2); } diff --git a/Firmware/ultralcd.h b/Firmware/ultralcd.h index 71bb89cf..d2d4d0a2 100644 --- a/Firmware/ultralcd.h +++ b/Firmware/ultralcd.h @@ -180,7 +180,8 @@ enum class WizState : uint8_t Xyz, //!< xyz calibration Z, //!< z calibration IsFil, //!< Is filament loaded? Entry point for 1st layer calibration - Preheat, //!< waiting for preheat nozzle for PLA + PreheatPla, //!< waiting for preheat nozzle for PLA + Preheat, //!< Preheat for any material Unload, //!< Unload filament LoadFil, //!< Load filament IsPla, //!< Is PLA filament? From f4960765083014016f9222d2b53802dfb82e9968 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Fri, 14 Sep 2018 18:33:03 +0200 Subject: [PATCH 103/141] Remove redundant code. No change in functionality. --- Firmware/ultralcd.cpp | 9 --------- 1 file changed, 9 deletions(-) diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index 5b9bed4d..21487b0b 100644 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -4583,23 +4583,14 @@ void lcd_wizard(WizState state) printf_P(_N("Wizard end state: %d\n"), state); switch (state) { //final message - case S::Run: //user dont want to use wizard - msg = _T(MSG_WIZARD_QUIT); - break; - case S::Restore: //printer was already calibrated msg = _T(MSG_WIZARD_DONE); break; case S::Selftest: //selftest - msg = _T(MSG_WIZARD_CALIBRATION_FAILED); - break; case S::Xyz: //xyz cal. - msg = _T(MSG_WIZARD_CALIBRATION_FAILED); - break; case S::Z: //z cal. msg = _T(MSG_WIZARD_CALIBRATION_FAILED); break; - case S::Lay1Cal: break; //exit wizard for v2 calibration, which is implemted in lcd_commands (we need lcd_update running) case S::Finish: //we are finished msg = _T(MSG_WIZARD_DONE); From a687b8e64ae3245d0df99893e38720797c786db4 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Mon, 17 Sep 2018 17:05:11 +0200 Subject: [PATCH 104/141] Don't enable lcd update inside mmu_eject_filament(). --- Firmware/lcd.h | 23 +++++++++++++++++++++++ Firmware/mmu.cpp | 15 ++++++++------- 2 files changed, 31 insertions(+), 7 deletions(-) diff --git a/Firmware/lcd.h b/Firmware/lcd.h index 251344de..1a7a8193 100644 --- a/Firmware/lcd.h +++ b/Firmware/lcd.h @@ -150,6 +150,29 @@ extern void lcd_update_enable(uint8_t enabled); extern void lcd_buttons_update(void); +//! @brief Helper class to temporarily disable LCD updates +//! +//! When constructed (on stack), original state state of lcd_update_enabled is stored +//! and LCD updates are disabled. +//! When destroyed (gone out of scope), original state of LCD update is restored. +//! It has zero overhead compared to storing bool saved = lcd_update_enabled +//! and calling lcd_update_enable(false) and lcd_update_enable(saved). +class LcdUpdateDisabler +{ +public: + LcdUpdateDisabler(): m_updateEnabled(lcd_update_enabled) + { + lcd_update_enable(false); + } + ~LcdUpdateDisabler() + { + lcd_update_enable(m_updateEnabled); + } + +private: + bool m_updateEnabled; +}; + diff --git a/Firmware/mmu.cpp b/Firmware/mmu.cpp index a8502e04..cb59b7e9 100644 --- a/Firmware/mmu.cpp +++ b/Firmware/mmu.cpp @@ -1012,14 +1012,15 @@ void mmu_eject_filament(uint8_t filament, bool recover) if (degHotend0() > EXTRUDE_MINTEMP) { st_synchronize(); - lcd_update_enable(false); - lcd_clear(); - lcd_set_cursor(0, 1); lcd_puts_P(_i("Ejecting filament")); - current_position[E_AXIS] -= 80; - plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 2500 / 60, active_extruder); - st_synchronize(); - lcd_update_enable(true); + { + LcdUpdateDisabler disableLcdUpdate; + lcd_clear(); + lcd_set_cursor(0, 1); lcd_puts_P(_i("Ejecting filament")); + current_position[E_AXIS] -= 80; + plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 2500 / 60, active_extruder); + st_synchronize(); + } mmu_command(MMU_CMD_E0 + filament); manage_response(false, false); From ab2d350ed193eb0e51d111183d933633bd0cc059 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Mon, 17 Sep 2018 21:23:13 +0200 Subject: [PATCH 105/141] Don't enable lcd update in lcd_show_fullscreen_message_and_wait_P(). Don't show menu in wizard when ejecting filament. --- Firmware/mmu.cpp | 18 +++++++++--------- Firmware/ultralcd.cpp | 1 + 2 files changed, 10 insertions(+), 9 deletions(-) diff --git a/Firmware/mmu.cpp b/Firmware/mmu.cpp index cb59b7e9..7a63bf8c 100644 --- a/Firmware/mmu.cpp +++ b/Firmware/mmu.cpp @@ -1020,16 +1020,16 @@ void mmu_eject_filament(uint8_t filament, bool recover) current_position[E_AXIS] -= 80; plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 2500 / 60, active_extruder); st_synchronize(); - } + mmu_command(MMU_CMD_E0 + filament); + manage_response(false, false); + if (recover) + { + lcd_show_fullscreen_message_and_wait_P(_i("Please remove filament and then press the knob.")); + mmu_command(MMU_CMD_R0); + manage_response(false, false); + } - mmu_command(MMU_CMD_E0 + filament); - manage_response(false, false); - if (recover) - { - lcd_show_fullscreen_message_and_wait_P(_i("Please remove filament and then press the knob.")); - mmu_command(MMU_CMD_R0); - manage_response(false, false); - } + } } else { diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index 21487b0b..9ef68343 100644 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -3244,6 +3244,7 @@ const char* lcd_display_message_fullscreen_P(const char *msg) */ void lcd_show_fullscreen_message_and_wait_P(const char *msg) { + LcdUpdateDisabler lcdUpdateDisabler; const char *msg_next = lcd_display_message_fullscreen_P(msg); bool multi_screen = msg_next != NULL; lcd_set_custom_characters_nextpage(); From 90a10a692a7715e3ccc99a9cb027ce7532fd8738 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Tue, 18 Sep 2018 14:00:57 +0200 Subject: [PATCH 106/141] Enable button debouncing also in modal mode (!lcd_update_enabled). In lcd_clicked() consume click event immediately. --- Firmware/lcd.cpp | 89 ++++++++++++++++++++----------------------- Firmware/menu.cpp | 2 + Firmware/ultralcd.cpp | 2 + 3 files changed, 46 insertions(+), 47 deletions(-) diff --git a/Firmware/lcd.cpp b/Firmware/lcd.cpp index 5ac6c317..7cd67fe3 100644 --- a/Firmware/lcd.cpp +++ b/Firmware/lcd.cpp @@ -686,7 +686,11 @@ LongTimer lcd_timeoutToStatus; uint8_t lcd_clicked(void) { bool clicked = LCD_CLICKED; - if(clicked) lcd_button_pressed = 0; + if(clicked) + { + lcd_button_pressed = 0; + lcd_buttons &= 0xff^EN_C; + } return clicked; } @@ -709,7 +713,7 @@ Sound_MakeSound(e_SOUND_TYPE_ButtonEcho); void lcd_quick_feedback(void) { lcd_draw_update = 2; - lcd_button_pressed = false; + lcd_button_pressed = false; lcd_beeper_quick_feedback(); } @@ -766,51 +770,42 @@ void lcd_buttons_update(void) uint8_t newbutton = 0; if (READ(BTN_EN1) == 0) newbutton |= EN_A; if (READ(BTN_EN2) == 0) newbutton |= EN_B; - if (lcd_update_enabled) - { //if we are in non-modal mode, long press can be used and short press triggers with button release - if (READ(BTN_ENC) == 0) - { //button is pressed - lcd_timeoutToStatus.start(); - if (!buttonBlanking.running() || buttonBlanking.expired(BUTTON_BLANKING_TIME)) { - buttonBlanking.start(); - safetyTimer.start(); - if ((lcd_button_pressed == 0) && (lcd_long_press_active == 0)) - { - longPressTimer.start(); - lcd_button_pressed = 1; - } - else - { - if (longPressTimer.expired(LONG_PRESS_TIME)) - { - lcd_long_press_active = 1; - if (lcd_longpress_func) - lcd_longpress_func(); - } - } - } - } - else - { //button not pressed - if (lcd_button_pressed) - { //button was released - buttonBlanking.start(); - if (lcd_long_press_active == 0) - { //button released before long press gets activated - newbutton |= EN_C; - } - //else if (menu_menu == lcd_move_z) lcd_quick_feedback(); - //lcd_button_pressed is set back to false via lcd_quick_feedback function - } - else - lcd_long_press_active = 0; - } - } - else - { //we are in modal mode - if (READ(BTN_ENC) == 0) - newbutton |= EN_C; - } + + if (READ(BTN_ENC) == 0) + { //button is pressed + lcd_timeoutToStatus.start(); + if (!buttonBlanking.running() || buttonBlanking.expired(BUTTON_BLANKING_TIME)) { + buttonBlanking.start(); + safetyTimer.start(); + if ((lcd_button_pressed == 0) && (lcd_long_press_active == 0)) + { + //long press is not possible in modal mode + if (lcd_update_enabled) longPressTimer.start(); + lcd_button_pressed = 1; + } + else if (longPressTimer.expired(LONG_PRESS_TIME)) + { + lcd_long_press_active = 1; + if (lcd_longpress_func) + lcd_longpress_func(); + } + } + } + else + { //button not pressed + if (lcd_button_pressed) + { //button was released + buttonBlanking.start(); + if (lcd_long_press_active == 0) + { //button released before long press gets activated + newbutton |= EN_C; + } + //else if (menu_menu == lcd_move_z) lcd_quick_feedback(); + //lcd_button_pressed is set back to false via lcd_quick_feedback function + } + else + lcd_long_press_active = 0; + } lcd_buttons = newbutton; //manage encoder rotation diff --git a/Firmware/menu.cpp b/Firmware/menu.cpp index bd523826..a92fc857 100644 --- a/Firmware/menu.cpp +++ b/Firmware/menu.cpp @@ -236,6 +236,8 @@ uint8_t menu_item_function_P(const char* str, menu_func_t func) if (menu_clicked && (lcd_encoder == menu_item)) { menu_clicked = false; + lcd_button_pressed = 0; + lcd_buttons &= 0xff^EN_C; lcd_update_enabled = 0; if (func) func(); lcd_update_enabled = 1; diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index cd73912e..89e6c6c2 100644 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -463,6 +463,8 @@ static uint8_t menu_item_sdfile(const char* } if (menu_clicked && (lcd_encoder == menu_item)) { + lcd_button_pressed = 0; + lcd_buttons &= 0xff^EN_C; menu_action_sdfile(str_fn); return menu_item_ret(); } From f532da4b17654c1563f9d03377158724bcc2f5be Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Mon, 17 Sep 2018 21:36:04 +0200 Subject: [PATCH 107/141] Remove duplicate button debouncing code. Save 254B flash. --- Firmware/ultralcd.cpp | 33 --------------------------------- 1 file changed, 33 deletions(-) diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index 89e6c6c2..edadda67 100644 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -3253,9 +3253,6 @@ void lcd_show_fullscreen_message_and_wait_P(const char *msg) for (uint8_t i = 0; i < 100; ++ i) { delay_keep_alive(50); if (lcd_clicked()) { - while (lcd_clicked()) ; - delay(10); - while (lcd_clicked()) ; if (msg_next == NULL) { KEEPALIVE_STATE(IN_HANDLER); lcd_set_custom_characters(); @@ -3289,9 +3286,6 @@ void lcd_wait_for_click() manage_heater(); manage_inactivity(true); if (lcd_clicked()) { - while (lcd_clicked()) ; - delay(10); - while (lcd_clicked()) ; KEEPALIVE_STATE(IN_HANDLER); return; } @@ -3338,9 +3332,6 @@ int8_t lcd_show_multiscreen_message_yes_no_and_wait_P(const char *msg, bool allo } } if (lcd_clicked()) { - while (lcd_clicked()); - delay(10); - while (lcd_clicked()); if (msg_next == NULL) { //KEEPALIVE_STATE(IN_HANDLER); lcd_set_custom_characters(); @@ -3415,9 +3406,6 @@ int8_t lcd_show_fullscreen_message_yes_no_and_wait_P(const char *msg, bool allow enc_dif = lcd_encoder_diff; } if (lcd_clicked()) { - while (lcd_clicked()); - delay(10); - while (lcd_clicked()); KEEPALIVE_STATE(IN_HANDLER); return yes; } @@ -3534,9 +3522,6 @@ void lcd_diag_show_end_stops() manage_inactivity(true); lcd_show_end_stops(); if (lcd_clicked()) { - while (lcd_clicked()) ; - delay(10); - while (lcd_clicked()) ; break; } } @@ -4299,9 +4284,6 @@ void lcd_v2_calibration() for (int i = 0; i < 20; i++) { //wait max. 2s delay_keep_alive(100); if (lcd_clicked()) { - while (lcd_clicked()); - delay(10); - while (lcd_clicked()); break; } } @@ -4901,9 +4883,6 @@ void bowden_menu() { } if (lcd_clicked()) { - while (lcd_clicked()); - delay(10); - while (lcd_clicked()); lcd_clear(); while (1) { @@ -4935,9 +4914,6 @@ void bowden_menu() { } delay(100); if (lcd_clicked()) { - while (lcd_clicked()); - delay(10); - while (lcd_clicked()); EEPROM_save_B(EEPROM_BOWDEN_LENGTH + cursor_pos * 2, &bowden_length[cursor_pos]); if (lcd_show_fullscreen_message_yes_no_and_wait_P(PSTR("Continue with another bowden?"))) { lcd_update_enable(true); @@ -4998,9 +4974,6 @@ static char snmm_stop_print_menu() { //menu for choosing which filaments will be } } if (lcd_clicked()) { - while (lcd_clicked()); - delay(10); - while (lcd_clicked()); KEEPALIVE_STATE(IN_HANDLER); return(cursor_pos - 1); } @@ -5187,9 +5160,6 @@ char reset_menu() { } if (lcd_clicked()) { - while (lcd_clicked()); - delay(10); - while (lcd_clicked()); return(cursor_pos + first); } @@ -5446,9 +5416,6 @@ unsigned char lcd_choose_color() { } if (lcd_clicked()) { - while (lcd_clicked()); - delay(10); - while (lcd_clicked()); switch(cursor_pos + first - 1) { case 0: return 1; break; case 1: return 0; break; From 6ee97468ee461046dd13090c27fb23077365fcaf Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Tue, 18 Sep 2018 10:17:09 +0200 Subject: [PATCH 108/141] Remove lcd_buttons_update() call from all other places than interrupt. There is no known reason, why lcd_buttons_update() should be called from multiple places and multiple contexts. Remove mutex, which is not needed anymore, and wasn't implemented properly anyway (Operation was not atomic.). --- Firmware/lcd.cpp | 5 ----- Firmware/ultralcd.cpp | 1 - 2 files changed, 6 deletions(-) diff --git a/Firmware/lcd.cpp b/Firmware/lcd.cpp index 7cd67fe3..31c7183e 100644 --- a/Firmware/lcd.cpp +++ b/Firmware/lcd.cpp @@ -730,7 +730,6 @@ void lcd_update(uint8_t lcdDrawUpdateOverride) lcd_draw_update = lcdDrawUpdateOverride; if (!lcd_update_enabled) return; - lcd_buttons_update(); if (lcd_lcdupdate_func) lcd_lcdupdate_func(); } @@ -764,9 +763,6 @@ void lcd_update_enable(uint8_t enabled) extern LongTimer safetyTimer; void lcd_buttons_update(void) { - static bool _lock = false; - if (_lock) return; - _lock = true; uint8_t newbutton = 0; if (READ(BTN_EN1) == 0) newbutton |= EN_A; if (READ(BTN_EN2) == 0) newbutton |= EN_B; @@ -843,7 +839,6 @@ void lcd_buttons_update(void) } } lcd_encoder_bits = enc; - _lock = false; } diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index edadda67..35426147 100644 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -7106,7 +7106,6 @@ void ultralcd_init() WRITE(SDCARDDETECT, HIGH); lcd_oldcardstatus = IS_SD_INSERTED; #endif//(SDCARDDETECT > 0) - lcd_buttons_update(); lcd_encoder_diff = 0; } From a7fdfdd2580b8f2efe113a3337513138ae2ad2cd Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Tue, 18 Sep 2018 17:15:13 +0200 Subject: [PATCH 109/141] Put repetitive code into separate function. No change in functionality. --- Firmware/lcd.cpp | 9 +++++++-- Firmware/lcd.h | 7 ++++++- Firmware/menu.cpp | 3 +-- Firmware/ultralcd.cpp | 3 +-- 4 files changed, 15 insertions(+), 7 deletions(-) diff --git a/Firmware/lcd.cpp b/Firmware/lcd.cpp index 31c7183e..c434aa08 100644 --- a/Firmware/lcd.cpp +++ b/Firmware/lcd.cpp @@ -683,13 +683,18 @@ ShortTimer longPressTimer; LongTimer lcd_timeoutToStatus; +//! @brief Was button clicked? +//! +//! Consume click event, following call would return 0. +//! +//! @retval 0 not clicked +//! @retval nonzero clicked uint8_t lcd_clicked(void) { bool clicked = LCD_CLICKED; if(clicked) { - lcd_button_pressed = 0; - lcd_buttons &= 0xff^EN_C; + lcd_consume_click(); } return clicked; } diff --git a/Firmware/lcd.h b/Firmware/lcd.h index 251344de..8d774b30 100644 --- a/Firmware/lcd.h +++ b/Firmware/lcd.h @@ -131,7 +131,6 @@ extern lcd_lcdupdate_func_t lcd_lcdupdate_func; extern uint8_t lcd_clicked(void); - extern void lcd_beeper_quick_feedback(void); //Cause an LCD refresh, and give the user visual or audible feedback that something has happened @@ -221,6 +220,12 @@ extern void lcd_set_custom_characters_progress(void); extern void lcd_set_custom_characters_nextpage(void); extern void lcd_set_custom_characters_degree(void); +//! @brief Consume click event +inline void lcd_consume_click() +{ + lcd_button_pressed = 0; + lcd_buttons &= 0xff^EN_C; +} #endif //_LCD_H diff --git a/Firmware/menu.cpp b/Firmware/menu.cpp index a92fc857..b002ca0e 100644 --- a/Firmware/menu.cpp +++ b/Firmware/menu.cpp @@ -236,8 +236,7 @@ uint8_t menu_item_function_P(const char* str, menu_func_t func) if (menu_clicked && (lcd_encoder == menu_item)) { menu_clicked = false; - lcd_button_pressed = 0; - lcd_buttons &= 0xff^EN_C; + lcd_consume_click(); lcd_update_enabled = 0; if (func) func(); lcd_update_enabled = 1; diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index 35426147..7b201f2a 100644 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -463,8 +463,7 @@ static uint8_t menu_item_sdfile(const char* } if (menu_clicked && (lcd_encoder == menu_item)) { - lcd_button_pressed = 0; - lcd_buttons &= 0xff^EN_C; + lcd_consume_click(); menu_action_sdfile(str_fn); return menu_item_ret(); } From 05d3b7032ddf156a8bda0d7de9e063314f1adce3 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Tue, 18 Sep 2018 17:48:11 +0200 Subject: [PATCH 110/141] Update documentation. --- Firmware/lcd.cpp | 3 +++ Firmware/lcd.h | 13 +++++++++++-- 2 files changed, 14 insertions(+), 2 deletions(-) diff --git a/Firmware/lcd.cpp b/Firmware/lcd.cpp index c434aa08..7e8b3ed4 100644 --- a/Firmware/lcd.cpp +++ b/Firmware/lcd.cpp @@ -686,6 +686,9 @@ LongTimer lcd_timeoutToStatus; //! @brief Was button clicked? //! //! Consume click event, following call would return 0. +//! See #LCD_CLICKED macro for version not consuming the event. +//! +//! Generally is used in modal dialogs. //! //! @retval 0 not clicked //! @retval nonzero clicked diff --git a/Firmware/lcd.h b/Firmware/lcd.h index 8d774b30..fe48b339 100644 --- a/Firmware/lcd.h +++ b/Firmware/lcd.h @@ -1,4 +1,4 @@ -//lcd.h +//! @file #ifndef _LCD_H #define _LCD_H @@ -186,7 +186,16 @@ extern void lcd_buttons_update(void); #define EN_A (1< Date: Fri, 21 Sep 2018 20:52:44 +0200 Subject: [PATCH 111/141] Add configuration store struct. --- Firmware/ConfigurationStore.cpp | 35 +++++++++++++++++++++++++++++++++ 1 file changed, 35 insertions(+) diff --git a/Firmware/ConfigurationStore.cpp b/Firmware/ConfigurationStore.cpp index 264486b7..25ac5951 100644 --- a/Firmware/ConfigurationStore.cpp +++ b/Firmware/ConfigurationStore.cpp @@ -239,6 +239,41 @@ void Config_PrintSettings(uint8_t level) #ifdef EEPROM_SETTINGS + +static_assert (EXTRUDERS == 1, "ConfigurationStore M500_conf not implemented for more extruders."); +static_assert (NUM_AXIS == 4, "ConfigurationStore M500_conf not implemented for more axis."); +typedef struct +{ + char version[4]; + float axis_steps_per_unit[4]; + float max_feedrate_normal[4]; + unsigned long max_acceleration_units_per_sq_second_normal[4]; + float acceleration; + float retract_acceleration; + float minimumfeedrate; + float mintravelfeedrate; + unsigned long minsegmenttime; + float max_jerk[4]; + float add_homing[3]; + float zprobe_zoffset; + float Kp; + float Ki; + float Kd; + float bedKp; + float bedKi; + float bedKd; + int lcd_contrast; + bool autoretract_enabled; + float retract_length; + float retract_feedrate; + float retract_zlift; + float retract_recover_length; + float retract_recover_feedrate; + bool volumetric_enabled; + float filament_size; + float max_feedrate_silent[4]; + unsigned long max_acceleration_units_per_sq_second_silent[4]; +} __attribute__ ((packed)) M500_conf; bool Config_RetrieveSettings(uint16_t offset) { int i=offset; From d9e2dcc7368ae21a20f842c0500e6c24866a840d Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Sun, 23 Sep 2018 22:21:28 +0200 Subject: [PATCH 112/141] Incomplete. --- Firmware/ConfigurationStore.cpp | 40 +++++++++++++++++++++++++++++++-- 1 file changed, 38 insertions(+), 2 deletions(-) diff --git a/Firmware/ConfigurationStore.cpp b/Firmware/ConfigurationStore.cpp index 25ac5951..58f12e0d 100644 --- a/Firmware/ConfigurationStore.cpp +++ b/Firmware/ConfigurationStore.cpp @@ -242,6 +242,10 @@ void Config_PrintSettings(uint8_t level) static_assert (EXTRUDERS == 1, "ConfigurationStore M500_conf not implemented for more extruders."); static_assert (NUM_AXIS == 4, "ConfigurationStore M500_conf not implemented for more axis."); +#ifdef ENABLE_AUTO_BED_LEVELING +static_assert (false, "zprobe_zoffset was not initialized in printers in field to -(Z_PROBE_OFFSET_FROM_EXTRUDER), so it contains" + "0.0, if this is not acceptable, increment EEPROM_VERSION to force use default_conf"); +#endif typedef struct { char version[4]; @@ -262,7 +266,7 @@ typedef struct float bedKp; float bedKi; float bedKd; - int lcd_contrast; + int lcd_contrast; //!< unused bool autoretract_enabled; float retract_length; float retract_feedrate; @@ -274,6 +278,38 @@ typedef struct float max_feedrate_silent[4]; unsigned long max_acceleration_units_per_sq_second_silent[4]; } __attribute__ ((packed)) M500_conf; + +static const M500_conf default_conf PROGMEM = +{ + EEPROM_VERSION, + DEFAULT_AXIS_STEPS_PER_UNIT, + DEFAULT_MAX_FEEDRATE, + DEFAULT_MAX_ACCELERATION, + DEFAULT_ACCELERATION, + DEFAULT_RETRACT_ACCELERATION, + DEFAULT_MINIMUMFEEDRATE, + DEFAULT_MINSEGMENTTIME, + DEFAULT_MINTRAVELFEEDRATE, + {DEFAULT_XJERK, DEFAULT_YJERK, DEFAULT_ZJERK, DEFAULT_EJERK}, + {0,0,0}, + -(Z_PROBE_OFFSET_FROM_EXTRUDER), + DEFAULT_Kp, + DEFAULT_Ki*PID_dT, + DEFAULT_Kd/PID_dT, + DEFAULT_bedKp, + DEFAULT_bedKi*PID_dT, + DEFAULT_bedKd/PID_dT, + 0, + false, + RETRACT_LENGTH, + RETRACT_FEEDRATE, + + +}; + +static_assert (sizeof(M500_conf) == 188, "sizeof(M500_conf) has changed, ensure that version has been incremented, " + "or if you added members in the end of struct, ensure that historically uninitialized values will be initialized"); + bool Config_RetrieveSettings(uint16_t offset) { int i=offset; @@ -440,7 +476,7 @@ void Config_ResetDefault() updatePID(); #ifdef PID_ADD_EXTRUSION_RATE - Kc = DEFAULT_Kc; + Kc = DEFAULT_Kc; //this is not stored by Config_StoreSettings #endif//PID_ADD_EXTRUSION_RATE #endif//PIDTEMP From 991db0e71d1266219f6ed9b41e239b84bc4d7a90 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Sun, 23 Sep 2018 23:36:01 +0200 Subject: [PATCH 113/141] Finish default_conf. --- Firmware/ConfigurationStore.cpp | 13 +++++++++---- 1 file changed, 9 insertions(+), 4 deletions(-) diff --git a/Firmware/ConfigurationStore.cpp b/Firmware/ConfigurationStore.cpp index 58f12e0d..76ce14b8 100644 --- a/Firmware/ConfigurationStore.cpp +++ b/Firmware/ConfigurationStore.cpp @@ -274,7 +274,7 @@ typedef struct float retract_recover_length; float retract_recover_feedrate; bool volumetric_enabled; - float filament_size; + float filament_size[1]; float max_feedrate_silent[4]; unsigned long max_acceleration_units_per_sq_second_silent[4]; } __attribute__ ((packed)) M500_conf; @@ -288,8 +288,8 @@ static const M500_conf default_conf PROGMEM = DEFAULT_ACCELERATION, DEFAULT_RETRACT_ACCELERATION, DEFAULT_MINIMUMFEEDRATE, - DEFAULT_MINSEGMENTTIME, DEFAULT_MINTRAVELFEEDRATE, + DEFAULT_MINSEGMENTTIME, {DEFAULT_XJERK, DEFAULT_YJERK, DEFAULT_ZJERK, DEFAULT_EJERK}, {0,0,0}, -(Z_PROBE_OFFSET_FROM_EXTRUDER), @@ -303,8 +303,13 @@ static const M500_conf default_conf PROGMEM = false, RETRACT_LENGTH, RETRACT_FEEDRATE, - - + RETRACT_ZLIFT, + RETRACT_RECOVER_LENGTH, + RETRACT_RECOVER_FEEDRATE, + false, + {DEFAULT_NOMINAL_FILAMENT_DIA}, + DEFAULT_MAX_FEEDRATE_SILENT, + DEFAULT_MAX_ACCELERATION_SILENT, }; static_assert (sizeof(M500_conf) == 188, "sizeof(M500_conf) has changed, ensure that version has been incremented, " From e94dc1341a0274081f856d7ba76d2fbe176e4bd1 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Mon, 24 Sep 2018 14:34:43 +0200 Subject: [PATCH 114/141] Use M500_conf cs in Config_ StoreSettings, RetrieveSettings and ResetDefault. --- Firmware/ConfigurationStore.cpp | 258 +++----------------------------- Firmware/ConfigurationStore.h | 35 +++++ 2 files changed, 55 insertions(+), 238 deletions(-) diff --git a/Firmware/ConfigurationStore.cpp b/Firmware/ConfigurationStore.cpp index 76ce14b8..aa54ebbe 100644 --- a/Firmware/ConfigurationStore.cpp +++ b/Firmware/ConfigurationStore.cpp @@ -9,6 +9,8 @@ #include "mesh_bed_leveling.h" #endif +M500_conf cs; + #ifdef DEBUG_EEPROM_WRITE #define EEPROM_WRITE_VAR(pos, value) _EEPROM_writeData(pos, (uint8_t*)&value, sizeof(value), #value) #else //DEBUG_EEPROM_WRITE @@ -68,84 +70,13 @@ void _EEPROM_readData(int &pos, uint8_t* value, uint8_t size, char* name) #ifdef EEPROM_SETTINGS void Config_StoreSettings(uint16_t offset) { - char ver[4]= "000"; int i = offset; - EEPROM_WRITE_VAR(i,ver); // invalidate data first - EEPROM_WRITE_VAR(i,axis_steps_per_unit); - EEPROM_WRITE_VAR(i,max_feedrate_normal); - EEPROM_WRITE_VAR(i,max_acceleration_units_per_sq_second_normal); - EEPROM_WRITE_VAR(i,acceleration); - EEPROM_WRITE_VAR(i,retract_acceleration); - EEPROM_WRITE_VAR(i,minimumfeedrate); - EEPROM_WRITE_VAR(i,mintravelfeedrate); - EEPROM_WRITE_VAR(i,minsegmenttime); - EEPROM_WRITE_VAR(i,max_jerk[X_AXIS]); - EEPROM_WRITE_VAR(i,max_jerk[Y_AXIS]); - EEPROM_WRITE_VAR(i,max_jerk[Z_AXIS]); - EEPROM_WRITE_VAR(i,max_jerk[E_AXIS]); - EEPROM_WRITE_VAR(i,add_homing); -/* EEPROM_WRITE_VAR(i,plaPreheatHotendTemp); - EEPROM_WRITE_VAR(i,plaPreheatHPBTemp); - EEPROM_WRITE_VAR(i,plaPreheatFanSpeed); - EEPROM_WRITE_VAR(i,absPreheatHotendTemp); - EEPROM_WRITE_VAR(i,absPreheatHPBTemp); - EEPROM_WRITE_VAR(i,absPreheatFanSpeed); -*/ + strcpy(cs.version,"000"); //!< invalidate data first @TODO use erase to save one erase cycle - EEPROM_WRITE_VAR(i,zprobe_zoffset); - #ifdef PIDTEMP - EEPROM_WRITE_VAR(i,Kp); - EEPROM_WRITE_VAR(i,Ki); - EEPROM_WRITE_VAR(i,Kd); - #else - float dummy = 3000.0f; - EEPROM_WRITE_VAR(i,dummy); - dummy = 0.0f; - EEPROM_WRITE_VAR(i,dummy); - EEPROM_WRITE_VAR(i,dummy); - #endif - #ifdef PIDTEMPBED - EEPROM_WRITE_VAR(i, bedKp); - EEPROM_WRITE_VAR(i, bedKi); - EEPROM_WRITE_VAR(i, bedKd); - #endif - - int lcd_contrast = 0; - EEPROM_WRITE_VAR(i,lcd_contrast); - - #ifdef FWRETRACT - EEPROM_WRITE_VAR(i,autoretract_enabled); - EEPROM_WRITE_VAR(i,retract_length); - #if EXTRUDERS > 1 - EEPROM_WRITE_VAR(i,retract_length_swap); - #endif - EEPROM_WRITE_VAR(i,retract_feedrate); - EEPROM_WRITE_VAR(i,retract_zlift); - EEPROM_WRITE_VAR(i,retract_recover_length); - #if EXTRUDERS > 1 - EEPROM_WRITE_VAR(i,retract_recover_length_swap); - #endif - EEPROM_WRITE_VAR(i,retract_recover_feedrate); - #endif - - // Save filament sizes - EEPROM_WRITE_VAR(i, volumetric_enabled); - EEPROM_WRITE_VAR(i, filament_size[0]); - #if EXTRUDERS > 1 - EEPROM_WRITE_VAR(i, filament_size[1]); - #if EXTRUDERS > 2 - EEPROM_WRITE_VAR(i, filament_size[2]); - #endif - #endif - - - - EEPROM_WRITE_VAR(i,max_feedrate_silent); - EEPROM_WRITE_VAR(i,max_acceleration_units_per_sq_second_silent); - - char ver2[4]=EEPROM_VERSION; - i=offset; - EEPROM_WRITE_VAR(i,ver2); // validate data + _EEPROM_writeData(i,reinterpret_cast(&cs),sizeof(cs),0); + strcpy(cs.version,EEPROM_VERSION); // // validate data + i = offset; + EEPROM_WRITE_VAR(i,cs.version); // validate data SERIAL_ECHO_START; SERIAL_ECHOLNPGM("Settings Stored"); } @@ -246,38 +177,7 @@ static_assert (NUM_AXIS == 4, "ConfigurationStore M500_conf not implemented for static_assert (false, "zprobe_zoffset was not initialized in printers in field to -(Z_PROBE_OFFSET_FROM_EXTRUDER), so it contains" "0.0, if this is not acceptable, increment EEPROM_VERSION to force use default_conf"); #endif -typedef struct -{ - char version[4]; - float axis_steps_per_unit[4]; - float max_feedrate_normal[4]; - unsigned long max_acceleration_units_per_sq_second_normal[4]; - float acceleration; - float retract_acceleration; - float minimumfeedrate; - float mintravelfeedrate; - unsigned long minsegmenttime; - float max_jerk[4]; - float add_homing[3]; - float zprobe_zoffset; - float Kp; - float Ki; - float Kd; - float bedKp; - float bedKi; - float bedKd; - int lcd_contrast; //!< unused - bool autoretract_enabled; - float retract_length; - float retract_feedrate; - float retract_zlift; - float retract_recover_length; - float retract_recover_feedrate; - bool volumetric_enabled; - float filament_size[1]; - float max_feedrate_silent[4]; - unsigned long max_acceleration_units_per_sq_second_silent[4]; -} __attribute__ ((packed)) M500_conf; + static const M500_conf default_conf PROGMEM = { @@ -315,90 +215,27 @@ static const M500_conf default_conf PROGMEM = static_assert (sizeof(M500_conf) == 188, "sizeof(M500_conf) has changed, ensure that version has been incremented, " "or if you added members in the end of struct, ensure that historically uninitialized values will be initialized"); +//! +//! @retval true Stored or default settings retrieved +//! @retval false default settings retrieved, eeprom was erased. bool Config_RetrieveSettings(uint16_t offset) { int i=offset; bool previous_settings_retrieved = true; - char stored_ver[4]; char ver[4]=EEPROM_VERSION; - EEPROM_READ_VAR(i,stored_ver); //read stored version - // SERIAL_ECHOLN("Version: [" << ver << "] Stored version: [" << stored_ver << "]"); - if (strncmp(ver,stored_ver,3) == 0) + EEPROM_READ_VAR(i,cs.version); //read stored version + // SERIAL_ECHOLN("Version: [" << ver << "] Stored version: [" << cs.version << "]"); + if (strncmp(ver,cs.version,3) == 0) // version number match { - // version number match - EEPROM_READ_VAR(i,axis_steps_per_unit); - EEPROM_READ_VAR(i,max_feedrate_normal); - EEPROM_READ_VAR(i,max_acceleration_units_per_sq_second_normal); + i=offset; + + EEPROM_READ_VAR(i,cs); + - // steps per sq second need to be updated to agree with the units per sq second (as they are what is used in the planner) - - EEPROM_READ_VAR(i,acceleration); - EEPROM_READ_VAR(i,retract_acceleration); - EEPROM_READ_VAR(i,minimumfeedrate); - EEPROM_READ_VAR(i,mintravelfeedrate); - EEPROM_READ_VAR(i,minsegmenttime); - EEPROM_READ_VAR(i,max_jerk[X_AXIS]); - EEPROM_READ_VAR(i,max_jerk[Y_AXIS]); - EEPROM_READ_VAR(i,max_jerk[Z_AXIS]); - EEPROM_READ_VAR(i,max_jerk[E_AXIS]); if (max_jerk[X_AXIS] > DEFAULT_XJERK) max_jerk[X_AXIS] = DEFAULT_XJERK; if (max_jerk[Y_AXIS] > DEFAULT_YJERK) max_jerk[Y_AXIS] = DEFAULT_YJERK; - EEPROM_READ_VAR(i,add_homing); - /* - EEPROM_READ_VAR(i,plaPreheatHotendTemp); - EEPROM_READ_VAR(i,plaPreheatHPBTemp); - EEPROM_READ_VAR(i,plaPreheatFanSpeed); - EEPROM_READ_VAR(i,absPreheatHotendTemp); - EEPROM_READ_VAR(i,absPreheatHPBTemp); - EEPROM_READ_VAR(i,absPreheatFanSpeed); - */ + calculate_extruder_multipliers(); - - EEPROM_READ_VAR(i,zprobe_zoffset); - #ifndef PIDTEMP - float Kp,Ki,Kd; - #endif - // do not need to scale PID values as the values in EEPROM are already scaled - EEPROM_READ_VAR(i,Kp); - EEPROM_READ_VAR(i,Ki); - EEPROM_READ_VAR(i,Kd); - #ifdef PIDTEMPBED - EEPROM_READ_VAR(i, bedKp); - EEPROM_READ_VAR(i, bedKi); - EEPROM_READ_VAR(i, bedKd); - #endif - - int lcd_contrast; - EEPROM_READ_VAR(i,lcd_contrast); - - #ifdef FWRETRACT - EEPROM_READ_VAR(i,autoretract_enabled); - EEPROM_READ_VAR(i,retract_length); - #if EXTRUDERS > 1 - EEPROM_READ_VAR(i,retract_length_swap); - #endif - EEPROM_READ_VAR(i,retract_feedrate); - EEPROM_READ_VAR(i,retract_zlift); - EEPROM_READ_VAR(i,retract_recover_length); - #if EXTRUDERS > 1 - EEPROM_READ_VAR(i,retract_recover_length_swap); - #endif - EEPROM_READ_VAR(i,retract_recover_feedrate); - #endif - - EEPROM_READ_VAR(i, volumetric_enabled); - EEPROM_READ_VAR(i, filament_size[0]); -#if EXTRUDERS > 1 - EEPROM_READ_VAR(i, filament_size[1]); -#if EXTRUDERS > 2 - EEPROM_READ_VAR(i, filament_size[2]); -#endif -#endif - - calculate_extruder_multipliers(); - - EEPROM_READ_VAR(i,max_feedrate_silent); - EEPROM_READ_VAR(i,max_acceleration_units_per_sq_second_silent); #ifdef TMC2130 for (uint8_t j = X_AXIS; j <= Y_AXIS; j++) @@ -441,73 +278,18 @@ bool Config_RetrieveSettings(uint16_t offset) void Config_ResetDefault() { - float tmp1[]=DEFAULT_AXIS_STEPS_PER_UNIT; - float tmp2[]=DEFAULT_MAX_FEEDRATE; - long tmp3[]=DEFAULT_MAX_ACCELERATION; - float tmp4[]=DEFAULT_MAX_FEEDRATE_SILENT; - long tmp5[]=DEFAULT_MAX_ACCELERATION_SILENT; - for (short i=0;i<4;i++) - { - axis_steps_per_unit[i]=tmp1[i]; - max_feedrate_normal[i]=tmp2[i]; - max_acceleration_units_per_sq_second_normal[i]=tmp3[i]; - max_feedrate_silent[i]=tmp4[i]; - max_acceleration_units_per_sq_second_silent[i]=tmp5[i]; - } + memcpy_P(&cs,&default_conf, sizeof(cs)); // steps per sq second need to be updated to agree with the units per sq second reset_acceleration_rates(); - acceleration=DEFAULT_ACCELERATION; - retract_acceleration=DEFAULT_RETRACT_ACCELERATION; - minimumfeedrate=DEFAULT_MINIMUMFEEDRATE; - minsegmenttime=DEFAULT_MINSEGMENTTIME; - mintravelfeedrate=DEFAULT_MINTRAVELFEEDRATE; - max_jerk[X_AXIS] = DEFAULT_XJERK; - max_jerk[Y_AXIS] = DEFAULT_YJERK; - max_jerk[Z_AXIS] = DEFAULT_ZJERK; - max_jerk[E_AXIS] = DEFAULT_EJERK; - add_homing[X_AXIS] = add_homing[Y_AXIS] = add_homing[Z_AXIS] = 0; - -#ifdef ENABLE_AUTO_BED_LEVELING - zprobe_zoffset = -Z_PROBE_OFFSET_FROM_EXTRUDER; -#endif #ifdef PIDTEMP - Kp = DEFAULT_Kp; - Ki = scalePID_i(DEFAULT_Ki); - Kd = scalePID_d(DEFAULT_Kd); - - // call updatePID (similar to when we have processed M301) updatePID(); - #ifdef PID_ADD_EXTRUSION_RATE Kc = DEFAULT_Kc; //this is not stored by Config_StoreSettings #endif//PID_ADD_EXTRUSION_RATE #endif//PIDTEMP -#ifdef FWRETRACT - autoretract_enabled = false; - retract_length = RETRACT_LENGTH; -#if EXTRUDERS > 1 - retract_length_swap = RETRACT_LENGTH_SWAP; -#endif - retract_feedrate = RETRACT_FEEDRATE; - retract_zlift = RETRACT_ZLIFT; - retract_recover_length = RETRACT_RECOVER_LENGTH; -#if EXTRUDERS > 1 - retract_recover_length_swap = RETRACT_RECOVER_LENGTH_SWAP; -#endif - retract_recover_feedrate = RETRACT_RECOVER_FEEDRATE; -#endif - - volumetric_enabled = false; - filament_size[0] = DEFAULT_NOMINAL_FILAMENT_DIA; -#if EXTRUDERS > 1 - filament_size[1] = DEFAULT_NOMINAL_FILAMENT_DIA; -#if EXTRUDERS > 2 - filament_size[2] = DEFAULT_NOMINAL_FILAMENT_DIA; -#endif -#endif calculate_extruder_multipliers(); SERIAL_ECHO_START; diff --git a/Firmware/ConfigurationStore.h b/Firmware/ConfigurationStore.h index 43001a47..761af1c8 100644 --- a/Firmware/ConfigurationStore.h +++ b/Firmware/ConfigurationStore.h @@ -4,6 +4,41 @@ #include "Configuration.h" +typedef struct +{ + char version[4]; + float axis_steps_per_unit[4]; + float max_feedrate_normal[4]; + unsigned long max_acceleration_units_per_sq_second_normal[4]; + float acceleration; + float retract_acceleration; + float minimumfeedrate; + float mintravelfeedrate; + unsigned long minsegmenttime; + float max_jerk[4]; + float add_homing[3]; + float zprobe_zoffset; + float Kp; + float Ki; + float Kd; + float bedKp; + float bedKi; + float bedKd; + int lcd_contrast; //!< unused + bool autoretract_enabled; + float retract_length; + float retract_feedrate; + float retract_zlift; + float retract_recover_length; + float retract_recover_feedrate; + bool volumetric_enabled; + float filament_size[1]; + float max_feedrate_silent[4]; + unsigned long max_acceleration_units_per_sq_second_silent[4]; +} __attribute__ ((packed)) M500_conf; + +extern M500_conf cs; + void Config_ResetDefault(); #ifndef DISABLE_M503 From d611cad087b806d2e254f97408af1d54eb68d61e Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Mon, 24 Sep 2018 14:42:01 +0200 Subject: [PATCH 115/141] Temporary hide M500_conf cs to allow automated renaming. --- Firmware/ConfigurationStore.cpp | 2 +- Firmware/ConfigurationStore.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Firmware/ConfigurationStore.cpp b/Firmware/ConfigurationStore.cpp index aa54ebbe..7d00742f 100644 --- a/Firmware/ConfigurationStore.cpp +++ b/Firmware/ConfigurationStore.cpp @@ -9,7 +9,7 @@ #include "mesh_bed_leveling.h" #endif -M500_conf cs; +//M500_conf cs; #ifdef DEBUG_EEPROM_WRITE #define EEPROM_WRITE_VAR(pos, value) _EEPROM_writeData(pos, (uint8_t*)&value, sizeof(value), #value) diff --git a/Firmware/ConfigurationStore.h b/Firmware/ConfigurationStore.h index 761af1c8..7837a56e 100644 --- a/Firmware/ConfigurationStore.h +++ b/Firmware/ConfigurationStore.h @@ -37,7 +37,7 @@ typedef struct unsigned long max_acceleration_units_per_sq_second_silent[4]; } __attribute__ ((packed)) M500_conf; -extern M500_conf cs; +//extern M500_conf cs; void Config_ResetDefault(); From 3f2863244380187161b77fe2b4b9cca2b9b9945f Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Mon, 24 Sep 2018 14:54:41 +0200 Subject: [PATCH 116/141] Use cs.axis_steps_per_unit from ConfigurationStore. --- Firmware/ConfigurationStore.cpp | 6 ++-- Firmware/ConfigurationStore.h | 2 +- Firmware/Marlin_main.cpp | 50 +++++++++++++------------- Firmware/fsensor.cpp | 3 +- Firmware/mesh_bed_calibration.cpp | 4 +-- Firmware/planner.cpp | 59 +++++++++++++++---------------- Firmware/planner.h | 2 -- Firmware/stepper.cpp | 9 ++--- Firmware/ultralcd.cpp | 8 ++--- 9 files changed, 71 insertions(+), 72 deletions(-) diff --git a/Firmware/ConfigurationStore.cpp b/Firmware/ConfigurationStore.cpp index 7d00742f..08334f35 100644 --- a/Firmware/ConfigurationStore.cpp +++ b/Firmware/ConfigurationStore.cpp @@ -9,7 +9,7 @@ #include "mesh_bed_leveling.h" #endif -//M500_conf cs; +M500_conf cs; #ifdef DEBUG_EEPROM_WRITE #define EEPROM_WRITE_VAR(pos, value) _EEPROM_writeData(pos, (uint8_t*)&value, sizeof(value), #value) @@ -97,7 +97,7 @@ void Config_PrintSettings(uint8_t level) "%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, axis_steps_per_unit[X_AXIS], axis_steps_per_unit[Y_AXIS], axis_steps_per_unit[Z_AXIS], axis_steps_per_unit[E_AXIS], + 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_normal[X_AXIS], max_feedrate_normal[Y_AXIS], max_feedrate_normal[Z_AXIS], max_feedrate_normal[E_AXIS], echomagic, echomagic, max_feedrate_silent[X_AXIS], max_feedrate_silent[Y_AXIS], max_feedrate_silent[Z_AXIS], max_feedrate_silent[E_AXIS], echomagic, echomagic, max_acceleration_units_per_sq_second_normal[X_AXIS], max_acceleration_units_per_sq_second_normal[Y_AXIS], max_acceleration_units_per_sq_second_normal[Z_AXIS], max_acceleration_units_per_sq_second_normal[E_AXIS], @@ -114,7 +114,7 @@ void Config_PrintSettings(uint8_t level) "%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, axis_steps_per_unit[X_AXIS], axis_steps_per_unit[Y_AXIS], axis_steps_per_unit[Z_AXIS], axis_steps_per_unit[E_AXIS], + 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, acceleration, retract_acceleration, diff --git a/Firmware/ConfigurationStore.h b/Firmware/ConfigurationStore.h index 7837a56e..761af1c8 100644 --- a/Firmware/ConfigurationStore.h +++ b/Firmware/ConfigurationStore.h @@ -37,7 +37,7 @@ typedef struct unsigned long max_acceleration_units_per_sq_second_silent[4]; } __attribute__ ((packed)) M500_conf; -//extern M500_conf cs; +extern M500_conf cs; void Config_ResetDefault(); diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index 2544dce6..cb24202b 100644 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -3054,13 +3054,13 @@ void gcode_M114() SERIAL_PROTOCOL(current_position[E_AXIS]); SERIAL_PROTOCOLRPGM(_n(" Count X: "));////MSG_COUNT_X c=0 r=0 - SERIAL_PROTOCOL(float(st_get_position(X_AXIS)) / axis_steps_per_unit[X_AXIS]); + SERIAL_PROTOCOL(float(st_get_position(X_AXIS)) / cs.axis_steps_per_unit[X_AXIS]); SERIAL_PROTOCOLPGM(" Y:"); - SERIAL_PROTOCOL(float(st_get_position(Y_AXIS)) / axis_steps_per_unit[Y_AXIS]); + SERIAL_PROTOCOL(float(st_get_position(Y_AXIS)) / cs.axis_steps_per_unit[Y_AXIS]); SERIAL_PROTOCOLPGM(" Z:"); - SERIAL_PROTOCOL(float(st_get_position(Z_AXIS)) / axis_steps_per_unit[Z_AXIS]); + SERIAL_PROTOCOL(float(st_get_position(Z_AXIS)) / cs.axis_steps_per_unit[Z_AXIS]); SERIAL_PROTOCOLPGM(" E:"); - SERIAL_PROTOCOL(float(st_get_position(E_AXIS)) / axis_steps_per_unit[E_AXIS]); + SERIAL_PROTOCOL(float(st_get_position(E_AXIS)) / cs.axis_steps_per_unit[E_AXIS]); SERIAL_PROTOCOLLN(""); } @@ -3942,7 +3942,7 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) // The following code correct the Z height difference from z-probe position and hotend tip position. // The Z height on homing is measured by Z-Probe, but the probe is quite far from the hotend. // When the bed is uneven, this height must be corrected. - real_z = float(st_get_position(Z_AXIS))/axis_steps_per_unit[Z_AXIS]; //get the real Z (since the auto bed leveling is already correcting the plane) + real_z = float(st_get_position(Z_AXIS))/cs.axis_steps_per_unit[Z_AXIS]; //get the real Z (since the auto bed leveling is already correcting the plane) x_tmp = current_position[X_AXIS] + X_PROBE_OFFSET_FROM_EXTRUDER; y_tmp = current_position[Y_AXIS] + Y_PROBE_OFFSET_FROM_EXTRUDER; z_tmp = current_position[Z_AXIS]; @@ -4148,7 +4148,7 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) lcd_temp_cal_show_result(find_z_result); break; } - z_shift = (int)((current_position[Z_AXIS] - zero_z)*axis_steps_per_unit[Z_AXIS]); + 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); @@ -4235,7 +4235,7 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 3000 / 60, active_extruder); st_synchronize(); find_bed_induction_sensor_point_z(-1.f); - z_shift = (int)((current_position[Z_AXIS] - zero_z)*axis_steps_per_unit[Z_AXIS]); + z_shift = (int)((current_position[Z_AXIS] - zero_z)*cs.axis_steps_per_unit[Z_AXIS]); printf_P(_N("\nTemperature: %d Z shift (mm): %.3f\n"), t_c, current_position[Z_AXIS] - zero_z); @@ -5699,15 +5699,15 @@ Sigma_Exit: if(i == 3) { // E float value = code_value(); if(value < 20.0) { - float factor = axis_steps_per_unit[i] / value; // increase e constants if M92 E14 is given for netfab. + float factor = cs.axis_steps_per_unit[i] / value; // increase e constants if M92 E14 is given for netfab. max_jerk[E_AXIS] *= factor; max_feedrate[i] *= factor; axis_steps_per_sqr_second[i] *= factor; } - axis_steps_per_unit[i] = value; + cs.axis_steps_per_unit[i] = value; } else { - axis_steps_per_unit[i] = code_value(); + cs.axis_steps_per_unit[i] = code_value(); } } } @@ -5905,7 +5905,7 @@ Sigma_Exit: #if 0 // Not used for Sprinter/grbl gen6 case 202: // M202 for(int8_t i=0; i < NUM_AXIS; i++) { - if(code_seen(axis_codes[i])) axis_travel_steps_per_sqr_second[i] = code_value() * axis_steps_per_unit[i]; + if(code_seen(axis_codes[i])) axis_travel_steps_per_sqr_second[i] = code_value() * cs.axis_steps_per_unit[i]; } break; #endif @@ -6548,7 +6548,7 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) for (uint8_t i = 0; i < 6; i++) { if(i>0) EEPROM_read_B(EEPROM_PROBE_TEMP_SHIFT + (i-1) * 2, &usteps); - float mm = ((float)usteps) / axis_steps_per_unit[Z_AXIS]; + float mm = ((float)usteps) / cs.axis_steps_per_unit[Z_AXIS]; i == 0 ? SERIAL_PROTOCOLPGM("n/a") : SERIAL_PROTOCOL(i - 1); SERIAL_PROTOCOLPGM(", "); SERIAL_PROTOCOL(35 + (i * 5)); @@ -6591,7 +6591,7 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) { usteps = 0; if (i>0) EEPROM_read_B(EEPROM_PROBE_TEMP_SHIFT + (i - 1) * 2, &usteps); - float mm = ((float)usteps) / axis_steps_per_unit[Z_AXIS]; + float mm = ((float)usteps) / cs.axis_steps_per_unit[Z_AXIS]; i == 0 ? SERIAL_PROTOCOLPGM("n/a") : SERIAL_PROTOCOL(i - 1); SERIAL_PROTOCOLPGM(", "); SERIAL_PROTOCOL(35 + (i * 5)); @@ -6740,13 +6740,13 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) if (res_new > res) { uint16_t fac = (res_new / res); - axis_steps_per_unit[axis] *= fac; + cs.axis_steps_per_unit[axis] *= fac; position[E_AXIS] *= fac; } else { uint16_t fac = (res / res_new); - axis_steps_per_unit[axis] /= fac; + cs.axis_steps_per_unit[axis] /= fac; position[E_AXIS] /= fac; } } @@ -7450,8 +7450,8 @@ void manage_inactivity(bool ignore_stepper_queue/*=false*/) //default argument s float oldepos=current_position[E_AXIS]; float oldedes=destination[E_AXIS]; plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], - destination[E_AXIS]+EXTRUDER_RUNOUT_EXTRUDE*EXTRUDER_RUNOUT_ESTEPS/axis_steps_per_unit[E_AXIS], - EXTRUDER_RUNOUT_SPEED/60.*EXTRUDER_RUNOUT_ESTEPS/axis_steps_per_unit[E_AXIS], active_extruder); + destination[E_AXIS]+EXTRUDER_RUNOUT_EXTRUDE*EXTRUDER_RUNOUT_ESTEPS/cs.axis_steps_per_unit[E_AXIS], + EXTRUDER_RUNOUT_SPEED/60.*EXTRUDER_RUNOUT_ESTEPS/cs.axis_steps_per_unit[E_AXIS], active_extruder); current_position[E_AXIS]=oldepos; destination[E_AXIS]=oldedes; plan_set_e_position(oldepos); @@ -8030,10 +8030,10 @@ void temp_compensation_apply() { if (target_temperature_bed % 10 == 0 && target_temperature_bed >= 60 && target_temperature_bed <= 100) { i_add = (target_temperature_bed - 60) / 10; EEPROM_read_B(EEPROM_PROBE_TEMP_SHIFT + i_add * 2, &z_shift); - z_shift_mm = z_shift / axis_steps_per_unit[Z_AXIS]; + z_shift_mm = z_shift / cs.axis_steps_per_unit[Z_AXIS]; }else { //interpolation - z_shift_mm = temp_comp_interpolation(target_temperature_bed) / axis_steps_per_unit[Z_AXIS]; + z_shift_mm = temp_comp_interpolation(target_temperature_bed) / cs.axis_steps_per_unit[Z_AXIS]; } printf_P(_N("\nZ shift applied:%.3f\n"), z_shift_mm); plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS] - z_shift_mm, current_position[E_AXIS], homing_feedrate[Z_AXIS] / 40, active_extruder); @@ -8116,7 +8116,7 @@ float temp_compensation_pinda_thermistor_offset(float temperature_pinda) { if (!temp_cal_active) return 0; if (!calibration_status_pinda()) return 0; - return temp_comp_interpolation(temperature_pinda) / axis_steps_per_unit[Z_AXIS]; + return temp_comp_interpolation(temperature_pinda) / cs.axis_steps_per_unit[Z_AXIS]; } #endif //PINDA_THERMISTOR @@ -8246,7 +8246,7 @@ void uvlo_() plan_buffer_line( current_position[X_AXIS], current_position[Y_AXIS], - current_position[Z_AXIS] + UVLO_Z_AXIS_SHIFT + float((1024 - z_microsteps + 7) >> 4) / axis_steps_per_unit[Z_AXIS], + current_position[Z_AXIS] + UVLO_Z_AXIS_SHIFT + float((1024 - z_microsteps + 7) >> 4) / cs.axis_steps_per_unit[Z_AXIS], current_position[E_AXIS] - default_retraction, 40, active_extruder); @@ -8256,7 +8256,7 @@ void uvlo_() plan_buffer_line( current_position[X_AXIS], current_position[Y_AXIS], - current_position[Z_AXIS] + UVLO_Z_AXIS_SHIFT + float((1024 - z_microsteps + 7) >> 4) / axis_steps_per_unit[Z_AXIS], + current_position[Z_AXIS] + UVLO_Z_AXIS_SHIFT + float((1024 - z_microsteps + 7) >> 4) / cs.axis_steps_per_unit[Z_AXIS], current_position[E_AXIS] - default_retraction, 40, active_extruder); st_synchronize(); @@ -8348,7 +8348,7 @@ plan_buffer_line( current_position[X_AXIS], current_position[Y_AXIS], // current_position[Z_AXIS]+float((1024-z_microsteps+7)>>4)/axis_steps_per_unit[Z_AXIS], - current_position[Z_AXIS]+UVLO_Z_AXIS_SHIFT+float((1024-z_microsteps+7)>>4)/axis_steps_per_unit[Z_AXIS], + current_position[Z_AXIS]+UVLO_Z_AXIS_SHIFT+float((1024-z_microsteps+7)>>4)/cs.axis_steps_per_unit[Z_AXIS], current_position[E_AXIS], 40, active_extruder); st_synchronize(); @@ -8472,10 +8472,10 @@ void recover_machine_state_after_power_panic(bool bTiny) // The current position after power panic is moved to the next closest 0th full step. if(bTiny) current_position[Z_AXIS] = eeprom_read_float((float*)(EEPROM_UVLO_TINY_CURRENT_POSITION_Z)) + - UVLO_Z_AXIS_SHIFT + float((1024 - eeprom_read_word((uint16_t*)(EEPROM_UVLO_TINY_Z_MICROSTEPS)) + 7) >> 4) / axis_steps_per_unit[Z_AXIS]; + UVLO_Z_AXIS_SHIFT + float((1024 - eeprom_read_word((uint16_t*)(EEPROM_UVLO_TINY_Z_MICROSTEPS)) + 7) >> 4) / cs.axis_steps_per_unit[Z_AXIS]; else current_position[Z_AXIS] = eeprom_read_float((float*)(EEPROM_UVLO_CURRENT_POSITION_Z)) + - UVLO_Z_AXIS_SHIFT + float((1024 - eeprom_read_word((uint16_t*)(EEPROM_UVLO_Z_MICROSTEPS)) + 7) >> 4) / axis_steps_per_unit[Z_AXIS]; + UVLO_Z_AXIS_SHIFT + float((1024 - eeprom_read_word((uint16_t*)(EEPROM_UVLO_Z_MICROSTEPS)) + 7) >> 4) / cs.axis_steps_per_unit[Z_AXIS]; if (eeprom_read_byte((uint8_t*)EEPROM_UVLO_E_ABS)) { current_position[E_AXIS] = eeprom_read_float((float*)(EEPROM_UVLO_CURRENT_POSITION_E)); sprintf_P(cmd, PSTR("G92 E")); diff --git a/Firmware/fsensor.cpp b/Firmware/fsensor.cpp index c4657293..d2608da4 100644 --- a/Firmware/fsensor.cpp +++ b/Firmware/fsensor.cpp @@ -7,6 +7,7 @@ #include "planner.h" #include "fastio.h" #include "cmdqueue.h" +#include "ConfigurationStore.h" //Basic params #define FSENSOR_CHUNK_LEN 0.64F //filament sensor chunk length 0.64mm @@ -114,7 +115,7 @@ void fsensor_init(void) printf_P(PSTR("PAT9125_init:%hhu\n"), pat9125); uint8_t fsensor = eeprom_read_byte((uint8_t*)EEPROM_FSENSOR); fsensor_autoload_enabled=eeprom_read_byte((uint8_t*)EEPROM_FSENS_AUTOLOAD_ENABLED); - fsensor_chunk_len = (int16_t)(FSENSOR_CHUNK_LEN * axis_steps_per_unit[E_AXIS]); + fsensor_chunk_len = (int16_t)(FSENSOR_CHUNK_LEN * cs.axis_steps_per_unit[E_AXIS]); if (!pat9125) { diff --git a/Firmware/mesh_bed_calibration.cpp b/Firmware/mesh_bed_calibration.cpp index 102aebae..9cb48c14 100644 --- a/Firmware/mesh_bed_calibration.cpp +++ b/Firmware/mesh_bed_calibration.cpp @@ -3009,7 +3009,7 @@ void babystep_apply() { babystep_load(); #ifdef BABYSTEP_LOADZ_BY_PLANNER - shift_z(- float(babystepLoadZ) / float(axis_steps_per_unit[Z_AXIS])); + shift_z(- float(babystepLoadZ) / float(cs.axis_steps_per_unit[Z_AXIS])); #else babystepsTodoZadd(babystepLoadZ); #endif /* BABYSTEP_LOADZ_BY_PLANNER */ @@ -3018,7 +3018,7 @@ void babystep_apply() void babystep_undo() { #ifdef BABYSTEP_LOADZ_BY_PLANNER - shift_z(float(babystepLoadZ) / float(axis_steps_per_unit[Z_AXIS])); + shift_z(float(babystepLoadZ) / float(cs.axis_steps_per_unit[Z_AXIS])); #else babystepsTodoZsubtract(babystepLoadZ); #endif /* BABYSTEP_LOADZ_BY_PLANNER */ diff --git a/Firmware/planner.cpp b/Firmware/planner.cpp index 058fd2a9..ef8ba5a8 100644 --- a/Firmware/planner.cpp +++ b/Firmware/planner.cpp @@ -57,6 +57,7 @@ #include "temperature.h" #include "ultralcd.h" #include "language.h" +#include "ConfigurationStore.h" #ifdef MESH_BED_LEVELING #include "mesh_bed_leveling.h" @@ -78,8 +79,6 @@ float max_feedrate_normal[NUM_AXIS]; // max speeds for normal mode float max_feedrate_silent[NUM_AXIS]; // max speeds for silent mode float* max_feedrate = max_feedrate_normal; -// Use M92 to override by software -float axis_steps_per_unit[NUM_AXIS]; // Use M201 to override by software unsigned long max_acceleration_units_per_sq_second_normal[NUM_AXIS]; @@ -623,9 +622,9 @@ void planner_abort_hard() else { float t = float(step_events_completed) / float(current_block->step_event_count); float vec[3] = { - current_block->steps_x / axis_steps_per_unit[X_AXIS], - current_block->steps_y / axis_steps_per_unit[Y_AXIS], - current_block->steps_z / axis_steps_per_unit[Z_AXIS] + current_block->steps_x / cs.axis_steps_per_unit[X_AXIS], + current_block->steps_y / cs.axis_steps_per_unit[Y_AXIS], + current_block->steps_z / cs.axis_steps_per_unit[Z_AXIS] }; float pos1[3], pos2[3]; for (int8_t i = 0; i < 3; ++ i) { @@ -743,18 +742,18 @@ void plan_buffer_line(float x, float y, float z, const float &e, float feed_rate // Calculate target position in absolute steps //this should be done after the wait, because otherwise a M92 code within the gcode disrupts this calculation somehow long target[4]; - target[X_AXIS] = lround(x*axis_steps_per_unit[X_AXIS]); - target[Y_AXIS] = lround(y*axis_steps_per_unit[Y_AXIS]); + target[X_AXIS] = lround(x*cs.axis_steps_per_unit[X_AXIS]); + target[Y_AXIS] = lround(y*cs.axis_steps_per_unit[Y_AXIS]); #ifdef MESH_BED_LEVELING if (mbl.active){ - target[Z_AXIS] = lround((z+mbl.get_z(x, y))*axis_steps_per_unit[Z_AXIS]); + target[Z_AXIS] = lround((z+mbl.get_z(x, y))*cs.axis_steps_per_unit[Z_AXIS]); }else{ - target[Z_AXIS] = lround(z*axis_steps_per_unit[Z_AXIS]); + target[Z_AXIS] = lround(z*cs.axis_steps_per_unit[Z_AXIS]); } #else - target[Z_AXIS] = lround(z*axis_steps_per_unit[Z_AXIS]); + target[Z_AXIS] = lround(z*cs.axis_steps_per_unit[Z_AXIS]); #endif // ENABLE_MESH_BED_LEVELING - target[E_AXIS] = lround(e*axis_steps_per_unit[E_AXIS]); + target[E_AXIS] = lround(e*cs.axis_steps_per_unit[E_AXIS]); #ifdef LIN_ADVANCE const float mm_D_float = sqrt(sq(x - position_float[X_AXIS]) + sq(y - position_float[Y_AXIS])); @@ -776,7 +775,7 @@ void plan_buffer_line(float x, float y, float z, const float &e, float feed_rate } #ifdef PREVENT_LENGTHY_EXTRUDE - if(labs(target[E_AXIS]-position[E_AXIS])>axis_steps_per_unit[E_AXIS]*EXTRUDE_MAXLENGTH) + if(labs(target[E_AXIS]-position[E_AXIS])>cs.axis_steps_per_unit[E_AXIS]*EXTRUDE_MAXLENGTH) { position[E_AXIS]=target[E_AXIS]; //behave as if the move really took place, but ignore E part #ifdef LIN_ADVANCE @@ -931,17 +930,17 @@ Having the real displacement of the head, we can calculate the total movement le */ #ifndef COREXY float delta_mm[4]; - delta_mm[X_AXIS] = (target[X_AXIS]-position[X_AXIS])/axis_steps_per_unit[X_AXIS]; - delta_mm[Y_AXIS] = (target[Y_AXIS]-position[Y_AXIS])/axis_steps_per_unit[Y_AXIS]; + delta_mm[X_AXIS] = (target[X_AXIS]-position[X_AXIS])/cs.axis_steps_per_unit[X_AXIS]; + delta_mm[Y_AXIS] = (target[Y_AXIS]-position[Y_AXIS])/cs.axis_steps_per_unit[Y_AXIS]; #else float delta_mm[6]; - delta_mm[X_HEAD] = (target[X_AXIS]-position[X_AXIS])/axis_steps_per_unit[X_AXIS]; - delta_mm[Y_HEAD] = (target[Y_AXIS]-position[Y_AXIS])/axis_steps_per_unit[Y_AXIS]; - delta_mm[X_AXIS] = ((target[X_AXIS]-position[X_AXIS]) + (target[Y_AXIS]-position[Y_AXIS]))/axis_steps_per_unit[X_AXIS]; - delta_mm[Y_AXIS] = ((target[X_AXIS]-position[X_AXIS]) - (target[Y_AXIS]-position[Y_AXIS]))/axis_steps_per_unit[Y_AXIS]; + delta_mm[X_HEAD] = (target[X_AXIS]-position[X_AXIS])/cs.axis_steps_per_unit[X_AXIS]; + delta_mm[Y_HEAD] = (target[Y_AXIS]-position[Y_AXIS])/cs.axis_steps_per_unit[Y_AXIS]; + delta_mm[X_AXIS] = ((target[X_AXIS]-position[X_AXIS]) + (target[Y_AXIS]-position[Y_AXIS]))/cs.axis_steps_per_unit[X_AXIS]; + delta_mm[Y_AXIS] = ((target[X_AXIS]-position[X_AXIS]) - (target[Y_AXIS]-position[Y_AXIS]))/cs.axis_steps_per_unit[Y_AXIS]; #endif - delta_mm[Z_AXIS] = (target[Z_AXIS]-position[Z_AXIS])/axis_steps_per_unit[Z_AXIS]; - delta_mm[E_AXIS] = (target[E_AXIS]-position[E_AXIS])/axis_steps_per_unit[E_AXIS]; + delta_mm[Z_AXIS] = (target[Z_AXIS]-position[Z_AXIS])/cs.axis_steps_per_unit[Z_AXIS]; + delta_mm[E_AXIS] = (target[E_AXIS]-position[E_AXIS])/cs.axis_steps_per_unit[E_AXIS]; if ( block->steps_x.wide <=dropsegments && block->steps_y.wide <=dropsegments && block->steps_z.wide <=dropsegments ) { block->millimeters = fabs(delta_mm[E_AXIS]); @@ -1188,7 +1187,7 @@ Having the real displacement of the head, we can calculate the total movement le extruder_advance_k * ((advance_ed_ratio < 0.000001) ? de_float / mm_D_float : advance_ed_ratio) // Use the fixed ratio, if set * (block->nominal_speed / (float)block->nominal_rate) - * axis_steps_per_unit[E_AXIS] * 256.0 + * cs.axis_steps_per_unit[E_AXIS] * 256.0 ); #endif @@ -1263,16 +1262,16 @@ void plan_set_position(float x, float y, float z, const float &e) y = world2machine_rotation_and_skew[1][0] * tmpx + world2machine_rotation_and_skew[1][1] * tmpy + world2machine_shift[1]; } - position[X_AXIS] = lround(x*axis_steps_per_unit[X_AXIS]); - position[Y_AXIS] = lround(y*axis_steps_per_unit[Y_AXIS]); + position[X_AXIS] = lround(x*cs.axis_steps_per_unit[X_AXIS]); + position[Y_AXIS] = lround(y*cs.axis_steps_per_unit[Y_AXIS]); #ifdef MESH_BED_LEVELING position[Z_AXIS] = mbl.active ? - lround((z+mbl.get_z(x, y))*axis_steps_per_unit[Z_AXIS]) : - lround(z*axis_steps_per_unit[Z_AXIS]); + lround((z+mbl.get_z(x, y))*cs.axis_steps_per_unit[Z_AXIS]) : + lround(z*cs.axis_steps_per_unit[Z_AXIS]); #else - position[Z_AXIS] = lround(z*axis_steps_per_unit[Z_AXIS]); + position[Z_AXIS] = lround(z*cs.axis_steps_per_unit[Z_AXIS]); #endif // ENABLE_MESH_BED_LEVELING - position[E_AXIS] = lround(e*axis_steps_per_unit[E_AXIS]); + position[E_AXIS] = lround(e*cs.axis_steps_per_unit[E_AXIS]); #ifdef LIN_ADVANCE position_float[X_AXIS] = x; position_float[Y_AXIS] = y; @@ -1293,7 +1292,7 @@ void plan_set_z_position(const float &z) #ifdef LIN_ADVANCE position_float[Z_AXIS] = z; #endif - position[Z_AXIS] = lround(z*axis_steps_per_unit[Z_AXIS]); + position[Z_AXIS] = lround(z*cs.axis_steps_per_unit[Z_AXIS]); st_set_position(position[X_AXIS], position[Y_AXIS], position[Z_AXIS], position[E_AXIS]); } @@ -1302,7 +1301,7 @@ void plan_set_e_position(const float &e) #ifdef LIN_ADVANCE position_float[E_AXIS] = e; #endif - position[E_AXIS] = lround(e*axis_steps_per_unit[E_AXIS]); + position[E_AXIS] = lround(e*cs.axis_steps_per_unit[E_AXIS]); st_set_e_position(position[E_AXIS]); } @@ -1317,7 +1316,7 @@ void set_extrude_min_temp(float temp) void reset_acceleration_rates() { for(int8_t i=0; i < NUM_AXIS; i++) - axis_steps_per_sqr_second[i] = max_acceleration_units_per_sq_second[i] * axis_steps_per_unit[i]; + axis_steps_per_sqr_second[i] = max_acceleration_units_per_sq_second[i] * cs.axis_steps_per_unit[i]; } #ifdef TMC2130 diff --git a/Firmware/planner.h b/Firmware/planner.h index 998a3595..5f9f2cb8 100644 --- a/Firmware/planner.h +++ b/Firmware/planner.h @@ -165,8 +165,6 @@ extern float max_feedrate_normal[NUM_AXIS]; extern float max_feedrate_silent[NUM_AXIS]; extern float* max_feedrate; -// Use M92 to override by software -extern float axis_steps_per_unit[NUM_AXIS]; // Use M201 to override by software extern unsigned long max_acceleration_units_per_sq_second_normal[NUM_AXIS]; diff --git a/Firmware/stepper.cpp b/Firmware/stepper.cpp index 45175c02..7218aa6a 100644 --- a/Firmware/stepper.cpp +++ b/Firmware/stepper.cpp @@ -42,6 +42,7 @@ int fsensor_counter = 0; //counter for e-steps #endif //FILAMENT_SENSOR #include "mmu.h" +#include "ConfigurationStore.h" #ifdef DEBUG_STACK_MONITOR uint16_t SP_min = 0x21FF; @@ -231,15 +232,15 @@ void checkHitEndstops() SERIAL_ECHO_START; SERIAL_ECHORPGM(_T(MSG_ENDSTOPS_HIT)); if(endstop_x_hit) { - SERIAL_ECHOPAIR(" X:",(float)endstops_trigsteps[X_AXIS]/axis_steps_per_unit[X_AXIS]); + SERIAL_ECHOPAIR(" X:",(float)endstops_trigsteps[X_AXIS]/cs.axis_steps_per_unit[X_AXIS]); // LCD_MESSAGERPGM(CAT2(_T(MSG_ENDSTOPS_HIT), PSTR("X"))); } if(endstop_y_hit) { - SERIAL_ECHOPAIR(" Y:",(float)endstops_trigsteps[Y_AXIS]/axis_steps_per_unit[Y_AXIS]); + SERIAL_ECHOPAIR(" Y:",(float)endstops_trigsteps[Y_AXIS]/cs.axis_steps_per_unit[Y_AXIS]); // LCD_MESSAGERPGM(CAT2(_T(MSG_ENDSTOPS_HIT), PSTR("Y"))); } if(endstop_z_hit) { - SERIAL_ECHOPAIR(" Z:",(float)endstops_trigsteps[Z_AXIS]/axis_steps_per_unit[Z_AXIS]); + SERIAL_ECHOPAIR(" Z:",(float)endstops_trigsteps[Z_AXIS]/cs.axis_steps_per_unit[Z_AXIS]); // LCD_MESSAGERPGM(CAT2(_T(MSG_ENDSTOPS_HIT),PSTR("Z"))); } SERIAL_ECHOLN(""); @@ -1390,7 +1391,7 @@ void st_get_position_xy(long &x, long &y) float st_get_position_mm(uint8_t axis) { float steper_position_in_steps = st_get_position(axis); - return steper_position_in_steps / axis_steps_per_unit[axis]; + return steper_position_in_steps / cs.axis_steps_per_unit[axis]; } diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index b78b4c97..3e7db020 100644 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -2764,9 +2764,9 @@ static void _lcd_babystep(int axis, const char *msg) if (calibration_status() >= CALIBRATION_STATUS_LIVE_ADJUST) _md->babystepMem[2] = 0; - _md->babystepMemMM[0] = _md->babystepMem[0]/axis_steps_per_unit[X_AXIS]; - _md->babystepMemMM[1] = _md->babystepMem[1]/axis_steps_per_unit[Y_AXIS]; - _md->babystepMemMM[2] = _md->babystepMem[2]/axis_steps_per_unit[Z_AXIS]; + _md->babystepMemMM[0] = _md->babystepMem[0]/cs.axis_steps_per_unit[X_AXIS]; + _md->babystepMemMM[1] = _md->babystepMem[1]/cs.axis_steps_per_unit[Y_AXIS]; + _md->babystepMemMM[2] = _md->babystepMem[2]/cs.axis_steps_per_unit[Z_AXIS]; lcd_draw_update = 1; //SERIAL_ECHO("Z baby step: "); //SERIAL_ECHO(_md->babystepMem[2]); @@ -2789,7 +2789,7 @@ static void _lcd_babystep(int axis, const char *msg) CRITICAL_SECTION_END } } - _md->babystepMemMM[axis] = _md->babystepMem[axis]/axis_steps_per_unit[axis]; + _md->babystepMemMM[axis] = _md->babystepMem[axis]/cs.axis_steps_per_unit[axis]; delay(50); lcd_encoder = 0; lcd_draw_update = 1; From 02becb5e6a1493f840059a5107867554b0fabe47 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Mon, 24 Sep 2018 15:09:19 +0200 Subject: [PATCH 117/141] Use cs.max_feedrate_normal from ConfigurationStore. --- Firmware/ConfigurationStore.cpp | 6 +++--- Firmware/Marlin_main.cpp | 2 +- Firmware/planner.cpp | 5 ++--- Firmware/planner.h | 1 - 4 files changed, 6 insertions(+), 8 deletions(-) diff --git a/Firmware/ConfigurationStore.cpp b/Firmware/ConfigurationStore.cpp index 08334f35..d8dabff7 100644 --- a/Firmware/ConfigurationStore.cpp +++ b/Firmware/ConfigurationStore.cpp @@ -98,7 +98,7 @@ void Config_PrintSettings(uint8_t level) "%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_normal[X_AXIS], max_feedrate_normal[Y_AXIS], max_feedrate_normal[Z_AXIS], max_feedrate_normal[E_AXIS], + echomagic, echomagic, cs.max_feedrate_normal[X_AXIS], cs.max_feedrate_normal[Y_AXIS], cs.max_feedrate_normal[Z_AXIS], cs.max_feedrate_normal[E_AXIS], echomagic, echomagic, max_feedrate_silent[X_AXIS], max_feedrate_silent[Y_AXIS], max_feedrate_silent[Z_AXIS], max_feedrate_silent[E_AXIS], echomagic, echomagic, max_acceleration_units_per_sq_second_normal[X_AXIS], max_acceleration_units_per_sq_second_normal[Y_AXIS], max_acceleration_units_per_sq_second_normal[Z_AXIS], max_acceleration_units_per_sq_second_normal[E_AXIS], echomagic, echomagic, max_acceleration_units_per_sq_second_silent[X_AXIS], max_acceleration_units_per_sq_second_silent[Y_AXIS], max_acceleration_units_per_sq_second_silent[Z_AXIS], max_acceleration_units_per_sq_second_silent[E_AXIS], @@ -240,8 +240,8 @@ bool Config_RetrieveSettings(uint16_t offset) #ifdef TMC2130 for (uint8_t j = X_AXIS; j <= Y_AXIS; j++) { - if (max_feedrate_normal[j] > NORMAL_MAX_FEEDRATE_XY) - max_feedrate_normal[j] = NORMAL_MAX_FEEDRATE_XY; + if (cs.max_feedrate_normal[j] > NORMAL_MAX_FEEDRATE_XY) + cs.max_feedrate_normal[j] = NORMAL_MAX_FEEDRATE_XY; if (max_feedrate_silent[j] > SILENT_MAX_FEEDRATE_XY) max_feedrate_silent[j] = SILENT_MAX_FEEDRATE_XY; if (max_acceleration_units_per_sq_second_normal[j] > NORMAL_MAX_ACCEL_XY) diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index cb24202b..bfeb73e7 100644 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -5924,7 +5924,7 @@ Sigma_Exit: if (val_silent > SILENT_MAX_FEEDRATE_XY) val_silent = SILENT_MAX_FEEDRATE_XY; } - max_feedrate_normal[i] = val; + cs.max_feedrate_normal[i] = val; max_feedrate_silent[i] = val_silent; #else //TMC2130 max_feedrate[i] = val; diff --git a/Firmware/planner.cpp b/Firmware/planner.cpp index ef8ba5a8..07d35e4c 100644 --- a/Firmware/planner.cpp +++ b/Firmware/planner.cpp @@ -75,9 +75,8 @@ unsigned long minsegmenttime; // Use M203 to override by software -float max_feedrate_normal[NUM_AXIS]; // max speeds for normal mode float max_feedrate_silent[NUM_AXIS]; // max speeds for silent mode -float* max_feedrate = max_feedrate_normal; +float* max_feedrate = cs.max_feedrate_normal; // Use M201 to override by software @@ -1324,7 +1323,7 @@ void update_mode_profile() { if (tmc2130_mode == TMC2130_MODE_NORMAL) { - max_feedrate = max_feedrate_normal; + max_feedrate = cs.max_feedrate_normal; max_acceleration_units_per_sq_second = max_acceleration_units_per_sq_second_normal; } else if (tmc2130_mode == TMC2130_MODE_SILENT) diff --git a/Firmware/planner.h b/Firmware/planner.h index 5f9f2cb8..ebee45d6 100644 --- a/Firmware/planner.h +++ b/Firmware/planner.h @@ -161,7 +161,6 @@ void check_axes_activity(); extern unsigned long minsegmenttime; // Use M203 to override by software -extern float max_feedrate_normal[NUM_AXIS]; extern float max_feedrate_silent[NUM_AXIS]; extern float* max_feedrate; From cee51cf9c3dd5685c742483d84b0c82df4cafe50 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Mon, 24 Sep 2018 15:40:35 +0200 Subject: [PATCH 118/141] Use cs.max_acceleration_units_per_sq_second_normal from ConfigurationStore. --- Firmware/ConfigurationStore.cpp | 6 +++--- Firmware/Marlin_main.cpp | 2 +- Firmware/planner.cpp | 5 ++--- Firmware/planner.h | 1 - 4 files changed, 6 insertions(+), 8 deletions(-) diff --git a/Firmware/ConfigurationStore.cpp b/Firmware/ConfigurationStore.cpp index d8dabff7..c4afb22d 100644 --- a/Firmware/ConfigurationStore.cpp +++ b/Firmware/ConfigurationStore.cpp @@ -100,7 +100,7 @@ void Config_PrintSettings(uint8_t level) 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, cs.max_feedrate_normal[X_AXIS], cs.max_feedrate_normal[Y_AXIS], cs.max_feedrate_normal[Z_AXIS], cs.max_feedrate_normal[E_AXIS], echomagic, echomagic, max_feedrate_silent[X_AXIS], max_feedrate_silent[Y_AXIS], max_feedrate_silent[Z_AXIS], max_feedrate_silent[E_AXIS], - echomagic, echomagic, max_acceleration_units_per_sq_second_normal[X_AXIS], max_acceleration_units_per_sq_second_normal[Y_AXIS], max_acceleration_units_per_sq_second_normal[Z_AXIS], max_acceleration_units_per_sq_second_normal[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, max_acceleration_units_per_sq_second_silent[X_AXIS], max_acceleration_units_per_sq_second_silent[Y_AXIS], max_acceleration_units_per_sq_second_silent[Z_AXIS], max_acceleration_units_per_sq_second_silent[E_AXIS], echomagic, echomagic, acceleration, retract_acceleration, echomagic, echomagic, minimumfeedrate, mintravelfeedrate, minsegmenttime, max_jerk[X_AXIS], max_jerk[Y_AXIS], max_jerk[Z_AXIS], max_jerk[E_AXIS], @@ -244,8 +244,8 @@ bool Config_RetrieveSettings(uint16_t offset) cs.max_feedrate_normal[j] = NORMAL_MAX_FEEDRATE_XY; if (max_feedrate_silent[j] > SILENT_MAX_FEEDRATE_XY) max_feedrate_silent[j] = SILENT_MAX_FEEDRATE_XY; - if (max_acceleration_units_per_sq_second_normal[j] > NORMAL_MAX_ACCEL_XY) - max_acceleration_units_per_sq_second_normal[j] = NORMAL_MAX_ACCEL_XY; + if (cs.max_acceleration_units_per_sq_second_normal[j] > NORMAL_MAX_ACCEL_XY) + cs.max_acceleration_units_per_sq_second_normal[j] = NORMAL_MAX_ACCEL_XY; if (max_acceleration_units_per_sq_second_silent[j] > SILENT_MAX_ACCEL_XY) max_acceleration_units_per_sq_second_silent[j] = SILENT_MAX_ACCEL_XY; } diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index bfeb73e7..40de9ec5 100644 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -5892,7 +5892,7 @@ Sigma_Exit: if (val_silent > SILENT_MAX_ACCEL_XY) val_silent = SILENT_MAX_ACCEL_XY; } - max_acceleration_units_per_sq_second_normal[i] = val; + cs.max_acceleration_units_per_sq_second_normal[i] = val; max_acceleration_units_per_sq_second_silent[i] = val_silent; #else //TMC2130 max_acceleration_units_per_sq_second[i] = val; diff --git a/Firmware/planner.cpp b/Firmware/planner.cpp index 07d35e4c..8f28ab71 100644 --- a/Firmware/planner.cpp +++ b/Firmware/planner.cpp @@ -80,9 +80,8 @@ float* max_feedrate = cs.max_feedrate_normal; // Use M201 to override by software -unsigned long max_acceleration_units_per_sq_second_normal[NUM_AXIS]; unsigned long max_acceleration_units_per_sq_second_silent[NUM_AXIS]; -unsigned long* max_acceleration_units_per_sq_second = max_acceleration_units_per_sq_second_normal; +unsigned long* max_acceleration_units_per_sq_second = cs.max_acceleration_units_per_sq_second_normal; float minimumfeedrate; float acceleration; // Normal acceleration mm/s^2 THIS IS THE DEFAULT ACCELERATION for all moves. M204 SXXXX @@ -1324,7 +1323,7 @@ void update_mode_profile() if (tmc2130_mode == TMC2130_MODE_NORMAL) { max_feedrate = cs.max_feedrate_normal; - max_acceleration_units_per_sq_second = max_acceleration_units_per_sq_second_normal; + max_acceleration_units_per_sq_second = cs.max_acceleration_units_per_sq_second_normal; } else if (tmc2130_mode == TMC2130_MODE_SILENT) { diff --git a/Firmware/planner.h b/Firmware/planner.h index ebee45d6..18f4cd02 100644 --- a/Firmware/planner.h +++ b/Firmware/planner.h @@ -166,7 +166,6 @@ extern float* max_feedrate; // Use M201 to override by software -extern unsigned long max_acceleration_units_per_sq_second_normal[NUM_AXIS]; extern unsigned long max_acceleration_units_per_sq_second_silent[NUM_AXIS]; extern unsigned long* max_acceleration_units_per_sq_second; From 7dbe0afdc4e7641fa4c32264eb879c0bed7495fd Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Mon, 24 Sep 2018 15:47:36 +0200 Subject: [PATCH 119/141] Use cs.acceleration from ConfigurationStore. --- Firmware/ConfigurationStore.cpp | 4 ++-- Firmware/ConfigurationStore.h | 2 +- Firmware/Marlin_main.cpp | 4 ++-- Firmware/planner.cpp | 3 +-- Firmware/planner.h | 1 - 5 files changed, 6 insertions(+), 8 deletions(-) diff --git a/Firmware/ConfigurationStore.cpp b/Firmware/ConfigurationStore.cpp index c4afb22d..7b99dc3c 100644 --- a/Firmware/ConfigurationStore.cpp +++ b/Firmware/ConfigurationStore.cpp @@ -102,7 +102,7 @@ void Config_PrintSettings(uint8_t level) echomagic, echomagic, max_feedrate_silent[X_AXIS], max_feedrate_silent[Y_AXIS], max_feedrate_silent[Z_AXIS], 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, max_acceleration_units_per_sq_second_silent[X_AXIS], max_acceleration_units_per_sq_second_silent[Y_AXIS], max_acceleration_units_per_sq_second_silent[Z_AXIS], max_acceleration_units_per_sq_second_silent[E_AXIS], - echomagic, echomagic, acceleration, retract_acceleration, + echomagic, echomagic, cs.acceleration, retract_acceleration, echomagic, echomagic, minimumfeedrate, mintravelfeedrate, minsegmenttime, max_jerk[X_AXIS], max_jerk[Y_AXIS], max_jerk[Z_AXIS], max_jerk[E_AXIS], echomagic, echomagic, add_homing[X_AXIS], add_homing[Y_AXIS], add_homing[Z_AXIS] #else //TMC2130 @@ -117,7 +117,7 @@ void Config_PrintSettings(uint8_t level) 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, acceleration, retract_acceleration, + echomagic, echomagic, cs.acceleration, retract_acceleration, echomagic, echomagic, minimumfeedrate, mintravelfeedrate, minsegmenttime, max_jerk[X_AXIS], max_jerk[Y_AXIS], max_jerk[Z_AXIS], max_jerk[E_AXIS], echomagic, echomagic, add_homing[X_AXIS], add_homing[Y_AXIS], add_homing[Z_AXIS] #endif //TMC2130 diff --git a/Firmware/ConfigurationStore.h b/Firmware/ConfigurationStore.h index 761af1c8..36ec2c1e 100644 --- a/Firmware/ConfigurationStore.h +++ b/Firmware/ConfigurationStore.h @@ -10,7 +10,7 @@ typedef struct float axis_steps_per_unit[4]; float max_feedrate_normal[4]; unsigned long max_acceleration_units_per_sq_second_normal[4]; - float acceleration; + float acceleration; //!< Normal acceleration mm/s^2 THIS IS THE DEFAULT ACCELERATION for all moves. M204 SXXXX float retract_acceleration; float minimumfeedrate; float mintravelfeedrate; diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index 40de9ec5..e5b76c9f 100644 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -5941,14 +5941,14 @@ 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). - acceleration = code_value(); + cs.acceleration = code_value(); // Interpret the T value as retract acceleration in the old Marlin format. if(code_seen('T')) retract_acceleration = code_value(); } else { // New acceleration format, compatible with the upstream Marlin. if(code_seen('P')) - acceleration = code_value(); + cs.acceleration = code_value(); if(code_seen('R')) retract_acceleration = code_value(); if(code_seen('T')) { diff --git a/Firmware/planner.cpp b/Firmware/planner.cpp index 8f28ab71..bd01ef3c 100644 --- a/Firmware/planner.cpp +++ b/Firmware/planner.cpp @@ -84,7 +84,6 @@ unsigned long max_acceleration_units_per_sq_second_silent[NUM_AXIS]; unsigned long* max_acceleration_units_per_sq_second = cs.max_acceleration_units_per_sq_second_normal; float minimumfeedrate; -float acceleration; // Normal acceleration mm/s^2 THIS IS THE DEFAULT ACCELERATION for all moves. M204 SXXXX float retract_acceleration; // mm/s^2 filament pull-pack and push-forward while standing still in the other axis M204 TXXXX // Jerk is a maximum immediate velocity change. float max_jerk[NUM_AXIS]; @@ -1009,7 +1008,7 @@ Having the real displacement of the head, we can calculate the total movement le } else { - block->acceleration_st = ceil(acceleration * steps_per_mm); // convert to: acceleration steps/sec^2 + block->acceleration_st = ceil(cs.acceleration * steps_per_mm); // convert to: acceleration steps/sec^2 // Limit acceleration per axis //FIXME Vojtech: One shall rather limit a projection of the acceleration vector instead of using the limit. if(((float)block->acceleration_st * (float)block->steps_x.wide / (float)block->step_event_count.wide) > axis_steps_per_sqr_second[X_AXIS]) diff --git a/Firmware/planner.h b/Firmware/planner.h index 18f4cd02..99e921d7 100644 --- a/Firmware/planner.h +++ b/Firmware/planner.h @@ -170,7 +170,6 @@ extern unsigned long max_acceleration_units_per_sq_second_silent[NUM_AXIS]; extern unsigned long* max_acceleration_units_per_sq_second; extern float minimumfeedrate; -extern float acceleration; // Normal acceleration mm/s^2 THIS IS THE DEFAULT ACCELERATION for all moves. M204 SXXXX extern float retract_acceleration; // mm/s^2 filament pull-pack and push-forward while standing still in the other axis M204 TXXXX // Jerk is a maximum immediate velocity change. extern float max_jerk[NUM_AXIS]; From b8fefceb4d8f20f67c5a390b9d231f4e6062d513 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Mon, 24 Sep 2018 15:53:35 +0200 Subject: [PATCH 120/141] Use cs.retract_acceleration from ConfigurationStore. --- Firmware/ConfigurationStore.cpp | 4 ++-- Firmware/ConfigurationStore.h | 2 +- Firmware/Marlin_main.cpp | 4 ++-- Firmware/planner.cpp | 3 +-- Firmware/planner.h | 1 - 5 files changed, 6 insertions(+), 8 deletions(-) diff --git a/Firmware/ConfigurationStore.cpp b/Firmware/ConfigurationStore.cpp index 7b99dc3c..3bdf2b66 100644 --- a/Firmware/ConfigurationStore.cpp +++ b/Firmware/ConfigurationStore.cpp @@ -102,7 +102,7 @@ void Config_PrintSettings(uint8_t level) echomagic, echomagic, max_feedrate_silent[X_AXIS], max_feedrate_silent[Y_AXIS], max_feedrate_silent[Z_AXIS], 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, max_acceleration_units_per_sq_second_silent[X_AXIS], max_acceleration_units_per_sq_second_silent[Y_AXIS], max_acceleration_units_per_sq_second_silent[Z_AXIS], max_acceleration_units_per_sq_second_silent[E_AXIS], - echomagic, echomagic, cs.acceleration, retract_acceleration, + echomagic, echomagic, cs.acceleration, cs.retract_acceleration, echomagic, echomagic, minimumfeedrate, mintravelfeedrate, minsegmenttime, max_jerk[X_AXIS], max_jerk[Y_AXIS], max_jerk[Z_AXIS], max_jerk[E_AXIS], echomagic, echomagic, add_homing[X_AXIS], add_homing[Y_AXIS], add_homing[Z_AXIS] #else //TMC2130 @@ -117,7 +117,7 @@ void Config_PrintSettings(uint8_t level) 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, retract_acceleration, + echomagic, echomagic, cs.acceleration, cs.retract_acceleration, echomagic, echomagic, minimumfeedrate, mintravelfeedrate, minsegmenttime, max_jerk[X_AXIS], max_jerk[Y_AXIS], max_jerk[Z_AXIS], max_jerk[E_AXIS], echomagic, echomagic, add_homing[X_AXIS], add_homing[Y_AXIS], add_homing[Z_AXIS] #endif //TMC2130 diff --git a/Firmware/ConfigurationStore.h b/Firmware/ConfigurationStore.h index 36ec2c1e..7a656276 100644 --- a/Firmware/ConfigurationStore.h +++ b/Firmware/ConfigurationStore.h @@ -11,7 +11,7 @@ typedef struct float max_feedrate_normal[4]; unsigned long max_acceleration_units_per_sq_second_normal[4]; float acceleration; //!< Normal acceleration mm/s^2 THIS IS THE DEFAULT ACCELERATION for all moves. M204 SXXXX - float retract_acceleration; + float retract_acceleration; //!< mm/s^2 filament pull-pack and push-forward while standing still in the other axis M204 TXXXX float minimumfeedrate; float mintravelfeedrate; unsigned long minsegmenttime; diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index e5b76c9f..845b37d2 100644 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -5944,13 +5944,13 @@ Sigma_Exit: cs.acceleration = code_value(); // Interpret the T value as retract acceleration in the old Marlin format. if(code_seen('T')) - retract_acceleration = code_value(); + cs.retract_acceleration = code_value(); } else { // New acceleration format, compatible with the upstream Marlin. if(code_seen('P')) cs.acceleration = code_value(); if(code_seen('R')) - retract_acceleration = code_value(); + cs.retract_acceleration = code_value(); if(code_seen('T')) { // Interpret the T value as the travel acceleration in the new Marlin format. //FIXME Prusa3D firmware currently does not support travel acceleration value independent from the extruding acceleration value. diff --git a/Firmware/planner.cpp b/Firmware/planner.cpp index bd01ef3c..dfb7f8a6 100644 --- a/Firmware/planner.cpp +++ b/Firmware/planner.cpp @@ -84,7 +84,6 @@ unsigned long max_acceleration_units_per_sq_second_silent[NUM_AXIS]; unsigned long* max_acceleration_units_per_sq_second = cs.max_acceleration_units_per_sq_second_normal; float minimumfeedrate; -float retract_acceleration; // mm/s^2 filament pull-pack and push-forward while standing still in the other axis M204 TXXXX // Jerk is a maximum immediate velocity change. float max_jerk[NUM_AXIS]; float mintravelfeedrate; @@ -1004,7 +1003,7 @@ Having the real displacement of the head, we can calculate the total movement le float steps_per_mm = block->step_event_count.wide/block->millimeters; if(block->steps_x.wide == 0 && block->steps_y.wide == 0 && block->steps_z.wide == 0) { - block->acceleration_st = ceil(retract_acceleration * steps_per_mm); // convert to: acceleration steps/sec^2 + block->acceleration_st = ceil(cs.retract_acceleration * steps_per_mm); // convert to: acceleration steps/sec^2 } else { diff --git a/Firmware/planner.h b/Firmware/planner.h index 99e921d7..937b6a59 100644 --- a/Firmware/planner.h +++ b/Firmware/planner.h @@ -170,7 +170,6 @@ extern unsigned long max_acceleration_units_per_sq_second_silent[NUM_AXIS]; extern unsigned long* max_acceleration_units_per_sq_second; extern float minimumfeedrate; -extern float retract_acceleration; // mm/s^2 filament pull-pack and push-forward while standing still in the other axis M204 TXXXX // Jerk is a maximum immediate velocity change. extern float max_jerk[NUM_AXIS]; extern float mintravelfeedrate; From 26e2fd1c76dfa05ff2a8b502d7361ec45e653702 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Mon, 24 Sep 2018 15:57:24 +0200 Subject: [PATCH 121/141] Use cs.minimumfeedrate from ConfigurationStore. --- Firmware/ConfigurationStore.cpp | 4 ++-- Firmware/Marlin_main.cpp | 2 +- Firmware/planner.cpp | 3 +-- Firmware/planner.h | 1 - 4 files changed, 4 insertions(+), 6 deletions(-) diff --git a/Firmware/ConfigurationStore.cpp b/Firmware/ConfigurationStore.cpp index 3bdf2b66..1ff4203d 100644 --- a/Firmware/ConfigurationStore.cpp +++ b/Firmware/ConfigurationStore.cpp @@ -103,7 +103,7 @@ void Config_PrintSettings(uint8_t level) 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, max_acceleration_units_per_sq_second_silent[X_AXIS], max_acceleration_units_per_sq_second_silent[Y_AXIS], max_acceleration_units_per_sq_second_silent[Z_AXIS], max_acceleration_units_per_sq_second_silent[E_AXIS], echomagic, echomagic, cs.acceleration, cs.retract_acceleration, - echomagic, echomagic, minimumfeedrate, mintravelfeedrate, minsegmenttime, max_jerk[X_AXIS], max_jerk[Y_AXIS], max_jerk[Z_AXIS], max_jerk[E_AXIS], + echomagic, echomagic, cs.minimumfeedrate, mintravelfeedrate, minsegmenttime, max_jerk[X_AXIS], max_jerk[Y_AXIS], max_jerk[Z_AXIS], max_jerk[E_AXIS], echomagic, echomagic, add_homing[X_AXIS], add_homing[Y_AXIS], add_homing[Z_AXIS] #else //TMC2130 printf_P(PSTR( @@ -118,7 +118,7 @@ void Config_PrintSettings(uint8_t level) 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, minimumfeedrate, mintravelfeedrate, minsegmenttime, max_jerk[X_AXIS], max_jerk[Y_AXIS], max_jerk[Z_AXIS], max_jerk[E_AXIS], + echomagic, echomagic, cs.minimumfeedrate, mintravelfeedrate, minsegmenttime, max_jerk[X_AXIS], max_jerk[Y_AXIS], max_jerk[Z_AXIS], max_jerk[E_AXIS], echomagic, echomagic, add_homing[X_AXIS], add_homing[Y_AXIS], add_homing[Z_AXIS] #endif //TMC2130 ); diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index 845b37d2..6a0023f4 100644 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -5961,7 +5961,7 @@ Sigma_Exit: break; case 205: //M205 advanced settings: minimum travel speed S=while printing T=travel only, B=minimum segment time X= maximum xy jerk, Z=maximum Z jerk { - if(code_seen('S')) minimumfeedrate = code_value(); + if(code_seen('S')) cs.minimumfeedrate = code_value(); if(code_seen('T')) mintravelfeedrate = code_value(); if(code_seen('B')) minsegmenttime = code_value() ; if(code_seen('X')) max_jerk[X_AXIS] = max_jerk[Y_AXIS] = code_value(); diff --git a/Firmware/planner.cpp b/Firmware/planner.cpp index dfb7f8a6..1e141fa7 100644 --- a/Firmware/planner.cpp +++ b/Firmware/planner.cpp @@ -83,7 +83,6 @@ float* max_feedrate = cs.max_feedrate_normal; unsigned long max_acceleration_units_per_sq_second_silent[NUM_AXIS]; unsigned long* max_acceleration_units_per_sq_second = cs.max_acceleration_units_per_sq_second_normal; -float minimumfeedrate; // Jerk is a maximum immediate velocity change. float max_jerk[NUM_AXIS]; float mintravelfeedrate; @@ -914,7 +913,7 @@ block->steps_y.wide = labs((target[X_AXIS]-position[X_AXIS]) - (target[Y_AXIS]-p } else { - if(feed_rate Date: Mon, 24 Sep 2018 16:01:58 +0200 Subject: [PATCH 122/141] Use cs.mintravelfeedrate from ConfigurationStore. --- Firmware/ConfigurationStore.cpp | 4 ++-- Firmware/Marlin_main.cpp | 2 +- Firmware/planner.cpp | 3 +-- Firmware/planner.h | 1 - 4 files changed, 4 insertions(+), 6 deletions(-) diff --git a/Firmware/ConfigurationStore.cpp b/Firmware/ConfigurationStore.cpp index 1ff4203d..cb0c6ac2 100644 --- a/Firmware/ConfigurationStore.cpp +++ b/Firmware/ConfigurationStore.cpp @@ -103,7 +103,7 @@ void Config_PrintSettings(uint8_t level) 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, max_acceleration_units_per_sq_second_silent[X_AXIS], max_acceleration_units_per_sq_second_silent[Y_AXIS], max_acceleration_units_per_sq_second_silent[Z_AXIS], max_acceleration_units_per_sq_second_silent[E_AXIS], echomagic, echomagic, cs.acceleration, cs.retract_acceleration, - echomagic, echomagic, cs.minimumfeedrate, mintravelfeedrate, minsegmenttime, max_jerk[X_AXIS], max_jerk[Y_AXIS], max_jerk[Z_AXIS], max_jerk[E_AXIS], + echomagic, echomagic, cs.minimumfeedrate, cs.mintravelfeedrate, minsegmenttime, max_jerk[X_AXIS], max_jerk[Y_AXIS], max_jerk[Z_AXIS], max_jerk[E_AXIS], echomagic, echomagic, add_homing[X_AXIS], add_homing[Y_AXIS], add_homing[Z_AXIS] #else //TMC2130 printf_P(PSTR( @@ -118,7 +118,7 @@ void Config_PrintSettings(uint8_t level) 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.minimumfeedrate, mintravelfeedrate, minsegmenttime, max_jerk[X_AXIS], max_jerk[Y_AXIS], max_jerk[Z_AXIS], max_jerk[E_AXIS], + echomagic, echomagic, cs.minimumfeedrate, cs.mintravelfeedrate, minsegmenttime, max_jerk[X_AXIS], max_jerk[Y_AXIS], max_jerk[Z_AXIS], max_jerk[E_AXIS], echomagic, echomagic, add_homing[X_AXIS], add_homing[Y_AXIS], add_homing[Z_AXIS] #endif //TMC2130 ); diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index 6a0023f4..ee8a9258 100644 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -5962,7 +5962,7 @@ Sigma_Exit: case 205: //M205 advanced settings: minimum travel speed S=while printing T=travel only, B=minimum segment time X= maximum xy jerk, Z=maximum Z jerk { if(code_seen('S')) cs.minimumfeedrate = code_value(); - if(code_seen('T')) mintravelfeedrate = code_value(); + if(code_seen('T')) cs.mintravelfeedrate = code_value(); if(code_seen('B')) minsegmenttime = code_value() ; if(code_seen('X')) max_jerk[X_AXIS] = max_jerk[Y_AXIS] = code_value(); if(code_seen('Y')) max_jerk[Y_AXIS] = code_value(); diff --git a/Firmware/planner.cpp b/Firmware/planner.cpp index 1e141fa7..fc843688 100644 --- a/Firmware/planner.cpp +++ b/Firmware/planner.cpp @@ -85,7 +85,6 @@ unsigned long* max_acceleration_units_per_sq_second = cs.max_acceleration_units_ // Jerk is a maximum immediate velocity change. float max_jerk[NUM_AXIS]; -float mintravelfeedrate; unsigned long axis_steps_per_sqr_second[NUM_AXIS]; #ifdef ENABLE_AUTO_BED_LEVELING @@ -909,7 +908,7 @@ block->steps_y.wide = labs((target[X_AXIS]-position[X_AXIS]) - (target[Y_AXIS]-p if (block->steps_e.wide == 0) { - if(feed_rate Date: Mon, 24 Sep 2018 16:22:50 +0200 Subject: [PATCH 123/141] Use cs.minsegmenttime from ConfigurationStore. --- Firmware/ConfigurationStore.cpp | 4 ++-- Firmware/Marlin_main.cpp | 2 +- Firmware/planner.cpp | 6 ++---- Firmware/planner.h | 2 -- 4 files changed, 5 insertions(+), 9 deletions(-) diff --git a/Firmware/ConfigurationStore.cpp b/Firmware/ConfigurationStore.cpp index cb0c6ac2..086c43e1 100644 --- a/Firmware/ConfigurationStore.cpp +++ b/Firmware/ConfigurationStore.cpp @@ -103,7 +103,7 @@ void Config_PrintSettings(uint8_t level) 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, max_acceleration_units_per_sq_second_silent[X_AXIS], max_acceleration_units_per_sq_second_silent[Y_AXIS], max_acceleration_units_per_sq_second_silent[Z_AXIS], max_acceleration_units_per_sq_second_silent[E_AXIS], echomagic, echomagic, cs.acceleration, cs.retract_acceleration, - echomagic, echomagic, cs.minimumfeedrate, cs.mintravelfeedrate, minsegmenttime, max_jerk[X_AXIS], max_jerk[Y_AXIS], max_jerk[Z_AXIS], max_jerk[E_AXIS], + echomagic, echomagic, cs.minimumfeedrate, cs.mintravelfeedrate, cs.minsegmenttime, max_jerk[X_AXIS], max_jerk[Y_AXIS], max_jerk[Z_AXIS], max_jerk[E_AXIS], echomagic, echomagic, add_homing[X_AXIS], add_homing[Y_AXIS], add_homing[Z_AXIS] #else //TMC2130 printf_P(PSTR( @@ -118,7 +118,7 @@ void Config_PrintSettings(uint8_t level) 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.minimumfeedrate, cs.mintravelfeedrate, minsegmenttime, max_jerk[X_AXIS], max_jerk[Y_AXIS], max_jerk[Z_AXIS], max_jerk[E_AXIS], + echomagic, echomagic, cs.minimumfeedrate, cs.mintravelfeedrate, cs.minsegmenttime, max_jerk[X_AXIS], max_jerk[Y_AXIS], max_jerk[Z_AXIS], max_jerk[E_AXIS], echomagic, echomagic, add_homing[X_AXIS], add_homing[Y_AXIS], add_homing[Z_AXIS] #endif //TMC2130 ); diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index ee8a9258..24f76f96 100644 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -5963,7 +5963,7 @@ Sigma_Exit: { if(code_seen('S')) cs.minimumfeedrate = code_value(); if(code_seen('T')) cs.mintravelfeedrate = code_value(); - if(code_seen('B')) minsegmenttime = code_value() ; + if(code_seen('B')) cs.minsegmenttime = code_value() ; if(code_seen('X')) max_jerk[X_AXIS] = max_jerk[Y_AXIS] = code_value(); if(code_seen('Y')) max_jerk[Y_AXIS] = code_value(); if(code_seen('Z')) max_jerk[Z_AXIS] = code_value(); diff --git a/Firmware/planner.cpp b/Firmware/planner.cpp index fc843688..fdbf6476 100644 --- a/Firmware/planner.cpp +++ b/Firmware/planner.cpp @@ -72,8 +72,6 @@ //=============================public variables ============================ //=========================================================================== -unsigned long minsegmenttime; - // Use M203 to override by software float max_feedrate_silent[NUM_AXIS]; // max speeds for silent mode float* max_feedrate = cs.max_feedrate_normal; @@ -961,9 +959,9 @@ Having the real displacement of the head, we can calculate the total movement le if (moves_queued > 1 && moves_queued < (BLOCK_BUFFER_SIZE >> 1)) { // segment time in micro seconds unsigned long segment_time = lround(1000000.0/inverse_second); - if (segment_time < minsegmenttime) + if (segment_time < cs.minsegmenttime) // buffer is draining, add extra time. The amount of time added increases if the buffer is still emptied more. - inverse_second=1000000.0/(segment_time+lround(2*(minsegmenttime-segment_time)/moves_queued)); + inverse_second=1000000.0/(segment_time+lround(2*(cs.minsegmenttime-segment_time)/moves_queued)); } #endif // SLOWDOWN diff --git a/Firmware/planner.h b/Firmware/planner.h index 98bc3b34..d64386ab 100644 --- a/Firmware/planner.h +++ b/Firmware/planner.h @@ -158,8 +158,6 @@ extern bool e_active(); void check_axes_activity(); -extern unsigned long minsegmenttime; - // Use M203 to override by software extern float max_feedrate_silent[NUM_AXIS]; extern float* max_feedrate; From ac7c0621617bd9e9f8c111dd72f1f24ac6de81c0 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Mon, 24 Sep 2018 16:35:33 +0200 Subject: [PATCH 124/141] Use cs.max_jerk from ConfigurationStore. --- Firmware/ConfigurationStore.cpp | 8 ++++---- Firmware/ConfigurationStore.h | 2 +- Firmware/Marlin_main.cpp | 14 +++++++------- Firmware/planner.cpp | 13 +++++-------- Firmware/planner.h | 3 --- 5 files changed, 17 insertions(+), 23 deletions(-) diff --git a/Firmware/ConfigurationStore.cpp b/Firmware/ConfigurationStore.cpp index 086c43e1..356c7b83 100644 --- a/Firmware/ConfigurationStore.cpp +++ b/Firmware/ConfigurationStore.cpp @@ -103,7 +103,7 @@ void Config_PrintSettings(uint8_t level) 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, max_acceleration_units_per_sq_second_silent[X_AXIS], max_acceleration_units_per_sq_second_silent[Y_AXIS], max_acceleration_units_per_sq_second_silent[Z_AXIS], max_acceleration_units_per_sq_second_silent[E_AXIS], echomagic, echomagic, cs.acceleration, cs.retract_acceleration, - echomagic, echomagic, cs.minimumfeedrate, cs.mintravelfeedrate, cs.minsegmenttime, max_jerk[X_AXIS], max_jerk[Y_AXIS], max_jerk[Z_AXIS], max_jerk[E_AXIS], + 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, add_homing[X_AXIS], add_homing[Y_AXIS], add_homing[Z_AXIS] #else //TMC2130 printf_P(PSTR( @@ -118,7 +118,7 @@ void Config_PrintSettings(uint8_t level) 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.minimumfeedrate, cs.mintravelfeedrate, cs.minsegmenttime, max_jerk[X_AXIS], max_jerk[Y_AXIS], max_jerk[Z_AXIS], max_jerk[E_AXIS], + 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, add_homing[X_AXIS], add_homing[Y_AXIS], add_homing[Z_AXIS] #endif //TMC2130 ); @@ -232,8 +232,8 @@ bool Config_RetrieveSettings(uint16_t offset) EEPROM_READ_VAR(i,cs); - if (max_jerk[X_AXIS] > DEFAULT_XJERK) max_jerk[X_AXIS] = DEFAULT_XJERK; - if (max_jerk[Y_AXIS] > DEFAULT_YJERK) max_jerk[Y_AXIS] = DEFAULT_YJERK; + if (cs.max_jerk[X_AXIS] > DEFAULT_XJERK) cs.max_jerk[X_AXIS] = DEFAULT_XJERK; + if (cs.max_jerk[Y_AXIS] > DEFAULT_YJERK) cs.max_jerk[Y_AXIS] = DEFAULT_YJERK; calculate_extruder_multipliers(); diff --git a/Firmware/ConfigurationStore.h b/Firmware/ConfigurationStore.h index 7a656276..8abab432 100644 --- a/Firmware/ConfigurationStore.h +++ b/Firmware/ConfigurationStore.h @@ -15,7 +15,7 @@ typedef struct float minimumfeedrate; float mintravelfeedrate; unsigned long minsegmenttime; - float max_jerk[4]; + float max_jerk[4]; //!< Jerk is a maximum immediate velocity change. float add_homing[3]; float zprobe_zoffset; float Kp; diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index 24f76f96..be4b5a8e 100644 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -5700,7 +5700,7 @@ Sigma_Exit: float value = code_value(); if(value < 20.0) { float factor = cs.axis_steps_per_unit[i] / value; // increase e constants if M92 E14 is given for netfab. - max_jerk[E_AXIS] *= factor; + cs.max_jerk[E_AXIS] *= factor; max_feedrate[i] *= factor; axis_steps_per_sqr_second[i] *= factor; } @@ -5964,12 +5964,12 @@ Sigma_Exit: if(code_seen('S')) cs.minimumfeedrate = code_value(); if(code_seen('T')) cs.mintravelfeedrate = code_value(); if(code_seen('B')) cs.minsegmenttime = code_value() ; - if(code_seen('X')) max_jerk[X_AXIS] = max_jerk[Y_AXIS] = code_value(); - if(code_seen('Y')) max_jerk[Y_AXIS] = code_value(); - if(code_seen('Z')) max_jerk[Z_AXIS] = code_value(); - if(code_seen('E')) max_jerk[E_AXIS] = code_value(); - if (max_jerk[X_AXIS] > DEFAULT_XJERK) max_jerk[X_AXIS] = DEFAULT_XJERK; - if (max_jerk[Y_AXIS] > DEFAULT_YJERK) max_jerk[Y_AXIS] = DEFAULT_YJERK; + if(code_seen('X')) cs.max_jerk[X_AXIS] = cs.max_jerk[Y_AXIS] = code_value(); + if(code_seen('Y')) cs.max_jerk[Y_AXIS] = code_value(); + if(code_seen('Z')) cs.max_jerk[Z_AXIS] = code_value(); + if(code_seen('E')) cs.max_jerk[E_AXIS] = code_value(); + if (cs.max_jerk[X_AXIS] > DEFAULT_XJERK) cs.max_jerk[X_AXIS] = DEFAULT_XJERK; + if (cs.max_jerk[Y_AXIS] > DEFAULT_YJERK) cs.max_jerk[Y_AXIS] = DEFAULT_YJERK; } break; case 206: // M206 additional homing offset diff --git a/Firmware/planner.cpp b/Firmware/planner.cpp index fdbf6476..05f9ba70 100644 --- a/Firmware/planner.cpp +++ b/Firmware/planner.cpp @@ -80,9 +80,6 @@ float* max_feedrate = cs.max_feedrate_normal; // Use M201 to override by software unsigned long max_acceleration_units_per_sq_second_silent[NUM_AXIS]; unsigned long* max_acceleration_units_per_sq_second = cs.max_acceleration_units_per_sq_second_normal; - -// Jerk is a maximum immediate velocity change. -float max_jerk[NUM_AXIS]; unsigned long axis_steps_per_sqr_second[NUM_AXIS]; #ifdef ENABLE_AUTO_BED_LEVELING @@ -1042,20 +1039,20 @@ Having the real displacement of the head, we can calculate the total movement le bool limited = false; for (uint8_t axis = 0; axis < 4; ++ axis) { float jerk = fabs(current_speed[axis]); - if (jerk > max_jerk[axis]) { + if (jerk > cs.max_jerk[axis]) { // The actual jerk is lower, if it has been limited by the XY jerk. if (limited) { // Spare one division by a following gymnastics: // Instead of jerk *= safe_speed / block->nominal_speed, // multiply max_jerk[axis] by the divisor. jerk *= safe_speed; - float mjerk = max_jerk[axis] * block->nominal_speed; + float mjerk = cs.max_jerk[axis] * block->nominal_speed; if (jerk > mjerk) { safe_speed *= mjerk / jerk; limited = true; } } else { - safe_speed = max_jerk[axis]; + safe_speed = cs.max_jerk[axis]; limited = true; } } @@ -1108,8 +1105,8 @@ Having the real displacement of the head, we can calculate the total movement le (v_entry - v_exit) : // axis reversal max(- v_exit, v_entry)); - if (jerk > max_jerk[axis]) { - v_factor *= max_jerk[axis] / jerk; + if (jerk > cs.max_jerk[axis]) { + v_factor *= cs.max_jerk[axis] / jerk; limited = true; } } diff --git a/Firmware/planner.h b/Firmware/planner.h index d64386ab..892c62a4 100644 --- a/Firmware/planner.h +++ b/Firmware/planner.h @@ -166,9 +166,6 @@ extern float* max_feedrate; // Use M201 to override by software extern unsigned long max_acceleration_units_per_sq_second_silent[NUM_AXIS]; extern unsigned long* max_acceleration_units_per_sq_second; - -// Jerk is a maximum immediate velocity change. -extern float max_jerk[NUM_AXIS]; extern unsigned long axis_steps_per_sqr_second[NUM_AXIS]; extern long position[NUM_AXIS]; From 959d0069fa75e178330c75cadfb77f27eb9a708e Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Mon, 24 Sep 2018 16:42:28 +0200 Subject: [PATCH 125/141] Use cs.add_homing from ConfigurationStore. --- Firmware/ConfigurationStore.cpp | 4 ++-- Firmware/Marlin.h | 1 - Firmware/Marlin_main.cpp | 21 +++++++++------------ 3 files changed, 11 insertions(+), 15 deletions(-) diff --git a/Firmware/ConfigurationStore.cpp b/Firmware/ConfigurationStore.cpp index 356c7b83..1969658d 100644 --- a/Firmware/ConfigurationStore.cpp +++ b/Firmware/ConfigurationStore.cpp @@ -104,7 +104,7 @@ void Config_PrintSettings(uint8_t level) echomagic, echomagic, max_acceleration_units_per_sq_second_silent[X_AXIS], max_acceleration_units_per_sq_second_silent[Y_AXIS], max_acceleration_units_per_sq_second_silent[Z_AXIS], max_acceleration_units_per_sq_second_silent[E_AXIS], echomagic, echomagic, cs.acceleration, cs.retract_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, add_homing[X_AXIS], add_homing[Y_AXIS], add_homing[Z_AXIS] + echomagic, echomagic, cs.add_homing[X_AXIS], cs.add_homing[Y_AXIS], cs.add_homing[Z_AXIS] #else //TMC2130 printf_P(PSTR( "%SSteps per unit:\n%S M92 X%.2f Y%.2f Z%.2f E%.2f\n" @@ -119,7 +119,7 @@ void Config_PrintSettings(uint8_t level) 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.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, add_homing[X_AXIS], add_homing[Y_AXIS], add_homing[Z_AXIS] + echomagic, echomagic, cs.add_homing[X_AXIS], cs.add_homing[Y_AXIS], cs.add_homing[Z_AXIS] #endif //TMC2130 ); #ifdef PIDTEMP diff --git a/Firmware/Marlin.h b/Firmware/Marlin.h index 13f04557..035633c7 100644 --- a/Firmware/Marlin.h +++ b/Firmware/Marlin.h @@ -275,7 +275,6 @@ extern float filament_size[EXTRUDERS]; // cross-sectional area of filament (in m 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 current_position[NUM_AXIS] ; extern float destination[NUM_AXIS] ; -extern float add_homing[3]; extern float min_pos[3]; extern float max_pos[3]; extern bool axis_known_position[3]; diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index be4b5a8e..b3264590 100644 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -393,9 +393,6 @@ float current_position[NUM_AXIS] = { 0.0, 0.0, 0.0, 0.0 }; #define _z current_position[Z_AXIS] #define _e current_position[E_AXIS] - -float add_homing[3]={0,0,0}; - float min_pos[3] = { X_MIN_POS, Y_MIN_POS, Z_MIN_POS }; float max_pos[3] = { X_MAX_POS, Y_MAX_POS, Z_MAX_POS }; bool axis_known_position[3] = {false, false, false}; @@ -2010,9 +2007,9 @@ XYZ_CONSTS_FROM_CONFIG(float, home_retract_mm, HOME_RETRACT_MM); XYZ_CONSTS_FROM_CONFIG(signed char, home_dir, HOME_DIR); static void axis_is_at_home(int axis) { - current_position[axis] = base_home_pos(axis) + add_homing[axis]; - min_pos[axis] = base_min_pos(axis) + add_homing[axis]; - max_pos[axis] = base_max_pos(axis) + add_homing[axis]; + current_position[axis] = base_home_pos(axis) + cs.add_homing[axis]; + min_pos[axis] = base_min_pos(axis) + cs.add_homing[axis]; + max_pos[axis] = base_max_pos(axis) + cs.add_homing[axis]; } @@ -2691,10 +2688,10 @@ void gcode_G28(bool home_x_axis, long home_x_value, bool home_y_axis, long home_ if(home_x_axis && home_x_value != 0) - current_position[X_AXIS]=home_x_value+add_homing[X_AXIS]; + current_position[X_AXIS]=home_x_value+cs.add_homing[X_AXIS]; if(home_y_axis && home_y_value != 0) - current_position[Y_AXIS]=home_y_value+add_homing[Y_AXIS]; + current_position[Y_AXIS]=home_y_value+cs.add_homing[Y_AXIS]; #if Z_HOME_DIR < 0 // If homing towards BED do Z last #ifndef Z_SAFE_HOMING @@ -2790,7 +2787,7 @@ void gcode_G28(bool home_x_axis, long home_x_value, bool home_y_axis, long home_ #endif // Z_HOME_DIR < 0 if(home_z_axis && home_z_value != 0) - current_position[Z_AXIS]=home_z_value+add_homing[Z_AXIS]; + current_position[Z_AXIS]=home_z_value+cs.add_homing[Z_AXIS]; #ifdef ENABLE_AUTO_BED_LEVELING if(home_z) current_position[Z_AXIS] += zprobe_zoffset; //Add Z_Probe offset (the distance is negative) @@ -4743,7 +4740,7 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) plan_set_e_position(current_position[E_AXIS]); } else { - current_position[i] = code_value()+add_homing[i]; + current_position[i] = code_value()+cs.add_homing[i]; plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]); } } @@ -5975,7 +5972,7 @@ Sigma_Exit: case 206: // M206 additional homing offset for(int8_t i=0; i < 3; i++) { - if(code_seen(axis_codes[i])) add_homing[i] = code_value(); + if(code_seen(axis_codes[i])) cs.add_homing[i] = code_value(); } break; #ifdef FWRETRACT @@ -7142,7 +7139,7 @@ void clamp_to_software_endstops(float target[3]) float negative_z_offset = 0; #ifdef ENABLE_AUTO_BED_LEVELING if (Z_PROBE_OFFSET_FROM_EXTRUDER < 0) negative_z_offset = negative_z_offset + Z_PROBE_OFFSET_FROM_EXTRUDER; - if (add_homing[Z_AXIS] < 0) negative_z_offset = negative_z_offset + add_homing[Z_AXIS]; + if (cs.add_homing[Z_AXIS] < 0) negative_z_offset = negative_z_offset + cs.add_homing[Z_AXIS]; #endif if (target[Z_AXIS] < min_pos[Z_AXIS]+negative_z_offset) target[Z_AXIS] = min_pos[Z_AXIS]+negative_z_offset; } From f2ae3fb1f754e047b7a86ad03f85030ce109de5c Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Mon, 24 Sep 2018 16:47:57 +0200 Subject: [PATCH 126/141] Use cs.zprobe_zoffset from ConfigurationStore. --- Firmware/Marlin.h | 1 - Firmware/Marlin_main.cpp | 11 +++++------ 2 files changed, 5 insertions(+), 7 deletions(-) diff --git a/Firmware/Marlin.h b/Firmware/Marlin.h index 035633c7..9791b420 100644 --- a/Firmware/Marlin.h +++ b/Firmware/Marlin.h @@ -278,7 +278,6 @@ extern float destination[NUM_AXIS] ; extern float min_pos[3]; extern float max_pos[3]; extern bool axis_known_position[3]; -extern float zprobe_zoffset; extern int fanSpeed; extern void homeaxis(int axis, uint8_t cnt = 1, uint8_t* pstep = 0); diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index b3264590..63633da4 100644 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -396,7 +396,6 @@ float current_position[NUM_AXIS] = { 0.0, 0.0, 0.0, 0.0 }; float min_pos[3] = { X_MIN_POS, Y_MIN_POS, Z_MIN_POS }; float max_pos[3] = { X_MAX_POS, Y_MAX_POS, Z_MAX_POS }; bool axis_known_position[3] = {false, false, false}; -float zprobe_zoffset; // Extruder offset #if EXTRUDERS > 1 @@ -2058,7 +2057,7 @@ static void set_bed_level_equation_lsq(double *plane_equation_coefficients) current_position[Z_AXIS] = corrected_position.z; // put the bed at 0 so we don't go below it. - current_position[Z_AXIS] = zprobe_zoffset; // in the lsq we reach here after raising the extruder due to the loop structure + 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]); } @@ -2086,7 +2085,7 @@ static void set_bed_level_equation_3pts(float z_at_pt_1, float z_at_pt_2, float current_position[Z_AXIS] = corrected_position.z; // put the bed at 0 so we don't go below it. - current_position[Z_AXIS] = zprobe_zoffset; + 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]); @@ -2790,7 +2789,7 @@ void gcode_G28(bool home_x_axis, long home_x_value, bool home_y_axis, long home_ current_position[Z_AXIS]=home_z_value+cs.add_homing[Z_AXIS]; #ifdef ENABLE_AUTO_BED_LEVELING if(home_z) - current_position[Z_AXIS] += zprobe_zoffset; //Add Z_Probe offset (the distance is negative) + current_position[Z_AXIS] += cs.zprobe_zoffset; //Add Z_Probe offset (the distance is negative) #endif // Set the planner and stepper routine positions. @@ -6376,7 +6375,7 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) value = code_value(); if ((Z_PROBE_OFFSET_RANGE_MIN <= value) && (value <= Z_PROBE_OFFSET_RANGE_MAX)) { - zprobe_zoffset = -value; // compare w/ line 278 of ConfigurationStore.cpp + cs.zprobe_zoffset = -value; // compare w/ line 278 of ConfigurationStore.cpp SERIAL_ECHO_START; SERIAL_ECHOLNRPGM(CAT4(MSG_ZPROBE_ZOFFSET, " ", _T(MSG_OK),PSTR(""))); SERIAL_PROTOCOLLN(""); @@ -6396,7 +6395,7 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) { SERIAL_ECHO_START; SERIAL_ECHOLNRPGM(CAT2(MSG_ZPROBE_ZOFFSET, PSTR(" : "))); - SERIAL_ECHO(-zprobe_zoffset); + SERIAL_ECHO(-cs.zprobe_zoffset); SERIAL_PROTOCOLLN(""); } break; From 54bcc8aa528341d0c5b614de8a53d958392be90b Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Mon, 24 Sep 2018 16:54:50 +0200 Subject: [PATCH 127/141] Use cs.Kp, cs.Ki and cs.Kd from ConfigurationStore. --- Firmware/ConfigurationStore.cpp | 2 +- Firmware/Marlin_main.cpp | 12 ++++++------ Firmware/temperature.cpp | 14 ++++++-------- Firmware/temperature.h | 2 +- 4 files changed, 14 insertions(+), 16 deletions(-) diff --git a/Firmware/ConfigurationStore.cpp b/Firmware/ConfigurationStore.cpp index 1969658d..1b558389 100644 --- a/Firmware/ConfigurationStore.cpp +++ b/Firmware/ConfigurationStore.cpp @@ -124,7 +124,7 @@ void Config_PrintSettings(uint8_t level) ); #ifdef PIDTEMP printf_P(PSTR("%SPID settings:\n%S M301 P%.2f I%.2f D%.2f\n"), - echomagic, echomagic, Kp, unscalePID_i(Ki), unscalePID_d(Kd)); + echomagic, echomagic, cs.Kp, unscalePID_i(cs.Ki), unscalePID_d(cs.Kd)); #endif #ifdef PIDTEMPBED printf_P(PSTR("%SPID heatbed settings:\n%S M304 P%.2f I%.2f D%.2f\n"), diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index 63633da4..cc55f0c4 100644 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -6212,9 +6212,9 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) #ifdef PIDTEMP case 301: // M301 { - if(code_seen('P')) Kp = code_value(); - if(code_seen('I')) Ki = scalePID_i(code_value()); - if(code_seen('D')) Kd = scalePID_d(code_value()); + if(code_seen('P')) cs.Kp = code_value(); + if(code_seen('I')) cs.Ki = scalePID_i(code_value()); + if(code_seen('D')) cs.Kd = scalePID_d(code_value()); #ifdef PID_ADD_EXTRUSION_RATE if(code_seen('C')) Kc = code_value(); @@ -6223,11 +6223,11 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) updatePID(); SERIAL_PROTOCOLRPGM(_T(MSG_OK)); SERIAL_PROTOCOL(" p:"); - SERIAL_PROTOCOL(Kp); + SERIAL_PROTOCOL(cs.Kp); SERIAL_PROTOCOL(" i:"); - SERIAL_PROTOCOL(unscalePID_i(Ki)); + SERIAL_PROTOCOL(unscalePID_i(cs.Ki)); SERIAL_PROTOCOL(" d:"); - SERIAL_PROTOCOL(unscalePID_d(Kd)); + SERIAL_PROTOCOL(unscalePID_d(cs.Kd)); #ifdef PID_ADD_EXTRUSION_RATE SERIAL_PROTOCOL(" c:"); //Kc does not have scaling applied above, or in resetting defaults diff --git a/Firmware/temperature.cpp b/Firmware/temperature.cpp index 6a21b825..7054703b 100644 --- a/Firmware/temperature.cpp +++ b/Firmware/temperature.cpp @@ -39,6 +39,7 @@ #include #include "adc.h" +#include "ConfigurationStore.h" //=========================================================================== @@ -79,9 +80,6 @@ float current_temperature_bed = 0.0; float _Kp, _Ki, _Kd; int pid_cycle, pid_number_of_cycles; bool pid_tuning_finished = false; - float Kp=DEFAULT_Kp; - float Ki=(DEFAULT_Ki*PID_dT); - float Kd=(DEFAULT_Kd/PID_dT); #ifdef PID_ADD_EXTRUSION_RATE float Kc=DEFAULT_Kc; #endif @@ -422,7 +420,7 @@ void updatePID() { #ifdef PIDTEMP for(int e = 0; e < EXTRUDERS; e++) { - temp_iState_max[e] = PID_INTEGRAL_DRIVE_MAX / Ki; + temp_iState_max[e] = PID_INTEGRAL_DRIVE_MAX / cs.Ki; } #endif #ifdef PIDTEMPBED @@ -638,14 +636,14 @@ void manage_heater() temp_iState[e] = 0.0; pid_reset[e] = false; } - pTerm[e] = Kp * pid_error[e]; + pTerm[e] = cs.Kp * pid_error[e]; temp_iState[e] += pid_error[e]; temp_iState[e] = constrain(temp_iState[e], temp_iState_min[e], temp_iState_max[e]); - iTerm[e] = Ki * temp_iState[e]; + iTerm[e] = cs.Ki * temp_iState[e]; //K1 defined in Configuration.h in the PID settings #define K2 (1.0-K1) - dTerm[e] = (Kd * (pid_input - temp_dState[e]))*K2 + (K1 * dTerm[e]); + dTerm[e] = (cs.Kd * (pid_input - temp_dState[e]))*K2 + (K1 * dTerm[e]); pid_output = pTerm[e] + iTerm[e] - dTerm[e]; if (pid_output > PID_MAX) { if (pid_error[e] > 0 ) temp_iState[e] -= pid_error[e]; // conditional un-integration @@ -1040,7 +1038,7 @@ void tp_init() maxttemp[e] = maxttemp[0]; #ifdef PIDTEMP temp_iState_min[e] = 0.0; - temp_iState_max[e] = PID_INTEGRAL_DRIVE_MAX / Ki; + temp_iState_max[e] = PID_INTEGRAL_DRIVE_MAX / cs.Ki; #endif //PIDTEMP #ifdef PIDTEMPBED temp_iState_min_bed = 0.0; diff --git a/Firmware/temperature.h b/Firmware/temperature.h index 0633158c..f2929564 100644 --- a/Firmware/temperature.h +++ b/Firmware/temperature.h @@ -73,7 +73,7 @@ extern int current_voltage_raw_bed; #ifdef PIDTEMP extern int pid_cycle, pid_number_of_cycles; - extern float Kp,Ki,Kd,Kc,_Kp,_Ki,_Kd; + extern float Kc,_Kp,_Ki,_Kd; extern bool pid_tuning_finished; float scalePID_i(float i); float scalePID_d(float d); From 20ba2b1c79767d7b0fb65eff68c16221d7043b57 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Mon, 24 Sep 2018 16:57:48 +0200 Subject: [PATCH 128/141] Use cs.bedKp, cs.bedKi and cs.bedKd from ConfigurationStore. --- Firmware/ConfigurationStore.cpp | 2 +- Firmware/Marlin_main.cpp | 12 ++++++------ Firmware/temperature.cpp | 16 +++++----------- Firmware/temperature.h | 3 --- 4 files changed, 12 insertions(+), 21 deletions(-) diff --git a/Firmware/ConfigurationStore.cpp b/Firmware/ConfigurationStore.cpp index 1b558389..2b5095ef 100644 --- a/Firmware/ConfigurationStore.cpp +++ b/Firmware/ConfigurationStore.cpp @@ -128,7 +128,7 @@ void Config_PrintSettings(uint8_t level) #endif #ifdef PIDTEMPBED printf_P(PSTR("%SPID heatbed settings:\n%S M304 P%.2f I%.2f D%.2f\n"), - echomagic, echomagic, bedKp, unscalePID_i(bedKi), unscalePID_d(bedKd)); + echomagic, echomagic, cs.bedKp, unscalePID_i(cs.bedKi), unscalePID_d(cs.bedKd)); #endif #ifdef FWRETRACT printf_P(PSTR( diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index cc55f0c4..c53606ce 100644 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -6240,18 +6240,18 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) #ifdef PIDTEMPBED case 304: // M304 { - if(code_seen('P')) bedKp = code_value(); - if(code_seen('I')) bedKi = scalePID_i(code_value()); - if(code_seen('D')) bedKd = scalePID_d(code_value()); + if(code_seen('P')) cs.bedKp = code_value(); + if(code_seen('I')) cs.bedKi = scalePID_i(code_value()); + if(code_seen('D')) cs.bedKd = scalePID_d(code_value()); updatePID(); SERIAL_PROTOCOLRPGM(_T(MSG_OK)); SERIAL_PROTOCOL(" p:"); - SERIAL_PROTOCOL(bedKp); + SERIAL_PROTOCOL(cs.bedKp); SERIAL_PROTOCOL(" i:"); - SERIAL_PROTOCOL(unscalePID_i(bedKi)); + SERIAL_PROTOCOL(unscalePID_i(cs.bedKi)); SERIAL_PROTOCOL(" d:"); - SERIAL_PROTOCOL(unscalePID_d(bedKd)); + SERIAL_PROTOCOL(unscalePID_d(cs.bedKd)); SERIAL_PROTOCOLLN(""); } break; diff --git a/Firmware/temperature.cpp b/Firmware/temperature.cpp index 7054703b..a630f51b 100644 --- a/Firmware/temperature.cpp +++ b/Firmware/temperature.cpp @@ -84,12 +84,6 @@ float current_temperature_bed = 0.0; float Kc=DEFAULT_Kc; #endif #endif //PIDTEMP - -#ifdef PIDTEMPBED - float bedKp=DEFAULT_bedKp; - float bedKi=(DEFAULT_bedKi*PID_dT); - float bedKd=(DEFAULT_bedKd/PID_dT); -#endif //PIDTEMPBED #ifdef FAN_SOFT_PWM unsigned char fanSpeedSoftPwm; @@ -424,7 +418,7 @@ void updatePID() } #endif #ifdef PIDTEMPBED - temp_iState_max_bed = PID_INTEGRAL_DRIVE_MAX / bedKi; + temp_iState_max_bed = PID_INTEGRAL_DRIVE_MAX / cs.bedKi; #endif } @@ -751,14 +745,14 @@ void manage_heater() #ifndef PID_OPENLOOP pid_error_bed = target_temperature_bed - pid_input; - pTerm_bed = bedKp * pid_error_bed; + pTerm_bed = cs.bedKp * pid_error_bed; temp_iState_bed += pid_error_bed; temp_iState_bed = constrain(temp_iState_bed, temp_iState_min_bed, temp_iState_max_bed); - iTerm_bed = bedKi * temp_iState_bed; + iTerm_bed = cs.bedKi * temp_iState_bed; //K1 defined in Configuration.h in the PID settings #define K2 (1.0-K1) - dTerm_bed= (bedKd * (pid_input - temp_dState_bed))*K2 + (K1 * dTerm_bed); + dTerm_bed= (cs.bedKd * (pid_input - temp_dState_bed))*K2 + (K1 * dTerm_bed); temp_dState_bed = pid_input; pid_output = pTerm_bed + iTerm_bed - dTerm_bed; @@ -1042,7 +1036,7 @@ void tp_init() #endif //PIDTEMP #ifdef PIDTEMPBED temp_iState_min_bed = 0.0; - temp_iState_max_bed = PID_INTEGRAL_DRIVE_MAX / bedKi; + temp_iState_max_bed = PID_INTEGRAL_DRIVE_MAX / cs.bedKi; #endif //PIDTEMPBED } diff --git a/Firmware/temperature.h b/Firmware/temperature.h index f2929564..9a3cee83 100644 --- a/Firmware/temperature.h +++ b/Firmware/temperature.h @@ -81,9 +81,6 @@ extern int current_voltage_raw_bed; float unscalePID_d(float d); #endif -#ifdef PIDTEMPBED - extern float bedKp,bedKi,bedKd; -#endif #ifdef BABYSTEPPING From 7e593e6922a8207d4d43df22c74a8f8650eb5b1f Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Mon, 24 Sep 2018 17:03:10 +0200 Subject: [PATCH 129/141] Use cs.autoretract_enabled from ConfigurationStore. --- Firmware/ConfigurationStore.cpp | 2 +- Firmware/Marlin.h | 1 - Firmware/Marlin_main.cpp | 7 +++---- 3 files changed, 4 insertions(+), 6 deletions(-) diff --git a/Firmware/ConfigurationStore.cpp b/Firmware/ConfigurationStore.cpp index 2b5095ef..50ac9f6e 100644 --- a/Firmware/ConfigurationStore.cpp +++ b/Firmware/ConfigurationStore.cpp @@ -138,7 +138,7 @@ void Config_PrintSettings(uint8_t level) ), echomagic, echomagic, retract_length, retract_feedrate*60, retract_zlift, echomagic, echomagic, retract_recover_length, retract_recover_feedrate*60, - echomagic, echomagic, (autoretract_enabled ? 1 : 0) + echomagic, echomagic, (cs.autoretract_enabled ? 1 : 0) ); #if EXTRUDERS > 1 printf_P(PSTR("%SMulti-extruder settings:\n%S Swap retract length (mm): %.2f\n%S Swap rec. addl. length (mm): %.2f\n"), diff --git a/Firmware/Marlin.h b/Firmware/Marlin.h index 9791b420..29b6946e 100644 --- a/Firmware/Marlin.h +++ b/Firmware/Marlin.h @@ -287,7 +287,6 @@ extern unsigned char fanSpeedSoftPwm; #endif #ifdef FWRETRACT -extern bool autoretract_enabled; extern bool retracted[EXTRUDERS]; extern float retract_length, retract_length_swap, retract_feedrate, retract_zlift; extern float retract_recover_length, retract_recover_length_swap, retract_recover_feedrate; diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index c53606ce..6405d69e 100644 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -411,7 +411,6 @@ uint8_t active_extruder = 0; int fanSpeed=0; #ifdef FWRETRACT - bool autoretract_enabled=false; bool retracted[EXTRUDERS]={false #if EXTRUDERS > 1 , false @@ -3721,7 +3720,7 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) total_filament_used = total_filament_used + ((destination[E_AXIS] - current_position[E_AXIS]) * 100); } #ifdef FWRETRACT - if(autoretract_enabled) + if(cs.autoretract_enabled) if( !(code_seen('X') || code_seen('Y') || code_seen('Z')) && code_seen('E')) { float echange=destination[E_AXIS]-current_position[E_AXIS]; @@ -6010,7 +6009,7 @@ Sigma_Exit: { case 0: { - autoretract_enabled=false; + cs.autoretract_enabled=false; retracted[0]=false; #if EXTRUDERS > 1 retracted[1]=false; @@ -6021,7 +6020,7 @@ Sigma_Exit: }break; case 1: { - autoretract_enabled=true; + cs.autoretract_enabled=true; retracted[0]=false; #if EXTRUDERS > 1 retracted[1]=false; From a201128b20be3df5e33bc4c03fac0a9427340a0a Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Mon, 24 Sep 2018 17:10:25 +0200 Subject: [PATCH 130/141] Use cs.retract_length, cs.retract_feedrate, cs.retract_zlift, cs.retract_recover_length and cs.retract_recover_feedrate from ConfigurationStore. --- Firmware/ConfigurationStore.cpp | 4 ++-- Firmware/Marlin.h | 4 ++-- Firmware/Marlin_main.cpp | 27 +++++++++++---------------- 3 files changed, 15 insertions(+), 20 deletions(-) diff --git a/Firmware/ConfigurationStore.cpp b/Firmware/ConfigurationStore.cpp index 50ac9f6e..f88bb856 100644 --- a/Firmware/ConfigurationStore.cpp +++ b/Firmware/ConfigurationStore.cpp @@ -136,8 +136,8 @@ void Config_PrintSettings(uint8_t level) "%SRecover: S=Extra length (mm) F:Speed (mm/m)\n%S M208 S%.2f F%.2f\n" "%SAuto-Retract: S=0 to disable, 1 to interpret extrude-only moves as retracts or recoveries\n%S M209 S%d\n" ), - echomagic, echomagic, retract_length, retract_feedrate*60, retract_zlift, - echomagic, echomagic, retract_recover_length, retract_recover_feedrate*60, + echomagic, echomagic, cs.retract_length, cs.retract_feedrate*60, cs.retract_zlift, + echomagic, echomagic, cs.retract_recover_length, cs.retract_recover_feedrate*60, echomagic, echomagic, (cs.autoretract_enabled ? 1 : 0) ); #if EXTRUDERS > 1 diff --git a/Firmware/Marlin.h b/Firmware/Marlin.h index 29b6946e..383ee8cf 100644 --- a/Firmware/Marlin.h +++ b/Firmware/Marlin.h @@ -288,8 +288,8 @@ extern unsigned char fanSpeedSoftPwm; #ifdef FWRETRACT extern bool retracted[EXTRUDERS]; -extern float retract_length, retract_length_swap, retract_feedrate, retract_zlift; -extern float retract_recover_length, retract_recover_length_swap, retract_recover_feedrate; +extern float retract_length_swap; +extern float retract_recover_length_swap; #endif #ifdef HOST_KEEPALIVE_FEATURE diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index 6405d69e..6b691eeb 100644 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -428,13 +428,8 @@ int fanSpeed=0; #endif }; - float retract_length = RETRACT_LENGTH; float retract_length_swap = RETRACT_LENGTH_SWAP; - float retract_feedrate = RETRACT_FEEDRATE; - float retract_zlift = RETRACT_ZLIFT; - float retract_recover_length = RETRACT_RECOVER_LENGTH; float retract_recover_length_swap = RETRACT_RECOVER_LENGTH_SWAP; - float retract_recover_feedrate = RETRACT_RECOVER_FEEDRATE; #endif #ifdef PS_DEFAULT_OFF @@ -2416,13 +2411,13 @@ void refresh_cmd_timeout(void) destination[Y_AXIS]=current_position[Y_AXIS]; destination[Z_AXIS]=current_position[Z_AXIS]; destination[E_AXIS]=current_position[E_AXIS]; - current_position[E_AXIS]+=(swapretract?retract_length_swap:retract_length)*float(extrudemultiply)*0.01f; + current_position[E_AXIS]+=(swapretract?retract_length_swap:cs.retract_length)*float(extrudemultiply)*0.01f; plan_set_e_position(current_position[E_AXIS]); float oldFeedrate = feedrate; - feedrate=retract_feedrate*60; + feedrate=cs.retract_feedrate*60; retracted[active_extruder]=true; prepare_move(); - current_position[Z_AXIS]-=retract_zlift; + 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]); prepare_move(); feedrate = oldFeedrate; @@ -2431,12 +2426,12 @@ void refresh_cmd_timeout(void) destination[Y_AXIS]=current_position[Y_AXIS]; destination[Z_AXIS]=current_position[Z_AXIS]; destination[E_AXIS]=current_position[E_AXIS]; - current_position[Z_AXIS]+=retract_zlift; + 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]); - current_position[E_AXIS]-=(swapretract?(retract_length_swap+retract_recover_length_swap):(retract_length+retract_recover_length))*float(extrudemultiply)*0.01f; + 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; - feedrate=retract_recover_feedrate*60; + feedrate=cs.retract_recover_feedrate*60; retracted[active_extruder]=false; prepare_move(); feedrate = oldFeedrate; @@ -5978,26 +5973,26 @@ Sigma_Exit: { if(code_seen('S')) { - retract_length = code_value() ; + cs.retract_length = code_value() ; } if(code_seen('F')) { - retract_feedrate = code_value()/60 ; + cs.retract_feedrate = code_value()/60 ; } if(code_seen('Z')) { - retract_zlift = code_value() ; + cs.retract_zlift = code_value() ; } }break; case 208: // M208 - set retract recover length S[positive mm surplus to the M207 S*] F[feedrate mm/min] { if(code_seen('S')) { - retract_recover_length = code_value() ; + cs.retract_recover_length = code_value() ; } if(code_seen('F')) { - retract_recover_feedrate = code_value()/60 ; + cs.retract_recover_feedrate = code_value()/60 ; } }break; case 209: // M209 - S<1=true/0=false> enable automatic retract detect if the slicer did not support G10/11: every normal extrude-only move will be classified as retract depending on the direction. From e225e9cab01a7b70f9bdba5423409fdebe6c4c5a Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Mon, 24 Sep 2018 17:12:16 +0200 Subject: [PATCH 131/141] Use cs.volumetric_enabled from ConfigurationStore. --- Firmware/ConfigurationStore.cpp | 2 +- Firmware/Marlin.h | 1 - Firmware/Marlin_main.cpp | 7 +++---- 3 files changed, 4 insertions(+), 6 deletions(-) diff --git a/Firmware/ConfigurationStore.cpp b/Firmware/ConfigurationStore.cpp index f88bb856..7a7a005d 100644 --- a/Firmware/ConfigurationStore.cpp +++ b/Firmware/ConfigurationStore.cpp @@ -144,7 +144,7 @@ void Config_PrintSettings(uint8_t level) printf_P(PSTR("%SMulti-extruder settings:\n%S Swap retract length (mm): %.2f\n%S Swap rec. addl. length (mm): %.2f\n"), echomagic, echomagic, retract_length_swap, echomagic, retract_recover_length_swap); #endif - if (volumetric_enabled) { + if (cs.volumetric_enabled) { printf_P(PSTR("%SFilament settings:\n%S M200 D%.2f\n"), echomagic, echomagic, filament_size[0]); #if EXTRUDERS > 1 diff --git a/Firmware/Marlin.h b/Firmware/Marlin.h index 383ee8cf..91d0ce59 100644 --- a/Firmware/Marlin.h +++ b/Firmware/Marlin.h @@ -269,7 +269,6 @@ extern float homing_feedrate[]; extern bool axis_relative_modes[]; extern int feedmultiply; extern int extrudemultiply; // Sets extrude multiply factor (in percent) for all extruders -extern bool volumetric_enabled; extern int extruder_multiply[EXTRUDERS]; // sets extrude multiply factor (in percent) for each extruder individually extern float filament_size[EXTRUDERS]; // cross-sectional area of filament (in millimeters), typically around 1.75 or 2.85, 0 disables the volumetric calculations for the extruder. extern float volumetric_multiplier[EXTRUDERS]; // reciprocal of cross-sectional area of filament (in square millimeters), stored this way to reduce computational burden in planner diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index 6b691eeb..a09c4a44 100644 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -368,7 +368,6 @@ char dir_names[3][9]; bool sortAlpha = false; -bool volumetric_enabled = false; float filament_size[EXTRUDERS] = { DEFAULT_NOMINAL_FILAMENT_DIA #if EXTRUDERS > 1 , DEFAULT_NOMINAL_FILAMENT_DIA @@ -5847,7 +5846,7 @@ Sigma_Exit: // setting any extruder filament size disables volumetric on the assumption that // slicers either generate in extruder values as cubic mm or as as filament feeds // for all extruders - volumetric_enabled = false; + cs.volumetric_enabled = false; } else { filament_size[extruder] = (float)code_value(); // make sure all extruders have some sane value for the filament size @@ -5858,7 +5857,7 @@ Sigma_Exit: filament_size[2] = (filament_size[2] == 0.0 ? DEFAULT_NOMINAL_FILAMENT_DIA : filament_size[2]); #endif #endif - volumetric_enabled = true; + cs.volumetric_enabled = true; } } else { //reserved for setting filament diameter via UFID or filament measuring device @@ -7646,7 +7645,7 @@ void save_statistics(unsigned long _total_filament_used, unsigned long _total_pr float calculate_extruder_multiplier(float diameter) { float out = 1.f; - if (volumetric_enabled && diameter > 0.f) { + if (cs.volumetric_enabled && diameter > 0.f) { float area = M_PI * diameter * diameter * 0.25; out = 1.f / area; } From ca179a2d1886b621415caba6a6b0bb94e9a74fc4 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Mon, 24 Sep 2018 17:29:02 +0200 Subject: [PATCH 132/141] Use cs.filament_size from ConfigurationStore. --- Firmware/ConfigurationStore.cpp | 26 +++++++++++++++++--------- Firmware/ConfigurationStore.h | 2 +- Firmware/Marlin.h | 1 - Firmware/Marlin_main.cpp | 23 ++++++++--------------- 4 files changed, 26 insertions(+), 26 deletions(-) diff --git a/Firmware/ConfigurationStore.cpp b/Firmware/ConfigurationStore.cpp index 7a7a005d..67e41d5a 100644 --- a/Firmware/ConfigurationStore.cpp +++ b/Firmware/ConfigurationStore.cpp @@ -146,13 +146,13 @@ void Config_PrintSettings(uint8_t level) #endif if (cs.volumetric_enabled) { printf_P(PSTR("%SFilament settings:\n%S M200 D%.2f\n"), - echomagic, echomagic, filament_size[0]); + echomagic, echomagic, cs.filament_size[0]); #if EXTRUDERS > 1 printf_P(PSTR("%S M200 T1 D%.2f\n"), - echomagic, echomagic, filament_size[1]); + echomagic, echomagic, cs.filament_size[1]); #if EXTRUDERS > 2 printf_P(PSTR("%S M200 T1 D%.2f\n"), - echomagic, echomagic, filament_size[2]); + echomagic, echomagic, cs.filament_size[2]); #endif #endif } else { @@ -171,13 +171,17 @@ void Config_PrintSettings(uint8_t level) #ifdef EEPROM_SETTINGS -static_assert (EXTRUDERS == 1, "ConfigurationStore M500_conf not implemented for more extruders."); -static_assert (NUM_AXIS == 4, "ConfigurationStore M500_conf not implemented for more axis."); +static_assert (EXTRUDERS == 1, "ConfigurationStore M500_conf not implemented for more extruders, fix filament_size array size."); +static_assert (NUM_AXIS == 4, "ConfigurationStore M500_conf not implemented for more axis." + "Fix axis_steps_per_unit max_feedrate_normal max_acceleration_units_per_sq_second_normal max_jerk max_feedrate_silent" + " max_acceleration_units_per_sq_second_silent array size."); #ifdef ENABLE_AUTO_BED_LEVELING static_assert (false, "zprobe_zoffset was not initialized in printers in field to -(Z_PROBE_OFFSET_FROM_EXTRUDER), so it contains" "0.0, if this is not acceptable, increment EEPROM_VERSION to force use default_conf"); #endif +static_assert (sizeof(M500_conf) == 188, "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"); static const M500_conf default_conf PROGMEM = { @@ -207,14 +211,18 @@ static const M500_conf default_conf PROGMEM = RETRACT_RECOVER_LENGTH, RETRACT_RECOVER_FEEDRATE, false, - {DEFAULT_NOMINAL_FILAMENT_DIA}, + {DEFAULT_NOMINAL_FILAMENT_DIA, +#if EXTRUDERS > 1 + DEFAULT_NOMINAL_FILAMENT_DIA, +#if EXTRUDERS > 2 + DEFAULT_NOMINAL_FILAMENT_DIA, +#endif +#endif + }, DEFAULT_MAX_FEEDRATE_SILENT, DEFAULT_MAX_ACCELERATION_SILENT, }; -static_assert (sizeof(M500_conf) == 188, "sizeof(M500_conf) has changed, ensure that version has been incremented, " - "or if you added members in the end of struct, ensure that historically uninitialized values will be initialized"); - //! //! @retval true Stored or default settings retrieved //! @retval false default settings retrieved, eeprom was erased. diff --git a/Firmware/ConfigurationStore.h b/Firmware/ConfigurationStore.h index 8abab432..b4bdfe94 100644 --- a/Firmware/ConfigurationStore.h +++ b/Firmware/ConfigurationStore.h @@ -32,7 +32,7 @@ typedef struct float retract_recover_length; float retract_recover_feedrate; bool volumetric_enabled; - float filament_size[1]; + float filament_size[1]; //!< cross-sectional area of filament (in millimeters), typically around 1.75 or 2.85, 0 disables the volumetric calculations for the extruder. float max_feedrate_silent[4]; unsigned long max_acceleration_units_per_sq_second_silent[4]; } __attribute__ ((packed)) M500_conf; diff --git a/Firmware/Marlin.h b/Firmware/Marlin.h index 91d0ce59..3dd626aa 100644 --- a/Firmware/Marlin.h +++ b/Firmware/Marlin.h @@ -270,7 +270,6 @@ extern bool axis_relative_modes[]; 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 filament_size[EXTRUDERS]; // cross-sectional area of filament (in millimeters), typically around 1.75 or 2.85, 0 disables the volumetric calculations for the extruder. extern float volumetric_multiplier[EXTRUDERS]; // reciprocal of cross-sectional area of filament (in square millimeters), stored this way to reduce computational burden in planner extern float current_position[NUM_AXIS] ; extern float destination[NUM_AXIS] ; diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index a09c4a44..0dd2ac4f 100644 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -368,14 +368,7 @@ char dir_names[3][9]; bool sortAlpha = false; -float filament_size[EXTRUDERS] = { DEFAULT_NOMINAL_FILAMENT_DIA - #if EXTRUDERS > 1 - , DEFAULT_NOMINAL_FILAMENT_DIA - #if EXTRUDERS > 2 - , DEFAULT_NOMINAL_FILAMENT_DIA - #endif - #endif -}; + float extruder_multiplier[EXTRUDERS] = {1.0 #if EXTRUDERS > 1 , 1.0 @@ -5848,13 +5841,13 @@ Sigma_Exit: // for all extruders cs.volumetric_enabled = false; } else { - filament_size[extruder] = (float)code_value(); + cs.filament_size[extruder] = (float)code_value(); // make sure all extruders have some sane value for the filament size - filament_size[0] = (filament_size[0] == 0.0 ? DEFAULT_NOMINAL_FILAMENT_DIA : filament_size[0]); + cs.filament_size[0] = (cs.filament_size[0] == 0.0 ? DEFAULT_NOMINAL_FILAMENT_DIA : cs.filament_size[0]); #if EXTRUDERS > 1 - filament_size[1] = (filament_size[1] == 0.0 ? DEFAULT_NOMINAL_FILAMENT_DIA : filament_size[1]); + cs.filament_size[1] = (cs.filament_size[1] == 0.0 ? DEFAULT_NOMINAL_FILAMENT_DIA : cs.filament_size[1]); #if EXTRUDERS > 2 - filament_size[2] = (filament_size[2] == 0.0 ? DEFAULT_NOMINAL_FILAMENT_DIA : filament_size[2]); + cs.filament_size[2] = (cs.filament_size[2] == 0.0 ? DEFAULT_NOMINAL_FILAMENT_DIA : cs.filament_size[2]); #endif #endif cs.volumetric_enabled = true; @@ -7655,11 +7648,11 @@ float calculate_extruder_multiplier(float diameter) { } void calculate_extruder_multipliers() { - extruder_multiplier[0] = calculate_extruder_multiplier(filament_size[0]); + extruder_multiplier[0] = calculate_extruder_multiplier(cs.filament_size[0]); #if EXTRUDERS > 1 - extruder_multiplier[1] = calculate_extruder_multiplier(filament_size[1]); + extruder_multiplier[1] = calculate_extruder_multiplier(cs.filament_size[1]); #if EXTRUDERS > 2 - extruder_multiplier[2] = calculate_extruder_multiplier(filament_size[2]); + extruder_multiplier[2] = calculate_extruder_multiplier(cs.filament_size[2]); #endif #endif } From c38fef281db746ba579d5ec8963b5b8615a5e5eb Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Mon, 24 Sep 2018 17:33:58 +0200 Subject: [PATCH 133/141] Use cs.max_feedrate_silent, cs.max_acceleration_units_per_sq_second_silent from ConfigurationStore. --- Firmware/ConfigurationStore.cpp | 12 ++++++------ Firmware/ConfigurationStore.h | 2 +- Firmware/Marlin_main.cpp | 4 ++-- Firmware/planner.cpp | 6 ++---- Firmware/planner.h | 2 -- 5 files changed, 11 insertions(+), 15 deletions(-) diff --git a/Firmware/ConfigurationStore.cpp b/Firmware/ConfigurationStore.cpp index 67e41d5a..3295f1b4 100644 --- a/Firmware/ConfigurationStore.cpp +++ b/Firmware/ConfigurationStore.cpp @@ -99,9 +99,9 @@ void Config_PrintSettings(uint8_t level) ), 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, cs.max_feedrate_normal[X_AXIS], cs.max_feedrate_normal[Y_AXIS], cs.max_feedrate_normal[Z_AXIS], cs.max_feedrate_normal[E_AXIS], - echomagic, echomagic, max_feedrate_silent[X_AXIS], max_feedrate_silent[Y_AXIS], max_feedrate_silent[Z_AXIS], max_feedrate_silent[E_AXIS], + 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, max_acceleration_units_per_sq_second_silent[X_AXIS], max_acceleration_units_per_sq_second_silent[Y_AXIS], max_acceleration_units_per_sq_second_silent[Z_AXIS], max_acceleration_units_per_sq_second_silent[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.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] @@ -250,12 +250,12 @@ bool Config_RetrieveSettings(uint16_t offset) { if (cs.max_feedrate_normal[j] > NORMAL_MAX_FEEDRATE_XY) cs.max_feedrate_normal[j] = NORMAL_MAX_FEEDRATE_XY; - if (max_feedrate_silent[j] > SILENT_MAX_FEEDRATE_XY) - max_feedrate_silent[j] = SILENT_MAX_FEEDRATE_XY; + if (cs.max_feedrate_silent[j] > SILENT_MAX_FEEDRATE_XY) + cs.max_feedrate_silent[j] = SILENT_MAX_FEEDRATE_XY; if (cs.max_acceleration_units_per_sq_second_normal[j] > NORMAL_MAX_ACCEL_XY) cs.max_acceleration_units_per_sq_second_normal[j] = NORMAL_MAX_ACCEL_XY; - if (max_acceleration_units_per_sq_second_silent[j] > SILENT_MAX_ACCEL_XY) - max_acceleration_units_per_sq_second_silent[j] = SILENT_MAX_ACCEL_XY; + if (cs.max_acceleration_units_per_sq_second_silent[j] > SILENT_MAX_ACCEL_XY) + cs.max_acceleration_units_per_sq_second_silent[j] = SILENT_MAX_ACCEL_XY; } #endif //TMC2130 diff --git a/Firmware/ConfigurationStore.h b/Firmware/ConfigurationStore.h index b4bdfe94..761ec95a 100644 --- a/Firmware/ConfigurationStore.h +++ b/Firmware/ConfigurationStore.h @@ -33,7 +33,7 @@ typedef struct float retract_recover_feedrate; bool volumetric_enabled; float filament_size[1]; //!< cross-sectional area of filament (in millimeters), typically around 1.75 or 2.85, 0 disables the volumetric calculations for the extruder. - float max_feedrate_silent[4]; + float max_feedrate_silent[4]; //!< max speeds for silent mode unsigned long max_acceleration_units_per_sq_second_silent[4]; } __attribute__ ((packed)) M500_conf; diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index 0dd2ac4f..ca2dcb88 100644 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -5875,7 +5875,7 @@ Sigma_Exit: val_silent = SILENT_MAX_ACCEL_XY; } cs.max_acceleration_units_per_sq_second_normal[i] = val; - max_acceleration_units_per_sq_second_silent[i] = val_silent; + cs.max_acceleration_units_per_sq_second_silent[i] = val_silent; #else //TMC2130 max_acceleration_units_per_sq_second[i] = val; #endif //TMC2130 @@ -5907,7 +5907,7 @@ Sigma_Exit: val_silent = SILENT_MAX_FEEDRATE_XY; } cs.max_feedrate_normal[i] = val; - max_feedrate_silent[i] = val_silent; + cs.max_feedrate_silent[i] = val_silent; #else //TMC2130 max_feedrate[i] = val; #endif //TMC2130 diff --git a/Firmware/planner.cpp b/Firmware/planner.cpp index 05f9ba70..8db1cd3c 100644 --- a/Firmware/planner.cpp +++ b/Firmware/planner.cpp @@ -73,12 +73,10 @@ //=========================================================================== // Use M203 to override by software -float max_feedrate_silent[NUM_AXIS]; // max speeds for silent mode float* max_feedrate = cs.max_feedrate_normal; // Use M201 to override by software -unsigned long max_acceleration_units_per_sq_second_silent[NUM_AXIS]; unsigned long* max_acceleration_units_per_sq_second = cs.max_acceleration_units_per_sq_second_normal; unsigned long axis_steps_per_sqr_second[NUM_AXIS]; @@ -1318,8 +1316,8 @@ void update_mode_profile() } else if (tmc2130_mode == TMC2130_MODE_SILENT) { - max_feedrate = max_feedrate_silent; - max_acceleration_units_per_sq_second = max_acceleration_units_per_sq_second_silent; + max_feedrate = cs.max_feedrate_silent; + max_acceleration_units_per_sq_second = cs.max_acceleration_units_per_sq_second_silent; } reset_acceleration_rates(); } diff --git a/Firmware/planner.h b/Firmware/planner.h index 892c62a4..b6a9f836 100644 --- a/Firmware/planner.h +++ b/Firmware/planner.h @@ -159,12 +159,10 @@ extern bool e_active(); void check_axes_activity(); // Use M203 to override by software -extern float max_feedrate_silent[NUM_AXIS]; extern float* max_feedrate; // Use M201 to override by software -extern unsigned long max_acceleration_units_per_sq_second_silent[NUM_AXIS]; extern unsigned long* max_acceleration_units_per_sq_second; extern unsigned long axis_steps_per_sqr_second[NUM_AXIS]; From 3662f60f8fb63538885d410602e61d1eb12ce18a Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Mon, 24 Sep 2018 17:57:35 +0200 Subject: [PATCH 134/141] if max_feedrate_silent and max_acceleration_units_per_sq_second_silent were never stored to eeprom, use default values; --- Firmware/ConfigurationStore.cpp | 17 +++++++++++++++++ 1 file changed, 17 insertions(+) diff --git a/Firmware/ConfigurationStore.cpp b/Firmware/ConfigurationStore.cpp index 3295f1b4..bd3656d8 100644 --- a/Firmware/ConfigurationStore.cpp +++ b/Firmware/ConfigurationStore.cpp @@ -245,6 +245,23 @@ bool Config_RetrieveSettings(uint16_t offset) calculate_extruder_multipliers(); + //if max_feedrate_silent and max_acceleration_units_per_sq_second_silent were never stored to eeprom, use default values: + { + const uint32_t erased = 0xffffffff; + bool initialized = false; + for (uint8_t i = 0; i < (sizeof(cs.max_feedrate_silent)/sizeof(cs.max_feedrate_silent[0])); ++i) + { + if(erased != reinterpret_cast(cs.max_feedrate_silent[i])) initialized = true; + if(erased != reinterpret_cast(cs.max_acceleration_units_per_sq_second_silent[i])) initialized = true; + } + if (!initialized) + { + memcpy_P(&cs.max_feedrate_silent,&default_conf.max_feedrate_silent, sizeof(cs.max_feedrate_silent)); + memcpy_P(&cs.max_acceleration_units_per_sq_second_silent,&default_conf.max_acceleration_units_per_sq_second_silent, + sizeof(cs.max_acceleration_units_per_sq_second_silent)); + } + } + #ifdef TMC2130 for (uint8_t j = X_AXIS; j <= Y_AXIS; j++) { From ccfcc6f98969610fe65640bda733416a57b14160 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Mon, 24 Sep 2018 18:32:01 +0200 Subject: [PATCH 135/141] Document. --- Firmware/ConfigurationStore.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Firmware/ConfigurationStore.cpp b/Firmware/ConfigurationStore.cpp index bd3656d8..858f3a65 100644 --- a/Firmware/ConfigurationStore.cpp +++ b/Firmware/ConfigurationStore.cpp @@ -224,8 +224,8 @@ static const M500_conf default_conf PROGMEM = }; //! -//! @retval true Stored or default settings retrieved -//! @retval false default settings retrieved, eeprom was erased. +//! @retval true Stored settings retrieved or default settings retrieved in case EEPROM has been erased. +//! @retval false default settings retrieved, because of older version or corrupted data bool Config_RetrieveSettings(uint16_t offset) { int i=offset; From 4151e19781137867de9a24580bc3c077a8c6cb5b Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Tue, 25 Sep 2018 16:27:20 +0200 Subject: [PATCH 136/141] Remove attribute packed. It is not needed on 8-bit platform. Change of platform would be detected by static_assert (sizeof(M500_conf) == 188). --- Firmware/ConfigurationStore.cpp | 4 +++- Firmware/ConfigurationStore.h | 2 +- 2 files changed, 4 insertions(+), 2 deletions(-) diff --git a/Firmware/ConfigurationStore.cpp b/Firmware/ConfigurationStore.cpp index 858f3a65..0016b7da 100644 --- a/Firmware/ConfigurationStore.cpp +++ b/Firmware/ConfigurationStore.cpp @@ -181,7 +181,9 @@ static_assert (false, "zprobe_zoffset was not initialized in printers in field t #endif static_assert (sizeof(M500_conf) == 188, "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"); + "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."); static const M500_conf default_conf PROGMEM = { diff --git a/Firmware/ConfigurationStore.h b/Firmware/ConfigurationStore.h index 761ec95a..4f01c3f5 100644 --- a/Firmware/ConfigurationStore.h +++ b/Firmware/ConfigurationStore.h @@ -35,7 +35,7 @@ typedef struct float filament_size[1]; //!< cross-sectional area of filament (in millimeters), typically around 1.75 or 2.85, 0 disables the volumetric calculations for the extruder. float max_feedrate_silent[4]; //!< max speeds for silent mode unsigned long max_acceleration_units_per_sq_second_silent[4]; -} __attribute__ ((packed)) M500_conf; +} M500_conf; extern M500_conf cs; From 0e33db0064b3358626501248abf252a3be724b57 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Wed, 26 Sep 2018 18:52:35 +0200 Subject: [PATCH 137/141] Documentation: Put scattered and unscattered Gcode documentation together in process_commands documentation. Mention at least existence of all implemented commands. Document T and T? commands. --- Firmware/Marlin_main.cpp | 456 ++++++++++++++++++++------------------- 1 file changed, 229 insertions(+), 227 deletions(-) diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index 198f6160..e2afaa64 100644 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -147,135 +147,6 @@ #define FILAMENT_PVA 2 #define FILAMENT_UNDEFINED 255 -// look here for descriptions of G-codes: http://linuxcnc.org/handbook/gcode/g-code.html -// http://objects.reprap.org/wiki/Mendel_User_Manual:_RepRapGCodes - -//Implemented Codes -//------------------- - -// PRUSA CODES -// P F - Returns FW versions -// P R - Returns revision of printer - -// G0 -> G1 -// G1 - Coordinated Movement X Y Z E -// G2 - CW ARC -// G3 - CCW ARC -// G4 - Dwell S or P -// G10 - retract filament according to settings of M207 -// G11 - retract recover filament according to settings of M208 -// G28 - Home all Axis -// G29 - Detailed Z-Probe, probes the bed at 3 or more points. Will fail if you haven't homed yet. -// G30 - Single Z Probe, probes bed at current XY location. -// G31 - Dock sled (Z_PROBE_SLED only) -// G32 - Undock sled (Z_PROBE_SLED only) -// G80 - Automatic mesh bed leveling -// G81 - Print bed profile -// G90 - Use Absolute Coordinates -// G91 - Use Relative Coordinates -// G92 - Set current position to coordinates given - -// M Codes -// M0 - Unconditional stop - Wait for user to press a button on the LCD -// M1 - Same as M0 -// M17 - Enable/Power all stepper motors -// M18 - Disable all stepper motors; same as M84 -// M20 - List SD card -// M21 - Init SD card -// M22 - Release SD card -// M23 - Select SD file (M23 filename.g) -// M24 - Start/resume SD print -// M25 - Pause SD print -// M26 - Set SD position in bytes (M26 S12345) -// M27 - Report SD print status -// M28 - Start SD write (M28 filename.g) -// M29 - Stop SD write -// M30 - Delete file from SD (M30 filename.g) -// M31 - Output time since last M109 or SD card start to serial -// M32 - Select file and start SD print (Can be used _while_ printing from SD card files): -// syntax "M32 /path/filename#", or "M32 S !filename#" -// Call gcode file : "M32 P !filename#" and return to caller file after finishing (similar to #include). -// The '#' is necessary when calling from within sd files, as it stops buffer prereading -// M42 - Change pin status via gcode Use M42 Px Sy to set pin x to value y, when omitting Px the onboard led will be used. -// M73 - Show percent done and print time remaining -// M80 - Turn on Power Supply -// M81 - Turn off Power Supply -// M82 - Set E codes absolute (default) -// M83 - Set E codes relative while in Absolute Coordinates (G90) mode -// M84 - Disable steppers until next move, -// or use S to specify an inactivity timeout, after which the steppers will be disabled. S0 to disable the timeout. -// M85 - Set inactivity shutdown timer with parameter S. To disable set zero (default) -// M86 - Set safety timer expiration time with parameter S; M86 S0 will disable safety timer -// M92 - Set axis_steps_per_unit - same syntax as G92 -// M104 - Set extruder target temp -// M105 - Read current temp -// M106 - Fan on -// M107 - Fan off -// M109 - Sxxx Wait for extruder current temp to reach target temp. Waits only when heating -// Rxxx Wait for extruder current temp to reach target temp. Waits when heating and cooling -// IF AUTOTEMP is enabled, S B F. Exit autotemp by any M109 without F -// M112 - Emergency stop -// M113 - Get or set the timeout interval for Host Keepalive "busy" messages -// M114 - Output current position to serial port -// M115 - Capabilities string -// M117 - display message -// M119 - Output Endstop status to serial port -// M126 - Solenoid Air Valve Open (BariCUDA support by jmil) -// M127 - Solenoid Air Valve Closed (BariCUDA vent to atmospheric pressure by jmil) -// M128 - EtoP Open (BariCUDA EtoP = electricity to air pressure transducer by jmil) -// M129 - EtoP Closed (BariCUDA EtoP = electricity to air pressure transducer by jmil) -// M140 - Set bed target temp -// 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. -// M190 - Sxxx Wait for bed current temp to reach target temp. Waits only when heating -// Rxxx Wait for bed current temp to reach target temp. Waits when heating and cooling -// M200 D- set filament diameter and set E axis units to cubic millimeters (use S0 to set back to millimeters). -// M201 - Set max acceleration in units/s^2 for print moves (M201 X1000 Y1000) -// M202 - Set max acceleration in units/s^2 for travel moves (M202 X1000 Y1000) Unused in Marlin!! -// M203 - Set maximum feedrate that your machine can sustain (M203 X200 Y200 Z300 E10000) in mm/sec -// M204 - Set default acceleration: S normal moves T filament only moves (M204 S3000 T7000) in mm/sec^2 also sets minimum segment time in ms (B20000) to prevent buffer under-runs and M20 minimum feedrate -// M205 - advanced settings: minimum travel speed S=while printing T=travel only, B=minimum segment time X= maximum xy jerk, Z=maximum Z jerk, E=maximum E jerk -// M206 - set additional homing offset -// M207 - set retract length S[positive mm] F[feedrate mm/min] Z[additional zlift/hop], stays in mm regardless of M200 setting -// M208 - set recover=unretract length S[positive mm surplus to the M207 S*] F[feedrate mm/sec] -// M209 - S<1=true/0=false> enable automatic retract detect if the slicer did not support G10/11: every normal extrude-only move will be classified as retract depending on the direction. -// M218 - set hotend offset (in mm): T X Y -// M220 S- set speed factor override percentage -// M221 S- set extrude factor override percentage -// M226 P S- Wait until the specified pin reaches the state required -// M240 - Trigger a camera to take a photograph -// M250 - Set LCD contrast C (value 0..63) -// M280 - set servo position absolute. P: servo index, S: angle or microseconds -// M300 - Play beep sound S P -// M301 - Set PID parameters P I and D -// M302 - Allow cold extrudes, or set the minimum extrude S. -// M303 - PID relay autotune S sets the target temperature. (default target temperature = 150C) -// M304 - Set bed PID parameters P I and D -// M400 - Finish all moves -// M401 - Lower z-probe if present -// M402 - Raise z-probe if present -// M404 - N Enter the nominal filament width (3mm, 1.75mm ) or will display nominal filament width without parameters -// M405 - Turn on Filament Sensor extrusion control. Optional D to set delay in centimeters between sensor and extruder -// M406 - Turn off Filament Sensor extrusion control -// M407 - Displays measured filament diameter -// M500 - stores parameters in EEPROM -// M501 - reads parameters from EEPROM (if you need reset them after you changed them temporarily). -// M502 - reverts to the default "factory settings". You still need to store them in EEPROM afterwards if you want to. -// M503 - print the current settings (from memory not from EEPROM) -// M509 - force language selection on next restart -// M540 - Use S[0|1] to enable or disable the stop SD card print on endstop hit (requires ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED) -// M600 - Pause for filament change X[pos] Y[pos] Z[relative lift] E[initial retract] L[later retract distance for removal] -// M605 - Set dual x-carriage movement mode: S [ X R ] -// M860 - Wait for PINDA thermistor to reach target temperature. -// M861 - Set / Read PINDA temperature compensation offsets -// M900 - Set LIN_ADVANCE options, if enabled. See Configuration_adv.h for details. -// M907 - Set digital trimpot motor current using axis codes. -// M908 - Control digital trimpot directly. -// M350 - Set microstepping mode. -// M351 - Toggle MS1 MS2 pins directly. - -// M928 - Start SD logging (M928 filename.g) - ended by M29 -// M999 - Restart after being stopped by error - //Stepper Movement Variables //=========================================================================== @@ -3302,7 +3173,136 @@ extern uint8_t st_backlash_x; extern uint8_t st_backlash_y; #endif //BACKLASH_Y - +//! @brief Parse and process commands +//! +//! look here for descriptions of G-codes: http://linuxcnc.org/handbook/gcode/g-code.html +//! http://objects.reprap.org/wiki/Mendel_User_Manual:_RepRapGCodes +//! +//! Implemented Codes +//! ------------------- +//! +//!@n PRUSA CODES +//!@n P F - Returns FW versions +//!@n P R - Returns revision of printer +//! +//!@n G0 -> G1 +//!@n G1 - Coordinated Movement X Y Z E +//!@n G2 - CW ARC +//!@n G3 - CCW ARC +//!@n G4 - Dwell S or P +//!@n G10 - retract filament according to settings of M207 +//!@n G11 - retract recover filament according to settings of M208 +//!@n G28 - Home all Axis +//!@n G29 - Detailed Z-Probe, probes the bed at 3 or more points. Will fail if you haven't homed yet. +//!@n G30 - Single Z Probe, probes bed at current XY location. +//!@n G31 - Dock sled (Z_PROBE_SLED only) +//!@n G32 - Undock sled (Z_PROBE_SLED only) +//!@n G80 - Automatic mesh bed leveling +//!@n G81 - Print bed profile +//!@n G90 - Use Absolute Coordinates +//!@n G91 - Use Relative Coordinates +//!@n G92 - Set current position to coordinates given +//! +//!@n M Codes +//!@n M0 - Unconditional stop - Wait for user to press a button on the LCD +//!@n M1 - Same as M0 +//!@n M17 - Enable/Power all stepper motors +//!@n M18 - Disable all stepper motors; same as M84 +//!@n M20 - List SD card +//!@n M21 - Init SD card +//!@n M22 - Release SD card +//!@n M23 - Select SD file (M23 filename.g) +//!@n M24 - Start/resume SD print +//!@n M25 - Pause SD print +//!@n M26 - Set SD position in bytes (M26 S12345) +//!@n M27 - Report SD print status +//!@n M28 - Start SD write (M28 filename.g) +//!@n M29 - Stop SD write +//!@n M30 - Delete file from SD (M30 filename.g) +//!@n M31 - Output time since last M109 or SD card start to serial +//!@n M32 - Select file and start SD print (Can be used _while_ printing from SD card files): +//! syntax "M32 /path/filename#", or "M32 S !filename#" +//! Call gcode file : "M32 P !filename#" and return to caller file after finishing (similar to #include). +//! The '#' is necessary when calling from within sd files, as it stops buffer prereading +//!@n M42 - Change pin status via gcode Use M42 Px Sy to set pin x to value y, when omitting Px the onboard led will be used. +//!@n M73 - Show percent done and print time remaining +//!@n M80 - Turn on Power Supply +//!@n M81 - Turn off Power Supply +//!@n M82 - Set E codes absolute (default) +//!@n M83 - Set E codes relative while in Absolute Coordinates (G90) mode +//!@n M84 - Disable steppers until next move, +//! or use S to specify an inactivity timeout, after which the steppers will be disabled. S0 to disable the timeout. +//!@n M85 - Set inactivity shutdown timer with parameter S. To disable set zero (default) +//!@n M86 - Set safety timer expiration time with parameter S; M86 S0 will disable safety timer +//!@n M92 - Set axis_steps_per_unit - same syntax as G92 +//!@n M104 - Set extruder target temp +//!@n M105 - Read current temp +//!@n M106 - Fan on +//!@n M107 - Fan off +//!@n M109 - Sxxx Wait for extruder current temp to reach target temp. Waits only when heating +//! Rxxx Wait for extruder current temp to reach target temp. Waits when heating and cooling +//! IF AUTOTEMP is enabled, S B F. Exit autotemp by any M109 without F +//!@n M112 - Emergency stop +//!@n M113 - Get or set the timeout interval for Host Keepalive "busy" messages +//!@n M114 - Output current position to serial port +//!@n M115 - Capabilities string +//!@n M117 - display message +//!@n M119 - Output Endstop status to serial port +//!@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 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- set filament diameter and set E axis units to cubic millimeters (use S0 to set back to millimeters). +//!@n M201 - Set max acceleration in units/s^2 for print moves (M201 X1000 Y1000) +//!@n M202 - Set max acceleration in units/s^2 for travel moves (M202 X1000 Y1000) Unused in Marlin!! +//!@n M203 - Set maximum feedrate that your machine can sustain (M203 X200 Y200 Z300 E10000) in mm/sec +//!@n M204 - Set default acceleration: S normal moves T filament only moves (M204 S3000 T7000) in mm/sec^2 also sets minimum segment time in ms (B20000) to prevent buffer under-runs and M20 minimum feedrate +//!@n M205 - advanced settings: minimum travel speed S=while printing T=travel only, B=minimum segment time X= maximum xy jerk, Z=maximum Z jerk, E=maximum E jerk +//!@n M206 - set additional homing offset +//!@n M207 - set retract length S[positive mm] F[feedrate mm/min] Z[additional zlift/hop], stays in mm regardless of M200 setting +//!@n M208 - set recover=unretract length S[positive mm surplus to the M207 S*] F[feedrate mm/sec] +//!@n M209 - S<1=true/0=false> enable automatic retract detect if the slicer did not support G10/11: every normal extrude-only move will be classified as retract depending on the direction. +//!@n M218 - set hotend offset (in mm): T X Y +//!@n M220 S- set speed factor override percentage +//!@n M221 S- set extrude factor override percentage +//!@n M226 P S- Wait until the specified pin reaches the state required +//!@n M240 - Trigger a camera to take a photograph +//!@n M250 - Set LCD contrast C (value 0..63) +//!@n M280 - set servo position absolute. P: servo index, S: angle or microseconds +//!@n M300 - Play beep sound S P +//!@n M301 - Set PID parameters P I and D +//!@n M302 - Allow cold extrudes, or set the minimum extrude S. +//!@n M303 - PID relay autotune S sets the target temperature. (default target temperature = 150C) +//!@n M304 - Set bed PID parameters P I and D +//!@n M400 - Finish all moves +//!@n M401 - Lower z-probe if present +//!@n M402 - Raise z-probe if present +//!@n M404 - N Enter the nominal filament width (3mm, 1.75mm ) or will display nominal filament width without parameters +//!@n M405 - Turn on Filament Sensor extrusion control. Optional D to set delay in centimeters between sensor and extruder +//!@n M406 - Turn off Filament Sensor extrusion control +//!@n M407 - Displays measured filament diameter +//!@n M500 - stores parameters in EEPROM +//!@n M501 - reads parameters from EEPROM (if you need reset them after you changed them temporarily). +//!@n M502 - reverts to the default "factory settings". You still need to store them in EEPROM afterwards if you want to. +//!@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 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 [ X R ] +//!@n M860 - Wait for PINDA thermistor to reach target temperature. +//!@n M861 - Set / Read PINDA temperature compensation offsets +//!@n M900 - Set LIN_ADVANCE options, if enabled. See Configuration_adv.h for details. +//!@n M907 - Set digital trimpot motor current using axis codes. +//!@n M908 - Control digital trimpot directly. +//!@n M350 - Set microstepping mode. +//!@n M351 - Toggle MS1 MS2 pins directly. +//! +//!@n M928 - Start SD logging (M928 filename.g) - ended by M29 +//!@n M999 - Restart after being stopped by error void process_commands() { if (!buflen) return; //empty command @@ -3344,21 +3344,21 @@ void process_commands() #ifdef TMC2130 else if (strncmp_P(CMDBUFFER_CURRENT_STRING, PSTR("CRASH_"), 6) == 0) { - if(code_seen("CRASH_DETECTED")) + if(code_seen("CRASH_DETECTED")) //! CRASH_DETECTED { uint8_t mask = 0; if (code_seen('X')) mask |= X_AXIS_MASK; if (code_seen('Y')) mask |= Y_AXIS_MASK; crashdet_detected(mask); } - else if(code_seen("CRASH_RECOVER")) + else if(code_seen("CRASH_RECOVER")) //! CRASH_RECOVER crashdet_recover(); - else if(code_seen("CRASH_CANCEL")) + else if(code_seen("CRASH_CANCEL")) //! CRASH_CANCEL crashdet_cancel(); } else if (strncmp_P(CMDBUFFER_CURRENT_STRING, PSTR("TMC_"), 4) == 0) { - if (strncmp_P(CMDBUFFER_CURRENT_STRING + 4, PSTR("SET_WAVE_"), 9) == 0) + if (strncmp_P(CMDBUFFER_CURRENT_STRING + 4, PSTR("SET_WAVE_"), 9) == 0) //! TMC_SET_WAVE_ { uint8_t axis = *(CMDBUFFER_CURRENT_STRING + 13); axis = (axis == 'E')?3:(axis - 'X'); @@ -3368,7 +3368,7 @@ void process_commands() tmc2130_set_wave(axis, 247, fac); } } - else if (strncmp_P(CMDBUFFER_CURRENT_STRING + 4, PSTR("SET_STEP_"), 9) == 0) + else if (strncmp_P(CMDBUFFER_CURRENT_STRING + 4, PSTR("SET_STEP_"), 9) == 0) //! TMC_SET_STEP_ { uint8_t axis = *(CMDBUFFER_CURRENT_STRING + 13); axis = (axis == 'E')?3:(axis - 'X'); @@ -3379,7 +3379,7 @@ void process_commands() tmc2130_goto_step(axis, step & (4*res - 1), 2, 1000, res); } } - else if (strncmp_P(CMDBUFFER_CURRENT_STRING + 4, PSTR("SET_CHOP_"), 9) == 0) + else if (strncmp_P(CMDBUFFER_CURRENT_STRING + 4, PSTR("SET_CHOP_"), 9) == 0) //! TMC_SET_CHOP_ { uint8_t axis = *(CMDBUFFER_CURRENT_STRING + 13); axis = (axis == 'E')?3:(axis - 'X'); @@ -3430,22 +3430,22 @@ void process_commands() } #endif //BACKLASH_Y #endif //TMC2130 - else if (code_seen("FSENSOR_RECOVER")) { + else if (code_seen("FSENSOR_RECOVER")) { //! FSENSOR_RECOVER fsensor_restore_print_and_continue(); } else if(code_seen("PRUSA")){ - if (code_seen("Ping")) { //PRUSA Ping + if (code_seen("Ping")) { //! PRUSA Ping if (farm_mode) { PingTime = millis(); //MYSERIAL.print(farm_no); MYSERIAL.println(": OK"); } } - else if (code_seen("PRN")) { + else if (code_seen("PRN")) { //! PRUSA PRN printf_P(_N("%d"), status_number); - }else if (code_seen("FAN")) { + }else if (code_seen("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")) { + }else if (code_seen("fn")) { //! PRUSA fn if (farm_mode) { printf_P(_N("%d"), farm_no); } @@ -3454,20 +3454,20 @@ void process_commands() } } - else if (code_seen("thx")) + else if (code_seen("thx")) //! PRUSA thx { no_response = false; } - else if (code_seen("uvlo")) + else if (code_seen("uvlo")) //! PRUSA uvlo { eeprom_update_byte((uint8_t*)EEPROM_UVLO,0); enquecommand_P(PSTR("M24")); } - else if (code_seen("MMURES")) + else if (code_seen("MMURES")) //! PRUSA MMURES { mmu_reset(); } - else if (code_seen("RESET")) { + else if (code_seen("RESET")) { //! PRUSA RESET // careful! if (farm_mode) { #ifdef WATCHDOG @@ -3483,7 +3483,7 @@ void process_commands() else { MYSERIAL.println("Not in farm mode."); } - }else if (code_seen("fv")) { + }else if (code_seen("fv")) { //! PRUSA fv // get file version #ifdef SDSUPPORT card.openFile(strchr_pointer + 3,true); @@ -3498,33 +3498,33 @@ void process_commands() #endif // SDSUPPORT - } else if (code_seen("M28")) { + } else if (code_seen("M28")) { //! PRUSA M28 trace(); prusa_sd_card_upload = true; card.openFile(strchr_pointer+4,false); - } else if (code_seen("SN")) { + } else if (code_seen("SN")) { //! PRUSA SN gcode_PRUSA_SN(); - } else if(code_seen("Fir")){ + } else if(code_seen("Fir")){ //! PRUSA Fir SERIAL_PROTOCOLLN(FW_VERSION_FULL); - } else if(code_seen("Rev")){ + } else if(code_seen("Rev")){ //! PRUSA Rev SERIAL_PROTOCOLLN(FILAMENT_SIZE "-" ELECTRONICS "-" NOZZLE_TYPE ); - } else if(code_seen("Lang")) { + } else if(code_seen("Lang")) { //! PRUSA Lang lang_reset(); - } else if(code_seen("Lz")) { + } else if(code_seen("Lz")) { //! PRUSA Lz EEPROM_save_B(EEPROM_BABYSTEP_Z,0); - } else if(code_seen("Beat")) { + } else if(code_seen("Beat")) { //! PRUSA Beat // Kick farm link timer kicktime = millis(); - } else if(code_seen("FR")) { + } else if(code_seen("FR")) { //! PRUSA FR // Factory full reset factory_reset(0); } @@ -4004,7 +4004,7 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) } break; - case 76: //PINDA probe temperature calibration + case 76: //! G76 - PINDA probe temperature calibration { #ifdef PINDA_THERMISTOR if (true) @@ -4263,12 +4263,9 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) #ifdef DIS case 77: { - //G77 X200 Y150 XP100 YP15 XO10 Y015 - - //for 9 point mesh bed leveling G77 X203 Y196 XP3 YP3 XO0 YO0 - - - //G77 X232 Y218 XP116 YP109 XO-11 YO0 + //! G77 X200 Y150 XP100 YP15 XO10 Y015 + //! for 9 point mesh bed leveling G77 X203 Y196 XP3 YP3 XO0 YO0 + //! G77 X232 Y218 XP116 YP109 XO-11 YO0 float dimension_x = 40; float dimension_y = 40; @@ -4307,12 +4304,12 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) * mesh to compensate for variable bed height * * The S0 report the points as below - * + * @code{.unparsed} * +----> X-axis * | * | * v Y-axis - * + * @endcode */ case 80: @@ -4745,7 +4742,7 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) } break; - case 98: // G98 (activate farm mode) + case 98: //! G98 (activate farm mode) farm_mode = 1; PingTime = millis(); eeprom_update_byte((unsigned char *)EEPROM_FARM_MODE, farm_mode); @@ -4754,7 +4751,7 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) eeprom_update_byte((unsigned char *)EEPROM_SILENT, SilentModeMenu); break; - case 99: // G99 (deactivate farm mode) + case 99: //! G99 (deactivate farm mode) farm_mode = 0; lcd_printer_connected(); eeprom_update_byte((unsigned char *)EEPROM_FARM_MODE, farm_mode); @@ -5000,7 +4997,7 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) } } break; - case 44: // M44: Prusa3D: Reset the bed skew and offset calibration. + case 44: //! M44: Prusa3D: Reset the bed skew and offset calibration. // Reset the baby step value and the baby step applied flag. calibration_status_store(CALIBRATION_STATUS_ASSEMBLED); @@ -5014,7 +5011,7 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) world2machine_revert_to_uncorrected(); break; - case 45: // M45: Prusa3D: bed skew and offset with manual Z up + case 45: //! M45: Prusa3D: bed skew and offset with manual Z up { int8_t verbosity_level = 0; bool only_Z = code_seen('Z'); @@ -5054,14 +5051,14 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) */ case 47: - // M47: Prusa3D: Show end stops dialog on the display. + //! M47: Prusa3D: Show end stops dialog on the display. KEEPALIVE_STATE(PAUSED_FOR_USER); lcd_diag_show_end_stops(); KEEPALIVE_STATE(IN_HANDLER); break; #if 0 - case 48: // M48: scan the bed induction sensor points, print the sensor trigger coordinates to the serial line for visualization on the PC. + case 48: //! M48: scan the bed induction sensor points, print the sensor trigger coordinates to the serial line for visualization on the PC. { // Disable the default update procedure of the display. We will do a modal dialog. lcd_update_enable(false); @@ -5096,23 +5093,22 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) } #endif -// M48 Z-Probe repeatability measurement function. -// -// Usage: M48 -// -// This function assumes the bed has been homed. Specificaly, that a G28 command -// as been issued prior to invoking the M48 Z-Probe repeatability measurement function. -// Any information generated by a prior G29 Bed leveling command will be lost and need to be -// regenerated. -// -// The number of samples will default to 10 if not specified. You can use upper or lower case -// letters for any of the options EXCEPT n. n must be in lower case because Marlin uses a capital -// N for its communication protocol and will get horribly confused if you send it a capital N. -// #ifdef ENABLE_AUTO_BED_LEVELING #ifdef Z_PROBE_REPEATABILITY_TEST - + //! M48 Z-Probe repeatability measurement function. + //! + //! Usage: M48 + //! + //! This function assumes the bed has been homed. Specificaly, that a G28 command + //! as been issued prior to invoking the M48 Z-Probe repeatability measurement function. + //! Any information generated by a prior G29 Bed leveling command will be lost and need to be + //! regenerated. + //! + //! The number of samples will default to 10 if not specified. You can use upper or lower case + //! letters for any of the options EXCEPT n. n must be in lower case because Marlin uses a capital + //! N for its communication protocol and will get horribly confused if you send it a capital N. + //! case 48: // M48 Z-Probe repeatability { #if Z_MIN_PIN == -1 @@ -5578,7 +5574,7 @@ Sigma_Exit: break; #if defined(FAN_PIN) && FAN_PIN > -1 - case 106: //M106 Fan On + case 106: //!M106 Sxxx Fan On S 0 .. 255 if (code_seen('S')){ fanSpeed=constrain(code_value(),0,255); } @@ -5707,7 +5703,7 @@ Sigma_Exit: } } break; - case 110: // M110 - reset line pos + case 110: //! M110 N - reset line pos if (code_seen('N')) gcode_LastN = code_value_long(); break; @@ -5754,10 +5750,10 @@ Sigma_Exit: case 114: // M114 gcode_M114(); break; - case 120: // M120 + case 120: //! M120 - Disable endstops enable_endstops(false) ; break; - case 121: // M121 + case 121: //! M121 - Enable endstops enable_endstops(true) ; break; case 119: // M119 @@ -5928,9 +5924,9 @@ Sigma_Exit: } break; case 204: - // M204 acclereration settings. - // Supporting old format: M204 S[normal moves] T[filmanent only moves] - // and new format: M204 P[printing moves] R[filmanent only moves] T[travel moves] (as of now T is ignored) + //! M204 acclereration settings. + //!@n Supporting old format: M204 S[normal moves] T[filmanent only moves] + //!@n and new format: M204 P[printing moves] R[filmanent only moves] T[travel moves] (as of now T is ignored) { if(code_seen('S')) { // Legacy acceleration format. This format is used by the legacy Marlin, MK2 or MK3 firmware, @@ -6314,11 +6310,11 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) } break; - case 403: //M403 set filament type (material) for particular extruder and send this information to mmu + case 403: //! M403 set filament type (material) for particular extruder and send this information to mmu { - //currently three different materials are needed (default, flex and PVA) - //add storing this information for different load/unload profiles etc. in the future - //firmware does not wait for "ok" from mmu + //! currently three different materials are needed (default, flex and PVA) + //! add storing this information for different load/unload profiles etc. in the future + //!firmware does not wait for "ok" from mmu if (mmu_enabled) { uint8_t extruder = 255; @@ -6479,13 +6475,13 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) } break; #endif //FILAMENTCHANGEENABLE - case 601: + case 601: //! M601 - Pause print { lcd_pause_print(); } break; - case 602: { + case 602: { //! M602 - Resume print lcd_resume_print(); } break; @@ -6644,13 +6640,13 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) #ifdef TMC2130 - case 910: // M910 TMC2130 init + case 910: //! M910 - TMC2130 init { tmc2130_init(); } break; - case 911: // M911 Set TMC2130 holding currents + case 911: //! M911 - Set TMC2130 holding currents { if (code_seen('X')) tmc2130_set_current_h(0, code_value()); if (code_seen('Y')) tmc2130_set_current_h(1, code_value()); @@ -6659,7 +6655,7 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) } break; - case 912: // M912 Set TMC2130 running currents + case 912: //! M912 - Set TMC2130 running currents { if (code_seen('X')) tmc2130_set_current_r(0, code_value()); if (code_seen('Y')) tmc2130_set_current_r(1, code_value()); @@ -6668,13 +6664,13 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) } break; - case 913: // M913 Print TMC2130 currents + case 913: //! M913 - Print TMC2130 currents { tmc2130_print_currents(); } break; - case 914: // M914 Set normal mode + case 914: //! M914 - Set normal mode { tmc2130_mode = TMC2130_MODE_NORMAL; update_mode_profile(); @@ -6682,7 +6678,7 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) } break; - case 915: // M915 Set silent mode + case 915: //! M915 - Set silent mode { tmc2130_mode = TMC2130_MODE_SILENT; update_mode_profile(); @@ -6690,7 +6686,7 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) } break; - case 916: // M916 Set sg_thrs + case 916: //! M916 - Set sg_thrs { if (code_seen('X')) tmc2130_sg_thr[X_AXIS] = code_value(); if (code_seen('Y')) tmc2130_sg_thr[Y_AXIS] = code_value(); @@ -6701,7 +6697,7 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) } break; - case 917: // M917 Set TMC2130 pwm_ampl + case 917: //! M917 - Set TMC2130 pwm_ampl { if (code_seen('X')) tmc2130_set_pwm_ampl(0, code_value()); if (code_seen('Y')) tmc2130_set_pwm_ampl(1, code_value()); @@ -6710,7 +6706,7 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) } break; - case 918: // M918 Set TMC2130 pwm_grad + case 918: //! M918 - Set TMC2130 pwm_grad { if (code_seen('X')) tmc2130_set_pwm_grad(0, code_value()); if (code_seen('Y')) tmc2130_set_pwm_grad(1, code_value()); @@ -6721,7 +6717,7 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) #endif //TMC2130 - case 350: // M350 Set microstepping mode. Warning: Steps per unit remains unchanged. S code sets stepping mode for all drivers. + case 350: //! M350 - Set microstepping mode. Warning: Steps per unit remains unchanged. S code sets stepping mode for all drivers. { #ifdef TMC2130 if(code_seen('E')) @@ -6757,7 +6753,7 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) #endif //TMC2130 } break; - case 351: // M351 Toggle MS1 MS2 pins directly, S# determines MS1 or MS2, X# sets the pin high/low. + case 351: //! M351 - Toggle MS1 MS2 pins directly, S# determines MS1 or MS2, X# sets the pin high/low. { #if defined(X_MS1_PIN) && X_MS1_PIN > -1 if(code_seen('S')) switch((int)code_value()) @@ -6775,23 +6771,23 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) #endif } break; - case 701: //M701: load filament + case 701: //! M701 - load filament { if (mmu_enabled && code_seen('E')) tmp_extruder = code_value(); gcode_M701(); } break; - case 702: + case 702: //! M702 [U C] - { if (mmu_enabled) { if (code_seen('U')) - extr_unload_used(); //unload all filaments which were used in current print + extr_unload_used(); //! if "U" unload all filaments which were used in current print else if (code_seen('C')) - extr_unload(); //unload just current filament + extr_unload(); //! if "C" unload just current filament else - extr_unload_all(); //unload all filaments + extr_unload_all(); //! otherwise unload all filaments } else unload_filament(); @@ -6811,7 +6807,13 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) mcode_in_progress = 0; } } // end if(code_seen('M')) (end of M codes) - + //! T - select extruder in case of multi extruder printer + //! select filament in case of MMU_V2 + //! if extruder is "?", open menu to let the user select extruder/filament + //! + //! For MMU_V2: + //! @n T Gcode to extrude must follow immediately to load to extruder wheels + //! @n T? Gcode to extrude doesn't have to follow, load to extruder wheels is done automatically else if(code_seen('T')) { int index; @@ -6954,45 +6956,45 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) switch((int)code_value()) { #ifdef DEBUG_DCODES - case -1: // D-1 - Endless loop + case -1: //! D-1 - Endless loop dcode__1(); break; - case 0: // D0 - Reset + case 0: //! D0 - Reset dcode_0(); break; - case 1: // D1 - Clear EEPROM + case 1: //! D1 - Clear EEPROM dcode_1(); break; - case 2: // D2 - Read/Write RAM + case 2: //! D2 - Read/Write RAM dcode_2(); break; #endif //DEBUG_DCODES #ifdef DEBUG_DCODE3 - case 3: // D3 - Read/Write EEPROM + case 3: //! D3 - Read/Write EEPROM dcode_3(); break; #endif //DEBUG_DCODE3 #ifdef DEBUG_DCODES - case 4: // D4 - Read/Write PIN + case 4: //! D4 - Read/Write PIN dcode_4(); break; - case 5: // D5 - Read/Write FLASH + case 5: //! D5 - Read/Write FLASH // dcode_5(); break; break; - case 6: // D6 - Read/Write external FLASH + case 6: //! D6 - Read/Write external FLASH dcode_6(); break; - case 7: // D7 - Read/Write Bootloader + case 7: //! D7 - Read/Write Bootloader dcode_7(); break; - case 8: // D8 - Read/Write PINDA + case 8: //! D8 - Read/Write PINDA dcode_8(); break; - case 9: // D9 - Read/Write ADC + case 9: //! D9 - Read/Write ADC dcode_9(); break; - case 10: // D10 - XYZ calibration = OK + case 10: //! D10 - XYZ calibration = OK dcode_10(); break; #ifdef TMC2130 - case 2130: // D9125 - TMC2130 + case 2130: //! D2130 - TMC2130 dcode_2130(); break; #endif //TMC2130 #ifdef FILAMENT_SENSOR - case 9125: // D9125 - FILAMENT_SENSOR + case 9125: //! D9125 - FILAMENT_SENSOR dcode_9125(); break; #endif //FILAMENT_SENSOR From c77672bf0f76daa515067164025defde53a0269c Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Fri, 5 Oct 2018 18:11:26 +0200 Subject: [PATCH 138/141] PFW-608 Decrease wear of mass erase EEPROM and do it faster. --- Firmware/Marlin_main.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index e2afaa64..ccce531a 100644 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -756,7 +756,7 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) // Erase EEPROM for (int i = 0; i < 4096; i++) { - eeprom_write_byte((uint8_t*)i, 0xFF); + eeprom_update_byte((uint8_t*)i, 0xFF); if (i % 41 == 0) { er_progress++; From 1585dc66b0f96c63dd65b57644326180761ef3c5 Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Mon, 8 Oct 2018 15:58:49 +0200 Subject: [PATCH 139/141] Merge remote-tracking branch 'prusa3d/MK3_dev' into simplify_EEPROM_M500 Known limitation: Unable to compile. --- Firmware/ConfigurationStore.cpp | 10 +- Firmware/Dcodes.cpp | 3 +- Firmware/Marlin.h | 21 +- Firmware/Marlin_main.cpp | 879 +++++++++++++++--------------- Firmware/cardreader.cpp | 180 +++--- Firmware/cardreader.h | 2 + Firmware/doxyfile | 4 +- Firmware/fsensor.cpp | 37 +- Firmware/fsensor.h | 1 - Firmware/lcd.cpp | 117 ++-- Firmware/lcd.h | 43 +- Firmware/menu.cpp | 1 + Firmware/mesh_bed_calibration.cpp | 37 +- Firmware/mesh_bed_leveling.cpp | 2 +- Firmware/mmu.cpp | 46 +- Firmware/mmu.h | 2 - Firmware/optiboot_w25x20cl.cpp | 5 +- Firmware/planner.cpp | 12 +- Firmware/sm4.c | 8 +- Firmware/sound.cpp | 2 +- Firmware/sound.h | 2 +- Firmware/stepper.cpp | 41 +- Firmware/stepper.h | 4 +- Firmware/temperature.cpp | 36 +- Firmware/tmc2130.cpp | 17 +- Firmware/tmc2130.h | 2 +- Firmware/uart2.c | 4 +- Firmware/ultralcd.cpp | 828 ++++++++++++++-------------- Firmware/ultralcd.h | 34 +- Firmware/xyzcal.cpp | 20 +- README.md | 9 +- README_cz.md | 7 +- 32 files changed, 1226 insertions(+), 1190 deletions(-) diff --git a/Firmware/ConfigurationStore.cpp b/Firmware/ConfigurationStore.cpp index 0016b7da..d16e92e5 100644 --- a/Firmware/ConfigurationStore.cpp +++ b/Firmware/ConfigurationStore.cpp @@ -13,10 +13,11 @@ M500_conf cs; #ifdef DEBUG_EEPROM_WRITE #define EEPROM_WRITE_VAR(pos, value) _EEPROM_writeData(pos, (uint8_t*)&value, sizeof(value), #value) +static void _EEPROM_writeData(int &pos, uint8_t* value, uint8_t size, char* name) #else //DEBUG_EEPROM_WRITE -#define EEPROM_WRITE_VAR(pos, value) _EEPROM_writeData(pos, (uint8_t*)&value, sizeof(value), 0) +#define EEPROM_WRITE_VAR(pos, value) _EEPROM_writeData(pos, (uint8_t*)&value, sizeof(value)) +static void _EEPROM_writeData(int &pos, uint8_t* value, uint8_t size) #endif //DEBUG_EEPROM_WRITE -void _EEPROM_writeData(int &pos, uint8_t* value, uint8_t size, char* name) { #ifdef DEBUG_EEPROM_WRITE printf_P(PSTR("EEPROM_WRITE_VAR addr=0x%04x size=0x%02hhx name=%s\n"), pos, size, name); @@ -41,10 +42,11 @@ void _EEPROM_writeData(int &pos, uint8_t* value, uint8_t size, char* name) #ifdef DEBUG_EEPROM_READ #define EEPROM_READ_VAR(pos, value) _EEPROM_readData(pos, (uint8_t*)&value, sizeof(value), #value) +static void _EEPROM_readData(int &pos, uint8_t* value, uint8_t size, char* name) #else //DEBUG_EEPROM_READ -#define EEPROM_READ_VAR(pos, value) _EEPROM_readData(pos, (uint8_t*)&value, sizeof(value), 0) +#define EEPROM_READ_VAR(pos, value) _EEPROM_readData(pos, (uint8_t*)&value, sizeof(value)) +static void _EEPROM_readData(int &pos, uint8_t* value, uint8_t size) #endif //DEBUG_EEPROM_READ -void _EEPROM_readData(int &pos, uint8_t* value, uint8_t size, char* name) { #ifdef DEBUG_EEPROM_READ printf_P(PSTR("EEPROM_READ_VAR addr=0x%04x size=0x%02hhx name=%s\n"), pos, size, name); diff --git a/Firmware/Dcodes.cpp b/Firmware/Dcodes.cpp index d1ddc61e..966e7af4 100644 --- a/Firmware/Dcodes.cpp +++ b/Firmware/Dcodes.cpp @@ -34,7 +34,6 @@ void print_eeprom(uint16_t address, uint16_t count, uint8_t countperline = 16) uint8_t count_line = countperline; while (count && count_line) { - uint8_t data = 0; putchar(' '); print_hex_byte(eeprom_read_byte((uint8_t*)address++)); count_line--; @@ -115,7 +114,7 @@ void dcode_3() count = parse_hex(strchr_pointer + 1, data, 16); if (count > 0) { - for (int i = 0; i < count; i++) + for (uint16_t i = 0; i < count; i++) eeprom_write_byte((uint8_t*)(address + i), data[i]); printf_P(_N("%d bytes written to EEPROM at address 0x%04x"), count, address); putchar('\n'); diff --git a/Firmware/Marlin.h b/Firmware/Marlin.h index 3dd626aa..a5b4c124 100644 --- a/Firmware/Marlin.h +++ b/Firmware/Marlin.h @@ -148,7 +148,7 @@ void manage_inactivity(bool ignore_stepper_queue=false); #define disable_z() { WRITE(Z_ENABLE_PIN,!Z_ENABLE_ON); WRITE(Z2_ENABLE_PIN,!Z_ENABLE_ON); axis_known_position[Z_AXIS] = false; } #else #define enable_z() WRITE(Z_ENABLE_PIN, Z_ENABLE_ON) - #define disable_z() ; + #define disable_z() {} #endif #else #ifdef Z_DUAL_STEPPER_DRIVERS @@ -160,8 +160,8 @@ void manage_inactivity(bool ignore_stepper_queue=false); #endif #endif #else - #define enable_z() ; - #define disable_z() ; + #define enable_z() {} + #define disable_z() {} #endif @@ -278,6 +278,7 @@ extern float max_pos[3]; extern bool axis_known_position[3]; extern int fanSpeed; extern void homeaxis(int axis, uint8_t cnt = 1, uint8_t* pstep = 0); +extern int8_t lcd_change_fil_state; #ifdef FAN_SOFT_PWM @@ -328,10 +329,6 @@ extern uint8_t active_extruder; #endif //Long pause -extern int saved_feedmultiply; -extern float HotendTempBckp; -extern int fanSpeedBckp; -extern float pause_lastpos[4]; extern unsigned long pause_time; extern unsigned long start_pause_print; extern unsigned long t_fan_rising_edge; @@ -355,12 +352,14 @@ extern uint8_t print_percent_done_normal; extern uint16_t print_time_remaining_normal; extern uint8_t print_percent_done_silent; extern uint16_t print_time_remaining_silent; + +#define PRINT_TIME_REMAINING_INIT 0xffff + extern uint16_t mcode_in_progress; extern uint16_t gcode_in_progress; extern bool wizard_active; //autoload temporarily disabled during wizard -#define PRINT_TIME_REMAINING_INIT 0xffff #define PRINT_PERCENT_DONE_INIT 0xff #define PRINTER_ACTIVE (IS_SD_PRINTING || is_usb_printing || isPrintPaused || (custom_message_type == CUSTOM_MSG_TYPE_TEMCAL) || saved_printing || (lcd_commands_type == LCD_COMMAND_V2_CAL) || card.paused || mmu_print_saved) @@ -373,6 +372,7 @@ extern void delay_keep_alive(unsigned int ms); extern void check_babystep(); extern void long_pause(); +extern void crashdet_stop_and_save_print(); #ifdef DIS @@ -413,6 +413,9 @@ extern void print_world_coordinates(); extern void print_physical_coordinates(); extern void print_mesh_bed_leveling_table(); +extern void stop_and_save_print_to_ram(float z_move, float e_move); +extern void restore_print_from_ram_and_continue(float e_move); + //estimated time to end of the print extern uint16_t print_time_remaining(); @@ -467,5 +470,5 @@ void proc_commands(); void M600_load_filament(); void M600_load_filament_movements(); -void M600_wait_for_user(); +void M600_wait_for_user(float HotendTempBckp); void M600_check_state(); diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index ca2dcb88..e75a31da 100644 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -145,135 +145,7 @@ #define FILAMENT_DEFAULT 0 #define FILAMENT_FLEX 1 #define FILAMENT_PVA 2 - -// look here for descriptions of G-codes: http://linuxcnc.org/handbook/gcode/g-code.html -// http://objects.reprap.org/wiki/Mendel_User_Manual:_RepRapGCodes - -//Implemented Codes -//------------------- - -// PRUSA CODES -// P F - Returns FW versions -// P R - Returns revision of printer - -// G0 -> G1 -// G1 - Coordinated Movement X Y Z E -// G2 - CW ARC -// G3 - CCW ARC -// G4 - Dwell S or P -// G10 - retract filament according to settings of M207 -// G11 - retract recover filament according to settings of M208 -// G28 - Home all Axis -// G29 - Detailed Z-Probe, probes the bed at 3 or more points. Will fail if you haven't homed yet. -// G30 - Single Z Probe, probes bed at current XY location. -// G31 - Dock sled (Z_PROBE_SLED only) -// G32 - Undock sled (Z_PROBE_SLED only) -// G80 - Automatic mesh bed leveling -// G81 - Print bed profile -// G90 - Use Absolute Coordinates -// G91 - Use Relative Coordinates -// G92 - Set current position to coordinates given - -// M Codes -// M0 - Unconditional stop - Wait for user to press a button on the LCD -// M1 - Same as M0 -// M17 - Enable/Power all stepper motors -// M18 - Disable all stepper motors; same as M84 -// M20 - List SD card -// M21 - Init SD card -// M22 - Release SD card -// M23 - Select SD file (M23 filename.g) -// M24 - Start/resume SD print -// M25 - Pause SD print -// M26 - Set SD position in bytes (M26 S12345) -// M27 - Report SD print status -// M28 - Start SD write (M28 filename.g) -// M29 - Stop SD write -// M30 - Delete file from SD (M30 filename.g) -// M31 - Output time since last M109 or SD card start to serial -// M32 - Select file and start SD print (Can be used _while_ printing from SD card files): -// syntax "M32 /path/filename#", or "M32 S !filename#" -// Call gcode file : "M32 P !filename#" and return to caller file after finishing (similar to #include). -// The '#' is necessary when calling from within sd files, as it stops buffer prereading -// M42 - Change pin status via gcode Use M42 Px Sy to set pin x to value y, when omitting Px the onboard led will be used. -// M73 - Show percent done and print time remaining -// M80 - Turn on Power Supply -// M81 - Turn off Power Supply -// M82 - Set E codes absolute (default) -// M83 - Set E codes relative while in Absolute Coordinates (G90) mode -// M84 - Disable steppers until next move, -// or use S to specify an inactivity timeout, after which the steppers will be disabled. S0 to disable the timeout. -// M85 - Set inactivity shutdown timer with parameter S. To disable set zero (default) -// M86 - Set safety timer expiration time with parameter S; M86 S0 will disable safety timer -// M92 - Set axis_steps_per_unit - same syntax as G92 -// M104 - Set extruder target temp -// M105 - Read current temp -// M106 - Fan on -// M107 - Fan off -// M109 - Sxxx Wait for extruder current temp to reach target temp. Waits only when heating -// Rxxx Wait for extruder current temp to reach target temp. Waits when heating and cooling -// IF AUTOTEMP is enabled, S B F. Exit autotemp by any M109 without F -// M112 - Emergency stop -// M113 - Get or set the timeout interval for Host Keepalive "busy" messages -// M114 - Output current position to serial port -// M115 - Capabilities string -// M117 - display message -// M119 - Output Endstop status to serial port -// M126 - Solenoid Air Valve Open (BariCUDA support by jmil) -// M127 - Solenoid Air Valve Closed (BariCUDA vent to atmospheric pressure by jmil) -// M128 - EtoP Open (BariCUDA EtoP = electricity to air pressure transducer by jmil) -// M129 - EtoP Closed (BariCUDA EtoP = electricity to air pressure transducer by jmil) -// M140 - Set bed target temp -// 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. -// M190 - Sxxx Wait for bed current temp to reach target temp. Waits only when heating -// Rxxx Wait for bed current temp to reach target temp. Waits when heating and cooling -// M200 D- set filament diameter and set E axis units to cubic millimeters (use S0 to set back to millimeters). -// M201 - Set max acceleration in units/s^2 for print moves (M201 X1000 Y1000) -// M202 - Set max acceleration in units/s^2 for travel moves (M202 X1000 Y1000) Unused in Marlin!! -// M203 - Set maximum feedrate that your machine can sustain (M203 X200 Y200 Z300 E10000) in mm/sec -// M204 - Set default acceleration: S normal moves T filament only moves (M204 S3000 T7000) in mm/sec^2 also sets minimum segment time in ms (B20000) to prevent buffer under-runs and M20 minimum feedrate -// M205 - advanced settings: minimum travel speed S=while printing T=travel only, B=minimum segment time X= maximum xy jerk, Z=maximum Z jerk, E=maximum E jerk -// M206 - set additional homing offset -// M207 - set retract length S[positive mm] F[feedrate mm/min] Z[additional zlift/hop], stays in mm regardless of M200 setting -// M208 - set recover=unretract length S[positive mm surplus to the M207 S*] F[feedrate mm/sec] -// M209 - S<1=true/0=false> enable automatic retract detect if the slicer did not support G10/11: every normal extrude-only move will be classified as retract depending on the direction. -// M218 - set hotend offset (in mm): T X Y -// M220 S- set speed factor override percentage -// M221 S- set extrude factor override percentage -// M226 P S- Wait until the specified pin reaches the state required -// M240 - Trigger a camera to take a photograph -// M250 - Set LCD contrast C (value 0..63) -// M280 - set servo position absolute. P: servo index, S: angle or microseconds -// M300 - Play beep sound S P -// M301 - Set PID parameters P I and D -// M302 - Allow cold extrudes, or set the minimum extrude S. -// M303 - PID relay autotune S sets the target temperature. (default target temperature = 150C) -// M304 - Set bed PID parameters P I and D -// M400 - Finish all moves -// M401 - Lower z-probe if present -// M402 - Raise z-probe if present -// M404 - N Enter the nominal filament width (3mm, 1.75mm ) or will display nominal filament width without parameters -// M405 - Turn on Filament Sensor extrusion control. Optional D to set delay in centimeters between sensor and extruder -// M406 - Turn off Filament Sensor extrusion control -// M407 - Displays measured filament diameter -// M500 - stores parameters in EEPROM -// M501 - reads parameters from EEPROM (if you need reset them after you changed them temporarily). -// M502 - reverts to the default "factory settings". You still need to store them in EEPROM afterwards if you want to. -// M503 - print the current settings (from memory not from EEPROM) -// M509 - force language selection on next restart -// M540 - Use S[0|1] to enable or disable the stop SD card print on endstop hit (requires ABORT_ON_ENDSTOP_HIT_FEATURE_ENABLED) -// M600 - Pause for filament change X[pos] Y[pos] Z[relative lift] E[initial retract] L[later retract distance for removal] -// M605 - Set dual x-carriage movement mode: S [ X R ] -// M860 - Wait for PINDA thermistor to reach target temperature. -// M861 - Set / Read PINDA temperature compensation offsets -// M900 - Set LIN_ADVANCE options, if enabled. See Configuration_adv.h for details. -// M907 - Set digital trimpot motor current using axis codes. -// M908 - Control digital trimpot directly. -// M350 - Set microstepping mode. -// M351 - Toggle MS1 MS2 pins directly. - -// M928 - Start SD logging (M928 filename.g) - ended by M29 -// M999 - Restart after being stopped by error +#define FILAMENT_UNDEFINED 255 //Stepper Movement Variables @@ -305,7 +177,6 @@ float homing_feedrate[] = HOMING_FEEDRATE; // Other axes are always absolute or relative based on the common relative_mode flag. bool axis_relative_modes[] = AXIS_RELATIVE_MODES; int feedmultiply=100; //100->1 200->2 -int saved_feedmultiply; int extrudemultiply=100; //100->1 200->2 int extruder_multiply[EXTRUDERS] = {100 #if EXTRUDERS > 1 @@ -329,10 +200,6 @@ unsigned int usb_printing_counter; int8_t lcd_change_fil_state = 0; -int feedmultiplyBckp = 100; -float HotendTempBckp = 0; -int fanSpeedBckp = 0; -float pause_lastpos[4]; unsigned long pause_time = 0; unsigned long start_pause_print = millis(); unsigned long t_fan_rising_edge = millis(); @@ -450,8 +317,6 @@ bool no_response = false; uint8_t important_status; uint8_t saved_filament_type; -// save/restore printing -bool saved_printing = false; // save/restore printing in case that mmu was not responding bool mmu_print_saved = false; @@ -512,15 +377,20 @@ unsigned long chdkHigh = 0; boolean chdkActive = false; #endif -// save/restore printing -static uint32_t saved_sdpos = 0; +//! @name RAM save/restore printing +//! @{ +bool saved_printing = false; //!< Print is paused and saved in RAM +static uint32_t saved_sdpos = 0; //!< SD card position, or line number in case of USB printing static uint8_t saved_printing_type = PRINTING_TYPE_SD; static float saved_pos[4] = { 0, 0, 0, 0 }; -// Feedrate hopefully derived from an active block of the planner at the time the print has been canceled, in mm/min. +//! Feedrate hopefully derived from an active block of the planner at the time the print has been canceled, in mm/min. static float saved_feedrate2 = 0; static uint8_t saved_active_extruder = 0; +static float saved_extruder_temperature = 0.0; //!< Active extruder temperature static bool saved_extruder_under_pressure = false; static bool saved_extruder_relative_mode = false; +static int saved_fanSpeed = 0; //!< Print fan speed +//! @} //=========================================================================== //=============================Routines====================================== @@ -632,9 +502,6 @@ void servo_init() } -void stop_and_save_print_to_ram(float z_move, float e_move); -void restore_print_from_ram_and_continue(float e_move); - bool fans_check_enabled = true; @@ -730,16 +597,11 @@ void crashdet_detected(uint8_t mask) if (automatic_recovery_after_crash) { enquecommand_P(PSTR("CRASH_RECOVER")); }else{ - HotendTempBckp = degTargetHotend(active_extruder); setTargetHotend(0, active_extruder); bool yesno = lcd_show_fullscreen_message_yes_no_and_wait_P(_i("Crash detected. Resume print?"), false); lcd_update_enable(true); if (yesno) { - char cmd1[10]; - strcpy(cmd1, "M109 S"); - strcat(cmd1, ftostr3(HotendTempBckp)); - enquecommand(cmd1); enquecommand_P(PSTR("CRASH_RECOVER")); } else @@ -786,9 +648,8 @@ void failstats_reset_print() // Factory reset function // This function is used to erase parts or whole EEPROM memory which is used for storing calibration and and so on. // Level input parameter sets depth of reset -// Quiet parameter masks all waitings for user interact. int er_progress = 0; -void factory_reset(char level, bool quiet) +static void factory_reset(char level) { lcd_clear(); switch (level) { @@ -877,7 +738,7 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) // Erase EEPROM for (int i = 0; i < 4096; i++) { - eeprom_write_byte((uint8_t*)i, 0xFF); + eeprom_update_byte((uint8_t*)i, 0xFF); if (i % 41 == 0) { er_progress++; @@ -903,9 +764,9 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) } -FILE _uartout = {0}; +FILE _uartout; //= {0}; Global variable is always zero initialized. No need to explicitly state this. -int uart_putchar(char c, FILE *stream) +int uart_putchar(char c, FILE *) { MYSERIAL.write(c); return 0; @@ -950,7 +811,7 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) _delay_ms(2000); char level = reset_menu(); - factory_reset(level, false); + factory_reset(level); switch (level) { case 0: _delay_ms(0); break; @@ -1627,7 +1488,7 @@ void setup() erase_eeprom_section(EEPROM_OFFSET, 156); //erase M500 part of eeprom } if (eeprom_read_byte((uint8_t*)EEPROM_WIZARD_ACTIVE) == 1) { - lcd_wizard(0); + lcd_wizard(WizState::Run); } if (eeprom_read_byte((uint8_t*)EEPROM_WIZARD_ACTIVE) == 0) { //dont show calibration status messages if wizard is currently active if (calibration_status() == CALIBRATION_STATUS_ASSEMBLED || @@ -2001,23 +1862,25 @@ static void axis_is_at_home(int axis) { inline void set_current_to_destination() { memcpy(current_position, destination, sizeof(current_position)); } inline void set_destination_to_current() { memcpy(destination, current_position, sizeof(destination)); } - -static void setup_for_endstop_move(bool enable_endstops_now = true) { +//! @return original feedmultiply +static int setup_for_endstop_move(bool enable_endstops_now = true) { saved_feedrate = feedrate; - saved_feedmultiply = feedmultiply; + int l_feedmultiply = feedmultiply; feedmultiply = 100; previous_millis_cmd = millis(); enable_endstops(enable_endstops_now); + return l_feedmultiply; } -static void clean_up_after_endstop_move() { +//! @param original_feedmultiply feedmultiply to restore +static void clean_up_after_endstop_move(int original_feedmultiply) { #ifdef ENDSTOPS_ONLY_FOR_HOMING enable_endstops(false); #endif feedrate = saved_feedrate; - feedmultiply = saved_feedmultiply; + feedmultiply = original_feedmultiply; previous_millis_cmd = millis(); } @@ -2250,43 +2113,43 @@ void homeaxis(int axis, uint8_t cnt, uint8_t* pstep) #endif //TMC2130 - // Move right a bit, so that the print head does not touch the left end position, - // and the following left movement has a chance to achieve the required velocity + // Move away a bit, so that the print head does not touch the end position, + // 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]); set_destination_to_current(); // destination[axis] = 11.f; - destination[axis] = 3.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); st_synchronize(); - // Move left away from the possible collision with the collision detection disabled. + // 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]); - destination[axis] = - 1.; + 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); st_synchronize(); // Now continue to move up to the left end stop with the collision detection enabled. enable_endstops(true); - destination[axis] = - 1.1 * max_length(axis); + 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); st_synchronize(); for (uint8_t i = 0; i < cnt; i++) { - // Move right from the collision to a known distance from the left end stop with the collision detection disabled. + // Move away from the collision to a known distance from the left end stop 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]); - destination[axis] = 10.f; + 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); st_synchronize(); endstops_hit_on_purpose(); // Now move left up to the collision, this time with a repeatable velocity. enable_endstops(true); - destination[axis] = - 11.f; + destination[axis] = 11.f * axis_home_dir; #ifdef TMC2130 feedrate = homing_feedrate[axis]; #else //TMC2130 @@ -2310,10 +2173,10 @@ void homeaxis(int axis, uint8_t cnt, uint8_t* pstep) { tmc2130_goto_step(axis, orig, 2, 1000, tmc2130_get_res(axis)); if (back > 0) - tmc2130_do_steps(axis, back, 1, 1000); + tmc2130_do_steps(axis, back, -axis_home_dir, 1000); } else - tmc2130_do_steps(axis, 8, 2, 1000); + tmc2130_do_steps(axis, 8, -axis_home_dir, 1000); tmc2130_home_exit(); #endif //TMC2130 @@ -2321,9 +2184,9 @@ void homeaxis(int axis, uint8_t cnt, uint8_t* pstep) axis_known_position[axis] = true; // Move from minimum #ifdef TMC2130 - float dist = 0.01f * tmc2130_home_fsteps[axis]; + float dist = - axis_home_dir * 0.01f * tmc2130_home_fsteps[axis]; #else //TMC2130 - float dist = 0.01f * 64; + 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]); @@ -2602,7 +2465,7 @@ void gcode_G28(bool home_x_axis, long home_x_value, bool home_y_axis, long home_ babystep_undo(); saved_feedrate = feedrate; - saved_feedmultiply = feedmultiply; + int l_feedmultiply = feedmultiply; feedmultiply = 100; previous_millis_cmd = millis(); @@ -2788,7 +2651,7 @@ void gcode_G28(bool home_x_axis, long home_x_value, bool home_y_axis, long home_ #endif feedrate = saved_feedrate; - feedmultiply = saved_feedmultiply; + feedmultiply = l_feedmultiply; previous_millis_cmd = millis(); endstops_hit_on_purpose(); #ifndef MESH_BED_LEVELING @@ -2839,6 +2702,11 @@ void adjust_bed_reset() eeprom_update_byte((unsigned char*)EEPROM_BED_CORRECTION_REAR, 0); } +//! @brief Calibrate XYZ +//! @param onlyZ if true, calibrate only Z axis +//! @param verbosity_level +//! @retval true Succeeded +//! @retval false Failed bool gcode_M45(bool onlyZ, int8_t verbosity_level) { bool final_result = false; @@ -2868,7 +2736,7 @@ bool gcode_M45(bool onlyZ, int8_t verbosity_level) // Home in the XY plane. //set_destination_to_current(); - setup_for_endstop_move(); + int l_feedmultiply = setup_for_endstop_move(); lcd_display_message_fullscreen_P(_T(MSG_AUTO_HOME)); home_xy(); @@ -2926,18 +2794,9 @@ bool gcode_M45(bool onlyZ, int8_t verbosity_level) if (st_get_position_mm(Z_AXIS) == MESH_HOME_Z_SEARCH) { - - int8_t verbosity_level = 0; - if (code_seen('V')) - { - // Just 'V' without a number counts as V1. - char c = strchr_pointer[1]; - verbosity_level = (c == ' ' || c == '\t' || c == 0) ? 1 : code_value_short(); - } - if (onlyZ) { - clean_up_after_endstop_move(); + clean_up_after_endstop_move(l_feedmultiply); // Z only calibration. // Load the machine correction matrix world2machine_initialize(); @@ -2962,7 +2821,7 @@ bool gcode_M45(bool onlyZ, int8_t verbosity_level) // Complete XYZ calibration. uint8_t point_too_far_mask = 0; BedSkewOffsetDetectionResultType result = find_bed_offset_and_skew(verbosity_level, point_too_far_mask); - clean_up_after_endstop_move(); + clean_up_after_endstop_move(l_feedmultiply); // Print head up. current_position[Z_AXIS] = MESH_HOME_Z_SEARCH; plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], homing_feedrate[Z_AXIS] / 40, active_extruder); @@ -2979,10 +2838,10 @@ bool gcode_M45(bool onlyZ, int8_t verbosity_level) mbl.reset(); world2machine_reset(); // Home in the XY plane. - setup_for_endstop_move(); + int l_feedmultiply = setup_for_endstop_move(); home_xy(); result = improve_bed_offset_and_skew(1, verbosity_level, point_too_far_mask); - clean_up_after_endstop_move(); + clean_up_after_endstop_move(l_feedmultiply); // Print head up. current_position[Z_AXIS] = MESH_HOME_Z_SEARCH; plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], homing_feedrate[Z_AXIS] / 40, active_extruder); @@ -3047,117 +2906,124 @@ void gcode_M114() SERIAL_PROTOCOLLN(""); } -void gcode_M600(bool automatic, float x_position, float y_position, float z_shift, float e_shift, float e_shift_late) { - st_synchronize(); - float lastpos[4]; +static void gcode_M600(bool automatic, float x_position, float y_position, float z_shift, float e_shift, float /*e_shift_late*/) +{ + st_synchronize(); + float lastpos[4]; - if (farm_mode) - { - prusa_statistics(22); - } + if (farm_mode) + { + prusa_statistics(22); + } - //First backup current position and settings - feedmultiplyBckp=feedmultiply; - HotendTempBckp = degTargetHotend(active_extruder); - fanSpeedBckp = fanSpeed; + //First backup current position and settings + int feedmultiplyBckp = feedmultiply; + float HotendTempBckp = degTargetHotend(active_extruder); + int fanSpeedBckp = fanSpeed; - lastpos[X_AXIS]=current_position[X_AXIS]; - lastpos[Y_AXIS]=current_position[Y_AXIS]; - lastpos[Z_AXIS]=current_position[Z_AXIS]; - lastpos[E_AXIS]=current_position[E_AXIS]; + lastpos[X_AXIS] = current_position[X_AXIS]; + lastpos[Y_AXIS] = current_position[Y_AXIS]; + lastpos[Z_AXIS] = current_position[Z_AXIS]; + lastpos[E_AXIS] = current_position[E_AXIS]; - //Retract E - current_position[E_AXIS]+= e_shift; - plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], FILAMENTCHANGE_RFEED, active_extruder); - st_synchronize(); + //Retract E + current_position[E_AXIS] += e_shift; + plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], + current_position[E_AXIS], FILAMENTCHANGE_RFEED, active_extruder); + st_synchronize(); - //Lift Z - current_position[Z_AXIS]+= z_shift; - plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], FILAMENTCHANGE_ZFEED, active_extruder); - st_synchronize(); - - //Move XY to side - current_position[X_AXIS]= x_position; - current_position[Y_AXIS]= y_position; - plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], FILAMENTCHANGE_XYFEED, active_extruder); - st_synchronize(); - - //Beep, manage nozzle heater and wait for user to start unload filament - if(!mmu_enabled) M600_wait_for_user(); - - lcd_change_fil_state = 0; - - // Unload filament - if (mmu_enabled) - extr_unload(); //unload just current filament for multimaterial printers (used also in M702) - else - unload_filament(); //unload filament for single material (used also in M702) - //finish moves - st_synchronize(); + //Lift Z + current_position[Z_AXIS] += z_shift; + plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], + current_position[E_AXIS], FILAMENTCHANGE_ZFEED, active_extruder); + st_synchronize(); - if (!mmu_enabled) - { - KEEPALIVE_STATE(PAUSED_FOR_USER); - lcd_change_fil_state = lcd_show_fullscreen_message_yes_no_and_wait_P(_i("Was filament unload successful?"), false, true);////MSG_UNLOAD_SUCCESSFUL c=20 r=2 - if (lcd_change_fil_state == 0) lcd_show_fullscreen_message_and_wait_P(_i("Please open idler and remove filament manually."));////MSG_CHECK_IDLER c=20 r=4 - lcd_update_enable(true); - } + //Move XY to side + current_position[X_AXIS] = x_position; + current_position[Y_AXIS] = y_position; + plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], + current_position[E_AXIS], FILAMENTCHANGE_XYFEED, active_extruder); + st_synchronize(); - if (mmu_enabled) - { - if (!automatic) { - if (saved_printing) mmu_eject_filament(mmu_extruder, false); //if M600 was invoked by filament senzor (FINDA) eject filament so user can easily remove it - mmu_M600_wait_and_beep(); - if (saved_printing) { + //Beep, manage nozzle heater and wait for user to start unload filament + if(!mmu_enabled) M600_wait_for_user(HotendTempBckp); - lcd_clear(); - lcd_set_cursor(0, 2); - lcd_puts_P(_T(MSG_PLEASE_WAIT)); + lcd_change_fil_state = 0; - mmu_command(MMU_CMD_R0); - manage_response(false, false); - } - } - mmu_M600_load_filament(automatic); - } - else - M600_load_filament(); + // Unload filament + if (mmu_enabled) extr_unload(); //unload just current filament for multimaterial printers (used also in M702) + else unload_filament(); //unload filament for single material (used also in M702) + //finish moves + st_synchronize(); - if(!automatic) M600_check_state(); + if (!mmu_enabled) + { + KEEPALIVE_STATE(PAUSED_FOR_USER); + lcd_change_fil_state = lcd_show_fullscreen_message_yes_no_and_wait_P(_i("Was filament unload successful?"), + false, true); ////MSG_UNLOAD_SUCCESSFUL c=20 r=2 + if (lcd_change_fil_state == 0) + lcd_show_fullscreen_message_and_wait_P(_i("Please open idler and remove filament manually."));////MSG_CHECK_IDLER c=20 r=4 + lcd_update_enable(true); + } + + if (mmu_enabled) + { + if (!automatic) { + if (saved_printing) mmu_eject_filament(mmu_extruder, false); //if M600 was invoked by filament senzor (FINDA) eject filament so user can easily remove it + mmu_M600_wait_and_beep(); + if (saved_printing) { + + lcd_clear(); + lcd_set_cursor(0, 2); + lcd_puts_P(_T(MSG_PLEASE_WAIT)); + + mmu_command(MMU_CMD_R0); + manage_response(false, false); + } + } + mmu_M600_load_filament(automatic); + } + else + M600_load_filament(); + + if (!automatic) M600_check_state(); lcd_update_enable(true); - //Not let's go back to print - fanSpeed = fanSpeedBckp; + //Not let's go back to print + fanSpeed = fanSpeedBckp; - //Feed a little of filament to stabilize pressure - if (!automatic) { - current_position[E_AXIS] += FILAMENTCHANGE_RECFEED; - plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], FILAMENTCHANGE_EXFEED, active_extruder); - } - - //Move XY back - plan_buffer_line(lastpos[X_AXIS], lastpos[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], FILAMENTCHANGE_XYFEED, active_extruder); - st_synchronize(); - //Move Z back - plan_buffer_line(lastpos[X_AXIS], lastpos[Y_AXIS], lastpos[Z_AXIS], current_position[E_AXIS], FILAMENTCHANGE_ZFEED, active_extruder); - st_synchronize(); + //Feed a little of filament to stabilize pressure + if (!automatic) + { + current_position[E_AXIS] += FILAMENTCHANGE_RECFEED; + plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], + current_position[E_AXIS], FILAMENTCHANGE_EXFEED, active_extruder); + } - //Set E position to original - plan_set_e_position(lastpos[E_AXIS]); + //Move XY back + plan_buffer_line(lastpos[X_AXIS], lastpos[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], + FILAMENTCHANGE_XYFEED, active_extruder); + st_synchronize(); + //Move Z back + plan_buffer_line(lastpos[X_AXIS], lastpos[Y_AXIS], lastpos[Z_AXIS], current_position[E_AXIS], + FILAMENTCHANGE_ZFEED, active_extruder); + st_synchronize(); - memcpy(current_position, lastpos, sizeof(lastpos)); - memcpy(destination, current_position, sizeof(current_position)); - - //Recover feed rate - feedmultiply=feedmultiplyBckp; - char cmd[9]; - sprintf_P(cmd, PSTR("M220 S%i"), feedmultiplyBckp); - enquecommand(cmd); - - lcd_setstatuspgm(_T(WELCOME_MSG)); - custom_message_type = CUSTOM_MSG_TYPE_STATUS; - + //Set E position to original + plan_set_e_position(lastpos[E_AXIS]); + + memcpy(current_position, lastpos, sizeof(lastpos)); + memcpy(destination, current_position, sizeof(current_position)); + + //Recover feed rate + feedmultiply = feedmultiplyBckp; + char cmd[9]; + sprintf_P(cmd, PSTR("M220 S%i"), feedmultiplyBckp); + enquecommand(cmd); + + lcd_setstatuspgm(_T(WELCOME_MSG)); + custom_message_type = CUSTOM_MSG_TYPE_STATUS; } @@ -3289,7 +3155,136 @@ extern uint8_t st_backlash_x; extern uint8_t st_backlash_y; #endif //BACKLASH_Y - +//! @brief Parse and process commands +//! +//! look here for descriptions of G-codes: http://linuxcnc.org/handbook/gcode/g-code.html +//! http://objects.reprap.org/wiki/Mendel_User_Manual:_RepRapGCodes +//! +//! Implemented Codes +//! ------------------- +//! +//!@n PRUSA CODES +//!@n P F - Returns FW versions +//!@n P R - Returns revision of printer +//! +//!@n G0 -> G1 +//!@n G1 - Coordinated Movement X Y Z E +//!@n G2 - CW ARC +//!@n G3 - CCW ARC +//!@n G4 - Dwell S or P +//!@n G10 - retract filament according to settings of M207 +//!@n G11 - retract recover filament according to settings of M208 +//!@n G28 - Home all Axis +//!@n G29 - Detailed Z-Probe, probes the bed at 3 or more points. Will fail if you haven't homed yet. +//!@n G30 - Single Z Probe, probes bed at current XY location. +//!@n G31 - Dock sled (Z_PROBE_SLED only) +//!@n G32 - Undock sled (Z_PROBE_SLED only) +//!@n G80 - Automatic mesh bed leveling +//!@n G81 - Print bed profile +//!@n G90 - Use Absolute Coordinates +//!@n G91 - Use Relative Coordinates +//!@n G92 - Set current position to coordinates given +//! +//!@n M Codes +//!@n M0 - Unconditional stop - Wait for user to press a button on the LCD +//!@n M1 - Same as M0 +//!@n M17 - Enable/Power all stepper motors +//!@n M18 - Disable all stepper motors; same as M84 +//!@n M20 - List SD card +//!@n M21 - Init SD card +//!@n M22 - Release SD card +//!@n M23 - Select SD file (M23 filename.g) +//!@n M24 - Start/resume SD print +//!@n M25 - Pause SD print +//!@n M26 - Set SD position in bytes (M26 S12345) +//!@n M27 - Report SD print status +//!@n M28 - Start SD write (M28 filename.g) +//!@n M29 - Stop SD write +//!@n M30 - Delete file from SD (M30 filename.g) +//!@n M31 - Output time since last M109 or SD card start to serial +//!@n M32 - Select file and start SD print (Can be used _while_ printing from SD card files): +//! syntax "M32 /path/filename#", or "M32 S !filename#" +//! Call gcode file : "M32 P !filename#" and return to caller file after finishing (similar to #include). +//! The '#' is necessary when calling from within sd files, as it stops buffer prereading +//!@n M42 - Change pin status via gcode Use M42 Px Sy to set pin x to value y, when omitting Px the onboard led will be used. +//!@n M73 - Show percent done and print time remaining +//!@n M80 - Turn on Power Supply +//!@n M81 - Turn off Power Supply +//!@n M82 - Set E codes absolute (default) +//!@n M83 - Set E codes relative while in Absolute Coordinates (G90) mode +//!@n M84 - Disable steppers until next move, +//! or use S to specify an inactivity timeout, after which the steppers will be disabled. S0 to disable the timeout. +//!@n M85 - Set inactivity shutdown timer with parameter S. To disable set zero (default) +//!@n M86 - Set safety timer expiration time with parameter S; M86 S0 will disable safety timer +//!@n M92 - Set axis_steps_per_unit - same syntax as G92 +//!@n M104 - Set extruder target temp +//!@n M105 - Read current temp +//!@n M106 - Fan on +//!@n M107 - Fan off +//!@n M109 - Sxxx Wait for extruder current temp to reach target temp. Waits only when heating +//! Rxxx Wait for extruder current temp to reach target temp. Waits when heating and cooling +//! IF AUTOTEMP is enabled, S B F. Exit autotemp by any M109 without F +//!@n M112 - Emergency stop +//!@n M113 - Get or set the timeout interval for Host Keepalive "busy" messages +//!@n M114 - Output current position to serial port +//!@n M115 - Capabilities string +//!@n M117 - display message +//!@n M119 - Output Endstop status to serial port +//!@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 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- set filament diameter and set E axis units to cubic millimeters (use S0 to set back to millimeters). +//!@n M201 - Set max acceleration in units/s^2 for print moves (M201 X1000 Y1000) +//!@n M202 - Set max acceleration in units/s^2 for travel moves (M202 X1000 Y1000) Unused in Marlin!! +//!@n M203 - Set maximum feedrate that your machine can sustain (M203 X200 Y200 Z300 E10000) in mm/sec +//!@n M204 - Set default acceleration: S normal moves T filament only moves (M204 S3000 T7000) in mm/sec^2 also sets minimum segment time in ms (B20000) to prevent buffer under-runs and M20 minimum feedrate +//!@n M205 - advanced settings: minimum travel speed S=while printing T=travel only, B=minimum segment time X= maximum xy jerk, Z=maximum Z jerk, E=maximum E jerk +//!@n M206 - set additional homing offset +//!@n M207 - set retract length S[positive mm] F[feedrate mm/min] Z[additional zlift/hop], stays in mm regardless of M200 setting +//!@n M208 - set recover=unretract length S[positive mm surplus to the M207 S*] F[feedrate mm/sec] +//!@n M209 - S<1=true/0=false> enable automatic retract detect if the slicer did not support G10/11: every normal extrude-only move will be classified as retract depending on the direction. +//!@n M218 - set hotend offset (in mm): T X Y +//!@n M220 S- set speed factor override percentage +//!@n M221 S- set extrude factor override percentage +//!@n M226 P S- Wait until the specified pin reaches the state required +//!@n M240 - Trigger a camera to take a photograph +//!@n M250 - Set LCD contrast C (value 0..63) +//!@n M280 - set servo position absolute. P: servo index, S: angle or microseconds +//!@n M300 - Play beep sound S P +//!@n M301 - Set PID parameters P I and D +//!@n M302 - Allow cold extrudes, or set the minimum extrude S. +//!@n M303 - PID relay autotune S sets the target temperature. (default target temperature = 150C) +//!@n M304 - Set bed PID parameters P I and D +//!@n M400 - Finish all moves +//!@n M401 - Lower z-probe if present +//!@n M402 - Raise z-probe if present +//!@n M404 - N Enter the nominal filament width (3mm, 1.75mm ) or will display nominal filament width without parameters +//!@n M405 - Turn on Filament Sensor extrusion control. Optional D to set delay in centimeters between sensor and extruder +//!@n M406 - Turn off Filament Sensor extrusion control +//!@n M407 - Displays measured filament diameter +//!@n M500 - stores parameters in EEPROM +//!@n M501 - reads parameters from EEPROM (if you need reset them after you changed them temporarily). +//!@n M502 - reverts to the default "factory settings". You still need to store them in EEPROM afterwards if you want to. +//!@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 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 [ X R ] +//!@n M860 - Wait for PINDA thermistor to reach target temperature. +//!@n M861 - Set / Read PINDA temperature compensation offsets +//!@n M900 - Set LIN_ADVANCE options, if enabled. See Configuration_adv.h for details. +//!@n M907 - Set digital trimpot motor current using axis codes. +//!@n M908 - Control digital trimpot directly. +//!@n M350 - Set microstepping mode. +//!@n M351 - Toggle MS1 MS2 pins directly. +//! +//!@n M928 - Start SD logging (M928 filename.g) - ended by M29 +//!@n M999 - Restart after being stopped by error void process_commands() { if (!buflen) return; //empty command @@ -3331,21 +3326,21 @@ void process_commands() #ifdef TMC2130 else if (strncmp_P(CMDBUFFER_CURRENT_STRING, PSTR("CRASH_"), 6) == 0) { - if(code_seen("CRASH_DETECTED")) + if(code_seen("CRASH_DETECTED")) //! CRASH_DETECTED { uint8_t mask = 0; if (code_seen('X')) mask |= X_AXIS_MASK; if (code_seen('Y')) mask |= Y_AXIS_MASK; crashdet_detected(mask); } - else if(code_seen("CRASH_RECOVER")) + else if(code_seen("CRASH_RECOVER")) //! CRASH_RECOVER crashdet_recover(); - else if(code_seen("CRASH_CANCEL")) + else if(code_seen("CRASH_CANCEL")) //! CRASH_CANCEL crashdet_cancel(); } else if (strncmp_P(CMDBUFFER_CURRENT_STRING, PSTR("TMC_"), 4) == 0) { - if (strncmp_P(CMDBUFFER_CURRENT_STRING + 4, PSTR("SET_WAVE_"), 9) == 0) + if (strncmp_P(CMDBUFFER_CURRENT_STRING + 4, PSTR("SET_WAVE_"), 9) == 0) //! TMC_SET_WAVE_ { uint8_t axis = *(CMDBUFFER_CURRENT_STRING + 13); axis = (axis == 'E')?3:(axis - 'X'); @@ -3355,7 +3350,7 @@ void process_commands() tmc2130_set_wave(axis, 247, fac); } } - else if (strncmp_P(CMDBUFFER_CURRENT_STRING + 4, PSTR("SET_STEP_"), 9) == 0) + else if (strncmp_P(CMDBUFFER_CURRENT_STRING + 4, PSTR("SET_STEP_"), 9) == 0) //! TMC_SET_STEP_ { uint8_t axis = *(CMDBUFFER_CURRENT_STRING + 13); axis = (axis == 'E')?3:(axis - 'X'); @@ -3366,7 +3361,7 @@ void process_commands() tmc2130_goto_step(axis, step & (4*res - 1), 2, 1000, res); } } - else if (strncmp_P(CMDBUFFER_CURRENT_STRING + 4, PSTR("SET_CHOP_"), 9) == 0) + else if (strncmp_P(CMDBUFFER_CURRENT_STRING + 4, PSTR("SET_CHOP_"), 9) == 0) //! TMC_SET_CHOP_ { uint8_t axis = *(CMDBUFFER_CURRENT_STRING + 13); axis = (axis == 'E')?3:(axis - 'X'); @@ -3417,22 +3412,22 @@ void process_commands() } #endif //BACKLASH_Y #endif //TMC2130 - else if (code_seen("FSENSOR_RECOVER")) { + else if (code_seen("FSENSOR_RECOVER")) { //! FSENSOR_RECOVER fsensor_restore_print_and_continue(); } else if(code_seen("PRUSA")){ - if (code_seen("Ping")) { //PRUSA Ping + if (code_seen("Ping")) { //! PRUSA Ping if (farm_mode) { PingTime = millis(); //MYSERIAL.print(farm_no); MYSERIAL.println(": OK"); } } - else if (code_seen("PRN")) { + else if (code_seen("PRN")) { //! PRUSA PRN printf_P(_N("%d"), status_number); - }else if (code_seen("FAN")) { + }else if (code_seen("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")) { + }else if (code_seen("fn")) { //! PRUSA fn if (farm_mode) { printf_P(_N("%d"), farm_no); } @@ -3441,20 +3436,20 @@ void process_commands() } } - else if (code_seen("thx")) + else if (code_seen("thx")) //! PRUSA thx { no_response = false; } - else if (code_seen("uvlo")) + else if (code_seen("uvlo")) //! PRUSA uvlo { eeprom_update_byte((uint8_t*)EEPROM_UVLO,0); enquecommand_P(PSTR("M24")); } - else if (code_seen("MMURES")) + else if (code_seen("MMURES")) //! PRUSA MMURES { mmu_reset(); } - else if (code_seen("RESET")) { + else if (code_seen("RESET")) { //! PRUSA RESET // careful! if (farm_mode) { #ifdef WATCHDOG @@ -3470,7 +3465,7 @@ void process_commands() else { MYSERIAL.println("Not in farm mode."); } - }else if (code_seen("fv")) { + }else if (code_seen("fv")) { //! PRUSA fv // get file version #ifdef SDSUPPORT card.openFile(strchr_pointer + 3,true); @@ -3485,35 +3480,35 @@ void process_commands() #endif // SDSUPPORT - } else if (code_seen("M28")) { + } else if (code_seen("M28")) { //! PRUSA M28 trace(); prusa_sd_card_upload = true; card.openFile(strchr_pointer+4,false); - } else if (code_seen("SN")) { + } else if (code_seen("SN")) { //! PRUSA SN gcode_PRUSA_SN(); - } else if(code_seen("Fir")){ + } else if(code_seen("Fir")){ //! PRUSA Fir SERIAL_PROTOCOLLN(FW_VERSION_FULL); - } else if(code_seen("Rev")){ + } else if(code_seen("Rev")){ //! PRUSA Rev SERIAL_PROTOCOLLN(FILAMENT_SIZE "-" ELECTRONICS "-" NOZZLE_TYPE ); - } else if(code_seen("Lang")) { + } else if(code_seen("Lang")) { //! PRUSA Lang lang_reset(); - } else if(code_seen("Lz")) { + } else if(code_seen("Lz")) { //! PRUSA Lz EEPROM_save_B(EEPROM_BABYSTEP_Z,0); - } else if(code_seen("Beat")) { + } else if(code_seen("Beat")) { //! PRUSA Beat // Kick farm link timer kicktime = millis(); - } else if(code_seen("FR")) { + } else if(code_seen("FR")) { //! PRUSA FR // Factory full reset - factory_reset(0,true); + factory_reset(0); } //else if (code_seen('Cal')) { // lcd_calibration(); @@ -3536,7 +3531,7 @@ void process_commands() if(READ(FR_SENS)){ - feedmultiplyBckp=feedmultiply; + int feedmultiplyBckp=feedmultiply; float target[4]; float lastpos[4]; target[X_AXIS]=current_position[X_AXIS]; @@ -3818,7 +3813,7 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) 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]); - setup_for_endstop_move(); + int l_feedmultiply = setup_for_endstop_move(); feedrate = homing_feedrate[Z_AXIS]; #ifdef AUTO_BED_LEVELING_GRID @@ -3884,7 +3879,7 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) xProbe += xInc; } } - clean_up_after_endstop_move(); + clean_up_after_endstop_move(l_feedmultiply); // solve lsq problem double *plane_equation_coefficients = qr_solve(AUTO_BED_LEVELING_GRID_POINTS*AUTO_BED_LEVELING_GRID_POINTS, 3, eqnAMatrix, eqnBVector); @@ -3913,7 +3908,7 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) // probe 3 float z_at_pt_3 = probe_pt(ABL_PROBE_PT_3_X, ABL_PROBE_PT_3_Y, current_position[Z_AXIS] + Z_RAISE_BETWEEN_PROBINGS); - clean_up_after_endstop_move(); + clean_up_after_endstop_move(l_feedmultiply); set_bed_level_equation_3pts(z_at_pt_1, z_at_pt_2, z_at_pt_3); @@ -3939,7 +3934,7 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) { st_synchronize(); // TODO: make sure the bed_level_rotation_matrix is identity or the planner will get set incorectly - setup_for_endstop_move(); + int l_feedmultiply = setup_for_endstop_move(); feedrate = homing_feedrate[Z_AXIS]; @@ -3953,7 +3948,7 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) SERIAL_PROTOCOL(current_position[Z_AXIS]); SERIAL_PROTOCOLPGM("\n"); - clean_up_after_endstop_move(); + clean_up_after_endstop_move(l_feedmultiply); } break; #else @@ -3971,7 +3966,7 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) { st_synchronize(); // TODO: make sure the bed_level_rotation_matrix is identity or the planner will get set incorectly - setup_for_endstop_move(); + int l_feedmultiply = setup_for_endstop_move(); feedrate = homing_feedrate[Z_AXIS]; @@ -3979,7 +3974,7 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) printf_P(_N("%S X: %.5f Y: %.5f Z: %.5f\n"), _T(MSG_BED), _x, _y, _z); - clean_up_after_endstop_move(); + clean_up_after_endstop_move(l_feedmultiply); } break; @@ -3991,7 +3986,7 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) } break; - case 76: //PINDA probe temperature calibration + case 76: //! G76 - PINDA probe temperature calibration { #ifdef PINDA_THERMISTOR if (true) @@ -4250,12 +4245,9 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) #ifdef DIS case 77: { - //G77 X200 Y150 XP100 YP15 XO10 Y015 - - //for 9 point mesh bed leveling G77 X203 Y196 XP3 YP3 XO0 YO0 - - - //G77 X232 Y218 XP116 YP109 XO-11 YO0 + //! G77 X200 Y150 XP100 YP15 XO10 Y015 + //! for 9 point mesh bed leveling G77 X203 Y196 XP3 YP3 XO0 YO0 + //! G77 X232 Y218 XP116 YP109 XO-11 YO0 float dimension_x = 40; float dimension_y = 40; @@ -4294,12 +4286,12 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) * mesh to compensate for variable bed height * * The S0 report the points as below - * + * @code{.unparsed} * +----> X-axis * | * | * v Y-axis - * + * @endcode */ case 80: @@ -4404,7 +4396,7 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) has_z ? SERIAL_PROTOCOLPGM("Z jitter data from Z cal. valid.\n") : SERIAL_PROTOCOLPGM("Z jitter data from Z cal. not valid.\n"); } #endif // SUPPORT_VERBOSITY - setup_for_endstop_move(false); //save feedrate and feedmultiply, sets feedmultiply to 100 + int l_feedmultiply = setup_for_endstop_move(false); //save feedrate and feedmultiply, sets feedmultiply to 100 const char *kill_message = NULL; while (mesh_point != MESH_MEAS_NUM_X_POINTS * MESH_MEAS_NUM_Y_POINTS) { // Get coords of a measuring point. @@ -4511,7 +4503,7 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) kill(kill_message); SERIAL_ECHOLNPGM("killed"); } - clean_up_after_endstop_move(); + clean_up_after_endstop_move(l_feedmultiply); // SERIAL_ECHOLNPGM("clean up finished "); bool apply_temp_comp = true; @@ -4635,9 +4627,9 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) */ case 82: SERIAL_PROTOCOLLNPGM("Finding bed "); - setup_for_endstop_move(); + int l_feedmultiply = setup_for_endstop_move(); find_bed_induction_sensor_point_z(); - clean_up_after_endstop_move(); + clean_up_after_endstop_move(l_feedmultiply); SERIAL_PROTOCOLPGM("Bed found at: "); SERIAL_PROTOCOL_F(current_position[Z_AXIS], 5); SERIAL_PROTOCOLPGM("\n"); @@ -4732,7 +4724,7 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) } break; - case 98: // G98 (activate farm mode) + case 98: //! G98 (activate farm mode) farm_mode = 1; PingTime = millis(); eeprom_update_byte((unsigned char *)EEPROM_FARM_MODE, farm_mode); @@ -4741,7 +4733,7 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) eeprom_update_byte((unsigned char *)EEPROM_SILENT, SilentModeMenu); break; - case 99: // G99 (deactivate farm mode) + case 99: //! G99 (deactivate farm mode) farm_mode = 0; lcd_printer_connected(); eeprom_update_byte((unsigned char *)EEPROM_FARM_MODE, farm_mode); @@ -4987,7 +4979,7 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) } } break; - case 44: // M44: Prusa3D: Reset the bed skew and offset calibration. + case 44: //! M44: Prusa3D: Reset the bed skew and offset calibration. // Reset the baby step value and the baby step applied flag. calibration_status_store(CALIBRATION_STATUS_ASSEMBLED); @@ -5001,7 +4993,7 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) world2machine_revert_to_uncorrected(); break; - case 45: // M45: Prusa3D: bed skew and offset with manual Z up + case 45: //! M45: Prusa3D: bed skew and offset with manual Z up { int8_t verbosity_level = 0; bool only_Z = code_seen('Z'); @@ -5041,14 +5033,14 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) */ case 47: - // M47: Prusa3D: Show end stops dialog on the display. + //! M47: Prusa3D: Show end stops dialog on the display. KEEPALIVE_STATE(PAUSED_FOR_USER); lcd_diag_show_end_stops(); KEEPALIVE_STATE(IN_HANDLER); break; #if 0 - case 48: // M48: scan the bed induction sensor points, print the sensor trigger coordinates to the serial line for visualization on the PC. + case 48: //! M48: scan the bed induction sensor points, print the sensor trigger coordinates to the serial line for visualization on the PC. { // Disable the default update procedure of the display. We will do a modal dialog. lcd_update_enable(false); @@ -5064,7 +5056,7 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) st_synchronize(); // Home in the XY plane. set_destination_to_current(); - setup_for_endstop_move(); + int l_feedmultiply = setup_for_endstop_move(); home_xy(); int8_t verbosity_level = 0; if (code_seen('V')) { @@ -5073,7 +5065,7 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) verbosity_level = (c == ' ' || c == '\t' || c == 0) ? 1 : code_value_short(); } bool success = scan_bed_induction_points(verbosity_level); - clean_up_after_endstop_move(); + clean_up_after_endstop_move(l_feedmultiply); // Print head up. current_position[Z_AXIS] = MESH_HOME_Z_SEARCH; plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS],current_position[Z_AXIS] , current_position[E_AXIS], homing_feedrate[Z_AXIS]/40, active_extruder); @@ -5083,23 +5075,22 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) } #endif -// M48 Z-Probe repeatability measurement function. -// -// Usage: M48 -// -// This function assumes the bed has been homed. Specificaly, that a G28 command -// as been issued prior to invoking the M48 Z-Probe repeatability measurement function. -// Any information generated by a prior G29 Bed leveling command will be lost and need to be -// regenerated. -// -// The number of samples will default to 10 if not specified. You can use upper or lower case -// letters for any of the options EXCEPT n. n must be in lower case because Marlin uses a capital -// N for its communication protocol and will get horribly confused if you send it a capital N. -// #ifdef ENABLE_AUTO_BED_LEVELING #ifdef Z_PROBE_REPEATABILITY_TEST - + //! M48 Z-Probe repeatability measurement function. + //! + //! Usage: M48 + //! + //! This function assumes the bed has been homed. Specificaly, that a G28 command + //! as been issued prior to invoking the M48 Z-Probe repeatability measurement function. + //! Any information generated by a prior G29 Bed leveling command will be lost and need to be + //! regenerated. + //! + //! The number of samples will default to 10 if not specified. You can use upper or lower case + //! letters for any of the options EXCEPT n. n must be in lower case because Marlin uses a capital + //! N for its communication protocol and will get horribly confused if you send it a capital N. + //! case 48: // M48 Z-Probe repeatability { #if Z_MIN_PIN == -1 @@ -5203,7 +5194,7 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) // Then retrace the right amount and use that in subsequent probes // - setup_for_endstop_move(); + int l_feedmultiply = setup_for_endstop_move(); run_z_probe(); current_position[Z_AXIS] = Z_current = st_get_position_mm(Z_AXIS); @@ -5267,7 +5258,7 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) do_blocking_move_to( X_probe_location, Y_probe_location, Z_start_location); // Go back to the probe location } - setup_for_endstop_move(); + int l_feedmultiply = setup_for_endstop_move(); run_z_probe(); sample_set[n] = current_position[Z_AXIS]; @@ -5318,9 +5309,9 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) delay(1000); - clean_up_after_endstop_move(); + clean_up_after_endstop_move(l_feedmultiply); -// enable_endstops(true); +// enable_endstops(true); if (verbose_level > 0) { SERIAL_PROTOCOLPGM("Mean: "); @@ -5565,7 +5556,7 @@ Sigma_Exit: break; #if defined(FAN_PIN) && FAN_PIN > -1 - case 106: //M106 Fan On + case 106: //!M106 Sxxx Fan On S 0 .. 255 if (code_seen('S')){ fanSpeed=constrain(code_value(),0,255); } @@ -5694,7 +5685,7 @@ Sigma_Exit: } } break; - case 110: // M110 - reset line pos + case 110: //! M110 N - reset line pos if (code_seen('N')) gcode_LastN = code_value_long(); break; @@ -5741,10 +5732,10 @@ Sigma_Exit: case 114: // M114 gcode_M114(); break; - case 120: // M120 + case 120: //! M120 - Disable endstops enable_endstops(false) ; break; - case 121: // M121 + case 121: //! M121 - Enable endstops enable_endstops(true) ; break; case 119: // M119 @@ -5915,9 +5906,9 @@ Sigma_Exit: } break; case 204: - // M204 acclereration settings. - // Supporting old format: M204 S[normal moves] T[filmanent only moves] - // and new format: M204 P[printing moves] R[filmanent only moves] T[travel moves] (as of now T is ignored) + //! M204 acclereration settings. + //!@n Supporting old format: M204 S[normal moves] T[filmanent only moves] + //!@n and new format: M204 P[printing moves] R[filmanent only moves] T[travel moves] (as of now T is ignored) { if(code_seen('S')) { // Legacy acceleration format. This format is used by the legacy Marlin, MK2 or MK3 firmware, @@ -6301,15 +6292,15 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) } break; - case 403: //M403 set filament type (material) for particular extruder and send this information to mmu + case 403: //! M403 set filament type (material) for particular extruder and send this information to mmu { - //currently three different materials are needed (default, flex and PVA) - //add storing this information for different load/unload profiles etc. in the future - //firmware does not wait for "ok" from mmu + //! currently three different materials are needed (default, flex and PVA) + //! add storing this information for different load/unload profiles etc. in the future + //!firmware does not wait for "ok" from mmu if (mmu_enabled) { - uint8_t extruder; - uint8_t filament; + uint8_t extruder = 255; + uint8_t filament = FILAMENT_UNDEFINED; if(code_seen('E')) extruder = code_value(); if(code_seen('F')) filament = code_value(); mmu_set_filament_type(extruder, filament); @@ -6466,13 +6457,14 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) } break; #endif //FILAMENTCHANGEENABLE - case 601: { - if(lcd_commands_type == 0) lcd_commands_type = LCD_COMMAND_LONG_PAUSE; + case 601: //! M601 - Pause print + { + lcd_pause_print(); } break; - case 602: { - if(lcd_commands_type == 0) lcd_commands_type = LCD_COMMAND_LONG_PAUSE_RESUME; + case 602: { //! M602 - Resume print + lcd_resume_print(); } break; @@ -6564,8 +6556,8 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) else if (code_seen('S')) { // Sxxx Iyyy - Set compensation ustep value S for compensation table index I int16_t usteps = code_value(); if (code_seen('I')) { - byte index = code_value(); - if ((index >= 0) && (index < 5)) { + uint8_t index = code_value(); + if (index < 5) { EEPROM_save_B(EEPROM_PROBE_TEMP_SHIFT + index * 2, &usteps); SERIAL_PROTOCOLLN("OK"); SERIAL_PROTOCOLLN("index, temp, ustep, um"); @@ -6630,13 +6622,13 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) #ifdef TMC2130 - case 910: // M910 TMC2130 init + case 910: //! M910 - TMC2130 init { tmc2130_init(); } break; - case 911: // M911 Set TMC2130 holding currents + case 911: //! M911 - Set TMC2130 holding currents { if (code_seen('X')) tmc2130_set_current_h(0, code_value()); if (code_seen('Y')) tmc2130_set_current_h(1, code_value()); @@ -6645,7 +6637,7 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) } break; - case 912: // M912 Set TMC2130 running currents + case 912: //! M912 - Set TMC2130 running currents { if (code_seen('X')) tmc2130_set_current_r(0, code_value()); if (code_seen('Y')) tmc2130_set_current_r(1, code_value()); @@ -6654,13 +6646,13 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) } break; - case 913: // M913 Print TMC2130 currents + case 913: //! M913 - Print TMC2130 currents { tmc2130_print_currents(); } break; - case 914: // M914 Set normal mode + case 914: //! M914 - Set normal mode { tmc2130_mode = TMC2130_MODE_NORMAL; update_mode_profile(); @@ -6668,7 +6660,7 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) } break; - case 915: // M915 Set silent mode + case 915: //! M915 - Set silent mode { tmc2130_mode = TMC2130_MODE_SILENT; update_mode_profile(); @@ -6676,7 +6668,7 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) } break; - case 916: // M916 Set sg_thrs + case 916: //! M916 - Set sg_thrs { if (code_seen('X')) tmc2130_sg_thr[X_AXIS] = code_value(); if (code_seen('Y')) tmc2130_sg_thr[Y_AXIS] = code_value(); @@ -6687,7 +6679,7 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) } break; - case 917: // M917 Set TMC2130 pwm_ampl + case 917: //! M917 - Set TMC2130 pwm_ampl { if (code_seen('X')) tmc2130_set_pwm_ampl(0, code_value()); if (code_seen('Y')) tmc2130_set_pwm_ampl(1, code_value()); @@ -6696,7 +6688,7 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) } break; - case 918: // M918 Set TMC2130 pwm_grad + case 918: //! M918 - Set TMC2130 pwm_grad { if (code_seen('X')) tmc2130_set_pwm_grad(0, code_value()); if (code_seen('Y')) tmc2130_set_pwm_grad(1, code_value()); @@ -6707,7 +6699,7 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) #endif //TMC2130 - case 350: // M350 Set microstepping mode. Warning: Steps per unit remains unchanged. S code sets stepping mode for all drivers. + case 350: //! M350 - Set microstepping mode. Warning: Steps per unit remains unchanged. S code sets stepping mode for all drivers. { #ifdef TMC2130 if(code_seen('E')) @@ -6743,7 +6735,7 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) #endif //TMC2130 } break; - case 351: // M351 Toggle MS1 MS2 pins directly, S# determines MS1 or MS2, X# sets the pin high/low. + case 351: //! M351 - Toggle MS1 MS2 pins directly, S# determines MS1 or MS2, X# sets the pin high/low. { #if defined(X_MS1_PIN) && X_MS1_PIN > -1 if(code_seen('S')) switch((int)code_value()) @@ -6761,23 +6753,23 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) #endif } break; - case 701: //M701: load filament + case 701: //! M701 - load filament { if (mmu_enabled && code_seen('E')) tmp_extruder = code_value(); gcode_M701(); } break; - case 702: + case 702: //! M702 [U C] - { if (mmu_enabled) { if (code_seen('U')) - extr_unload_used(); //unload all filaments which were used in current print + extr_unload_used(); //! if "U" unload all filaments which were used in current print else if (code_seen('C')) - extr_unload(); //unload just current filament + extr_unload(); //! if "C" unload just current filament else - extr_unload_all(); //unload all filaments + extr_unload_all(); //! otherwise unload all filaments } else unload_filament(); @@ -6797,7 +6789,13 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) mcode_in_progress = 0; } } // end if(code_seen('M')) (end of M codes) - + //! T - select extruder in case of multi extruder printer + //! select filament in case of MMU_V2 + //! if extruder is "?", open menu to let the user select extruder/filament + //! + //! For MMU_V2: + //! @n T Gcode to extrude must follow immediately to load to extruder wheels + //! @n T? Gcode to extrude doesn't have to follow, load to extruder wheels is done automatically else if(code_seen('T')) { int index; @@ -6808,8 +6806,15 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) SERIAL_ECHOLNPGM("Invalid T code."); } else { - if (*(strchr_pointer + index) == '?') { - tmp_extruder = choose_extruder_menu(); + if (*(strchr_pointer + index) == '?') + { + if(mmu_enabled) + { + tmp_extruder = choose_menu_P(_T(MSG_CHOOSE_FILAMENT), _T(MSG_FILAMENT)); + } else + { + tmp_extruder = choose_menu_P(_T(MSG_CHOOSE_EXTRUDER), _T(MSG_EXTRUDER)); + } } else { tmp_extruder = code_value(); @@ -6933,45 +6938,45 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) switch((int)code_value()) { #ifdef DEBUG_DCODES - case -1: // D-1 - Endless loop + case -1: //! D-1 - Endless loop dcode__1(); break; - case 0: // D0 - Reset + case 0: //! D0 - Reset dcode_0(); break; - case 1: // D1 - Clear EEPROM + case 1: //! D1 - Clear EEPROM dcode_1(); break; - case 2: // D2 - Read/Write RAM + case 2: //! D2 - Read/Write RAM dcode_2(); break; #endif //DEBUG_DCODES #ifdef DEBUG_DCODE3 - case 3: // D3 - Read/Write EEPROM + case 3: //! D3 - Read/Write EEPROM dcode_3(); break; #endif //DEBUG_DCODE3 #ifdef DEBUG_DCODES - case 4: // D4 - Read/Write PIN + case 4: //! D4 - Read/Write PIN dcode_4(); break; - case 5: // D5 - Read/Write FLASH + case 5: //! D5 - Read/Write FLASH // dcode_5(); break; break; - case 6: // D6 - Read/Write external FLASH + case 6: //! D6 - Read/Write external FLASH dcode_6(); break; - case 7: // D7 - Read/Write Bootloader + case 7: //! D7 - Read/Write Bootloader dcode_7(); break; - case 8: // D8 - Read/Write PINDA + case 8: //! D8 - Read/Write PINDA dcode_8(); break; - case 9: // D9 - Read/Write ADC + case 9: //! D9 - Read/Write ADC dcode_9(); break; - case 10: // D10 - XYZ calibration = OK + case 10: //! D10 - XYZ calibration = OK dcode_10(); break; #ifdef TMC2130 - case 2130: // D9125 - TMC2130 + case 2130: //! D2130 - TMC2130 dcode_2130(); break; #endif //TMC2130 #ifdef FILAMENT_SENSOR - case 9125: // D9125 - FILAMENT_SENSOR + case 9125: //! D9125 - FILAMENT_SENSOR dcode_9125(); break; #endif //FILAMENT_SENSOR @@ -7843,7 +7848,7 @@ void bed_analysis(float x_dimension, float y_dimension, int x_points_num, int y_ int XY_AXIS_FEEDRATE = homing_feedrate[X_AXIS] / 20; int Z_LIFT_FEEDRATE = homing_feedrate[Z_AXIS] / 40; - setup_for_endstop_move(false); + int l_feedmultiply = setup_for_endstop_move(false); SERIAL_PROTOCOLPGM("Num X,Y: "); SERIAL_PROTOCOL(x_points_num); @@ -7972,7 +7977,7 @@ void bed_analysis(float x_dimension, float y_dimension, int x_points_num, int y_ } card.closefile(); - + clean_up_after_endstop_move(l_feedmultiply); } #endif @@ -8106,18 +8111,7 @@ void long_pause() //long pause print { st_synchronize(); - //save currently set parameters to global variables - saved_feedmultiply = feedmultiply; - HotendTempBckp = degTargetHotend(active_extruder); - fanSpeedBckp = fanSpeed; start_pause_print = millis(); - - - //save position - pause_lastpos[X_AXIS] = current_position[X_AXIS]; - pause_lastpos[Y_AXIS] = current_position[Y_AXIS]; - pause_lastpos[Z_AXIS] = current_position[Z_AXIS]; - pause_lastpos[E_AXIS] = current_position[E_AXIS]; //retract current_position[E_AXIS] -= default_retraction; @@ -8128,9 +8122,6 @@ void long_pause() //long pause print if (current_position[Z_AXIS] > Z_MAX_POS) current_position[Z_AXIS] = Z_MAX_POS; plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 15, active_extruder); - //set nozzle target temperature to 0 - setAllTargetHotends(0); - //Move XY to side current_position[X_AXIS] = X_PAUSE_POS; current_position[Y_AXIS] = Y_PAUSE_POS; @@ -8593,9 +8584,14 @@ void restore_print_from_eeprom() { #endif //UVLO_SUPPORT -//////////////////////////////////////////////////////////////////////////////// -// save/restore printing - +//! @brief Immediately stop print moves +//! +//! Immediately stop print moves, save current extruder temperature and position to RAM. +//! If printing from sd card, position in file is saved. +//! If printing from USB, line number is saved. +//! +//! @param z_move +//! @param e_move void stop_and_save_print_to_ram(float z_move, float e_move) { if (saved_printing) return; @@ -8731,9 +8727,11 @@ void stop_and_save_print_to_ram(float z_move, float e_move) planner_abort_hard(); //abort printing memcpy(saved_pos, current_position, sizeof(saved_pos)); saved_active_extruder = active_extruder; //save active_extruder + saved_extruder_temperature = degTargetHotend(active_extruder); saved_extruder_under_pressure = extruder_under_pressure; //extruder under pressure flag - currently unused saved_extruder_relative_mode = axis_relative_modes[E_AXIS]; + saved_fanSpeed = fanSpeed; cmdqueue_reset(); //empty cmdqueue card.sdprinting = false; // card.closefile(); @@ -8778,14 +8776,27 @@ void stop_and_save_print_to_ram(float z_move, float e_move) } } +//! @brief Restore print from ram +//! +//! Restore print saved by stop_and_save_print_to_ram(). Is blocking, +//! waits for extruder temperature restore, then restores position and continues +//! print moves. +//! Internaly lcd_update() is called by wait_for_heater(). +//! +//! @param e_move void restore_print_from_ram_and_continue(float e_move) { if (!saved_printing) return; // for (int axis = X_AXIS; axis <= E_AXIS; axis++) // current_position[axis] = st_get_position_mm(axis); active_extruder = saved_active_extruder; //restore active_extruder + setTargetHotendSafe(saved_extruder_temperature,saved_active_extruder); + heating_status = 1; + wait_for_heater(millis(),saved_active_extruder); + heating_status = 2; feedrate = saved_feedrate2; //restore feedrate axis_relative_modes[E_AXIS] = saved_extruder_relative_mode; + fanSpeed = saved_fanSpeed; float e = saved_pos[E_AXIS] - e_move; plan_set_e_position(e); //first move print head in XY to the saved position: @@ -8881,7 +8892,6 @@ static void print_time_remaining_init() print_percent_done_silent = PRINT_PERCENT_DONE_INIT; } - void M600_check_state() { //Wait for user to check the state @@ -8915,8 +8925,13 @@ void M600_check_state() } } -void M600_wait_for_user() { - //Beep, manage nozzle heater and wait for user to start unload filament +//! @brief Wait for user action +//! +//! Beep, manage nozzle heater and wait for user to start unload filament +//! If times out, active extruder temperature is set to 0. +//! +//! @param HotendTempBckp Temperature to be restored for active extruder, after user resolves MMU problem. +void M600_wait_for_user(float HotendTempBckp) { KEEPALIVE_STATE(PAUSED_FOR_USER); @@ -8956,9 +8971,7 @@ void M600_wait_for_user() { 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 wait_for_user_state = 1; - setTargetHotend(0, 0); - setTargetHotend(0, 1); - setTargetHotend(0, 2); + setAllTargetHotends(0); st_synchronize(); disable_e0(); disable_e1(); diff --git a/Firmware/cardreader.cpp b/Firmware/cardreader.cpp index fe181362..44db2c19 100644 --- a/Firmware/cardreader.cpp +++ b/Firmware/cardreader.cpp @@ -288,6 +288,76 @@ void CardReader::getAbsFilename(char *t) else t[0]=0; } +/** + * @brief Dive into subfolder + * + * Method sets curDir to point to root, in case fileName is null. + * Method sets curDir to point to workDir, in case fileName path is relative + * (doesn't start with '/') + * Method sets curDir to point to dir, which is specified by absolute path + * specified by fileName. In such case fileName is updated so it points to + * file name without the path. + * + * @param[in,out] fileName + * expects file name including path + * in case of absolute path, file name without path is returned + * @param[in,out] dir SdFile object to operate with, + * in case of absolute path, curDir is modified to point to dir, + * so it is not possible to create on stack inside this function, + * as curDir would point to destroyed object. + */ +void CardReader::diveSubfolder (const char *fileName, SdFile& dir) +{ + curDir=&root; + if (!fileName) return; + + const char *dirname_start, *dirname_end; + if (fileName[0] == '/') // absolute path + { + dirname_start = fileName + 1; + while (*dirname_start) + { + dirname_end = strchr(dirname_start, '/'); + //SERIAL_ECHO("start:");SERIAL_ECHOLN((int)(dirname_start-name)); + //SERIAL_ECHO("end :");SERIAL_ECHOLN((int)(dirname_end-name)); + if (dirname_end && dirname_end > dirname_start) + { + const size_t maxLen = 12; + char subdirname[maxLen+1]; + subdirname[maxLen] = 0; + const size_t len = ((static_cast(dirname_end-dirname_start))>maxLen) ? maxLen : (dirname_end-dirname_start); + strncpy(subdirname, dirname_start, len); + SERIAL_ECHOLN(subdirname); + if (!dir.open(curDir, subdirname, O_READ)) + { + SERIAL_PROTOCOLRPGM(_T(MSG_SD_OPEN_FILE_FAIL)); + SERIAL_PROTOCOL(subdirname); + SERIAL_PROTOCOLLNPGM("."); + return; + } + else + { + //SERIAL_ECHOLN("dive ok"); + } + + curDir = &dir; + dirname_start = dirname_end + 1; + } + else // the reminder after all /fsa/fdsa/ is the filename + { + fileName = dirname_start; + //SERIAL_ECHOLN("remaider"); + //SERIAL_ECHOLN(fname); + break; + } + + } + } + else //relative path + { + curDir = &workDir; + } +} void CardReader::openFile(const char* name,bool read, bool replace_current/*=true*/) { @@ -340,53 +410,9 @@ void CardReader::openFile(const char* name,bool read, bool replace_current/*=tru SdFile myDir; - curDir=&root; const char *fname=name; - - char *dirname_start,*dirname_end; - if(name[0]=='/') - { - dirname_start=strchr(name,'/')+1; - while(dirname_start>0) - { - dirname_end=strchr(dirname_start,'/'); - //SERIAL_ECHO("start:");SERIAL_ECHOLN((int)(dirname_start-name)); - //SERIAL_ECHO("end :");SERIAL_ECHOLN((int)(dirname_end-name)); - if(dirname_end>0 && dirname_end>dirname_start) - { - char subdirname[13]; - strncpy(subdirname, dirname_start, dirname_end-dirname_start); - subdirname[dirname_end-dirname_start]=0; - SERIAL_ECHOLN(subdirname); - if(!myDir.open(curDir,subdirname,O_READ)) - { - SERIAL_PROTOCOLRPGM(_T(MSG_SD_OPEN_FILE_FAIL)); - SERIAL_PROTOCOL(subdirname); - SERIAL_PROTOCOLLNPGM("."); - return; - } - else - { - //SERIAL_ECHOLN("dive ok"); - } - - curDir=&myDir; - dirname_start=dirname_end+1; - } - else // the reminder after all /fsa/fdsa/ is the filename - { - fname=dirname_start; - //SERIAL_ECHOLN("remaider"); - //SERIAL_ECHOLN(fname); - break; - } - - } - } - else //relative path - { - curDir=&workDir; - } + diveSubfolder(fname,myDir); + if(read) { if (file.open(curDir, fname, O_READ)) @@ -431,60 +457,14 @@ void CardReader::openFile(const char* name,bool read, bool replace_current/*=tru void CardReader::removeFile(const char* name) { - if(!cardOK) - return; - file.close(); - sdprinting = false; - - - SdFile myDir; - curDir=&root; - const char *fname=name; - - char *dirname_start,*dirname_end; - if(name[0]=='/') - { - dirname_start=strchr(name,'/')+1; - while(dirname_start>0) - { - dirname_end=strchr(dirname_start,'/'); - //SERIAL_ECHO("start:");SERIAL_ECHOLN((int)(dirname_start-name)); - //SERIAL_ECHO("end :");SERIAL_ECHOLN((int)(dirname_end-name)); - if(dirname_end>0 && dirname_end>dirname_start) - { - char subdirname[13]; - strncpy(subdirname, dirname_start, dirname_end-dirname_start); - subdirname[dirname_end-dirname_start]=0; - SERIAL_ECHOLN(subdirname); - if(!myDir.open(curDir,subdirname,O_READ)) - { - SERIAL_PROTOCOLRPGM("open failed, File: "); - SERIAL_PROTOCOL(subdirname); - SERIAL_PROTOCOLLNPGM("."); - return; - } - else - { - //SERIAL_ECHOLN("dive ok"); - } - - curDir=&myDir; - dirname_start=dirname_end+1; - } - else // the reminder after all /fsa/fdsa/ is the filename - { - fname=dirname_start; - //SERIAL_ECHOLN("remaider"); - //SERIAL_ECHOLN(fname); - break; - } - - } - } - else //relative path - { - curDir=&workDir; - } + if(!cardOK) return; + file.close(); + sdprinting = false; + + SdFile myDir; + const char *fname=name; + diveSubfolder(fname,myDir); + if (file.remove(curDir, fname)) { SERIAL_PROTOCOLPGM("File deleted:"); diff --git a/Firmware/cardreader.h b/Firmware/cardreader.h index 4acc9376..f287a44f 100644 --- a/Firmware/cardreader.h +++ b/Firmware/cardreader.h @@ -154,6 +154,8 @@ private: LsAction lsAction; //stored for recursion. int16_t nrFiles; //counter for the files in the current directory and recycled as position counter for getting the nrFiles'th name in the directory. char* diveDirName; + + void diveSubfolder (const char *fileName, SdFile& dir); void lsDive(const char *prepend, SdFile parent, const char * const match=NULL); #ifdef SDCARD_SORT_ALPHA void flush_presort(); diff --git a/Firmware/doxyfile b/Firmware/doxyfile index 6fa1ef4f..9c2d550c 100644 --- a/Firmware/doxyfile +++ b/Firmware/doxyfile @@ -453,7 +453,7 @@ EXTRACT_PACKAGE = NO # included in the documentation. # The default value is: NO. -EXTRACT_STATIC = NO +EXTRACT_STATIC = YES # If the EXTRACT_LOCAL_CLASSES tag is set to YES, classes (and structs) defined # locally in source files will be included in the documentation. If set to NO, @@ -2421,7 +2421,7 @@ DIAFILE_DIRS = # generate a warning when it encounters a \startuml command in this case and # will not generate output for the diagram. -PLANTUML_JAR_PATH = +PLANTUML_JAR_PATH = /usr/share/plantuml/ # When using plantuml, the PLANTUML_CFG_FILE tag can be used to specify a # configuration file for plantuml. diff --git a/Firmware/fsensor.cpp b/Firmware/fsensor.cpp index d2608da4..e7c5d467 100644 --- a/Firmware/fsensor.cpp +++ b/Firmware/fsensor.cpp @@ -7,6 +7,7 @@ #include "planner.h" #include "fastio.h" #include "cmdqueue.h" +#include "ultralcd.h" #include "ConfigurationStore.h" //Basic params @@ -28,10 +29,6 @@ const char ERRMSG_PAT9125_NOT_RESP[] PROGMEM = "PAT9125 not responding (%d)!\n"; #define FSENSOR_INT_PIN 63 //filament sensor interrupt pin PK1 #define FSENSOR_INT_PIN_MSK 0x02 //filament sensor interrupt pin mask (bit1) -extern void stop_and_save_print_to_ram(float z_move, float e_move); -extern void restore_print_from_ram_and_continue(float e_move); -extern int8_t FSensorStateMenu; - void fsensor_stop_and_save_print(void) { printf_P(PSTR("fsensor_stop_and_save_print\n")); @@ -102,9 +99,9 @@ uint16_t fsensor_oq_er_sum; //max error counter value durring meassurement uint8_t fsensor_oq_er_max; //minimum delta value -uint16_t fsensor_oq_yd_min; +int16_t fsensor_oq_yd_min; //maximum delta value -uint16_t fsensor_oq_yd_max; +int16_t fsensor_oq_yd_max; //sum of shutter value uint16_t fsensor_oq_sh_sum; @@ -219,7 +216,9 @@ bool fsensor_check_autoload(void) fsensor_autoload_check_start(); return false; } +#if 0 uint8_t fsensor_autoload_c_old = fsensor_autoload_c; +#endif if ((millis() - fsensor_autoload_last_millis) < 25) return false; fsensor_autoload_last_millis = millis(); if (!pat9125_update_y()) //update sensor @@ -244,9 +243,11 @@ bool fsensor_check_autoload(void) else if (fsensor_autoload_c > 0) fsensor_autoload_c--; if (fsensor_autoload_c == 0) fsensor_autoload_sum = 0; -// puts_P(_N("fsensor_check_autoload\n")); -// if (fsensor_autoload_c != fsensor_autoload_c_old) -// printf_P(PSTR("fsensor_check_autoload dy=%d c=%d sum=%d\n"), dy, fsensor_autoload_c, fsensor_autoload_sum); +#if 0 + puts_P(_N("fsensor_check_autoload\n")); + if (fsensor_autoload_c != fsensor_autoload_c_old) + printf_P(PSTR("fsensor_check_autoload dy=%d c=%d sum=%d\n"), dy, fsensor_autoload_c, fsensor_autoload_sum); +#endif // if ((fsensor_autoload_c >= 15) && (fsensor_autoload_sum > 30)) if ((fsensor_autoload_c >= 12) && (fsensor_autoload_sum > 20)) { @@ -427,6 +428,11 @@ void fsensor_st_block_chunk(block_t* bl, int cnt) } } +//! update (perform M600 on filament runout) +//! +//! Works only if filament sensor is enabled. +//! When the filament sensor error count is larger then FSENSOR_ERR_MAX, pauses print, tries to move filament back and forth. +//! If there is still no plausible signal from filament sensor plans M600 (Filament change). void fsensor_update(void) { if (fsensor_enabled) @@ -449,19 +455,6 @@ void fsensor_update(void) fsensor_err_cnt = 0; fsensor_oq_meassure_start(0); -// st_synchronize(); -// for (int axis = X_AXIS; axis <= E_AXIS; axis++) -// current_position[axis] = st_get_position_mm(axis); -/* - current_position[E_AXIS] -= 3; - plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 200 / 60, active_extruder); - st_synchronize(); - - current_position[E_AXIS] += 3; - plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 200 / 60, active_extruder); - st_synchronize(); -*/ - enquecommand_front_P((PSTR("G1 E-3 F200"))); process_commands(); cmdqueue_pop_front(); diff --git a/Firmware/fsensor.h b/Firmware/fsensor.h index df58def2..0b262a51 100644 --- a/Firmware/fsensor.h +++ b/Firmware/fsensor.h @@ -27,7 +27,6 @@ extern void fsensor_disable(void); extern bool fsensor_autoload_enabled; extern void fsensor_autoload_set(bool State); -//update (perform M600 on filament runout) extern void fsensor_update(void); //setup pin-change interrupt diff --git a/Firmware/lcd.cpp b/Firmware/lcd.cpp index ac2863fe..7e8b3ed4 100644 --- a/Firmware/lcd.cpp +++ b/Firmware/lcd.cpp @@ -56,7 +56,7 @@ #define LCD_5x8DOTS 0x00 -FILE _lcdout = {0}; +FILE _lcdout; // = {0}; Global variable is always zero initialized, no need to explicitly state that. uint8_t lcd_rs_pin; // LOW: command. HIGH: character. @@ -157,7 +157,7 @@ uint8_t lcd_write(uint8_t value) return 1; // assume sucess } -void lcd_begin(uint8_t cols, uint8_t lines, uint8_t dotsize, uint8_t clear) +static void lcd_begin(uint8_t lines, uint8_t dotsize, uint8_t clear) { if (lines > 1) lcd_displayfunction |= LCD_2LINE; lcd_numlines = lines; @@ -221,7 +221,7 @@ void lcd_begin(uint8_t cols, uint8_t lines, uint8_t dotsize, uint8_t clear) lcd_escape[0] = 0; } -int lcd_putchar(char c, FILE *stream) +int lcd_putchar(char c, FILE *) { lcd_write(c); return 0; @@ -247,20 +247,20 @@ void lcd_init(void) pinMode(lcd_enable_pin, OUTPUT); if (fourbitmode) lcd_displayfunction = LCD_4BITMODE | LCD_1LINE | LCD_5x8DOTS; else lcd_displayfunction = LCD_8BITMODE | LCD_1LINE | LCD_5x8DOTS; - lcd_begin(LCD_WIDTH, LCD_HEIGHT, LCD_5x8DOTS, 1); + lcd_begin(LCD_HEIGHT, LCD_5x8DOTS, 1); //lcd_clear(); fdev_setup_stream(lcdout, lcd_putchar, NULL, _FDEV_SETUP_WRITE); //setup lcdout stream } void lcd_refresh(void) { - lcd_begin(LCD_WIDTH, LCD_HEIGHT, LCD_5x8DOTS, 1); + lcd_begin(LCD_HEIGHT, LCD_5x8DOTS, 1); lcd_set_custom_characters(); } void lcd_refresh_noclear(void) { - lcd_begin(LCD_WIDTH, LCD_HEIGHT, LCD_5x8DOTS, 0); + lcd_begin(LCD_HEIGHT, LCD_5x8DOTS, 0); lcd_set_custom_characters(); } @@ -506,7 +506,6 @@ uint8_t lcd_escape_write(uint8_t chr) break; } escape_cnt = 0; // reset escape -end: return 1; // assume sucess } @@ -684,10 +683,22 @@ ShortTimer longPressTimer; LongTimer lcd_timeoutToStatus; +//! @brief Was button clicked? +//! +//! Consume click event, following call would return 0. +//! See #LCD_CLICKED macro for version not consuming the event. +//! +//! Generally is used in modal dialogs. +//! +//! @retval 0 not clicked +//! @retval nonzero clicked uint8_t lcd_clicked(void) { bool clicked = LCD_CLICKED; - if(clicked) lcd_button_pressed = 0; + if(clicked) + { + lcd_consume_click(); + } return clicked; } @@ -695,7 +706,7 @@ void lcd_beeper_quick_feedback(void) { SET_OUTPUT(BEEPER); //-// -Sound_MakeSound(e_SOUND_CLASS_Echo,e_SOUND_TYPE_ButtonEcho); +Sound_MakeSound(e_SOUND_TYPE_ButtonEcho); /* for(int8_t i = 0; i < 10; i++) { @@ -710,7 +721,7 @@ Sound_MakeSound(e_SOUND_CLASS_Echo,e_SOUND_TYPE_ButtonEcho); void lcd_quick_feedback(void) { lcd_draw_update = 2; - lcd_button_pressed = false; + lcd_button_pressed = false; lcd_beeper_quick_feedback(); } @@ -727,7 +738,6 @@ void lcd_update(uint8_t lcdDrawUpdateOverride) lcd_draw_update = lcdDrawUpdateOverride; if (!lcd_update_enabled) return; - lcd_buttons_update(); if (lcd_lcdupdate_func) lcd_lcdupdate_func(); } @@ -761,57 +771,45 @@ void lcd_update_enable(uint8_t enabled) extern LongTimer safetyTimer; void lcd_buttons_update(void) { - static bool _lock = false; - if (_lock) return; - _lock = true; uint8_t newbutton = 0; if (READ(BTN_EN1) == 0) newbutton |= EN_A; if (READ(BTN_EN2) == 0) newbutton |= EN_B; - if (lcd_update_enabled) - { //if we are in non-modal mode, long press can be used and short press triggers with button release - if (READ(BTN_ENC) == 0) - { //button is pressed - lcd_timeoutToStatus.start(); - if (!buttonBlanking.running() || buttonBlanking.expired(BUTTON_BLANKING_TIME)) { - buttonBlanking.start(); - safetyTimer.start(); - if ((lcd_button_pressed == 0) && (lcd_long_press_active == 0)) - { - longPressTimer.start(); - lcd_button_pressed = 1; - } - else - { - if (longPressTimer.expired(LONG_PRESS_TIME)) - { - lcd_long_press_active = 1; - if (lcd_longpress_func) - lcd_longpress_func(); - } - } - } - } - else - { //button not pressed - if (lcd_button_pressed) - { //button was released - buttonBlanking.start(); - if (lcd_long_press_active == 0) - { //button released before long press gets activated - newbutton |= EN_C; - } - //else if (menu_menu == lcd_move_z) lcd_quick_feedback(); - //lcd_button_pressed is set back to false via lcd_quick_feedback function - } - else - lcd_long_press_active = 0; - } - } - else - { //we are in modal mode - if (READ(BTN_ENC) == 0) - newbutton |= EN_C; - } + + if (READ(BTN_ENC) == 0) + { //button is pressed + lcd_timeoutToStatus.start(); + if (!buttonBlanking.running() || buttonBlanking.expired(BUTTON_BLANKING_TIME)) { + buttonBlanking.start(); + safetyTimer.start(); + if ((lcd_button_pressed == 0) && (lcd_long_press_active == 0)) + { + //long press is not possible in modal mode + if (lcd_update_enabled) longPressTimer.start(); + lcd_button_pressed = 1; + } + else if (longPressTimer.expired(LONG_PRESS_TIME)) + { + lcd_long_press_active = 1; + if (lcd_longpress_func) + lcd_longpress_func(); + } + } + } + else + { //button not pressed + if (lcd_button_pressed) + { //button was released + buttonBlanking.start(); + if (lcd_long_press_active == 0) + { //button released before long press gets activated + newbutton |= EN_C; + } + //else if (menu_menu == lcd_move_z) lcd_quick_feedback(); + //lcd_button_pressed is set back to false via lcd_quick_feedback function + } + else + lcd_long_press_active = 0; + } lcd_buttons = newbutton; //manage encoder rotation @@ -849,7 +847,6 @@ void lcd_buttons_update(void) } } lcd_encoder_bits = enc; - _lock = false; } diff --git a/Firmware/lcd.h b/Firmware/lcd.h index 251344de..8554922d 100644 --- a/Firmware/lcd.h +++ b/Firmware/lcd.h @@ -1,4 +1,4 @@ -//lcd.h +//! @file #ifndef _LCD_H #define _LCD_H @@ -131,7 +131,6 @@ extern lcd_lcdupdate_func_t lcd_lcdupdate_func; extern uint8_t lcd_clicked(void); - extern void lcd_beeper_quick_feedback(void); //Cause an LCD refresh, and give the user visual or audible feedback that something has happened @@ -150,6 +149,29 @@ extern void lcd_update_enable(uint8_t enabled); extern void lcd_buttons_update(void); +//! @brief Helper class to temporarily disable LCD updates +//! +//! When constructed (on stack), original state state of lcd_update_enabled is stored +//! and LCD updates are disabled. +//! When destroyed (gone out of scope), original state of LCD update is restored. +//! It has zero overhead compared to storing bool saved = lcd_update_enabled +//! and calling lcd_update_enable(false) and lcd_update_enable(saved). +class LcdUpdateDisabler +{ +public: + LcdUpdateDisabler(): m_updateEnabled(lcd_update_enabled) + { + lcd_update_enable(false); + } + ~LcdUpdateDisabler() + { + lcd_update_enable(m_updateEnabled); + } + +private: + bool m_updateEnabled; +}; + @@ -187,7 +209,16 @@ extern void lcd_buttons_update(void); #define EN_A (1<= 20) SERIAL_ECHOPGM("Point on first row"); #endif // SUPPORT_VERBOSITY - float w = point_weight_y(i, npts, measured_pts[2 * i + 1]); + float w = point_weight_y(i, measured_pts[2 * i + 1]); if (sqrt(errX) > BED_CALIBRATION_POINT_OFFSET_MAX_1ST_ROW_X || (w != 0.f && sqrt(errY) > BED_CALIBRATION_POINT_OFFSET_MAX_1ST_ROW_Y)) { result = BED_SKEW_OFFSET_DETECTION_FITTING_FAILED; @@ -550,7 +553,7 @@ BedSkewOffsetDetectionResultType calculate_machine_skew_and_offset_LS( for (int8_t i = 0; i < npts; ++ i) { float x = vec_x[0] * measured_pts[i * 2] + vec_y[0] * measured_pts[i * 2 + 1]; float y = vec_x[1] * measured_pts[i * 2] + vec_y[1] * measured_pts[i * 2 + 1]; - float w = point_weight_x(i, npts, y); + float w = point_weight_x(i, y); cntr[0] += w * (pgm_read_float(true_pts + i * 2) - x); wx += w; #ifdef SUPPORT_VERBOSITY @@ -567,7 +570,7 @@ BedSkewOffsetDetectionResultType calculate_machine_skew_and_offset_LS( MYSERIAL.print(wx); } #endif // SUPPORT_VERBOSITY - w = point_weight_y(i, npts, y); + w = point_weight_y(i, y); cntr[1] += w * (pgm_read_float(true_pts + i * 2 + 1) - y); wy += w; #ifdef SUPPORT_VERBOSITY @@ -960,7 +963,11 @@ static inline void update_current_position_z() } // At the current position, find the Z stop. -inline bool find_bed_induction_sensor_point_z(float minimum_z, uint8_t n_iter, int verbosity_level) +inline bool find_bed_induction_sensor_point_z(float minimum_z, uint8_t n_iter, int +#ifdef SUPPORT_VERBOSITY + verbosity_level +#endif //SUPPORT_VERBOSITY + ) { #ifdef TMC2130 FORCE_HIGH_POWER_START; @@ -1047,7 +1054,11 @@ extern bool xyzcal_find_bed_induction_sensor_point_xy(); #endif //HEATBED_V2 #ifdef HEATBED_V2 -inline bool find_bed_induction_sensor_point_xy(int verbosity_level) +inline bool find_bed_induction_sensor_point_xy(int +#if !defined (NEW_XYZCAL) && defined (SUPPORT_VERBOSITY) + verbosity_level +#endif + ) { #ifdef NEW_XYZCAL return xyzcal_find_bed_induction_sensor_point_xy(); diff --git a/Firmware/mesh_bed_leveling.cpp b/Firmware/mesh_bed_leveling.cpp index 506d3746..746458ae 100644 --- a/Firmware/mesh_bed_leveling.cpp +++ b/Firmware/mesh_bed_leveling.cpp @@ -21,7 +21,7 @@ static inline bool vec_undef(const float v[2]) return vx[0] == 0x0FFFFFFFF || vx[1] == 0x0FFFFFFFF; } -void mesh_bed_leveling::get_meas_xy(int ix, int iy, float &x, float &y, bool use_default) +void mesh_bed_leveling::get_meas_xy(int ix, int iy, float &x, float &y, bool /*use_default*/) { #if 0 float cntr[2] = { diff --git a/Firmware/mmu.cpp b/Firmware/mmu.cpp index 3e71737a..7a63bf8c 100644 --- a/Firmware/mmu.cpp +++ b/Firmware/mmu.cpp @@ -29,12 +29,13 @@ bool mmu_enabled = false; bool mmu_ready = false; -int8_t mmu_state = 0; +static int8_t mmu_state = 0; uint8_t mmu_cmd = 0; uint8_t mmu_extruder = 0; +//! This variable probably has no meaning and is planed to be removed uint8_t tmp_extruder = 0; int8_t mmu_finda = -1; @@ -494,15 +495,11 @@ void mmu_M600_wait_and_beep() { void mmu_M600_load_filament(bool automatic) { //load filament for mmu v2 - - bool response = false; - bool yes = false; tmp_extruder = mmu_extruder; if (!automatic) { #ifdef MMU_M600_SWITCH_EXTRUDER - yes = lcd_show_fullscreen_message_yes_no_and_wait_P(_i("Do you want to switch extruder?"), false); + bool yes = lcd_show_fullscreen_message_yes_no_and_wait_P(_i("Do you want to switch extruder?"), false); if(yes) tmp_extruder = choose_extruder_menu(); - else tmp_extruder = mmu_extruder; #endif //MMU_M600_SWITCH_EXTRUDER } else { @@ -541,7 +538,11 @@ void extr_mov(float shift, float feed_rate) } -void change_extr(int extr) { //switches multiplexer for extruders +void change_extr(int +#ifdef SNMM + extr +#endif //SNMM + ) { //switches multiplexer for extruders #ifdef SNMM st_synchronize(); delay(100); @@ -1011,23 +1012,24 @@ void mmu_eject_filament(uint8_t filament, bool recover) if (degHotend0() > EXTRUDE_MINTEMP) { st_synchronize(); - lcd_update_enable(false); - lcd_clear(); - lcd_set_cursor(0, 1); lcd_puts_P(_i("Ejecting filament")); - current_position[E_AXIS] -= 80; - plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 2500 / 60, active_extruder); - st_synchronize(); - lcd_update_enable(true); - - mmu_command(MMU_CMD_E0 + filament); - manage_response(false, false); - if (recover) { - lcd_show_fullscreen_message_and_wait_P(_i("Please remove filament and then press the knob.")); - mmu_command(MMU_CMD_R0); - manage_response(false, false); - } + LcdUpdateDisabler disableLcdUpdate; + lcd_clear(); + lcd_set_cursor(0, 1); lcd_puts_P(_i("Ejecting filament")); + current_position[E_AXIS] -= 80; + plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], 2500 / 60, active_extruder); + st_synchronize(); + mmu_command(MMU_CMD_E0 + filament); + manage_response(false, false); + if (recover) + { + lcd_show_fullscreen_message_and_wait_P(_i("Please remove filament and then press the knob.")); + mmu_command(MMU_CMD_R0); + manage_response(false, false); + } + + } } else { diff --git a/Firmware/mmu.h b/Firmware/mmu.h index 35c1e18c..7ca5e25a 100644 --- a/Firmware/mmu.h +++ b/Firmware/mmu.h @@ -5,8 +5,6 @@ extern bool mmu_enabled; -extern int8_t mmu_state; - extern uint8_t mmu_extruder; extern uint8_t tmp_extruder; diff --git a/Firmware/optiboot_w25x20cl.cpp b/Firmware/optiboot_w25x20cl.cpp index cc6c66cd..d05ae59f 100644 --- a/Firmware/optiboot_w25x20cl.cpp +++ b/Firmware/optiboot_w25x20cl.cpp @@ -272,7 +272,6 @@ void optiboot_w25x20cl_enter() /* Read memory block mode, length is big endian. */ else if(ch == STK_READ_PAGE) { uint32_t addr = (((uint32_t)rampz) << 16) | address; - uint8_t desttype; register pagelen_t i; // Read the page length, with the length transferred each nibble separately to work around // the Prusa's USB to serial infamous semicolon issue. @@ -280,8 +279,8 @@ void optiboot_w25x20cl_enter() length |= ((pagelen_t)getch()) << 8; length |= getch(); length |= getch(); - // Read the destination type. It should always be 'F' as flash. - desttype = getch(); + // Read the destination type. It should always be 'F' as flash. It is not checked. + (void)getch(); verifySpace(); w25x20cl_wait_busy(); w25x20cl_rd_data(addr, buff, length); diff --git a/Firmware/planner.cpp b/Firmware/planner.cpp index 8db1cd3c..c465c938 100644 --- a/Firmware/planner.cpp +++ b/Firmware/planner.cpp @@ -872,22 +872,22 @@ block->steps_y.wide = labs((target[X_AXIS]-position[X_AXIS]) - (target[Y_AXIS]-p enable_e0(); g_uc_extruder_last_move[0] = BLOCK_BUFFER_SIZE*2; - if(g_uc_extruder_last_move[1] == 0) disable_e1(); - if(g_uc_extruder_last_move[2] == 0) disable_e2(); + if(g_uc_extruder_last_move[1] == 0) {disable_e1();} + if(g_uc_extruder_last_move[2] == 0) {disable_e2();} break; case 1: enable_e1(); g_uc_extruder_last_move[1] = BLOCK_BUFFER_SIZE*2; - if(g_uc_extruder_last_move[0] == 0) disable_e0(); - if(g_uc_extruder_last_move[2] == 0) disable_e2(); + if(g_uc_extruder_last_move[0] == 0) {disable_e0();} + if(g_uc_extruder_last_move[2] == 0) {disable_e2();} break; case 2: enable_e2(); g_uc_extruder_last_move[2] = BLOCK_BUFFER_SIZE*2; - if(g_uc_extruder_last_move[0] == 0) disable_e0(); - if(g_uc_extruder_last_move[1] == 0) disable_e1(); + if(g_uc_extruder_last_move[0] == 0) {disable_e0();} + if(g_uc_extruder_last_move[1] == 0) {disable_e1();} break; } } diff --git a/Firmware/sm4.c b/Firmware/sm4.c index 509ac23f..34cf8a3c 100644 --- a/Firmware/sm4.c +++ b/Firmware/sm4.c @@ -85,8 +85,8 @@ void sm4_set_dir(uint8_t axis, uint8_t dir) uint8_t sm4_get_dir_bits(void) { - uint8_t register dir_bits = 0; - uint8_t register portL = PORTL; + register uint8_t dir_bits = 0; + register uint8_t portL = PORTL; //TODO -optimize in asm #if ((MOTHERBOARD == BOARD_RAMBO_MINI_1_0) || (MOTHERBOARD == BOARD_RAMBO_MINI_1_3)) if (portL & 2) dir_bits |= 1; @@ -106,7 +106,7 @@ uint8_t sm4_get_dir_bits(void) void sm4_set_dir_bits(uint8_t dir_bits) { - uint8_t register portL = PORTL; + register uint8_t portL = PORTL; portL &= 0xb8; //set direction bits to zero //TODO -optimize in asm #if ((MOTHERBOARD == BOARD_RAMBO_MINI_1_0) || (MOTHERBOARD == BOARD_RAMBO_MINI_1_3)) @@ -129,7 +129,7 @@ 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)) - uint8_t register portC = PORTC & 0xf0; + 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 diff --git a/Firmware/sound.cpp b/Firmware/sound.cpp index d808dfa8..6e41d252 100644 --- a/Firmware/sound.cpp +++ b/Firmware/sound.cpp @@ -59,7 +59,7 @@ switch(eSoundMode) Sound_SaveMode(); } -void Sound_MakeSound(eSOUND_CLASS eSoundClass,eSOUND_TYPE eSoundType) +void Sound_MakeSound(eSOUND_TYPE eSoundType) { switch(eSoundMode) { diff --git a/Firmware/sound.h b/Firmware/sound.h index 9415b763..479f113e 100644 --- a/Firmware/sound.h +++ b/Firmware/sound.h @@ -26,7 +26,7 @@ extern void Sound_Init(void); extern void Sound_Default(void); extern void Sound_Save(void); extern void Sound_CycleState(void); -extern void Sound_MakeSound(eSOUND_CLASS eSoundClass,eSOUND_TYPE eSoundType); +extern void Sound_MakeSound(eSOUND_TYPE eSoundType); //static void Sound_DoSound_Echo(void); //static void Sound_DoSound_Prompt(void); diff --git a/Firmware/stepper.cpp b/Firmware/stepper.cpp index 7218aa6a..f64277c5 100644 --- a/Firmware/stepper.cpp +++ b/Firmware/stepper.cpp @@ -107,8 +107,6 @@ static bool z_endstop_invert = false; volatile long count_position[NUM_AXIS] = { 0, 0, 0, 0}; volatile signed char count_direction[NUM_AXIS] = { 1, 1, 1, 1}; -uint8_t LastStepMask = 0; - #ifdef LIN_ADVANCE static uint16_t nextMainISR = 0; @@ -720,7 +718,6 @@ FORCE_INLINE void stepper_tick_lowres() counter_x.lo += current_block->steps_x.lo; if (counter_x.lo > 0) { WRITE_NC(X_STEP_PIN, !INVERT_X_STEP_PIN); - LastStepMask |= X_AXIS_MASK; #ifdef DEBUG_XSTEP_DUP_PIN WRITE_NC(DEBUG_XSTEP_DUP_PIN,!INVERT_X_STEP_PIN); #endif //DEBUG_XSTEP_DUP_PIN @@ -735,7 +732,6 @@ FORCE_INLINE void stepper_tick_lowres() counter_y.lo += current_block->steps_y.lo; if (counter_y.lo > 0) { WRITE_NC(Y_STEP_PIN, !INVERT_Y_STEP_PIN); - LastStepMask |= Y_AXIS_MASK; #ifdef DEBUG_YSTEP_DUP_PIN WRITE_NC(DEBUG_YSTEP_DUP_PIN,!INVERT_Y_STEP_PIN); #endif //DEBUG_YSTEP_DUP_PIN @@ -750,7 +746,6 @@ FORCE_INLINE void stepper_tick_lowres() counter_z.lo += current_block->steps_z.lo; if (counter_z.lo > 0) { WRITE_NC(Z_STEP_PIN, !INVERT_Z_STEP_PIN); - LastStepMask |= Z_AXIS_MASK; 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); @@ -785,7 +780,6 @@ FORCE_INLINE void stepper_tick_highres() counter_x.wide += current_block->steps_x.wide; if (counter_x.wide > 0) { WRITE_NC(X_STEP_PIN, !INVERT_X_STEP_PIN); - LastStepMask |= X_AXIS_MASK; #ifdef DEBUG_XSTEP_DUP_PIN WRITE_NC(DEBUG_XSTEP_DUP_PIN,!INVERT_X_STEP_PIN); #endif //DEBUG_XSTEP_DUP_PIN @@ -800,7 +794,6 @@ FORCE_INLINE void stepper_tick_highres() counter_y.wide += current_block->steps_y.wide; if (counter_y.wide > 0) { WRITE_NC(Y_STEP_PIN, !INVERT_Y_STEP_PIN); - LastStepMask |= Y_AXIS_MASK; #ifdef DEBUG_YSTEP_DUP_PIN WRITE_NC(DEBUG_YSTEP_DUP_PIN,!INVERT_Y_STEP_PIN); #endif //DEBUG_YSTEP_DUP_PIN @@ -815,7 +808,6 @@ FORCE_INLINE void stepper_tick_highres() counter_z.wide += current_block->steps_z.wide; if (counter_z.wide > 0) { WRITE_NC(Z_STEP_PIN, !INVERT_Z_STEP_PIN); - LastStepMask |= Z_AXIS_MASK; 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); @@ -853,8 +845,6 @@ FORCE_INLINE void isr() { if (current_block == NULL) stepper_next_block(); - LastStepMask = 0; - if (current_block != NULL) { stepper_check_endstops(); @@ -1079,7 +1069,7 @@ FORCE_INLINE void isr() { } #ifdef TMC2130 - tmc2130_st_isr(LastStepMask); + tmc2130_st_isr(); #endif //TMC2130 //WRITE_NC(LOGIC_ANALYZER_CH0, false); @@ -1434,13 +1424,10 @@ void babystep(const uint8_t axis,const bool direction) //perform step WRITE(X_STEP_PIN, !INVERT_X_STEP_PIN); - LastStepMask |= X_AXIS_MASK; #ifdef DEBUG_XSTEP_DUP_PIN WRITE(DEBUG_XSTEP_DUP_PIN,!INVERT_X_STEP_PIN); #endif //DEBUG_XSTEP_DUP_PIN - { - volatile float x=1./float(axis+1)/float(axis+2); //wait a tiny bit - } + delayMicroseconds(1); WRITE(X_STEP_PIN, INVERT_X_STEP_PIN); #ifdef DEBUG_XSTEP_DUP_PIN WRITE(DEBUG_XSTEP_DUP_PIN,INVERT_X_STEP_PIN); @@ -1460,13 +1447,10 @@ void babystep(const uint8_t axis,const bool direction) //perform step WRITE(Y_STEP_PIN, !INVERT_Y_STEP_PIN); - LastStepMask |= Y_AXIS_MASK; #ifdef DEBUG_YSTEP_DUP_PIN WRITE(DEBUG_YSTEP_DUP_PIN,!INVERT_Y_STEP_PIN); #endif //DEBUG_YSTEP_DUP_PIN - { - volatile float x=1./float(axis+1)/float(axis+2); //wait a tiny bit - } + delayMicroseconds(1); WRITE(Y_STEP_PIN, INVERT_Y_STEP_PIN); #ifdef DEBUG_YSTEP_DUP_PIN WRITE(DEBUG_YSTEP_DUP_PIN,INVERT_Y_STEP_PIN); @@ -1489,14 +1473,10 @@ void babystep(const uint8_t axis,const bool direction) #endif //perform step WRITE(Z_STEP_PIN, !INVERT_Z_STEP_PIN); - LastStepMask |= Z_AXIS_MASK; #ifdef Z_DUAL_STEPPER_DRIVERS WRITE(Z2_STEP_PIN, !INVERT_Z_STEP_PIN); #endif - //wait a tiny bit - { - volatile float x=1./float(axis+1); //absolutely useless - } + delayMicroseconds(1); WRITE(Z_STEP_PIN, INVERT_Z_STEP_PIN); #ifdef Z_DUAL_STEPPER_DRIVERS WRITE(Z2_STEP_PIN, INVERT_Z_STEP_PIN); @@ -1516,16 +1496,16 @@ void babystep(const uint8_t axis,const bool direction) } #endif //BABYSTEPPING +#if defined(DIGIPOTSS_PIN) && DIGIPOTSS_PIN > -1 void digitalPotWrite(int address, int value) // From Arduino DigitalPotControl example { - #if defined(DIGIPOTSS_PIN) && DIGIPOTSS_PIN > -1 digitalWrite(DIGIPOTSS_PIN,LOW); // take the SS pin low to select the chip SPI.transfer(address); // send in the address and value via SPI: SPI.transfer(value); digitalWrite(DIGIPOTSS_PIN,HIGH); // take the SS pin high to de-select the chip: //delay(10); - #endif } +#endif void EEPROM_read_st(int pos, uint8_t* value, uint8_t size) { @@ -1569,19 +1549,19 @@ uint8_t SilentMode = eeprom_read_byte((uint8_t*)EEPROM_SILENT); - +#ifdef MOTOR_CURRENT_PWM_XY_PIN void st_current_set(uint8_t driver, int current) { - #ifdef MOTOR_CURRENT_PWM_XY_PIN if (driver == 0) analogWrite(MOTOR_CURRENT_PWM_XY_PIN, (long)current * 255L / (long)MOTOR_CURRENT_PWM_RANGE); if (driver == 1) analogWrite(MOTOR_CURRENT_PWM_Z_PIN, (long)current * 255L / (long)MOTOR_CURRENT_PWM_RANGE); if (driver == 2) analogWrite(MOTOR_CURRENT_PWM_E_PIN, (long)current * 255L / (long)MOTOR_CURRENT_PWM_RANGE); - #endif } +#else //MOTOR_CURRENT_PWM_XY_PIN +void st_current_set(uint8_t, int ){} +#endif //MOTOR_CURRENT_PWM_XY_PIN void microstep_init() { - const uint8_t microstep_modes[] = MICROSTEP_MODES; #if defined(E1_MS1_PIN) && E1_MS1_PIN > -1 pinMode(E1_MS1_PIN,OUTPUT); @@ -1589,6 +1569,7 @@ void microstep_init() #endif #if defined(X_MS1_PIN) && X_MS1_PIN > -1 + const uint8_t microstep_modes[] = MICROSTEP_MODES; pinMode(X_MS1_PIN,OUTPUT); pinMode(X_MS2_PIN,OUTPUT); pinMode(Y_MS1_PIN,OUTPUT); diff --git a/Firmware/stepper.h b/Firmware/stepper.h index ac508944..6130f3bb 100644 --- a/Firmware/stepper.h +++ b/Firmware/stepper.h @@ -90,10 +90,12 @@ extern bool x_min_endstop; extern bool x_max_endstop; extern bool y_min_endstop; extern bool y_max_endstop; +extern volatile long count_position[NUM_AXIS]; void quickStop(); - +#if defined(DIGIPOTSS_PIN) && DIGIPOTSS_PIN > -1 void digitalPotWrite(int address, int value); +#endif //defined(DIGIPOTSS_PIN) && DIGIPOTSS_PIN > -1 void microstep_ms(uint8_t driver, int8_t ms1, int8_t ms2); void microstep_mode(uint8_t driver, uint8_t stepping); void st_current_init(); diff --git a/Firmware/temperature.cpp b/Firmware/temperature.cpp index a630f51b..411b92ef 100644 --- a/Firmware/temperature.cpp +++ b/Firmware/temperature.cpp @@ -175,7 +175,6 @@ static int bed_maxttemp_raw = HEATER_BED_RAW_HI_TEMP; static float analog2temp(int raw, uint8_t e); static float analog2tempBed(int raw); static float analog2tempAmbient(int raw); -static float analog2tempPINDA(int raw); static void updateTemperaturesFromRawValues(); enum TempRunawayStates @@ -493,9 +492,6 @@ void checkFanSpeed() } } -extern void stop_and_save_print_to_ram(float z_move, float e_move); -extern void restore_print_from_ram_and_continue(float e_move); - void fanSpeedError(unsigned char _fan) { if (get_message_level() != 0 && isPrintPaused) return; //to ensure that target temp. is not set to zero in case taht we are resuming print @@ -504,8 +500,7 @@ void fanSpeedError(unsigned char _fan) { lcd_print_stop(); } else { - isPrintPaused = true; - lcd_sdcard_pause(); + lcd_pause_print(); } } else { @@ -928,35 +923,6 @@ static float analog2tempBed(int raw) { #endif } -#ifdef PINDA_THERMISTOR - -static float analog2tempPINDA(int raw) { - - float celsius = 0; - byte i; - - for (i = 1; i raw) - { - celsius = PGM_RD_W(BEDTEMPTABLE[i - 1][1]) + - (raw - PGM_RD_W(BEDTEMPTABLE[i - 1][0])) * - (float)(PGM_RD_W(BEDTEMPTABLE[i][1]) - PGM_RD_W(BEDTEMPTABLE[i - 1][1])) / - (float)(PGM_RD_W(BEDTEMPTABLE[i][0]) - PGM_RD_W(BEDTEMPTABLE[i - 1][0])); - break; - } - } - - // Overflow: Set to last value in the table - if (i == BEDTEMPTABLE_LEN) celsius = PGM_RD_W(BEDTEMPTABLE[i - 1][1]); - - return celsius; -} - - -#endif //PINDA_THERMISTOR - - #ifdef AMBIENT_THERMISTOR static float analog2tempAmbient(int raw) { diff --git a/Firmware/tmc2130.cpp b/Firmware/tmc2130.cpp index 0ff1b905..732f290d 100644 --- a/Firmware/tmc2130.cpp +++ b/Firmware/tmc2130.cpp @@ -13,12 +13,6 @@ #define TMC2130_GCONF_SGSENS 0x00003180 // spreadCycle with stallguard (stall activates DIAG0 and DIAG1 [pushpull]) #define TMC2130_GCONF_SILENT 0x00000004 // stealthChop -//externals for debuging -extern float current_position[4]; -extern void st_get_position_xy(long &x, long &y); -extern long st_get_position(uint8_t axis); -extern void crashdet_stop_and_save_print(); -extern void crashdet_stop_and_save_print2(); //mode uint8_t tmc2130_mode = TMC2130_MODE_NORMAL; @@ -236,7 +230,7 @@ uint8_t tmc2130_sample_diag() extern bool is_usb_printing; -void tmc2130_st_isr(uint8_t last_step_mask) +void tmc2130_st_isr() { if (tmc2130_mode == TMC2130_MODE_SILENT || tmc2130_sg_stop_on_crash == false) return; uint8_t crash = 0; @@ -793,7 +787,7 @@ void tmc2130_do_steps(uint8_t axis, uint16_t steps, uint8_t dir, uint16_t delay_ void tmc2130_goto_step(uint8_t axis, uint8_t step, uint8_t dir, uint16_t delay_us, uint16_t microstep_resolution) { printf_P(PSTR("tmc2130_goto_step %d %d %d %d \n"), axis, step, dir, delay_us, microstep_resolution); - uint8_t shift; for (shift = 0; shift < 8; shift++) if (microstep_resolution == (256 >> shift)) break; + uint8_t shift; for (shift = 0; shift < 8; shift++) if (microstep_resolution == (256u >> shift)) break; uint16_t cnt = 4 * (1 << (8 - shift)); uint16_t mscnt = tmc2130_rd_MSCNT(axis); if (dir == 2) @@ -805,7 +799,7 @@ void tmc2130_goto_step(uint8_t axis, uint8_t step, uint8_t dir, uint16_t delay_u dir ^= 1; steps = -steps; } - if (steps > (cnt / 2)) + if (steps > static_cast(cnt / 2)) { dir ^= 1; steps = cnt - steps; @@ -830,7 +824,7 @@ void tmc2130_get_wave(uint8_t axis, uint8_t* data, FILE* stream) tmc2130_setup_chopper(axis, tmc2130_usteps2mres(256), tmc2130_current_h[axis], tmc2130_current_r[axis]); tmc2130_goto_step(axis, 0, 2, 100, 256); tmc2130_set_dir(axis, tmc2130_get_inv(axis)?0:1); - for (int i = 0; i <= 255; i++) + for (unsigned int i = 0; i <= 255; i++) { uint32_t val = tmc2130_rd_MSCURACT(axis); uint16_t mscnt = tmc2130_rd_MSCNT(axis); @@ -847,6 +841,7 @@ void tmc2130_get_wave(uint8_t axis, uint8_t* data, FILE* stream) delayMicroseconds(100); } tmc2130_setup_chopper(axis, tmc2130_mres[axis], tmc2130_current_h[axis], tmc2130_current_r[axis]); + tmc2130_set_pwr(axis, pwr); } void tmc2130_set_wave(uint8_t axis, uint8_t amp, uint8_t fac1000) @@ -869,7 +864,7 @@ void tmc2130_set_wave(uint8_t axis, uint8_t amp, uint8_t fac1000) int8_t b; //encoded bit value int8_t dA; //delta value int i; //microstep index - uint32_t reg; //tmc2130 register + uint32_t reg = 0; //tmc2130 register tmc2130_wr_MSLUTSTART(axis, 0, amp); for (i = 0; i < 256; i++) { diff --git a/Firmware/tmc2130.h b/Firmware/tmc2130.h index 28ecb7be..66c2b92b 100644 --- a/Firmware/tmc2130.h +++ b/Firmware/tmc2130.h @@ -53,7 +53,7 @@ extern tmc2130_chopper_config_t tmc2130_chopper_config[4]; //initialize tmc2130 extern void tmc2130_init(); //check diag pins (called from stepper isr) -extern void tmc2130_st_isr(uint8_t last_step_mask); +extern void tmc2130_st_isr(); //update stall guard (called from st_synchronize inside the loop) extern bool tmc2130_update_sg(); //temperature watching (called from ) diff --git a/Firmware/uart2.c b/Firmware/uart2.c index cfed5c09..47238999 100644 --- a/Firmware/uart2.c +++ b/Firmware/uart2.c @@ -16,7 +16,7 @@ uint8_t uart2_ibuf[14] = {0, 0}; FILE _uart2io = {0}; -int uart2_putchar(char c, FILE *stream) +int uart2_putchar(char c, FILE *stream __attribute__((unused))) { while (!uart2_txready); UDR2 = c; // transmit byte @@ -25,7 +25,7 @@ int uart2_putchar(char c, FILE *stream) return 0; } -int uart2_getchar(FILE *stream) +int uart2_getchar(FILE *stream __attribute__((unused))) { if (rbuf_empty(uart2_ibuf)) return -1; return rbuf_get(uart2_ibuf); diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index 3e7db020..428760a5 100644 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -1,3 +1,5 @@ +//! @file + #include "temperature.h" #include "ultralcd.h" #include "fsensor.h" @@ -44,8 +46,6 @@ char longFilenameOLD[LONG_FILENAME_LENGTH]; static void lcd_sd_updir(); - - int8_t ReInitLCD = 0; @@ -111,20 +111,20 @@ static const char* lcd_display_message_fullscreen_nonBlocking_P(const char *msg, static void lcd_status_screen(); static void lcd_language_menu(); -extern bool powersupply; static void lcd_main_menu(); static void lcd_tune_menu(); -static void lcd_prepare_menu(); //static void lcd_move_menu(); static void lcd_settings_menu(); static void lcd_calibration_menu(); +#ifdef LINEARITY_CORRECTION +static void lcd_settings_menu_back(); +#endif //LINEARITY_CORRECTION static void lcd_control_temperature_menu(); static void lcd_control_temperature_preheat_pla_settings_menu(); static void lcd_control_temperature_preheat_abs_settings_menu(); static void lcd_control_motion_menu(); static void lcd_control_volumetric_menu(); static void lcd_settings_linearity_correction_menu_save(); - static void prusa_stat_printerstatus(int _status); static void prusa_stat_farm_number(); static void prusa_stat_temperatures(); @@ -139,11 +139,10 @@ static void lcd_menu_fails_stats(); #endif //TMC2130 or FILAMENT_SENSOR static void lcd_selftest_v(); -static bool lcd_selfcheck_endstops(); #ifdef TMC2130 -static void reset_crash_det(char axis); -static bool lcd_selfcheck_axis_sg(char axis); +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(); @@ -159,8 +158,13 @@ static bool lcd_selftest_fan_dialog(int _fan); static bool lcd_selftest_fsensor(); static void lcd_selftest_error(int _error_no, const char *_error_1, const char *_error_2); static void lcd_colorprint_change(); +#ifdef SNMM +static int get_ext_nr(); +#endif //SNMM +#if defined (SNMM) || defined(SNMM_V2) static void fil_load_menu(); static void fil_unload_menu(); +#endif // SNMM || SNMM_V2 static void lcd_disable_farm_mode(); static void lcd_set_fan_check(); static char snmm_stop_print_menu(); @@ -170,11 +174,12 @@ static char snmm_stop_print_menu(); static float count_e(float layer_heigth, float extrusion_width, float extrusion_length); static void lcd_babystep_z(); static void lcd_send_status(); +#ifdef FARM_CONNECT_MESSAGE static void lcd_connect_printer(); +#endif //FARM_CONNECT_MESSAGE void lcd_finishstatus(); -static void lcd_control_retract_menu(); static void lcd_sdcard_menu(); #ifdef DELTA_CALIBRATION_MENU @@ -183,8 +188,8 @@ static void lcd_delta_calibrate_menu(); /* Different types of actions that can be used in menu items. */ -void menu_action_sdfile(const char* filename, char* longFilename); -void menu_action_sddirectory(const char* filename, char* longFilename); +static void menu_action_sdfile(const char* filename); +static void menu_action_sddirectory(const char* filename); #define ENCODER_FEEDRATE_DEADZONE 10 @@ -227,7 +232,7 @@ bool wait_for_unclick; const char STR_SEPARATOR[] PROGMEM = "------------"; -void lcd_implementation_drawmenu_sdfile_selected(uint8_t row, const char* pstr, const char* filename, char* longFilename) +static void lcd_implementation_drawmenu_sdfile_selected(uint8_t row, char* longFilename) { char c; int enc_dif = lcd_encoder_diff; @@ -279,8 +284,7 @@ void lcd_implementation_drawmenu_sdfile_selected(uint8_t row, const char* pstr, while(n--) lcd_print(' '); } - -void lcd_implementation_drawmenu_sdfile(uint8_t row, const char* pstr, const char* filename, char* longFilename) +static void lcd_implementation_drawmenu_sdfile(uint8_t row, const char* filename, char* longFilename) { char c; uint8_t n = LCD_WIDTH - 1; @@ -300,7 +304,7 @@ void lcd_implementation_drawmenu_sdfile(uint8_t row, const char* pstr, const cha while(n--) lcd_print(' '); } -void lcd_implementation_drawmenu_sddirectory_selected(uint8_t row, const char* pstr, const char* filename, char* longFilename) +static void lcd_implementation_drawmenu_sddirectory_selected(uint8_t row, const char* filename, char* longFilename) { char c; uint8_t n = LCD_WIDTH - 2; @@ -321,7 +325,7 @@ void lcd_implementation_drawmenu_sddirectory_selected(uint8_t row, const char* p while(n--) lcd_print(' '); } -void lcd_implementation_drawmenu_sddirectory(uint8_t row, const char* pstr, const char* filename, char* longFilename) +static void lcd_implementation_drawmenu_sddirectory(uint8_t row, const char* filename, char* longFilename) { char c; uint8_t n = LCD_WIDTH - 2; @@ -345,7 +349,7 @@ void lcd_implementation_drawmenu_sddirectory(uint8_t row, const char* pstr, cons -#define MENU_ITEM_SDDIR(str, str_fn, str_fnl) do { if (menu_item_sddir(str, str_fn, str_fnl)) return; } while (0) +#define MENU_ITEM_SDDIR(str_fn, str_fnl) do { if (menu_item_sddir(str_fn, str_fnl)) return; } while (0) //#define MENU_ITEM_SDDIR(str, str_fn, str_fnl) MENU_ITEM(sddirectory, str, str_fn, str_fnl) //extern uint8_t menu_item_sddir(const char* str, const char* str_fn, char* str_fnl); @@ -354,7 +358,7 @@ void lcd_implementation_drawmenu_sddirectory(uint8_t row, const char* pstr, cons //extern uint8_t menu_item_sdfile(const char* str, const char* str_fn, char* str_fnl); -uint8_t menu_item_sddir(const char* str, const char* str_fn, char* str_fnl) +uint8_t menu_item_sddir(const char* str_fn, char* str_fnl) { #ifdef NEW_SD_MENU // str_fnl[18] = 0; @@ -385,15 +389,15 @@ uint8_t menu_item_sddir(const char* str, const char* str_fn, char* str_fnl) if (lcd_draw_update) { if (lcd_encoder == menu_item) - lcd_implementation_drawmenu_sddirectory_selected(menu_row, str, str_fn, str_fnl); + lcd_implementation_drawmenu_sddirectory_selected(menu_row, str_fn, str_fnl); else - lcd_implementation_drawmenu_sddirectory(menu_row, str, str_fn, str_fnl); + lcd_implementation_drawmenu_sddirectory(menu_row, str_fn, str_fnl); } if (menu_clicked && (lcd_encoder == menu_item)) { menu_clicked = false; lcd_update_enabled = 0; - menu_action_sddirectory(str_fn, str_fnl); + menu_action_sddirectory(str_fn); lcd_update_enabled = 1; return menu_item_ret(); } @@ -404,7 +408,11 @@ uint8_t menu_item_sddir(const char* str, const char* str_fn, char* str_fnl) #endif //NEW_SD_MENU } -uint8_t menu_item_sdfile(const char* str, const char* str_fn, char* str_fnl) +static uint8_t menu_item_sdfile(const char* +#ifdef NEW_SD_MENU + str +#endif //NEW_SD_MENU + ,const char* str_fn, char* str_fnl) { #ifdef NEW_SD_MENU // printf_P(PSTR("menu sdfile\n")); @@ -451,13 +459,14 @@ uint8_t menu_item_sdfile(const char* str, const char* str_fn, char* str_fnl) if (lcd_draw_update) { if (lcd_encoder == menu_item) - lcd_implementation_drawmenu_sdfile_selected(menu_row, str, str_fn, str_fnl); + lcd_implementation_drawmenu_sdfile_selected(menu_row, str_fnl); else - lcd_implementation_drawmenu_sdfile(menu_row, str, str_fn, str_fnl); + lcd_implementation_drawmenu_sdfile(menu_row, str_fn, str_fnl); } if (menu_clicked && (lcd_encoder == menu_item)) { - menu_action_sdfile(str_fn, str_fnl); + lcd_consume_click(); + menu_action_sdfile(str_fn); return menu_item_ret(); } } @@ -476,12 +485,10 @@ void lcdui_print_temp(char type, int val_current, int val_target) // Print Z-coordinate (8 chars total) void lcdui_print_Z_coord(void) { - int chars = 8; if (custom_message_type == CUSTOM_MSG_TYPE_MESHBL) lcd_puts_P(_N("Z --- ")); else - chars = lcd_printf_P(_N("Z%6.2f "), current_position[Z_AXIS]); -// lcd_space(8 - chars); + lcd_printf_P(_N("Z%6.2f "), current_position[Z_AXIS]); } #ifdef PLANNER_DIAGNOSTICS @@ -521,8 +528,7 @@ void lcdui_print_percent_done(void) char per[4]; bool num = IS_SD_PRINTING || (PRINTER_ACTIVE && (print_percent_done_normal != PRINT_PERCENT_DONE_INIT)); sprintf_P(per, num?_N("%3hhd"):_N("---"), calc_percent_done()); - int chars = lcd_printf_P(_N("%3S%3s%%"), src, per); -// lcd_space(7 - chars); + lcd_printf_P(_N("%3S%3s%%"), src, per); } // Print extruder status (5 chars total) @@ -968,86 +974,15 @@ void lcd_commands() { if (lcd_commands_type == LCD_COMMAND_LONG_PAUSE) { - if(lcd_commands_step == 0) { - if (card.sdprinting) { - card.pauseSDPrint(); - lcd_setstatuspgm(_T(MSG_FINISHING_MOVEMENTS)); - lcd_draw_update = 3; - lcd_commands_step = 1; - } - else { - lcd_commands_type = 0; - } - } - if (lcd_commands_step == 1 && !blocks_queued() && !homing_flag) { + if (!blocks_queued() && !homing_flag) + { lcd_setstatuspgm(_i("Print paused"));////MSG_PRINT_PAUSED c=20 r=1 - isPrintPaused = true; long_pause(); lcd_commands_type = 0; lcd_commands_step = 0; } - } - if (lcd_commands_type == LCD_COMMAND_LONG_PAUSE_RESUME) { - char cmd1[30]; - if (lcd_commands_step == 0) { - - lcd_draw_update = 3; - lcd_commands_step = 4; - } - if (lcd_commands_step == 1 && !blocks_queued() && cmd_buffer_empty()) { //recover feedmultiply; cmd_buffer_empty() ensures that card.sdprinting is synchronized with buffered commands and thus print cant be paused until resume is finished - - sprintf_P(cmd1, PSTR("M220 S%d"), saved_feedmultiply); - enquecommand(cmd1); - isPrintPaused = false; - pause_time += (millis() - start_pause_print); //accumulate time when print is paused for correct statistics calculation - card.startFileprint(); - lcd_commands_step = 0; - lcd_commands_type = 0; - } - if (lcd_commands_step == 2 && !blocks_queued()) { //turn on fan, move Z and unretract - - sprintf_P(cmd1, PSTR("M106 S%d"), fanSpeedBckp); - enquecommand(cmd1); - strcpy(cmd1, "G1 Z"); - strcat(cmd1, ftostr32(pause_lastpos[Z_AXIS])); - enquecommand(cmd1); - - if (axis_relative_modes[3] == false) { - enquecommand_P(PSTR("M83")); // set extruder to relative mode - enquecommand_P(PSTR("G1 E" STRINGIFY(default_retraction))); //unretract - enquecommand_P(PSTR("M82")); // set extruder to absolute mode - } - else { - enquecommand_P(PSTR("G1 E" STRINGIFY(default_retraction))); //unretract - } - - lcd_commands_step = 1; - } - if (lcd_commands_step == 3 && !blocks_queued()) { //wait for nozzle to reach target temp - - strcpy(cmd1, "M109 S"); - strcat(cmd1, ftostr3(HotendTempBckp)); - enquecommand(cmd1); - lcd_commands_step = 2; - } - if (lcd_commands_step == 4 && !blocks_queued()) { //set temperature back and move xy - - strcpy(cmd1, "M104 S"); - strcat(cmd1, ftostr3(HotendTempBckp)); - enquecommand(cmd1); - enquecommand_P(PSTR("G90")); //absolute positioning - strcpy(cmd1, "G1 X"); - strcat(cmd1, ftostr32(pause_lastpos[X_AXIS])); - strcat(cmd1, " Y"); - strcat(cmd1, ftostr32(pause_lastpos[Y_AXIS])); - enquecommand(cmd1); - - lcd_setstatuspgm(_T(MSG_RESUMING_PRINT)); - lcd_commands_step = 3; - } - } #ifdef SNMM if (lcd_commands_type == LCD_COMMAND_V2_CAL) @@ -1307,7 +1242,7 @@ void lcd_commands() lcd_commands_step = 0; lcd_commands_type = 0; if (eeprom_read_byte((uint8_t*)EEPROM_WIZARD_ACTIVE) == 1) { - lcd_wizard(10); + lcd_wizard(WizState::RepeatLay1Cal); } } @@ -1318,43 +1253,101 @@ void lcd_commands() if (lcd_commands_type == LCD_COMMAND_V2_CAL) { char cmd1[30]; + uint8_t filament = 0; float width = 0.4; float length = 20 - width; float extr = count_e(0.2, width, length); float extr_short_segment = count_e(0.2, width, width); if(lcd_commands_step>1) lcd_timeoutToStatus.start(); //if user dont confirm live adjust Z value by pressing the knob, we are saving last value by timeout to status screen - if (lcd_commands_step == 0) + + if (lcd_commands_step == 0 && !blocks_queued() && cmd_buffer_empty()) { - lcd_commands_step = 9; + lcd_commands_step = 10; } - if (lcd_commands_step == 9 && !blocks_queued() && cmd_buffer_empty()) + if (lcd_commands_step == 20 && !blocks_queued() && cmd_buffer_empty()) + { + filament = 0; + lcd_commands_step = 10; + } + if (lcd_commands_step == 21 && !blocks_queued() && cmd_buffer_empty()) + { + filament = 1; + lcd_commands_step = 10; + } + if (lcd_commands_step == 22 && !blocks_queued() && cmd_buffer_empty()) + { + filament = 2; + lcd_commands_step = 10; + } + if (lcd_commands_step == 23 && !blocks_queued() && cmd_buffer_empty()) + { + filament = 3; + lcd_commands_step = 10; + } + if (lcd_commands_step == 24 && !blocks_queued() && cmd_buffer_empty()) + { + filament = 4; + lcd_commands_step = 10; + } + + if (lcd_commands_step == 10) { enquecommand_P(PSTR("M107")); enquecommand_P(PSTR("M104 S" STRINGIFY(PLA_PREHEAT_HOTEND_TEMP))); enquecommand_P(PSTR("M140 S" STRINGIFY(PLA_PREHEAT_HPB_TEMP))); + if (mmu_enabled) + { + strcpy(cmd1, "T"); + strcat(cmd1, itostr3left(filament)); + enquecommand(cmd1); + } enquecommand_P(PSTR("M190 S" STRINGIFY(PLA_PREHEAT_HPB_TEMP))); enquecommand_P(PSTR("M109 S" STRINGIFY(PLA_PREHEAT_HOTEND_TEMP))); enquecommand_P(_T(MSG_M117_V2_CALIBRATION)); - if (mmu_enabled) - enquecommand_P(PSTR("T?")); enquecommand_P(PSTR("G28")); enquecommand_P(PSTR("G92 E0.0")); - lcd_commands_step = 8; + + lcd_commands_step = 9; } + if (lcd_commands_step == 9 && !blocks_queued() && cmd_buffer_empty()) + { + lcd_clear(); + menu_depth = 0; + menu_submenu(lcd_babystep_z); + + if (mmu_enabled) + { + enquecommand_P(PSTR("M83")); //intro line + enquecommand_P(PSTR("G1 Y-3.0 F1000.0")); //intro line + enquecommand_P(PSTR("G1 Z0.4 F1000.0")); //intro line + enquecommand_P(PSTR("G1 X55.0 E32.0 F1073.0")); //intro line + enquecommand_P(PSTR("G1 X5.0 E32.0 F1800.0")); //intro line + enquecommand_P(PSTR("G1 X55.0 E8.0 F2000.0")); //intro line + enquecommand_P(PSTR("G1 Z0.3 F1000.0")); //intro line + enquecommand_P(PSTR("G92 E0.0")); //intro line + enquecommand_P(PSTR("G1 X240.0 E25.0 F2200.0")); //intro line + enquecommand_P(PSTR("G1 Y-2.0 F1000.0")); //intro line + enquecommand_P(PSTR("G1 X55.0 E25 F1400.0")); //intro line + enquecommand_P(PSTR("G1 Z0.20 F1000.0")); //intro line + enquecommand_P(PSTR("G1 X5.0 E4.0 F1000.0")); //intro line + + } else + { + enquecommand_P(PSTR("G1 X60.0 E9.0 F1000.0")); //intro line + enquecommand_P(PSTR("G1 X100.0 E12.5 F1000.0")); //intro line + } + + lcd_commands_step = 8; + } if (lcd_commands_step == 8 && !blocks_queued() && cmd_buffer_empty()) { - lcd_clear(); - menu_depth = 0; - menu_submenu(lcd_babystep_z); - enquecommand_P(PSTR("G1 X60.0 E9.0 F1000.0")); //intro line - enquecommand_P(PSTR("G1 X100.0 E12.5 F1000.0")); //intro line enquecommand_P(PSTR("G92 E0.0")); enquecommand_P(PSTR("G21")); //set units to millimeters enquecommand_P(PSTR("G90")); //use absolute coordinates enquecommand_P(PSTR("M83")); //use relative distances for extrusion enquecommand_P(PSTR("G1 E-1.50000 F2100.00000")); - enquecommand_P(PSTR("G1 Z0.150 F7200.000")); + enquecommand_P(PSTR("G1 Z5 F7200.000")); enquecommand_P(PSTR("M204 S1000")); //set acceleration enquecommand_P(PSTR("G1 F4000")); lcd_commands_step = 7; @@ -1384,6 +1377,7 @@ void lcd_commands() enquecommand_P(PSTR("G1 X50 Y155")); + enquecommand_P(PSTR("G1 Z0.150 F7200.000")); enquecommand_P(PSTR("G1 F1080")); enquecommand_P(PSTR("G1 X75 Y155 E2.5")); enquecommand_P(PSTR("G1 X100 Y155 E2")); @@ -1544,7 +1538,7 @@ void lcd_commands() lcd_commands_step = 0; lcd_commands_type = 0; if (eeprom_read_byte((uint8_t*)EEPROM_WIZARD_ACTIVE) == 1) { - lcd_wizard(10); + lcd_wizard(WizState::RepeatLay1Cal); } } @@ -1752,18 +1746,19 @@ void lcd_return_to_status() menu_depth = 0; } - -void lcd_sdcard_pause() { - lcd_return_to_status(); - lcd_commands_type = LCD_COMMAND_LONG_PAUSE; - +//! @brief Pause print, disable nozzle heater, move to park position +void lcd_pause_print() +{ + lcd_return_to_status(); + stop_and_save_print_to_ram(0.0,0.0); + setAllTargetHotends(0); + isPrintPaused = true; + if (LCD_COMMAND_IDLE == lcd_commands_type) + { + lcd_commands_type = LCD_COMMAND_LONG_PAUSE; + } } -static void lcd_sdcard_resume() { - lcd_return_to_status(); - lcd_reset_alert_level(); //for fan speed error - lcd_commands_type = LCD_COMMAND_LONG_PAUSE_RESUME; -} float move_menu_scale; static void lcd_move_menu_axis(); @@ -1793,55 +1788,61 @@ void lcd_preheat_farm_nozzle() void lcd_preheat_pla() { setTargetHotend0(PLA_PREHEAT_HOTEND_TEMP); - setTargetBed(PLA_PREHEAT_HPB_TEMP); + if (!wizard_active) setTargetBed(PLA_PREHEAT_HPB_TEMP); fanSpeed = 0; lcd_return_to_status(); setWatch(); // heater sanity check timer + if (wizard_active) lcd_wizard(WizState::Unload); } void lcd_preheat_abs() { setTargetHotend0(ABS_PREHEAT_HOTEND_TEMP); - setTargetBed(ABS_PREHEAT_HPB_TEMP); + if (!wizard_active) setTargetBed(ABS_PREHEAT_HPB_TEMP); fanSpeed = 0; lcd_return_to_status(); setWatch(); // heater sanity check timer + if (wizard_active) lcd_wizard(WizState::Unload); } void lcd_preheat_pp() { setTargetHotend0(PP_PREHEAT_HOTEND_TEMP); - setTargetBed(PP_PREHEAT_HPB_TEMP); + if (!wizard_active) setTargetBed(PP_PREHEAT_HPB_TEMP); fanSpeed = 0; lcd_return_to_status(); setWatch(); // heater sanity check timer + if (wizard_active) lcd_wizard(WizState::Unload); } void lcd_preheat_pet() { setTargetHotend0(PET_PREHEAT_HOTEND_TEMP); - setTargetBed(PET_PREHEAT_HPB_TEMP); + if (!wizard_active) setTargetBed(PET_PREHEAT_HPB_TEMP); fanSpeed = 0; lcd_return_to_status(); setWatch(); // heater sanity check timer + if (wizard_active) lcd_wizard(WizState::Unload); } void lcd_preheat_hips() { setTargetHotend0(HIPS_PREHEAT_HOTEND_TEMP); - setTargetBed(HIPS_PREHEAT_HPB_TEMP); + if (!wizard_active) setTargetBed(HIPS_PREHEAT_HPB_TEMP); fanSpeed = 0; lcd_return_to_status(); setWatch(); // heater sanity check timer + if (wizard_active) lcd_wizard(WizState::Unload); } void lcd_preheat_flex() { setTargetHotend0(FLEX_PREHEAT_HOTEND_TEMP); - setTargetBed(FLEX_PREHEAT_HPB_TEMP); + if (!wizard_active) setTargetBed(FLEX_PREHEAT_HPB_TEMP); fanSpeed = 0; lcd_return_to_status(); setWatch(); // heater sanity check timer + if (wizard_active) lcd_wizard(WizState::Unload); } @@ -2067,7 +2068,7 @@ static void lcd_preheat_menu() { MENU_BEGIN(); - MENU_ITEM_BACK_P(_T(MSG_MAIN)); + if (!wizard_active) MENU_ITEM_BACK_P(_T(MSG_MAIN)); if (farm_mode) { MENU_ITEM_FUNCTION_P(PSTR("farm - " STRINGIFY(FARM_PREHEAT_HOTEND_TEMP) "/" STRINGIFY(FARM_PREHEAT_HPB_TEMP)), lcd_preheat_farm); @@ -2081,7 +2082,7 @@ static void lcd_preheat_menu() MENU_ITEM_FUNCTION_P(PSTR("HIPS - " STRINGIFY(HIPS_PREHEAT_HOTEND_TEMP) "/" STRINGIFY(HIPS_PREHEAT_HPB_TEMP)), lcd_preheat_hips); MENU_ITEM_FUNCTION_P(PSTR("PP - " STRINGIFY(PP_PREHEAT_HOTEND_TEMP) "/" STRINGIFY(PP_PREHEAT_HPB_TEMP)), lcd_preheat_pp); MENU_ITEM_FUNCTION_P(PSTR("FLEX - " STRINGIFY(FLEX_PREHEAT_HOTEND_TEMP) "/" STRINGIFY(FLEX_PREHEAT_HPB_TEMP)), lcd_preheat_flex); - MENU_ITEM_FUNCTION_P(_T(MSG_COOLDOWN), lcd_cooldown); + if (!wizard_active) MENU_ITEM_FUNCTION_P(_T(MSG_COOLDOWN), lcd_cooldown); } @@ -2467,7 +2468,6 @@ void lcd_menu_statistics() if (IS_SD_PRINTING) { float _met = ((float)total_filament_used) / (100000.f); - int _cm = (total_filament_used - (_met * 100000)) / 10; int _t = (millis() - starttime) / 1000; int _h = _t / 3600; int _m = (_t - (_h * 3600)) / 60; @@ -2810,15 +2810,6 @@ static void _lcd_babystep(int axis, const char *msg) if (LCD_CLICKED) menu_back(); } -static void lcd_babystep_x() -{ - _lcd_babystep(X_AXIS, (_i("Babystepping X")));////MSG_BABYSTEPPING_X c=0 r=0 -} - -static void lcd_babystep_y() -{ - _lcd_babystep(Y_AXIS, (_i("Babystepping Y")));////MSG_BABYSTEPPING_Y c=0 r=0 -} static void lcd_babystep_z() { @@ -3254,6 +3245,7 @@ const char* lcd_display_message_fullscreen_P(const char *msg) */ void lcd_show_fullscreen_message_and_wait_P(const char *msg) { + LcdUpdateDisabler lcdUpdateDisabler; const char *msg_next = lcd_display_message_fullscreen_P(msg); bool multi_screen = msg_next != NULL; lcd_set_custom_characters_nextpage(); @@ -3269,9 +3261,6 @@ void lcd_show_fullscreen_message_and_wait_P(const char *msg) for (uint8_t i = 0; i < 100; ++ i) { delay_keep_alive(50); if (lcd_clicked()) { - while (lcd_clicked()) ; - delay(10); - while (lcd_clicked()) ; if (msg_next == NULL) { KEEPALIVE_STATE(IN_HANDLER); lcd_set_custom_characters(); @@ -3305,20 +3294,38 @@ void lcd_wait_for_click() manage_heater(); manage_inactivity(true); if (lcd_clicked()) { - while (lcd_clicked()) ; - delay(10); - while (lcd_clicked()) ; KEEPALIVE_STATE(IN_HANDLER); return; } } } +//! @brief Show multiple screen message with yes and no possible choices and wait with possible timeout +//! @param msg Message to show +//! @param allow_timeouting if true, allows time outing of the screen +//! @param default_yes if true, yes choice is selected by default, otherwise no choice is preselected +//! @retval 1 yes choice selected by user +//! @retval 0 no choice selected by user +//! @retval -1 screen timed out int8_t lcd_show_multiscreen_message_yes_no_and_wait_P(const char *msg, bool allow_timeouting, bool default_yes) //currently just max. n*4 + 3 lines supported (set in language header files) +{ + return lcd_show_multiscreen_message_two_choices_and_wait_P(msg, allow_timeouting, default_yes, _T(MSG_YES), _T(MSG_NO)); +} +//! @brief Show multiple screen message with two possible choices and wait with possible timeout +//! @param msg Message to show +//! @param allow_timeouting if true, allows time outing of the screen +//! @param default_first if true, fist choice is selected by default, otherwise second choice is preselected +//! @param first_choice text caption of first possible choice +//! @param second_choice text caption of second possible choice +//! @retval 1 first choice selected by user +//! @retval 0 second choice selected by user +//! @retval -1 screen timed out +int8_t lcd_show_multiscreen_message_two_choices_and_wait_P(const char *msg, bool allow_timeouting, bool default_first, + const char *first_choice, const char *second_choice) { const char *msg_next = lcd_display_message_fullscreen_P(msg); bool multi_screen = msg_next != NULL; - bool yes = default_yes ? true : false; + bool yes = default_first ? true : false; // Wait for user confirmation or a timeout. unsigned long previous_millis_cmd = millis(); @@ -3354,9 +3361,6 @@ int8_t lcd_show_multiscreen_message_yes_no_and_wait_P(const char *msg, bool allo } } if (lcd_clicked()) { - while (lcd_clicked()); - delay(10); - while (lcd_clicked()); if (msg_next == NULL) { //KEEPALIVE_STATE(IN_HANDLER); lcd_set_custom_characters(); @@ -3375,15 +3379,22 @@ int8_t lcd_show_multiscreen_message_yes_no_and_wait_P(const char *msg, bool allo lcd_set_cursor(0, 3); if (yes) lcd_puts_P(PSTR(">")); lcd_set_cursor(1, 3); - lcd_puts_P(_T(MSG_YES)); + lcd_puts_P(first_choice); lcd_set_cursor(7, 3); if (!yes) lcd_puts_P(PSTR(">")); lcd_set_cursor(8, 3); - lcd_puts_P(_T(MSG_NO)); + lcd_puts_P(second_choice); } } } +//! @brief Show single screen message with yes and no possible choices and wait with possible timeout +//! @param msg Message to show +//! @param allow_timeouting if true, allows time outing of the screen +//! @param default_yes if true, yes choice is selected by default, otherwise no choice is preselected +//! @retval 1 yes choice selected by user +//! @retval 0 no choice selected by user +//! @retval -1 screen timed out int8_t lcd_show_fullscreen_message_yes_no_and_wait_P(const char *msg, bool allow_timeouting, bool default_yes) { @@ -3431,16 +3442,13 @@ int8_t lcd_show_fullscreen_message_yes_no_and_wait_P(const char *msg, bool allow enc_dif = lcd_encoder_diff; } if (lcd_clicked()) { - while (lcd_clicked()); - delay(10); - while (lcd_clicked()); KEEPALIVE_STATE(IN_HANDLER); return yes; } } } -void lcd_bed_calibration_show_result(uint8_t result, uint8_t point_too_far_mask) +void lcd_bed_calibration_show_result(BedSkewOffsetDetectionResultType result, uint8_t point_too_far_mask) { const char *msg = NULL; if (result == BED_SKEW_OFFSET_DETECTION_POINT_NOT_FOUND) { @@ -3532,26 +3540,24 @@ static void lcd_show_end_stops() { lcd_puts_P((READ(Z_MIN_PIN) ^ (bool)Z_MIN_ENDSTOP_INVERTING) ? (PSTR("Z1")) : (PSTR("Z0"))); } +#ifndef TMC2130 static void menu_show_end_stops() { lcd_show_end_stops(); if (LCD_CLICKED) menu_back(); } +#endif // not defined TMC2130 // Lets the user move the Z carriage up to the end stoppers. // When done, it sets the current Z to Z_MAX_POS and returns true. // Otherwise the Z calibration is not changed and false is returned. void lcd_diag_show_end_stops() { - int enc_dif = lcd_encoder_diff; lcd_clear(); for (;;) { manage_heater(); manage_inactivity(true); lcd_show_end_stops(); if (lcd_clicked()) { - while (lcd_clicked()) ; - delay(10); - while (lcd_clicked()) ; break; } } @@ -4295,7 +4301,14 @@ void lcd_toshiba_flash_air_compatibility_toggle() void lcd_v2_calibration() { if (mmu_enabled) - lcd_commands_type = LCD_COMMAND_V2_CAL; + { + const uint8_t filament = choose_menu_P(_i("Select PLA filament:"),_T(MSG_FILAMENT),_i("Cancel")); ////c=20 r=1 ////c=19 r=1 + if (filament < 5) + { + lcd_commands_step = 20 + filament; + lcd_commands_type = LCD_COMMAND_V2_CAL; + } + } else { bool loaded = lcd_show_fullscreen_message_yes_no_and_wait_P(_i("Is PLA filament loaded?"), false, true);////MSG_PLA_FILAMENT_LOADED c=20 r=2 @@ -4307,9 +4320,6 @@ void lcd_v2_calibration() for (int i = 0; i < 20; i++) { //wait max. 2s delay_keep_alive(100); if (lcd_clicked()) { - while (lcd_clicked()); - delay(10); - while (lcd_clicked()); break; } } @@ -4326,7 +4336,7 @@ void lcd_wizard() { } if (result) { calibration_status_store(CALIBRATION_STATUS_ASSEMBLED); - lcd_wizard(0); + lcd_wizard(WizState::Run); } else { lcd_return_to_status(); @@ -4355,19 +4365,67 @@ void lcd_language() lang_select(LANG_ID_PRI); } -void lcd_wizard(int state) { +static void wait_preheat() +{ + current_position[Z_AXIS] = 100; //move in z axis to make space for loading filament + plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], homing_feedrate[Z_AXIS] / 60, active_extruder); + delay_keep_alive(2000); + lcd_display_message_fullscreen_P(_T(MSG_WIZARD_HEATING)); + while (abs(degHotend(0) - degTargetHotend(0)) > 3) { + lcd_display_message_fullscreen_P(_T(MSG_WIZARD_HEATING)); + lcd_set_cursor(0, 4); + lcd_print(LCD_STR_THERMOMETER[0]); + lcd_print(ftostr3(degHotend(0))); + lcd_print("/"); + lcd_print(degTargetHotend(0)); + lcd_print(LCD_STR_DEGREE); + lcd_set_custom_characters(); + delay_keep_alive(1000); + } +} + +//! @brief Printer first run wizard (Selftest and calibration) +//! +//! +//! First layer calibration with MMU state diagram +//! +//! @startuml +//! [*] --> IsFil +//! IsFil : Is filament 1 loaded? +//! isPLA : Is filament 1 PLA? +//! unload : Eject or Unload? +//! load : Push the button to start loading PLA Filament 1 +//! +//! IsFil --> isPLA : yes +//! IsFil --> load : no +//! isPLA --> unload : no +//! unload --> load : eject +//! unload --> load : unload +//! load --> calibration : click +//! isPLA --> calibration : yes +//! @enduml +//! +//! @param state Entry point of the wizard +//! +//! state | description +//! ---------------------- | ---------------- +//! WizState::Run | Main entry point +//! WizState::RepeatLay1Cal | Entry point after passing 1st layer calibration +void lcd_wizard(WizState state) +{ + using S = WizState; bool end = false; int wizard_event; const char *msg = NULL; while (!end) { printf_P(PSTR("Wizard state: %d"), state); switch (state) { - case 0: // run wizard? + case S::Run: //Run wizard? wizard_active = true; wizard_event = lcd_show_multiscreen_message_yes_no_and_wait_P(_i("Hi, I am your Original Prusa i3 printer. Would you like me to guide you through the setup process?"), false, true);////MSG_WIZARD_WELCOME c=20 r=7 if (wizard_event) { - state = 1; + state = S::Restore; eeprom_write_byte((uint8_t*)EEPROM_WIZARD_ACTIVE, 1); } else { @@ -4375,72 +4433,97 @@ void lcd_wizard(int state) { end = true; } break; - case 1: // restore calibration status + case S::Restore: // restore calibration status switch (calibration_status()) { - case CALIBRATION_STATUS_ASSEMBLED: state = 2; break; //run selftest - case CALIBRATION_STATUS_XYZ_CALIBRATION: state = 3; break; //run xyz cal. - case CALIBRATION_STATUS_Z_CALIBRATION: state = 4; break; //run z cal. - case CALIBRATION_STATUS_LIVE_ADJUST: state = 5; break; //run live adjust + case CALIBRATION_STATUS_ASSEMBLED: state = S::Selftest; break; //run selftest + case CALIBRATION_STATUS_XYZ_CALIBRATION: state = S::Xyz; break; //run xyz cal. + case CALIBRATION_STATUS_Z_CALIBRATION: state = S::Z; break; //run z cal. + case CALIBRATION_STATUS_LIVE_ADJUST: state = S::IsFil; break; //run live adjust case CALIBRATION_STATUS_CALIBRATED: end = true; eeprom_write_byte((uint8_t*)EEPROM_WIZARD_ACTIVE, 0); break; - default: state = 2; break; //if calibration status is unknown, run wizard from the beginning + default: state = S::Selftest; break; //if calibration status is unknown, run wizard from the beginning } break; - case 2: //selftest + case S::Selftest: lcd_show_fullscreen_message_and_wait_P(_i("First, I will run the selftest to check most common assembly problems."));////MSG_WIZARD_SELFTEST c=20 r=8 wizard_event = lcd_selftest(); if (wizard_event) { calibration_status_store(CALIBRATION_STATUS_XYZ_CALIBRATION); - state = 3; + state = S::Xyz; } else end = true; break; - case 3: //xyz cal. + case S::Xyz: //xyz calibration lcd_show_fullscreen_message_and_wait_P(_i("I will run xyz calibration now. It will take approx. 12 mins."));////MSG_WIZARD_XYZ_CAL c=20 r=8 wizard_event = gcode_M45(false, 0); - if (wizard_event) state = 5; + if (wizard_event) state = S::IsFil; else end = true; break; - case 4: //z cal. + case S::Z: //z calibration lcd_show_fullscreen_message_and_wait_P(_i("I will run z calibration now."));////MSG_WIZARD_Z_CAL c=20 r=8 wizard_event = lcd_show_fullscreen_message_yes_no_and_wait_P(_T(MSG_STEEL_SHEET_CHECK), false, false); if (!wizard_event) lcd_show_fullscreen_message_and_wait_P(_T(MSG_PLACE_STEEL_SHEET)); wizard_event = gcode_M45(true, 0); - if (wizard_event) state = 11; //shipped, no need to set first layer, go to final message directly + if (wizard_event) state = S::Finish; //shipped, no need to set first layer, go to final message directly else end = true; break; - case 5: //is filament loaded? + case S::IsFil: //is filament loaded? //start to preheat nozzle and bed to save some time later setTargetHotend(PLA_PREHEAT_HOTEND_TEMP, 0); setTargetBed(PLA_PREHEAT_HPB_TEMP); - wizard_event = lcd_show_fullscreen_message_yes_no_and_wait_P(_i("Is filament loaded?"), false);////MSG_WIZARD_FILAMENT_LOADED c=20 r=2 - if (wizard_event) state = 8; - else state = 6; - - break; - case 6: //waiting for preheat nozzle for PLA; -#ifndef SNMM - lcd_display_message_fullscreen_P(_i("Now I will preheat nozzle for PLA."));////MSG_WIZARD_WILL_PREHEAT c=20 r=4 - current_position[Z_AXIS] = 100; //move in z axis to make space for loading filament - plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS], homing_feedrate[Z_AXIS] / 60, active_extruder); - delay_keep_alive(2000); - lcd_display_message_fullscreen_P(_T(MSG_WIZARD_HEATING)); - while (abs(degHotend(0) - PLA_PREHEAT_HOTEND_TEMP) > 3) { - lcd_display_message_fullscreen_P(_T(MSG_WIZARD_HEATING)); - - lcd_set_cursor(0, 4); - lcd_print(LCD_STR_THERMOMETER[0]); - lcd_print(ftostr3(degHotend(0))); - lcd_print("/"); - lcd_print(PLA_PREHEAT_HOTEND_TEMP); - lcd_print(LCD_STR_DEGREE); - lcd_set_custom_characters(); - delay_keep_alive(1000); + if (mmu_enabled) + { + wizard_event = lcd_show_fullscreen_message_yes_no_and_wait_P(_i("Is filament 1 loaded?"), false);////c=20 r=2 + } else + { + wizard_event = lcd_show_fullscreen_message_yes_no_and_wait_P(_i("Is filament loaded?"), false);////MSG_WIZARD_FILAMENT_LOADED c=20 r=2 + } + if (wizard_event) state = S::IsPla; + else + { + if(mmu_enabled) state = S::LoadFil; + else state = S::PreheatPla; } -#endif //not SNMM - state = 7; break; - case 7: //load filament - lcd_show_fullscreen_message_and_wait_P(_i("Please insert PLA filament to the extruder, then press knob to load it."));////MSG_WIZARD_LOAD_FILAMENT c=20 r=8 + case S::PreheatPla: +#ifndef SNMM + lcd_display_message_fullscreen_P(_i("Now I will preheat nozzle for PLA."));////MSG_WIZARD_WILL_PREHEAT c=20 r=4 + wait_preheat(); +#endif //not SNMM + state = S::LoadFil; + break; + case S::Preheat: + menu_goto(lcd_preheat_menu,0,false,true); + lcd_show_fullscreen_message_and_wait_P(_i("Select nozzle preheat temperature which matches your material.")); + end = true; // Leave wizard temporarily for lcd_preheat_menu + break; + case S::Unload: + wait_preheat(); + if(mmu_enabled) + { + int8_t unload = lcd_show_multiscreen_message_two_choices_and_wait_P( + _i("Use unload to remove filament 1 if it protrudes outside of the rear MMU tube. Use eject if it is hidden in tube.") + ,false, true, _i("Unload"), _i("Eject")); + if (unload) + { + extr_unload_0(); + } else + { + mmu_eject_fil_0(); + } + } else + { + unload_filament(); + } + state = S::LoadFil; + break; + case S::LoadFil: //load filament + if (mmu_enabled) + { + lcd_show_fullscreen_message_and_wait_P(_i("Please insert PLA filament to the first tube of MMU, then press the knob to load it."));////c=20 r=8 + } else + { + lcd_show_fullscreen_message_and_wait_P(_i("Please insert PLA filament to the extruder, then press knob to load it."));////MSG_WIZARD_LOAD_FILAMENT c=20 r=8 + } lcd_update_enable(false); lcd_clear(); lcd_puts_at_P(0, 2, _T(MSG_LOADING_FILAMENT)); @@ -4449,30 +4532,31 @@ void lcd_wizard(int state) { #endif loading_flag = true; gcode_M701(); - state = 9; + state = S::Lay1Cal; break; - case 8: + case S::IsPla: wizard_event = lcd_show_fullscreen_message_yes_no_and_wait_P(_i("Is it PLA filament?"), false, true);////MSG_WIZARD_PLA_FILAMENT c=20 r=2 - if (wizard_event) state = 9; - else end = true; + if (wizard_event) state = S::Lay1Cal; + else state = S::Preheat; break; - case 9: + case S::Lay1Cal: lcd_show_fullscreen_message_and_wait_P(_i("Now I will calibrate distance between tip of the nozzle and heatbed surface."));////MSG_WIZARD_V2_CAL c=20 r=8 lcd_show_fullscreen_message_and_wait_P(_i("I will start to print line and you will gradually lower the nozzle by rotating the knob, until you reach optimal height. Check the pictures in our handbook in chapter Calibration."));////MSG_WIZARD_V2_CAL_2 c=20 r=12 lcd_commands_type = LCD_COMMAND_V2_CAL; + lcd_return_to_status(); end = true; break; - case 10: //repeat first layer cal.? + case S::RepeatLay1Cal: //repeat first layer cal.? wizard_event = lcd_show_multiscreen_message_yes_no_and_wait_P(_i("Do you want to repeat last step to readjust distance between nozzle and heatbed?"), false);////MSG_WIZARD_REPEAT_V2_CAL c=20 r=7 if (wizard_event) { lcd_show_fullscreen_message_and_wait_P(_i("Please clean heatbed and then press the knob."));////MSG_WIZARD_CLEAN_HEATBED c=20 r=8 - state = 9; + state = S::Lay1Cal; } else { - state = 11; + state = S::Finish; } break; - case 11: //we are finished + case S::Finish: //we are finished eeprom_write_byte((uint8_t*)EEPROM_WIZARD_ACTIVE, 0); end = true; break; @@ -4483,27 +4567,15 @@ void lcd_wizard(int state) { printf_P(_N("Wizard end state: %d\n"), state); switch (state) { //final message - case 0: //user dont want to use wizard - msg = _T(MSG_WIZARD_QUIT); - break; - - case 1: //printer was already calibrated + case S::Restore: //printer was already calibrated msg = _T(MSG_WIZARD_DONE); break; - case 2: //selftest + case S::Selftest: //selftest + case S::Xyz: //xyz cal. + case S::Z: //z cal. msg = _T(MSG_WIZARD_CALIBRATION_FAILED); break; - case 3: //xyz cal. - msg = _T(MSG_WIZARD_CALIBRATION_FAILED); - break; - case 4: //z cal. - msg = _T(MSG_WIZARD_CALIBRATION_FAILED); - break; - case 8: - msg = _i("Please load PLA filament and then resume Wizard by rebooting the printer.");////MSG_WIZARD_INSERT_CORRECT_FILAMENT c=20 r=8 - break; - case 9: break; //exit wizard for v2 calibration, which is implemted in lcd_commands (we need lcd_update running) - case 11: //we are finished + case S::Finish: //we are finished msg = _T(MSG_WIZARD_DONE); lcd_reset_alert_level(); @@ -4515,12 +4587,11 @@ void lcd_wizard(int state) { break; } - if (state != 9) { + if (!((S::Lay1Cal == state) || (S::Preheat == state))) { lcd_show_fullscreen_message_and_wait_P(msg); wizard_active = false; } lcd_update_enable(true); - lcd_return_to_status(); lcd_update(2); } @@ -4698,6 +4769,7 @@ static void auto_deplete_switch() lcd_autoDeplete = !lcd_autoDeplete; eeprom_update_byte((unsigned char *)EEPROM_AUTO_DEPLETE, lcd_autoDeplete); } + static void lcd_settings_menu() { EEPROM_read(EEPROM_SILENT, (uint8_t*)&SilentModeMenu, sizeof(SilentModeMenu)); @@ -4760,11 +4832,6 @@ static void lcd_settings_menu() MENU_END(); } -static void lcd_selftest_() -{ - lcd_selftest(); -} - #ifdef TMC2130 static void lcd_ustep_linearity_menu_save() { @@ -4898,9 +4965,6 @@ void bowden_menu() { } if (lcd_clicked()) { - while (lcd_clicked()); - delay(10); - while (lcd_clicked()); lcd_clear(); while (1) { @@ -4932,9 +4996,6 @@ void bowden_menu() { } delay(100); if (lcd_clicked()) { - while (lcd_clicked()); - delay(10); - while (lcd_clicked()); EEPROM_save_B(EEPROM_BOWDEN_LENGTH + cursor_pos * 2, &bowden_length[cursor_pos]); if (lcd_show_fullscreen_message_yes_no_and_wait_P(PSTR("Continue with another bowden?"))) { lcd_update_enable(true); @@ -4995,9 +5056,6 @@ static char snmm_stop_print_menu() { //menu for choosing which filaments will be } } if (lcd_clicked()) { - while (lcd_clicked()); - delay(10); - while (lcd_clicked()); KEEPALIVE_STATE(IN_HANDLER); return(cursor_pos - 1); } @@ -5005,95 +5063,104 @@ static char snmm_stop_print_menu() { //menu for choosing which filaments will be } -char choose_extruder_menu() +//! @brief Select one of numbered items +//! +//! Create list of items with header. Header can not be selected. +//! Each item has text description passed by function parameter and +//! number. There are 5 numbered items, if mmu_enabled, 4 otherwise. +//! Items are numbered from 1 to 4 or 5. But index returned starts at 0. +//! There can be last item with different text and no number. +//! +//! @param header Header text +//! @param item Item text +//! @param last_item Last item text, or nullptr if there is no Last item +//! @return selected item index, first item index is 0 +uint8_t choose_menu_P(const char *header, const char *item, const char *last_item) { - int items_no = mmu_enabled?5:4; - int first = 0; - int enc_dif = 0; - char cursor_pos = 1; + //following code should handle 3 to 127 number of items well + const int8_t items_no = last_item?(mmu_enabled?6:5):(mmu_enabled?5:4); + const uint8_t item_len = item?strlen_P(item):0; + int8_t first = 0; + int8_t enc_dif = lcd_encoder_diff; + int8_t cursor_pos = 1; - enc_dif = lcd_encoder_diff; lcd_clear(); - if (mmu_enabled) lcd_puts_P(_T(MSG_CHOOSE_FILAMENT)); - else lcd_puts_P(_T(MSG_CHOOSE_EXTRUDER)); - lcd_set_cursor(0, 1); - lcd_print(">"); - for (int i = 0; i < 3; i++) { - lcd_puts_at_P(1, i + 1, mmu_enabled ? _T(MSG_FILAMENT) : _T(MSG_EXTRUDER)); - } + KEEPALIVE_STATE(PAUSED_FOR_USER); - while (1) { - - for (int i = 0; i < 3; i++) { - lcd_set_cursor(2 + strlen_P( mmu_enabled ? _T(MSG_FILAMENT) : _T(MSG_EXTRUDER)), i+1); - lcd_print(first + i + 1); - } - + while (1) + { manage_heater(); manage_inactivity(true); - if (abs((enc_dif - lcd_encoder_diff)) > 4) { - - if ((abs(enc_dif - lcd_encoder_diff)) > 1) { - if (enc_dif > lcd_encoder_diff) { - cursor_pos--; - } - - if (enc_dif < lcd_encoder_diff) { - cursor_pos++; - } - - if (cursor_pos > 3) { - cursor_pos = 3; - if (first < items_no - 3) { - first++; - lcd_clear(); - if (mmu_enabled) lcd_puts_P(_T(MSG_CHOOSE_FILAMENT)); - else lcd_puts_P(_T(MSG_CHOOSE_EXTRUDER)); - for (int i = 0; i < 3; i++) { - lcd_puts_at_P(1, i + 1, mmu_enabled ? _T(MSG_FILAMENT) : _T(MSG_EXTRUDER)); - } - } - } - - if (cursor_pos < 1) { - cursor_pos = 1; - if (first > 0) { - first--; - lcd_clear(); - if (mmu_enabled) lcd_puts_P(_T(MSG_CHOOSE_FILAMENT)); - else lcd_puts_P(_T(MSG_CHOOSE_EXTRUDER)); - for (int i = 0; i < 3; i++) { - lcd_puts_at_P(1, i + 1, mmu_enabled ? _T(MSG_FILAMENT) : _T(MSG_EXTRUDER)); - } - } - } - 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(">"); - enc_dif = lcd_encoder_diff; - delay(100); - } + if (abs((enc_dif - lcd_encoder_diff)) > 4) + { + if (enc_dif > lcd_encoder_diff) + { + cursor_pos--; + } + if (enc_dif < lcd_encoder_diff) + { + cursor_pos++; + } + enc_dif = lcd_encoder_diff; } - if (lcd_clicked()) { - lcd_update(2); - while (lcd_clicked()); - delay(10); - while (lcd_clicked()); - KEEPALIVE_STATE(IN_HANDLER); + if (cursor_pos > 3) + { + cursor_pos = 3; + if (first < items_no - 3) + { + first++; + lcd_clear(); + } + } + + if (cursor_pos < 1) + { + cursor_pos = 1; + if (first > 0) + { + first--; + lcd_clear(); + } + } + + if (header) lcd_puts_at_P(0,0,header); + + const bool last_visible = (first == items_no - 3); + const int8_t ordinary_items = (last_item&&last_visible)?2:3; + + for (int i = 0; i < ordinary_items; i++) + { + if (item) lcd_puts_at_P(1, i + 1, item); + } + + for (int i = 0; i < ordinary_items; i++) + { + lcd_set_cursor(2 + item_len, i+1); + lcd_print(first + i + 1); + } + + 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(">"); + + delay(100); + + if (lcd_clicked()) + { + KEEPALIVE_STATE(IN_HANDLER); return(cursor_pos + first - 1); - } - } - } //#endif @@ -5175,9 +5242,6 @@ char reset_menu() { } if (lcd_clicked()) { - while (lcd_clicked()); - delay(10); - while (lcd_clicked()); return(cursor_pos + first); } @@ -5198,7 +5262,6 @@ static void lcd_disable_farm_mode() } - static void fil_load_menu() { MENU_BEGIN(); @@ -5282,7 +5345,7 @@ void unload_filament() disable_e2(); delay(100); - Sound_MakeSound(e_SOUND_CLASS_Prompt, e_SOUND_TYPE_StandardPrompt); + Sound_MakeSound(e_SOUND_TYPE_StandardPrompt); uint8_t counterBeep = 0; while (!lcd_clicked() && (counterBeep < 50)) { delay_keep_alive(100); @@ -5435,9 +5498,6 @@ unsigned char lcd_choose_color() { } if (lcd_clicked()) { - while (lcd_clicked()); - delay(10); - while (lcd_clicked()); switch(cursor_pos + first - 1) { case 0: return 1; break; case 1: return 0; break; @@ -5529,6 +5589,7 @@ void lcd_confirm_print() #include "w25x20cl.h" +#ifdef LCD_TEST static void lcd_test_menu() { W25X20CL_SPI_ENTER(); @@ -5536,6 +5597,20 @@ static void lcd_test_menu() w25x20cl_chip_erase(); w25x20cl_disable_wr(); } +#endif //LCD_TEST + +//! @brief Resume paused print +//! @todo It is not good to call restore_print_from_ram_and_continue() from function called by lcd_update(), +//! as restore_print_from_ram_and_continue() calls lcd_update() internally. +void lcd_resume_print() +{ + lcd_return_to_status(); + lcd_setstatuspgm(_T(MSG_RESUMING_PRINT)); + lcd_reset_alert_level(); //for fan speed error + restore_print_from_ram_and_continue(0.0); + pause_time += (millis() - start_pause_print); //accumulate time when print is paused for correct statistics calculation + isPrintPaused = false; +} static void lcd_main_menu() { @@ -5630,11 +5705,11 @@ static void lcd_main_menu() if (mesh_bed_leveling_flag == false && homing_flag == false) { if (card.sdprinting) { - MENU_ITEM_FUNCTION_P(_i("Pause print"), lcd_sdcard_pause);////MSG_PAUSE_PRINT c=0 r=0 + MENU_ITEM_FUNCTION_P(_i("Pause print"), lcd_pause_print);////MSG_PAUSE_PRINT c=0 r=0 } else { - MENU_ITEM_FUNCTION_P(_i("Resume print"), lcd_sdcard_resume);////MSG_RESUME_PRINT c=0 r=0 + MENU_ITEM_SUBMENU_P(_i("Resume print"), lcd_resume_print);////MSG_RESUME_PRINT c=0 r=0 } MENU_ITEM_SUBMENU_P(_T(MSG_STOP_PRINT), lcd_sdcard_stop); } @@ -5710,8 +5785,9 @@ static void lcd_main_menu() #endif MENU_ITEM_SUBMENU_P(_i("Support"), lcd_support_menu);////MSG_SUPPORT c=0 r=0 - -// MENU_ITEM_SUBMENU_P(_i("W25x20CL init"), lcd_test_menu);////MSG_SUPPORT c=0 r=0 +#ifdef LCD_TEST + MENU_ITEM_SUBMENU_P(_i("W25x20CL init"), lcd_test_menu);////MSG_SUPPORT c=0 r=0 +#endif //LCD_TEST MENU_END(); @@ -5748,34 +5824,6 @@ void stepper_timer_overflow() { } #endif /* DEBUG_STEPPER_TIMER_MISSED */ -#ifdef SDSUPPORT -static void lcd_autostart_sd() -{ - card.lastnr = 0; - card.setroot(); - card.checkautostart(true); -} -#endif - - - -static void lcd_silent_mode_set_tune() { - switch (SilentModeMenu) { -#ifdef TMC2130 - case SILENT_MODE_NORMAL: SilentModeMenu = SILENT_MODE_STEALTH; break; - case SILENT_MODE_STEALTH: SilentModeMenu = SILENT_MODE_NORMAL; break; - default: SilentModeMenu = SILENT_MODE_NORMAL; break; // (probably) not needed -#else - case SILENT_MODE_POWER: SilentModeMenu = SILENT_MODE_SILENT; break; - case SILENT_MODE_SILENT: SilentModeMenu = SILENT_MODE_AUTO; break; - case SILENT_MODE_AUTO: SilentModeMenu = SILENT_MODE_POWER; break; - default: SilentModeMenu = SILENT_MODE_POWER; break; // (probably) not needed -#endif //TMC2130 - } - eeprom_update_byte((unsigned char *)EEPROM_SILENT, SilentModeMenu); - st_current_init(); - menu_back(); -} static void lcd_colorprint_change() { @@ -5883,12 +5931,6 @@ static void lcd_tune_menu() MENU_END(); } -static void lcd_move_menu_01mm() -{ - move_menu_scale = 0.1; - lcd_move_menu_axis(); -} - static void lcd_control_temperature_menu() { #ifdef PIDTEMP @@ -6005,7 +6047,7 @@ void lcd_sdcard_stop() void lcd_sdcard_menu() { uint8_t sdSort = eeprom_read_byte((uint8_t*)EEPROM_SD_SORT); - int tempScrool = 0; + if (presort_flag == true) { presort_flag = false; card.presort(); @@ -6047,7 +6089,7 @@ void lcd_sdcard_menu() #endif if (card.filenameIsDir) - MENU_ITEM_SDDIR(_T(MSG_CARD_MENU), card.filename, card.longFilename); + MENU_ITEM_SDDIR(card.filename, card.longFilename); else MENU_ITEM_SDFILE(_T(MSG_CARD_MENU), card.filename, card.longFilename); } else { @@ -6250,14 +6292,14 @@ bool lcd_selftest() #ifdef TMC2130 -static void reset_crash_det(char axis) { +static void reset_crash_det(unsigned char axis) { current_position[axis] += 10; plan_buffer_line(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[3], manual_feedrate[0] / 60, active_extruder); st_synchronize(); if (eeprom_read_byte((uint8_t*)EEPROM_CRASH_DET)) tmc2130_sg_stop_on_crash = true; } -static bool lcd_selfcheck_axis_sg(char axis) { +static bool lcd_selfcheck_axis_sg(unsigned char axis) { // each axis length is measured twice float axis_length, current_position_init, current_position_final; float measured_axis_length[2]; @@ -6544,7 +6586,6 @@ static bool lcd_selfcheck_pulleys(int axis) } return(true); } -#endif //TMC2130 static bool lcd_selfcheck_endstops() @@ -6577,7 +6618,7 @@ static bool lcd_selfcheck_endstops() manage_inactivity(true); return _result; } -//#endif //not defined TMC2130 +#endif //not defined TMC2130 static bool lcd_selfcheck_check_heater(bool _isbed) { @@ -7060,7 +7101,7 @@ static bool check_file(const char* filename) { } -void menu_action_sdfile(const char* filename, char* longFilename) +static void menu_action_sdfile(const char* filename) { loading_flag = false; char cmd[30]; @@ -7105,7 +7146,7 @@ void menu_action_sdfile(const char* filename, char* longFilename) lcd_return_to_status(); } -void menu_action_sddirectory(const char* filename, char* longFilename) +void menu_action_sddirectory(const char* filename) { uint8_t depth = (uint8_t)card.getWorkDirDepth(); @@ -7147,7 +7188,6 @@ void ultralcd_init() WRITE(SDCARDDETECT, HIGH); lcd_oldcardstatus = IS_SD_INSERTED; #endif//(SDCARDDETECT > 0) - lcd_buttons_update(); lcd_encoder_diff = 0; } @@ -7170,11 +7210,11 @@ static void lcd_send_status() { } } +#ifdef FARM_CONNECT_MESSAGE static void lcd_connect_printer() { lcd_update_enable(false); lcd_clear(); - bool pressed = false; int i = 0; int t = 0; lcd_set_custom_characters_progress(); @@ -7203,6 +7243,7 @@ static void lcd_connect_printer() { lcd_update_enable(true); lcd_update(2); } +#endif //FARM_CONNECT_MESSAGE void lcd_ping() { //chceck if printer is connected to monitoring when in farm mode if (farm_mode) { @@ -7266,19 +7307,6 @@ uint8_t get_message_level() } - - - - - - - - - - - - - void menu_lcd_longpress_func(void) { move_menu_scale = 1.0; diff --git a/Firmware/ultralcd.h b/Firmware/ultralcd.h index fe740822..d2d4d0a2 100644 --- a/Firmware/ultralcd.h +++ b/Firmware/ultralcd.h @@ -5,6 +5,7 @@ #include "lcd.h" #include "conv2str.h" #include "menu.h" +#include "mesh_bed_calibration.h" extern int lcd_puts_P(const char* str); extern int lcd_printf_P(const char* format, ...); @@ -31,7 +32,8 @@ void lcd_loading_filament(); void lcd_change_success(); void lcd_loading_color(); void lcd_sdcard_stop(); -void lcd_sdcard_pause(); +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(); @@ -50,6 +52,8 @@ extern void lcd_wait_for_click(); extern void lcd_show_fullscreen_message_and_wait_P(const char *msg); // 0: no, 1: yes, -1: timeouted extern int8_t lcd_show_fullscreen_message_yes_no_and_wait_P(const char *msg, bool allow_timeouting = true, bool default_yes = false); +extern int8_t lcd_show_multiscreen_message_two_choices_and_wait_P(const char *msg, bool allow_timeouting, bool default_yes, + const char *first_choice, const char *second_choice); extern int8_t lcd_show_multiscreen_message_yes_no_and_wait_P(const char *msg, bool allow_timeouting = true, bool default_yes = false); // Ask the user to move the Z axis up to the end stoppers and let // the user confirm that it has been done. @@ -59,7 +63,7 @@ extern bool lcd_calibrate_z_end_stop_manual(bool only_z); #endif // Show the result of the calibration process on the LCD screen. -extern void lcd_bed_calibration_show_result(uint8_t result, uint8_t point_too_far_mask); + extern void lcd_bed_calibration_show_result(BedSkewOffsetDetectionResultType result, uint8_t point_too_far_mask); extern void lcd_diag_show_end_stops(); @@ -76,11 +80,11 @@ extern void lcd_diag_show_end_stops(); #define LCD_COMMAND_STOP_PRINT 2 #define LCD_COMMAND_FARM_MODE_CONFIRM 4 #define LCD_COMMAND_LONG_PAUSE 5 -#define LCD_COMMAND_LONG_PAUSE_RESUME 6 #define LCD_COMMAND_PID_EXTRUDER 7 #define LCD_COMMAND_V2_CAL 8 extern int lcd_commands_type; +extern int8_t FSensorStateMenu; #define CUSTOM_MSG_TYPE_STATUS 0 // status message from lcd_status_message variable #define CUSTOM_MSG_TYPE_MESHBL 1 // Mesh bed leveling in progress @@ -150,7 +154,7 @@ bool lcd_wait_for_pinda(float temp); void bowden_menu(); char reset_menu(); -char choose_extruder_menu(); +uint8_t choose_menu_P(const char *header, const char *item, const char *last_item = nullptr); void lcd_pinda_calibration_menu(); void lcd_calibrate_pinda(); @@ -166,6 +170,26 @@ void lcd_set_progress(); void lcd_language(); void lcd_wizard(); -void lcd_wizard(int state); + +//! @brief Wizard state +enum class WizState : uint8_t +{ + Run, //!< run wizard? Entry point. + Restore, //!< restore calibration status + Selftest, + Xyz, //!< xyz calibration + Z, //!< z calibration + IsFil, //!< Is filament loaded? Entry point for 1st layer calibration + PreheatPla, //!< waiting for preheat nozzle for PLA + Preheat, //!< Preheat for any material + Unload, //!< Unload filament + LoadFil, //!< Load filament + IsPla, //!< Is PLA filament? + Lay1Cal, //!< First layer calibration + RepeatLay1Cal, //!< Repeat first layer calibration? + Finish, //!< Deactivate wizard +}; + +void lcd_wizard(WizState state); #endif //ULTRALCD_H diff --git a/Firmware/xyzcal.cpp b/Firmware/xyzcal.cpp index 03bdb2fb..3b9c0a4f 100644 --- a/Firmware/xyzcal.cpp +++ b/Firmware/xyzcal.cpp @@ -32,8 +32,6 @@ #define _PI 3.14159265F -extern volatile long count_position[NUM_AXIS]; - 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); @@ -87,7 +85,7 @@ uint8_t check_pinda_1() uint8_t xyzcal_dm = 0; -void xyzcal_update_pos(uint16_t dx, uint16_t dy, uint16_t dz, uint16_t de) +void xyzcal_update_pos(uint16_t dx, uint16_t dy, uint16_t dz, uint16_t) { // DBG(_n("xyzcal_update_pos dx=%d dy=%d dz=%d dir=%02x\n"), dx, dy, dz, xyzcal_dm); if (xyzcal_dm&1) count_position[0] -= dx; else count_position[0] += dx; @@ -108,11 +106,9 @@ uint16_t xyzcal_sm4_ac2 = (uint32_t)xyzcal_sm4_ac * 1024 / 10000; //float xyzcal_sm4_vm = 10000; #endif //SM4_ACCEL_TEST +#ifdef SM4_ACCEL_TEST uint16_t xyzcal_calc_delay(uint16_t nd, uint16_t dd) { - return xyzcal_sm4_delay; -#ifdef SM4_ACCEL_TEST - uint16_t del_us = 0; if (xyzcal_sm4_v & 0xf000) //>=4096 { @@ -138,9 +134,13 @@ uint16_t xyzcal_calc_delay(uint16_t nd, uint16_t dd) // return xyzcal_sm4_delay; // DBG(_n("xyzcal_calc_delay nd=%d dd=%d v=%d del_us=%d\n"), nd, dd, xyzcal_sm4_v, del_us); return 0; -#endif //SM4_ACCEL_TEST } - +#else //SM4_ACCEL_TEST +uint16_t xyzcal_calc_delay(uint16_t, uint16_t) +{ + return xyzcal_sm4_delay; +} +#endif //SM4_ACCEL_TEST bool xyzcal_lineXYZ_to(int16_t x, int16_t y, int16_t z, uint16_t delay_us, int8_t check_pinda) { @@ -285,7 +285,7 @@ void xyzcal_scan_pixels_32x32(int16_t cx, int16_t cy, int16_t min_z, int16_t max xyzcal_lineXYZ_to(cx, cy, z, 2*delay_us, 0); for (uint8_t r = 0; r < 32; r++) { - int8_t _pinda = _PINDA; +// 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, 1); xyzcal_lineXYZ_to(_X, _Y, max_z, delay_us, -1); @@ -330,7 +330,7 @@ void xyzcal_scan_pixels_32x32(int16_t cx, int16_t cy, int16_t min_z, int16_t max } sm4_do_step(X_AXIS_MASK); delayMicroseconds(600); - _pinda = pinda; +// _pinda = pinda; } sum >>= 6; //div 64 if (z_sum < 0) diff --git a/README.md b/README.md index 72598ee0..4de43b93 100644 --- a/README.md +++ b/README.md @@ -2,8 +2,7 @@ 1. install `"Arduino Software IDE"` for your preferred operating system `https://www.arduino.cc -> Software->Downloads` -it is strongly recommended to use older version `"1.6.9"`, by which we can assure correct compilation results -_note: in versions `1.7.x` and `1.8.x` there are known some C/C++ compilator disasters, which disallow correct source code compilation (you can obtain `"... internal compiler error: in extract_insn, at ..."` error message, for example); we are not able to affect this situation afraid_ +it is recommended to use older version `"1.6.9"`, as it is used on out build server to produce official builds. _note: in the case of persistent compilation problems, check the version of the currently used C/C++ compiler (GCC) - should be `4.8.1`; version can be verified by entering the command `avr-gcc --version` 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_ @@ -26,8 +25,10 @@ _note: select this item for any variant of board used in printers `'Prusa i3 MKx 'clicking' the item will display the installation button; select choice `"1.0.1"` from the list(last known version as of the date of issue of this document) _(after installation, the item is labeled as `"INSTALLED"` and can then be used for target board selection)_ - 3. modify platform.txt to enable float printf support: - `"compiler.c.elf.flags=-w -Os -Wl,-u,vfprintf -lprintf_flt -lm -Wl,--gc-sections"` + 3. modify platform.txt to enable float printf support: +add "-Wl,-u,vfprintf -lprintf_flt -lm" to "compiler.c.elf.flags=" before existing flag "-Wl,--gc-sections" +example: +`"compiler.c.elf.flags=-w -Os -Wl,-u,vfprintf -lprintf_flt -lm -Wl,--gc-sections"` # 2. Source code compilation diff --git a/README_cz.md b/README_cz.md index 5c649963..282babdc 100644 --- a/README_cz.md +++ b/README_cz.md @@ -2,8 +2,7 @@ 1. nainstalujte vývojové prostředí `"Arduino Software IDE"` pro operační prostředí, které jste zvyklí používat `https://www.arduino.cc -> Software->Downloads` -důrazně doporučujeme použít starší verzi `"1.6.8"`, u které jsme schopni garantovat bezproblémový překlad a správné výsledky -_pozn.: ve verzích `1.7.x` a `1.8.x` jsou k datu vydání tohoto dokumentu evidovány chyby v překladači jazyka C/C++, které znemožňují překlad zdrojového kódu (můžete např. obdržet chybové hlášení `"... internal compiler error: in extract_insn, at ..."`); tuto nepříjemnou situaci bohužel nedokážeme nijak ovlivnit_ +doporučujeme použít starší verzi `"1.6.9"`, kterou používáme na našem build serveru pro překlad oficiálních buildů _pozn.: v případě přetrvávajících potíží s překladem zkontrolujte verzi aktuálně použitého překladače jazyka C/C++ (GCC) - měla by být `4.8.1`; verzi ověříte zadáním příkazu `avr-gcc --version` pokud si nejste jisti umístěním souboru (závisí na způsobu, jakým bylo `"Arduino Software IDE"` nainstalováno), použijte funkci vyhledání v rámci systému souborů_ @@ -26,6 +25,10 @@ _pozn.: tuto položku zvolte pro všechny varianty desek použitých v tiskárn 'kliknutím' na položku se zobrazí tlačítko pro instalaci; ve výběrovém seznamu zvolte verzi `"1.0.1"` (poslední známá verze k datu vydání tohoto dokumentu) _(po provedení instalace je položka označena poznámkou `"INSTALLED"` a lze ji následně použít při výběru cílové desky)_ + 3. modify platform.txt to enable float printf support: +add "-Wl,-u,vfprintf -lprintf_flt -lm" to "compiler.c.elf.flags=" before existing flag "-Wl,--gc-sections" +example: +`"compiler.c.elf.flags=-w -Os -Wl,-u,vfprintf -lprintf_flt -lm -Wl,--gc-sections"` # 2. Překlad zdrojoveho kódu From 9cae0c378a21f72c37fae6d4c84056499d25418e Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Mon, 8 Oct 2018 20:24:56 +0200 Subject: [PATCH 140/141] Rename _EEPROM_writeData to EEPROM_writeData. Rename _EEPROM_readData to EEPROM_readData. Add return value to EEPROM_writeData to detect failure to write. Do not mark data as valid, if write has failed. Remove EEPROM_WRITE_VAR and EEPROM_READ_VAR macros. Make pos input only parameter. Convert EEPROM_OFFSET macro to typed constatant EEPROM_M500_base, it was defined in two places, leave it in one place. Use Config_StoreSettings() instead of erase_eeprom_section(). Compare float with 0xff byte by byte to avoid compiler warning "Dereferencing type punned pointer will break strict aliasing rules." --- Firmware/ConfigurationStore.cpp | 101 ++++++++++++++++---------------- Firmware/ConfigurationStore.h | 6 +- Firmware/Marlin.h | 1 - Firmware/Marlin_main.cpp | 13 ++-- Firmware/eeprom.h | 7 ++- 5 files changed, 62 insertions(+), 66 deletions(-) diff --git a/Firmware/ConfigurationStore.cpp b/Firmware/ConfigurationStore.cpp index d16e92e5..2aafdd44 100644 --- a/Firmware/ConfigurationStore.cpp +++ b/Firmware/ConfigurationStore.cpp @@ -1,3 +1,5 @@ +//! @file + #include "Marlin.h" #include "planner.h" #include "temperature.h" @@ -11,74 +13,67 @@ M500_conf cs; +//! @brief Write data to EEPROM +//! @param pos destination in EEPROM, 0 is start +//! @param value value to be written +//! @param size size of type pointed by value +//! @param name name of variable written, used only for debug input if DEBUG_EEPROM_WRITE defined +//! @retval true success +//! @retval false failed #ifdef DEBUG_EEPROM_WRITE -#define EEPROM_WRITE_VAR(pos, value) _EEPROM_writeData(pos, (uint8_t*)&value, sizeof(value), #value) -static void _EEPROM_writeData(int &pos, uint8_t* value, uint8_t size, char* name) +static bool EEPROM_writeData(uint8_t* pos, uint8_t* value, uint8_t size, const char* name) #else //DEBUG_EEPROM_WRITE -#define EEPROM_WRITE_VAR(pos, value) _EEPROM_writeData(pos, (uint8_t*)&value, sizeof(value)) -static void _EEPROM_writeData(int &pos, uint8_t* value, uint8_t size) +static bool EEPROM_writeData(uint8_t* pos, uint8_t* value, uint8_t size, const char*) #endif //DEBUG_EEPROM_WRITE { #ifdef DEBUG_EEPROM_WRITE printf_P(PSTR("EEPROM_WRITE_VAR addr=0x%04x size=0x%02hhx name=%s\n"), pos, size, name); #endif //DEBUG_EEPROM_WRITE - while (size--) { - uint8_t * const p = (uint8_t * const)pos; - uint8_t v = *value; - // EEPROM has only ~100,000 write cycles, - // so only write bytes that have changed! - if (v != eeprom_read_byte(p)) { - eeprom_write_byte(p, v); - if (eeprom_read_byte(p) != v) { - SERIAL_ECHOLNPGM("EEPROM Error"); - return; - } - } + while (size--) + { + + eeprom_update_byte(pos, *value); + if (eeprom_read_byte(pos) != *value) { + SERIAL_ECHOLNPGM("EEPROM Error"); + return false; + } + pos++; value++; - }; - + } + return true; } #ifdef DEBUG_EEPROM_READ -#define EEPROM_READ_VAR(pos, value) _EEPROM_readData(pos, (uint8_t*)&value, sizeof(value), #value) -static void _EEPROM_readData(int &pos, uint8_t* value, uint8_t size, char* name) +static void EEPROM_readData(uint8_t* pos, uint8_t* value, uint8_t size, const char* name) #else //DEBUG_EEPROM_READ -#define EEPROM_READ_VAR(pos, value) _EEPROM_readData(pos, (uint8_t*)&value, sizeof(value)) -static void _EEPROM_readData(int &pos, uint8_t* value, uint8_t size) +static void EEPROM_readData(uint8_t* pos, uint8_t* value, uint8_t size, const char*) #endif //DEBUG_EEPROM_READ { #ifdef DEBUG_EEPROM_READ printf_P(PSTR("EEPROM_READ_VAR addr=0x%04x size=0x%02hhx name=%s\n"), pos, size, name); #endif //DEBUG_EEPROM_READ - do + while(size--) { - *value = eeprom_read_byte((unsigned char*)pos); + *value = eeprom_read_byte(pos); pos++; value++; - }while(--size); + } } -//====================================================================================== -#define EEPROM_OFFSET 20 -// IMPORTANT: Whenever there are changes made to the variables stored in EEPROM -// in the functions below, also increment the version number. This makes sure that -// the default values are used whenever there is a change to the data, to prevent -// wrong data being written to the variables. -// ALSO: always make sure the variables in the Store and retrieve sections are in the same order. - #define EEPROM_VERSION "V2" #ifdef EEPROM_SETTINGS -void Config_StoreSettings(uint16_t offset) +void Config_StoreSettings() { - int i = offset; strcpy(cs.version,"000"); //!< invalidate data first @TODO use erase to save one erase cycle - _EEPROM_writeData(i,reinterpret_cast(&cs),sizeof(cs),0); - strcpy(cs.version,EEPROM_VERSION); // // validate data - i = offset; - EEPROM_WRITE_VAR(i,cs.version); // validate data + if (EEPROM_writeData(reinterpret_cast(EEPROM_M500_base),reinterpret_cast(&cs),sizeof(cs),0), "cs, invalid version") + { + strcpy(cs.version,EEPROM_VERSION); //!< validate data if write succeed + EEPROM_writeData(reinterpret_cast(EEPROM_M500_base->version), reinterpret_cast(cs.version), sizeof(cs.version), "cs.version valid"); + } + SERIAL_ECHO_START; SERIAL_ECHOLNPGM("Settings Stored"); } @@ -227,21 +222,19 @@ static const M500_conf default_conf PROGMEM = DEFAULT_MAX_ACCELERATION_SILENT, }; -//! -//! @retval true Stored settings retrieved or default settings retrieved in case EEPROM has been erased. -//! @retval false default settings retrieved, because of older version or corrupted data -bool Config_RetrieveSettings(uint16_t offset) +//! @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. +bool Config_RetrieveSettings() { - int i=offset; bool previous_settings_retrieved = true; char ver[4]=EEPROM_VERSION; - EEPROM_READ_VAR(i,cs.version); //read stored version + EEPROM_readData(reinterpret_cast(EEPROM_M500_base->version), reinterpret_cast(cs.version), sizeof(cs.version), "cs.version"); //read stored version // SERIAL_ECHOLN("Version: [" << ver << "] Stored version: [" << cs.version << "]"); if (strncmp(ver,cs.version,3) == 0) // version number match { - i=offset; - EEPROM_READ_VAR(i,cs); + EEPROM_readData(reinterpret_cast(EEPROM_M500_base), reinterpret_cast(&cs), sizeof(cs), "cs"); if (cs.max_jerk[X_AXIS] > DEFAULT_XJERK) cs.max_jerk[X_AXIS] = DEFAULT_XJERK; @@ -255,8 +248,11 @@ bool Config_RetrieveSettings(uint16_t offset) bool initialized = false; for (uint8_t i = 0; i < (sizeof(cs.max_feedrate_silent)/sizeof(cs.max_feedrate_silent[0])); ++i) { - if(erased != reinterpret_cast(cs.max_feedrate_silent[i])) initialized = true; - if(erased != reinterpret_cast(cs.max_acceleration_units_per_sq_second_silent[i])) initialized = true; + for(uint8_t j = 0; j < sizeof(float); ++j) + { + if(0xff != reinterpret_cast(&(cs.max_feedrate_silent[i]))[j]) initialized = true; + } + if(erased != cs.max_acceleration_units_per_sq_second_silent[i]) initialized = true; } if (!initialized) { @@ -292,9 +288,10 @@ bool Config_RetrieveSettings(uint16_t offset) Config_ResetDefault(); //Return false to inform user that eeprom version was changed and firmware is using default hardcoded settings now. //In case that storing to eeprom was not used yet, do not inform user that hardcoded settings are used. - if (eeprom_read_byte((uint8_t *)offset) != 0xFF || - eeprom_read_byte((uint8_t *)offset + 1) != 0xFF || - eeprom_read_byte((uint8_t *)offset + 2) != 0xFF) { + if (eeprom_read_byte(reinterpret_cast(&(EEPROM_M500_base->version[0]))) != 0xFF || + eeprom_read_byte(reinterpret_cast(&(EEPROM_M500_base->version[1]))) != 0xFF || + eeprom_read_byte(reinterpret_cast(&(EEPROM_M500_base->version[2]))) != 0xFF) + { previous_settings_retrieved = false; } } diff --git a/Firmware/ConfigurationStore.h b/Firmware/ConfigurationStore.h index 4f01c3f5..aa201369 100644 --- a/Firmware/ConfigurationStore.h +++ b/Firmware/ConfigurationStore.h @@ -3,6 +3,8 @@ #define EEPROM_SETTINGS #include "Configuration.h" +#include +#include typedef struct { @@ -48,8 +50,8 @@ FORCE_INLINE void Config_PrintSettings() {} #endif #ifdef EEPROM_SETTINGS -void Config_StoreSettings(uint16_t offset); -bool Config_RetrieveSettings(uint16_t offset); +void Config_StoreSettings(); +bool Config_RetrieveSettings(); #else FORCE_INLINE void Config_StoreSettings() {} FORCE_INLINE void Config_RetrieveSettings() { Config_ResetDefault(); Config_PrintSettings(); } diff --git a/Firmware/Marlin.h b/Firmware/Marlin.h index a5b4c124..dd185689 100644 --- a/Firmware/Marlin.h +++ b/Firmware/Marlin.h @@ -385,7 +385,6 @@ float temp_comp_interpolation(float temperature); void temp_compensation_apply(); void temp_compensation_start(); void show_fw_version_warnings(); -void erase_eeprom_section(uint16_t offset, uint16_t bytes); uint8_t check_printer_version(); #ifdef PINDA_THERMISTOR diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index e75a31da..d7716e86 100644 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -866,11 +866,6 @@ uint8_t check_printer_version() return version_changed; } -void erase_eeprom_section(uint16_t offset, uint16_t bytes) -{ - for (unsigned int i = offset; i < (offset+bytes); i++) eeprom_write_byte((uint8_t*)i, 0xFF); -} - #ifdef BOOTAPP #include "bootapp.h" //bootloader support #endif //BOOTAPP @@ -1187,7 +1182,7 @@ void setup() bool previous_settings_retrieved = false; uint8_t hw_changed = check_printer_version(); if (!(hw_changed & 0b10)) { //if printer version wasn't changed, check for eeprom version and retrieve settings from eeprom in case that version wasn't changed - previous_settings_retrieved = Config_RetrieveSettings(EEPROM_OFFSET); + previous_settings_retrieved = Config_RetrieveSettings(); } else { //printer version was changed so use default settings Config_ResetDefault(); @@ -1485,7 +1480,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 - erase_eeprom_section(EEPROM_OFFSET, 156); //erase M500 part of eeprom + Config_StoreSettings(); } if (eeprom_read_byte((uint8_t*)EEPROM_WIZARD_ACTIVE) == 1) { lcd_wizard(WizState::Run); @@ -6310,12 +6305,12 @@ if((eSoundMode==e_SOUND_MODE_LOUD)||(eSoundMode==e_SOUND_MODE_ONCE)) case 500: // M500 Store settings in EEPROM { - Config_StoreSettings(EEPROM_OFFSET); + Config_StoreSettings(); } break; case 501: // M501 Read settings from EEPROM { - Config_RetrieveSettings(EEPROM_OFFSET); + Config_RetrieveSettings(); } break; case 502: // M502 Revert to default settings diff --git a/Firmware/eeprom.h b/Firmware/eeprom.h index 54a21648..b1d7766c 100644 --- a/Firmware/eeprom.h +++ b/Firmware/eeprom.h @@ -182,7 +182,10 @@ // Magic string, indicating that the current or the previous firmware running was the Prusa3D firmware. #define EEPROM_FIRMWARE_PRUSA_MAGIC 0 -#define EEPROM_OFFSET 20 //offset for storing settings using M500 -//#define EEPROM_OFFSET +#ifdef __cplusplus +#include "ConfigurationStore.h" +static M500_conf * const EEPROM_M500_base = reinterpret_cast(20); //offset for storing settings using M500 +#endif + #endif // EEPROM_H From 9dff6431e6abae172190e4b52281367d6b5250ef Mon Sep 17 00:00:00 2001 From: Marek Bel Date: Tue, 9 Oct 2018 22:33:54 +0200 Subject: [PATCH 141/141] Format fsensor documentation. --- Firmware/fsensor.cpp | 89 ++++++++++++++++++++++++-------------------- Firmware/fsensor.h | 33 ++++++++++------ 2 files changed, 70 insertions(+), 52 deletions(-) diff --git a/Firmware/fsensor.cpp b/Firmware/fsensor.cpp index a035683c..4e992691 100644 --- a/Firmware/fsensor.cpp +++ b/Firmware/fsensor.cpp @@ -1,3 +1,5 @@ +//! @file + #include "Marlin.h" #include "fsensor.h" @@ -9,24 +11,27 @@ #include "cmdqueue.h" #include "ultralcd.h" -//Basic params -#define FSENSOR_CHUNK_LEN 0.64F //filament sensor chunk length 0.64mm -#define FSENSOR_ERR_MAX 17 //filament sensor maximum error count for runout detection - -//Optical quality meassurement params -#define FSENSOR_OQ_MAX_ES 6 //maximum error sum while loading (length ~64mm = 100chunks) -#define FSENSOR_OQ_MAX_EM 2 //maximum error counter value while loading -#define FSENSOR_OQ_MIN_YD 2 //minimum yd per chunk (applied to avg value) -#define FSENSOR_OQ_MAX_YD 200 //maximum yd per chunk (applied to avg value) -#define FSENSOR_OQ_MAX_PD 4 //maximum positive deviation (= yd_max/yd_avg) -#define FSENSOR_OQ_MAX_ND 5 //maximum negative deviation (= yd_avg/yd_min) -#define FSENSOR_OQ_MAX_SH 13 //maximum shutter value +//! @name Basic parameters +//! @{ +#define FSENSOR_CHUNK_LEN 0.64F //!< filament sensor chunk length 0.64mm +#define FSENSOR_ERR_MAX 17 //!< filament sensor maximum error count for runout detection +//! @} +//! @name Optical quality measurement parameters +//! @{ +#define FSENSOR_OQ_MAX_ES 6 //!< maximum error sum while loading (length ~64mm = 100chunks) +#define FSENSOR_OQ_MAX_EM 2 //!< maximum error counter value while loading +#define FSENSOR_OQ_MIN_YD 2 //!< minimum yd per chunk (applied to avg value) +#define FSENSOR_OQ_MAX_YD 200 //!< maximum yd per chunk (applied to avg value) +#define FSENSOR_OQ_MAX_PD 4 //!< maximum positive deviation (= yd_max/yd_avg) +#define FSENSOR_OQ_MAX_ND 5 //!< maximum negative deviation (= yd_avg/yd_min) +#define FSENSOR_OQ_MAX_SH 13 //!< maximum shutter value +//! @} const char ERRMSG_PAT9125_NOT_RESP[] PROGMEM = "PAT9125 not responding (%d)!\n"; -#define FSENSOR_INT_PIN 63 //filament sensor interrupt pin PK1 -#define FSENSOR_INT_PIN_MSK 0x02 //filament sensor interrupt pin mask (bit1) +#define FSENSOR_INT_PIN 63 //!< filament sensor interrupt pin PK1 +#define FSENSOR_INT_PIN_MSK 0x02 //!< filament sensor interrupt pin mask (bit1) void fsensor_stop_and_save_print(void) { @@ -44,32 +49,32 @@ void fsensor_restore_print_and_continue(void) uint8_t fsensor_int_pin_old = 0; int16_t fsensor_chunk_len = 0; -//enabled = initialized and sampled every chunk event +//! enabled = initialized and sampled every chunk event bool fsensor_enabled = true; -//runout watching is done in fsensor_update (called from main loop) +//! runout watching is done in fsensor_update (called from main loop) bool fsensor_watch_runout = true; -//not responding - is set if any communication error occured durring initialization or readout +//! not responding - is set if any communication error occurred during initialization or readout bool fsensor_not_responding = false; -//printing saved +//! printing saved bool fsensor_printing_saved = false; -//number of errors, updated in ISR +//! number of errors, updated in ISR uint8_t fsensor_err_cnt = 0; -//variable for accumolating step count (updated callbacks from stepper and ISR) +//! variable for accumulating step count (updated callbacks from stepper and ISR) int16_t fsensor_st_cnt = 0; -//last dy value from pat9125 sensor (used in ISR) +//! last dy value from pat9125 sensor (used in ISR) int16_t fsensor_dy_old = 0; -//log flag: 0=log disabled, 1=log enabled +//! log flag: 0=log disabled, 1=log enabled uint8_t fsensor_log = 1; -//////////////////////////////////////////////////////////////////////////////// -//filament autoload variables -//autoload feature enabled +//! @name filament autoload variables +//! @{ + +//! autoload feature enabled bool fsensor_autoload_enabled = true; - -//autoload watching enable/disable flag +//! autoload watching enable/disable flag bool fsensor_watch_autoload = false; // uint16_t fsensor_autoload_y; @@ -79,31 +84,33 @@ uint8_t fsensor_autoload_c; uint32_t fsensor_autoload_last_millis; // uint8_t fsensor_autoload_sum; +//! @} -//////////////////////////////////////////////////////////////////////////////// -//filament optical quality meassurement variables -//meassurement enable/disable flag +//! @name filament optical quality measurement variables +//! @{ + +//! Measurement enable/disable flag bool fsensor_oq_meassure = false; -//skip-chunk counter, for accurate meassurement is necesary to skip first chunk... +//! skip-chunk counter, for accurate measurement is necessary to skip first chunk... uint8_t fsensor_oq_skipchunk; -//number of samples from start of meassurement +//! number of samples from start of measurement uint8_t fsensor_oq_samples; -//sum of steps in positive direction movements +//! sum of steps in positive direction movements uint16_t fsensor_oq_st_sum; -//sum of deltas in positive direction movements +//! sum of deltas in positive direction movements uint16_t fsensor_oq_yd_sum; -//sum of errors durring meassurement +//! sum of errors during measurement uint16_t fsensor_oq_er_sum; -//max error counter value durring meassurement +//! max error counter value during measurement uint8_t fsensor_oq_er_max; -//minimum delta value +//! minimum delta value int16_t fsensor_oq_yd_min; -//maximum delta value +//! maximum delta value int16_t fsensor_oq_yd_max; -//sum of shutter value +//! sum of shutter value uint16_t fsensor_oq_sh_sum; - +//! @} void fsensor_init(void) { @@ -427,7 +434,7 @@ void fsensor_st_block_chunk(block_t* bl, int cnt) } } -//! update (perform M600 on filament runout) +//! @brief filament sensor update (perform M600 on filament runout) //! //! Works only if filament sensor is enabled. //! When the filament sensor error count is larger then FSENSOR_ERR_MAX, pauses print, tries to move filament back and forth. diff --git a/Firmware/fsensor.h b/Firmware/fsensor.h index 0b262a51..fd41c8f1 100644 --- a/Firmware/fsensor.h +++ b/Firmware/fsensor.h @@ -1,27 +1,32 @@ +//! @file #ifndef FSENSOR_H #define FSENSOR_H #include -//minimum meassured chunk length in steps +//! minimum meassured chunk length in steps extern int16_t fsensor_chunk_len; -//enable/disable flag +// enable/disable flag extern bool fsensor_enabled; -//not responding flag +// not responding flag extern bool fsensor_not_responding; -//save restore printing +//! @name save restore printing +//! @{ extern void fsensor_stop_and_save_print(void); extern void fsensor_restore_print_and_continue(void); +//! @} -//initialize +//! initialize extern void fsensor_init(void); -//enable/disable +//! @name enable/disable +//! @{ extern bool fsensor_enable(void); extern void fsensor_disable(void); +//! @} //autoload feature enabled extern bool fsensor_autoload_enabled; @@ -29,23 +34,29 @@ extern void fsensor_autoload_set(bool State); extern void fsensor_update(void); -//setup pin-change interrupt +//! setup pin-change interrupt extern void fsensor_setup_interrupt(void); -//autoload support +//! @name autoload support +//! @{ extern void fsensor_autoload_check_start(void); extern void fsensor_autoload_check_stop(void); extern bool fsensor_check_autoload(void); +//! @} -//optical quality meassurement support +//! @name optical quality measurement support +//! @{ extern void fsensor_oq_meassure_start(uint8_t skip); extern void fsensor_oq_meassure_stop(void); extern bool fsensor_oq_result(void); +//! @} + -//callbacks from stepper #include "planner.h" +//! @name callbacks from stepper +//! @{ extern void fsensor_st_block_begin(block_t* bl); extern void fsensor_st_block_chunk(block_t* bl, int cnt); - +//! @} #endif //FSENSOR_H