From 9ff1f6c3ee827d5af07af19109e7f44662c32aed Mon Sep 17 00:00:00 2001 From: leptun Date: Tue, 30 Jul 2019 16:05:40 +0300 Subject: [PATCH 001/158] Re-enable Tone --- Firmware/system_timer.h | 8 ++++---- Firmware/timer02.c | 10 ---------- Firmware/timer02.h | 7 ------- 3 files changed, 4 insertions(+), 21 deletions(-) diff --git a/Firmware/system_timer.h b/Firmware/system_timer.h index ca8f2f9a..626e8234 100644 --- a/Firmware/system_timer.h +++ b/Firmware/system_timer.h @@ -11,8 +11,8 @@ #define _millis millis2 #define _micros micros2 #define _delay delay2 -#define _tone tone2 -#define _noTone noTone2 +#define _tone tone +#define _noTone noTone #define timer02_set_pwm0(pwm0) @@ -20,8 +20,8 @@ #define _millis millis #define _micros micros #define _delay delay -#define _tone(x, y) /*tone*/ -#define _noTone(x) /*noTone*/ +#define _tone tone +#define _noTone noTone #define timer02_set_pwm0(pwm0) #endif //SYSTEM_TIMER_2 diff --git a/Firmware/timer02.c b/Firmware/timer02.c index 6b6cbe2c..1f898940 100644 --- a/Firmware/timer02.c +++ b/Firmware/timer02.c @@ -136,14 +136,4 @@ void delay2(unsigned long ms) } } -void tone2(__attribute__((unused)) uint8_t _pin, __attribute__((unused)) unsigned int frequency/*, unsigned long duration*/) -{ - PIN_SET(BEEPER); -} - -void noTone2(__attribute__((unused)) uint8_t _pin) -{ - PIN_CLR(BEEPER); -} - #endif //SYSTEM_TIMER_2 diff --git a/Firmware/timer02.h b/Firmware/timer02.h index 48a4842f..2eef98f6 100644 --- a/Firmware/timer02.h +++ b/Firmware/timer02.h @@ -23,13 +23,6 @@ extern unsigned long micros2(void); ///! Reimplemented original delay() using timer2 extern void delay2(unsigned long ms); -///! Reimplemented original tone() using timer2 -///! Does not perform any PWM tone generation, it just sets the beeper pin to 1 -extern void tone2(uint8_t _pin, unsigned int frequency/*, unsigned long duration*/); - -///! Turn off beeping - set beeper pin to 0 -extern void noTone2(uint8_t _pin); - #if defined(__cplusplus) } #endif //defined(__cplusplus) From 570b5989f4972b399e39ee2d74330928292e4cce Mon Sep 17 00:00:00 2001 From: leptun Date: Sun, 6 Oct 2019 10:50:11 +0300 Subject: [PATCH 002/158] Disable bed PWM while probing bed. --- Firmware/heatbed_pwm.cpp | 6 ++++++ Firmware/mesh_bed_calibration.cpp | 4 ++++ 2 files changed, 10 insertions(+) diff --git a/Firmware/heatbed_pwm.cpp b/Firmware/heatbed_pwm.cpp index a3e5444c..6f5a9316 100755 --- a/Firmware/heatbed_pwm.cpp +++ b/Firmware/heatbed_pwm.cpp @@ -61,6 +61,8 @@ enum class States : uint8_t { ///! Inner states of the finite automaton static States state = States::ZERO_START; +bool bedPWMDisabled = 0; + ///! Fast PWM counter is used in the RISE and FALL states (62.5kHz) static uint8_t slowCounter = 0; ///! Slow PWM counter is used in the ZERO and ONE states (62.5kHz/8 or 64) @@ -93,6 +95,7 @@ ISR(TIMER0_OVF_vect) // timer compare interrupt service routine { switch(state){ case States::ZERO_START: + if (bedPWMDisabled) break; pwm = soft_pwm_bed << 1;// expecting soft_pwm_bed to be 7bit! if( pwm != 0 ){ state = States::ZERO; // do nothing, let it tick once again after the 30Hz period @@ -144,6 +147,9 @@ ISR(TIMER0_OVF_vect) // timer compare interrupt service routine // if slowInc==2, soft_pwm == 251 will be the first to do short drops to zero. 252 will keep full heating return; // want full duty for the next ONE cycle again - so keep on heating and just wait for the next timer ovf } + if (bedPWMDisabled){ + return; + } // otherwise moving towards FALL // @@TODO it looks like ONE_TO_FALL isn't necessary, there are no artefacts at all state = States::ONE;//_TO_FALL; diff --git a/Firmware/mesh_bed_calibration.cpp b/Firmware/mesh_bed_calibration.cpp index 6466edc4..36fbfda4 100644 --- a/Firmware/mesh_bed_calibration.cpp +++ b/Firmware/mesh_bed_calibration.cpp @@ -23,6 +23,7 @@ float world2machine_shift[2]; #define WEIGHT_FIRST_ROW_Y_HIGH (0.3f) #define WEIGHT_FIRST_ROW_Y_LOW (0.0f) +extern bool bedPWMDisabled; // Scaling of the real machine axes against the programmed dimensions in the firmware. @@ -946,6 +947,7 @@ inline bool find_bed_induction_sensor_point_z(float minimum_z, uint8_t n_iter, i ) { bool high_deviation_occured = false; + bedPWMDisabled = 1; #ifdef TMC2130 FORCE_HIGH_POWER_START; #endif @@ -1044,6 +1046,7 @@ inline bool find_bed_induction_sensor_point_z(float minimum_z, uint8_t n_iter, i #ifdef TMC2130 FORCE_HIGH_POWER_END; #endif + bedPWMDisabled = 0; return true; error: @@ -1053,6 +1056,7 @@ error: #ifdef TMC2130 FORCE_HIGH_POWER_END; #endif + bedPWMDisabled = 0; return false; } From 7650e2b60cf6404924af8ae026bd92d10a75486a Mon Sep 17 00:00:00 2001 From: leptun Date: Sun, 6 Oct 2019 12:43:03 +0300 Subject: [PATCH 003/158] Handle disable_heater() --- Firmware/mesh_bed_calibration.cpp | 2 +- Firmware/temperature.cpp | 1 + Firmware/temperature.h | 2 ++ 3 files changed, 4 insertions(+), 1 deletion(-) diff --git a/Firmware/mesh_bed_calibration.cpp b/Firmware/mesh_bed_calibration.cpp index 36fbfda4..88cbc671 100644 --- a/Firmware/mesh_bed_calibration.cpp +++ b/Firmware/mesh_bed_calibration.cpp @@ -6,6 +6,7 @@ #include "mesh_bed_leveling.h" #include "stepper.h" #include "ultralcd.h" +#include "temperature.h" #ifdef TMC2130 #include "tmc2130.h" @@ -23,7 +24,6 @@ float world2machine_shift[2]; #define WEIGHT_FIRST_ROW_Y_HIGH (0.3f) #define WEIGHT_FIRST_ROW_Y_LOW (0.0f) -extern bool bedPWMDisabled; // Scaling of the real machine axes against the programmed dimensions in the firmware. diff --git a/Firmware/temperature.cpp b/Firmware/temperature.cpp index df8a39e0..15f2d3a3 100755 --- a/Firmware/temperature.cpp +++ b/Firmware/temperature.cpp @@ -1394,6 +1394,7 @@ void disable_heater() target_temperature_bed=0; soft_pwm_bed=0; timer02_set_pwm0(soft_pwm_bed << 1); + bedPWMDisabled = 0; #if defined(HEATER_BED_PIN) && HEATER_BED_PIN > -1 //WRITE(HEATER_BED_PIN,LOW); #endif diff --git a/Firmware/temperature.h b/Firmware/temperature.h index 7c40eae6..cbebb3f2 100755 --- a/Firmware/temperature.h +++ b/Firmware/temperature.h @@ -79,6 +79,8 @@ extern int current_voltage_raw_bed; extern unsigned char soft_pwm_bed; #endif +extern bool bedPWMDisabled; + #ifdef PIDTEMP extern int pid_cycle, pid_number_of_cycles; extern float Kc,_Kp,_Ki,_Kd; From dde61bb444cebe490636baaa5a695475d46109a3 Mon Sep 17 00:00:00 2001 From: leptun Date: Sun, 6 Oct 2019 12:44:45 +0300 Subject: [PATCH 004/158] Automaton changes. Keep heater ON during probing only if pwm is high --- Firmware/heatbed_pwm.cpp | 16 +++++++++------- 1 file changed, 9 insertions(+), 7 deletions(-) diff --git a/Firmware/heatbed_pwm.cpp b/Firmware/heatbed_pwm.cpp index 6f5a9316..1e467c4e 100755 --- a/Firmware/heatbed_pwm.cpp +++ b/Firmware/heatbed_pwm.cpp @@ -140,14 +140,16 @@ ISR(TIMER0_OVF_vect) // timer compare interrupt service routine case States::ONE: // state ONE - we'll either stay in ONE or change to FALL OCR0B = 255; slowCounter += slowInc; // this does software timer_clk/256 or less - if( slowCounter < pwm ){ - return; + if (!bedPWMDisabled){ //disable heating as soon as possible + if( slowCounter < pwm ){ + return; + } + if( (soft_pwm_bed << 1) >= (255 - slowInc - 1) ){ //@@TODO simplify & explain + // if slowInc==2, soft_pwm == 251 will be the first to do short drops to zero. 252 will keep full heating + return; // want full duty for the next ONE cycle again - so keep on heating and just wait for the next timer ovf + } } - if( (soft_pwm_bed << 1) >= (255 - slowInc - 1) ){ //@@TODO simplify & explain - // if slowInc==2, soft_pwm == 251 will be the first to do short drops to zero. 252 will keep full heating - return; // want full duty for the next ONE cycle again - so keep on heating and just wait for the next timer ovf - } - if (bedPWMDisabled){ + else if (pwm > 200){ //if duty cycle is high and BED PWM is disabled keep heater on. Prevents overcooling return; } // otherwise moving towards FALL From 350e27810af6ab36ffb8dfdea7b0bb9ae12e8870 Mon Sep 17 00:00:00 2001 From: leptun Date: Fri, 11 Oct 2019 21:00:51 +0300 Subject: [PATCH 005/158] fix selftest Z crash. Use stallGuard when testing Z --- Firmware/Marlin.h | 4 ++-- Firmware/Marlin_main.cpp | 17 +++++++---------- Firmware/planner.h | 3 +++ Firmware/tmc2130.cpp | 2 +- Firmware/ultralcd.cpp | 27 ++++++++++++++++----------- 5 files changed, 29 insertions(+), 24 deletions(-) diff --git a/Firmware/Marlin.h b/Firmware/Marlin.h index c1a7b562..aa862907 100755 --- a/Firmware/Marlin.h +++ b/Firmware/Marlin.h @@ -309,9 +309,9 @@ extern int fanSpeed; extern int8_t lcd_change_fil_state; #ifdef TMC2130 -void homeaxis(int axis, uint8_t cnt = 1, uint8_t* pstep = 0); +bool homeaxis(int axis, bool doError = 1, uint8_t cnt = 1, uint8_t* pstep = 0); #else -void homeaxis(int axis, uint8_t cnt = 1); +bool homeaxis(int axis, bool doError = 1, uint8_t cnt = 1); #endif //TMC2130 diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index 45dd118c..0f58aad0 100755 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -1898,10 +1898,6 @@ static void axis_is_at_home(int axis) { max_pos[axis] = base_max_pos(axis) + cs.add_homing[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)); } - //! @return original feedmultiply static int setup_for_endstop_move(bool enable_endstops_now = true) { saved_feedrate = feedrate; @@ -2144,9 +2140,9 @@ bool calibrate_z_auto() #endif //TMC2130 #ifdef TMC2130 -void homeaxis(int axis, uint8_t cnt, uint8_t* pstep) +bool homeaxis(int axis, bool doError, uint8_t cnt, uint8_t* pstep) #else -void homeaxis(int axis, uint8_t cnt) +bool homeaxis(int axis, bool doError, uint8_t cnt) #endif //TMC2130 { bool endstops_enabled = enable_endstops(true); //RP: endstops should be allways enabled durring homing @@ -2261,8 +2257,8 @@ void homeaxis(int axis, uint8_t cnt) #ifdef TMC2130 if (READ(Z_TMC2130_DIAG) != 0) { //Z crash FORCE_HIGH_POWER_END; - kill(_T(MSG_BED_LEVELING_FAILED_POINT_LOW)); - return; + if (doError) kill(_T(MSG_BED_LEVELING_FAILED_POINT_LOW)); + return 0; } #endif //TMC2130 current_position[axis] = 0; @@ -2277,8 +2273,8 @@ void homeaxis(int axis, uint8_t cnt) #ifdef TMC2130 if (READ(Z_TMC2130_DIAG) != 0) { //Z crash FORCE_HIGH_POWER_END; - kill(_T(MSG_BED_LEVELING_FAILED_POINT_LOW)); - return; + if (doError) kill(_T(MSG_BED_LEVELING_FAILED_POINT_LOW)); + return 0; } #endif //TMC2130 axis_is_at_home(axis); @@ -2291,6 +2287,7 @@ void homeaxis(int axis, uint8_t cnt) #endif } enable_endstops(endstops_enabled); + return 1; } /**/ diff --git a/Firmware/planner.h b/Firmware/planner.h index 7904c45a..79126fc2 100644 --- a/Firmware/planner.h +++ b/Firmware/planner.h @@ -161,6 +161,9 @@ void plan_set_position(float x, float y, float z, const float &e); void plan_set_z_position(const float &z); void plan_set_e_position(const float &e); +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)); } + extern bool e_active(); void check_axes_activity(); diff --git a/Firmware/tmc2130.cpp b/Firmware/tmc2130.cpp index 42359ba8..3a1f523c 100755 --- a/Firmware/tmc2130.cpp +++ b/Firmware/tmc2130.cpp @@ -994,7 +994,7 @@ bool tmc2130_home_calibrate(uint8_t axis) uint8_t step[16]; uint8_t cnt[16]; uint8_t val[16]; - homeaxis(axis, 16, step); + homeaxis(axis, 1, 16, step); bubblesort_uint8(step, 16, 0); printf_P(PSTR("sorted samples:\n")); for (uint8_t i = 0; i < 16; i++) diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index f4952802..a1868751 100755 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -7468,21 +7468,27 @@ bool lcd_selftest() #ifdef TMC2130 tmc2130_home_exit(); enable_endstops(false); - current_position[X_AXIS] = current_position[X_AXIS] + 14; - current_position[Y_AXIS] = current_position[Y_AXIS] + 12; #endif //homeaxis(X_AXIS); //homeaxis(Y_AXIS); + current_position[X_AXIS] += pgm_read_float(bed_ref_points_4); + current_position[Y_AXIS] += pgm_read_float(bed_ref_points_4+1); +#ifdef TMC2130 + //current_position[X_AXIS] += 0; + current_position[Y_AXIS] += 4; +#endif //TMC2130 current_position[Z_AXIS] = current_position[Z_AXIS] + 10; plan_buffer_line_curposXYZE(manual_feedrate[0] / 60, active_extruder); st_synchronize(); + set_destination_to_current(); _progress = lcd_selftest_screen(TestScreen::AxisZ, _progress, 3, true, 1500); - _result = lcd_selfcheck_axis(2, Z_MAX_POS); - if (eeprom_read_byte((uint8_t*)EEPROM_WIZARD_ACTIVE) != 1) { - enquecommand_P(PSTR("G28 W")); - enquecommand_P(PSTR("G1 Z15 F1000")); - } + _result = homeaxis(Z_AXIS, 0); + + //raise Z to not damage the bed during and hotend testing + current_position[Z_AXIS] += 20; + plan_buffer_line_curposXYZE(manual_feedrate[0] / 60, active_extruder); + st_synchronize(); } #ifdef TMC2130 @@ -7793,7 +7799,9 @@ static bool lcd_selfcheck_axis(int _axis, int _travel) { lcd_selftest_error(TestError::Motor, _error_1, _error_2); } - } + } + current_position[_axis] = 0; //simulate axis home to avoid negative numbers for axis position, especially Z. + plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]); return _stepresult; } @@ -7843,9 +7851,6 @@ static bool lcd_selfcheck_pulleys(int axis) ((READ(Y_MIN_PIN) ^ Y_MIN_ENDSTOP_INVERTING) == 1)) { endstop_triggered = true; if (current_position_init - 1 <= current_position[axis] && current_position_init + 1 >= current_position[axis]) { - current_position[axis] += (axis == X_AXIS) ? 13 : 9; - plan_buffer_line_curposXYZE(manual_feedrate[0] / 60, active_extruder); - st_synchronize(); return(true); } else { From 4703853a3d3f450e62922299c5b2f8f15035868c Mon Sep 17 00:00:00 2001 From: leptun Date: Sat, 12 Oct 2019 13:19:17 +0300 Subject: [PATCH 006/158] Small fixes --- Firmware/Marlin_main.cpp | 4 ++++ Firmware/ultralcd.cpp | 7 +++++-- 2 files changed, 9 insertions(+), 2 deletions(-) diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index 0f58aad0..51e57818 100755 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -2258,6 +2258,8 @@ bool homeaxis(int axis, bool doError, uint8_t cnt) if (READ(Z_TMC2130_DIAG) != 0) { //Z crash FORCE_HIGH_POWER_END; if (doError) kill(_T(MSG_BED_LEVELING_FAILED_POINT_LOW)); + current_position[axis] = -5; //assume that nozzle crashed into bed + plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]); return 0; } #endif //TMC2130 @@ -2274,6 +2276,8 @@ bool homeaxis(int axis, bool doError, uint8_t cnt) if (READ(Z_TMC2130_DIAG) != 0) { //Z crash FORCE_HIGH_POWER_END; if (doError) kill(_T(MSG_BED_LEVELING_FAILED_POINT_LOW)); + current_position[axis] = -5; //assume that nozzle crashed into bed + plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]); return 0; } #endif //TMC2130 diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index a1868751..38076f53 100755 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -7483,7 +7483,11 @@ bool lcd_selftest() st_synchronize(); set_destination_to_current(); _progress = lcd_selftest_screen(TestScreen::AxisZ, _progress, 3, true, 1500); +#ifdef TMC2130 _result = homeaxis(Z_AXIS, 0); +#else + _result = lcd_selfcheck_axis(Z_AXIS, Z_MAX_POS); +#endif //TMC2130 //raise Z to not damage the bed during and hotend testing current_position[Z_AXIS] += 20; @@ -7700,7 +7704,7 @@ static bool lcd_selfcheck_axis_sg(unsigned char axis) { } #endif //TMC2130 -//#ifndef TMC2130 +#ifndef TMC2130 static bool lcd_selfcheck_axis(int _axis, int _travel) { @@ -7806,7 +7810,6 @@ static bool lcd_selfcheck_axis(int _axis, int _travel) return _stepresult; } -#ifndef TMC2130 static bool lcd_selfcheck_pulleys(int axis) { float tmp_motor_loud[3] = DEFAULT_PWM_MOTOR_CURRENT_LOUD; From 28e812d91fe2b4633c9427abdf554e5a9449dd17 Mon Sep 17 00:00:00 2001 From: leptun Date: Wed, 2 Oct 2019 17:34:09 +0300 Subject: [PATCH 007/158] Mesh bed leveling testing --- Firmware/Marlin_main.cpp | 10 +++------- Firmware/mesh_bed_calibration.cpp | 8 ++++---- 2 files changed, 7 insertions(+), 11 deletions(-) diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index 45dd118c..f65ec4b6 100755 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -4767,11 +4767,7 @@ if(eSoundMode!=e_SOUND_MODE_SILENT) z_offset_u = eeprom_read_word((uint16_t*)(EEPROM_BED_CALIBRATION_Z_JITTER + 2 * (ix + iy * 3 - 1))); } z0 = mbl.z_values[0][0] + *reinterpret_cast(&z_offset_u) * 0.01; - #ifdef SUPPORT_VERBOSITY - if (verbosity_level >= 1) { - printf_P(PSTR("Bed leveling, point: %d, calibration Z stored in eeprom: %d, calibration z: %f \n"), mesh_point, z_offset_u, z0); - } - #endif // SUPPORT_VERBOSITY + // printf_P(PSTR("Bed leveling, point: %d, calibration Z stored in eeprom: %d, calibration z: %f \n"), mesh_point, z_offset_u, z0); } // Move Z up to MESH_HOME_Z_SEARCH. @@ -4798,7 +4794,7 @@ if(eSoundMode!=e_SOUND_MODE_SILENT) world2machine_clamp(current_position[X_AXIS], current_position[Y_AXIS]); #endif // SUPPORT_VERBOSITY - //printf_P(PSTR("after clamping: [%f;%f]\n"), current_position[X_AXIS], current_position[Y_AXIS]); + printf_P(PSTR("after clamping: [%f;%f]\n"), current_position[X_AXIS], current_position[Y_AXIS]); plan_buffer_line_curposXYZE(XY_AXIS_FEEDRATE, active_extruder); st_synchronize(); @@ -4809,7 +4805,7 @@ if(eSoundMode!=e_SOUND_MODE_SILENT) break; } if (init_z_bckp - current_position[Z_AXIS] < 0.1f) { //broken cable or initial Z coordinate too low. Go to MESH_HOME_Z_SEARCH and repeat last step (z-probe) again to distinguish between these two cases. - //printf_P(PSTR("Another attempt! Current Z position: %f\n"), current_position[Z_AXIS]); + printf_P(PSTR("Another attempt! Current Z position: %f\n"), current_position[Z_AXIS]); current_position[Z_AXIS] = MESH_HOME_Z_SEARCH; plan_buffer_line_curposXYZE(Z_LIFT_FEEDRATE, active_extruder); st_synchronize(); diff --git a/Firmware/mesh_bed_calibration.cpp b/Firmware/mesh_bed_calibration.cpp index 88cbc671..fed100e6 100644 --- a/Firmware/mesh_bed_calibration.cpp +++ b/Firmware/mesh_bed_calibration.cpp @@ -991,7 +991,7 @@ inline bool find_bed_induction_sensor_point_z(float minimum_z, uint8_t n_iter, i update_current_position_z(); //printf_P(PSTR("Zs: %f, Z: %f, delta Z: %f"), z_bckp, current_position[Z_AXIS], (z_bckp - current_position[Z_AXIS])); if (abs(current_position[Z_AXIS] - z_bckp) < 0.025) { - //printf_P(PSTR("PINDA triggered immediately, move Z higher and repeat measurement\n")); + printf_P(PSTR("PINDA triggered immediately, move Z higher and repeat measurement\n")); current_position[Z_AXIS] += 0.5; go_to_current(homing_feedrate[Z_AXIS]/60); current_position[Z_AXIS] = minimum_z; @@ -1019,10 +1019,10 @@ inline bool find_bed_induction_sensor_point_z(float minimum_z, uint8_t n_iter, i float dz = i?abs(current_position[Z_AXIS] - (z / i)):0; z += current_position[Z_AXIS]; //printf_P(PSTR("Z[%d] = %d, dz=%d\n"), i, (int)(current_position[Z_AXIS] * 1000), (int)(dz * 1000)); - //printf_P(PSTR("Z- measurement deviation from avg value %f um\n"), dz); + printf_P(PSTR("Z- measurement deviation from avg value %f um\n"), dz); if (dz > 0.05) { //deviation > 50um if (high_deviation_occured == false) { //first occurence may be caused in some cases by mechanic resonance probably especially if printer is placed on unstable surface - //printf_P(PSTR("high dev. first occurence\n")); + printf_P(PSTR("high dev. first occurence\n")); delay_keep_alive(500); //damping //start measurement from the begining, but this time with higher movements in Z axis which should help to reduce mechanical resonance high_deviation_occured = true; @@ -1033,7 +1033,7 @@ inline bool find_bed_induction_sensor_point_z(float minimum_z, uint8_t n_iter, i goto error; } } - //printf_P(PSTR("PINDA triggered at %f\n"), current_position[Z_AXIS]); + printf_P(PSTR("PINDA triggered at %f\n"), current_position[Z_AXIS]); } current_position[Z_AXIS] = z; if (n_iter > 1) From 3ce631052dbda683c3666b268bceadc688aea63c Mon Sep 17 00:00:00 2001 From: unknown <3d.gussner@gmail.com> Date: Fri, 29 Nov 2019 22:35:07 +0100 Subject: [PATCH 008/158] Set PF-build.sh to use v1.0.2 Arduino_Boards --- PF-build.sh | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/PF-build.sh b/PF-build.sh index 7f538ea0..984df8a5 100755 --- a/PF-build.sh +++ b/PF-build.sh @@ -213,12 +213,12 @@ fi #### Set build environment ARDUINO_ENV="1.8.5" BUILD_ENV="1.0.6" -BOARD="rambo" +BOARD="prusa_einsy_rambo" BOARD_PACKAGE_NAME="PrusaResearchRambo" -BOARD_VERSION="1.0.1" +BOARD_VERSION="1.0.2" BOARD_URL="https://raw.githubusercontent.com/prusa3d/Arduino_Boards/master/IDE_Board_Manager/package_prusa3d_index.json" -BOARD_FILENAME="prusa3drambo" -BOARD_FILE_URL="https://raw.githubusercontent.com/prusa3d/Arduino_Boards/master/IDE_Board_Manager/prusa3drambo-1.0.1.tar.bz2" +BOARD_FILENAME="prusa3dboards" +BOARD_FILE_URL="https://raw.githubusercontent.com/prusa3d/Arduino_Boards/master/IDE_Board_Manager/prusa3dboards-1.0.2.tar.bz2" PF_BUILD_FILE_URL="https://github.com/3d-gussner/PF-build-env/releases/download/$BUILD_ENV/PF-build-env-$BUILD_ENV.zip" LIB="PrusaLibrary" SCRIPT_PATH="$( cd "$(dirname "$0")" ; pwd -P )" From 28b66bc909744cbbe1a11328cfe5c262a726aa4a Mon Sep 17 00:00:00 2001 From: 3d-gussner <3d.gussner@gmail.com> Date: Sun, 15 Dec 2019 17:27:15 +0100 Subject: [PATCH 009/158] Update to prepare for new prusa3d/PF-build-env Fixed a bug in Arduino user preferences --- PF-build.sh | 15 +++++++++------ 1 file changed, 9 insertions(+), 6 deletions(-) diff --git a/PF-build.sh b/PF-build.sh index 984df8a5..9cbedd54 100755 --- a/PF-build.sh +++ b/PF-build.sh @@ -56,7 +56,7 @@ # Some may argue that this is only used by a script, BUT as soon someone accidentally or on purpose starts Arduino IDE # it will use the default Arduino IDE folders and so can corrupt the build environment. # -# Version: 1.0.6-Build_10 +# Version: 1.0.6-Build_12 # Change log: # 12 Jan 2019, 3d-gussner, Fixed "compiler.c.elf.flags=-w -Os -Wl,-u,vfprintf -lprintf_flt -lm -Wl,--gc-sections" in 'platform.txt' # 16 Jan 2019, 3d-gussner, Build_2, Added development check to modify 'Configuration.h' to prevent unwanted LCD messages that Firmware is unknown @@ -114,7 +114,9 @@ # 26 Jul 2019, 3d-gussner, Change JSON repository to prusa3d after PR https://github.com/prusa3d/Arduino_Boards/pull/1 was merged # 23 Sep 2019, 3d-gussner, Prepare PF-build.sh for comming Prusa3d/Arduino_Boards version 1.0.2 Pull Request # 17 Oct 2019, 3d-gussner, Changed folder and check file names to have seperated build enviroments depening on Arduino IDE version and -# board-versions. +# board-versions. +# 15 Dec 2019, 3d-gussner, Prepare for switch to Prusa3d/PF-build-env repository +# 15 Dec 2019, 3d-gussner, Fix Audrino user preferences for the chosen board. #### Start check if OSTYPE is supported OS_FOUND=$( command -v uname) @@ -219,7 +221,8 @@ BOARD_VERSION="1.0.2" BOARD_URL="https://raw.githubusercontent.com/prusa3d/Arduino_Boards/master/IDE_Board_Manager/package_prusa3d_index.json" BOARD_FILENAME="prusa3dboards" BOARD_FILE_URL="https://raw.githubusercontent.com/prusa3d/Arduino_Boards/master/IDE_Board_Manager/prusa3dboards-1.0.2.tar.bz2" -PF_BUILD_FILE_URL="https://github.com/3d-gussner/PF-build-env/releases/download/$BUILD_ENV/PF-build-env-$BUILD_ENV.zip" +PF_BUILD_FILE_URL="https://github.com/3d-gussner/PF-build-env-1/releases/download/$BUILD_ENV-WinLin/PF-build-env-WinLin-$BUILD_ENV.zip" +#PF_BUILD_FILE_URL="https://github.com/prusa3d/PF-build-env/releases/download/$BUILD_ENV-WinLin/PF-build-env-WinLin-$BUILD_ENV.zip" LIB="PrusaLibrary" SCRIPT_PATH="$( cd "$(dirname "$0")" ; pwd -P )" @@ -321,7 +324,7 @@ if [ ! -e ../PF-build-env-$BUILD_ENV/Preferences-$ARDUINO_ENV-$BOARD_VERSION-$TA echo "update.check" sed -i 's/update.check = true/update.check = false/g' ../PF-build-env-$BUILD_ENV/$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor/lib/preferences.txt echo "board" - sed -i 's/board = uno/board = $BOARD/g' ../PF-build-env-$BUILD_ENV/$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor/lib/preferences.txt + sed -i "s/board = uno/board = $BOARD/g" ../PF-build-env-$BUILD_ENV/$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor/lib/preferences.txt echo "editor.linenumbers" sed -i 's/editor.linenumbers = false/editor.linenumbers = true/g' ../PF-build-env-$BUILD_ENV/$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor/lib/preferences.txt echo "boardsmanager.additional.urls" @@ -364,7 +367,7 @@ if [[ ! -d "../PF-build-env-$BUILD_ENV/$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$P fi # Download and extract Prusa Firmware specific library files -if [ ! -f "PF-build-env-$BUILD_ENV.zip" ]; then +if [ ! -f "PF-build-env-WinLin-$BUILD_ENV.zip" ]; then echo "$(tput setaf 6)Downloading Prusa Firmware build environment...$(tput setaf 2)" sleep 2 wget $PF_BUILD_FILE_URL || exit 11 @@ -373,7 +376,7 @@ fi if [ ! -e "../PF-build-env-$BUILD_ENV/PF-build-env-$BUILD_ENV-$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor.txt" ]; then echo "$(tput setaf 6)Unzipping Prusa Firmware build environment...$(tput setaf 2)" sleep 2 - unzip -o PF-build-env-$BUILD_ENV.zip -d ../PF-build-env-$BUILD_ENV/$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor || exit 12 + unzip -o PF-build-env-WinLin-$BUILD_ENV.zip -d ../PF-build-env-$BUILD_ENV/$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor || exit 12 echo "# PF-build-env-$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor-$BUILD_ENV" >> ../PF-build-env-$BUILD_ENV/PF-build-env-$BUILD_ENV-$ARDUINO_ENV-$BOARD_VERSION-$TARGET_OS-$Processor.txt echo "$(tput sgr0)" fi From a8e6020238c4c88a0d9a78e70ae22788af625bb9 Mon Sep 17 00:00:00 2001 From: Alex Voinea Date: Mon, 16 Dec 2019 15:21:55 +0200 Subject: [PATCH 010/158] Fix VERBOSITY --- 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 4970091e..a08b3aa3 100755 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -4840,7 +4840,7 @@ if(eSoundMode!=e_SOUND_MODE_SILENT) #ifdef SUPPORT_VERBOSITY if (verbosity_level >= 1) { - clamped = world2machine_clamp(current_position[X_AXIS], current_position[Y_AXIS]); + bool clamped = world2machine_clamp(current_position[X_AXIS], current_position[Y_AXIS]); SERIAL_PROTOCOL(mesh_point); clamped ? SERIAL_PROTOCOLPGM(": xy clamped.\n") : SERIAL_PROTOCOLPGM(": no xy clamping\n"); } From 46c06f7eee5c289fa5abda658c7e55c5e80f09a9 Mon Sep 17 00:00:00 2001 From: 3d-gussner <3d.gussner@gmail.com> Date: Tue, 17 Dec 2019 14:05:39 +0100 Subject: [PATCH 011/158] Updated it to use Arduino_Boards v1.0.3 and linked everything to prusa3d repositories --- PF-build.sh | 18 +++++++++++------- README.md | 2 +- 2 files changed, 12 insertions(+), 8 deletions(-) diff --git a/PF-build.sh b/PF-build.sh index 9cbedd54..8f1fa247 100755 --- a/PF-build.sh +++ b/PF-build.sh @@ -56,7 +56,7 @@ # Some may argue that this is only used by a script, BUT as soon someone accidentally or on purpose starts Arduino IDE # it will use the default Arduino IDE folders and so can corrupt the build environment. # -# Version: 1.0.6-Build_12 +# Version: 1.0.6-Build_13 # Change log: # 12 Jan 2019, 3d-gussner, Fixed "compiler.c.elf.flags=-w -Os -Wl,-u,vfprintf -lprintf_flt -lm -Wl,--gc-sections" in 'platform.txt' # 16 Jan 2019, 3d-gussner, Build_2, Added development check to modify 'Configuration.h' to prevent unwanted LCD messages that Firmware is unknown @@ -117,6 +117,7 @@ # board-versions. # 15 Dec 2019, 3d-gussner, Prepare for switch to Prusa3d/PF-build-env repository # 15 Dec 2019, 3d-gussner, Fix Audrino user preferences for the chosen board. +# 17 Dec 2019, 3d-gussner, Fix "timer0_fract = 0" warning by using Arduino_boards v1.0.3 #### Start check if OSTYPE is supported OS_FOUND=$( command -v uname) @@ -209,20 +210,22 @@ if ! type python > /dev/null; then fi fi -#### End prepare bash environment +#### End prepare bash / Linux environment #### Set build environment ARDUINO_ENV="1.8.5" BUILD_ENV="1.0.6" BOARD="prusa_einsy_rambo" -BOARD_PACKAGE_NAME="PrusaResearchRambo" -BOARD_VERSION="1.0.2" +BOARD_PACKAGE_NAME="PrusaResearch" +BOARD_VERSION="1.0.3" +#BOARD_URL="https://raw.githubusercontent.com/3d-gussner/Arduino_Boards/Prusa_Merge_v1.0.3/IDE_Board_Manager/package_prusa3d_index.json" BOARD_URL="https://raw.githubusercontent.com/prusa3d/Arduino_Boards/master/IDE_Board_Manager/package_prusa3d_index.json" BOARD_FILENAME="prusa3dboards" -BOARD_FILE_URL="https://raw.githubusercontent.com/prusa3d/Arduino_Boards/master/IDE_Board_Manager/prusa3dboards-1.0.2.tar.bz2" -PF_BUILD_FILE_URL="https://github.com/3d-gussner/PF-build-env-1/releases/download/$BUILD_ENV-WinLin/PF-build-env-WinLin-$BUILD_ENV.zip" -#PF_BUILD_FILE_URL="https://github.com/prusa3d/PF-build-env/releases/download/$BUILD_ENV-WinLin/PF-build-env-WinLin-$BUILD_ENV.zip" +#BOARD_FILE_URL="https://raw.githubusercontent.com/3d-gussner/Arduino_Boards/Prusa_Merge_v1.0.3/IDE_Board_Manager/prusa3dboards-1.0.3.tar.bz2" +BOARD_FILE_URL="https://raw.githubusercontent.com/prusa3d/Arduino_Boards/master/IDE_Board_Manager/prusa3dboards-1.0.3.tar.bz2" +#PF_BUILD_FILE_URL="https://github.com/3d-gussner/PF-build-env-1/releases/download/$BUILD_ENV-WinLin/PF-build-env-WinLin-$BUILD_ENV.zip" +PF_BUILD_FILE_URL="https://github.com/prusa3d/PF-build-env/releases/download/$BUILD_ENV-WinLin/PF-build-env-WinLin-$BUILD_ENV.zip" LIB="PrusaLibrary" SCRIPT_PATH="$( cd "$(dirname "$0")" ; pwd -P )" @@ -236,6 +239,7 @@ echo "Ardunio IDE :" $ARDUINO_ENV echo "Build env :" $BUILD_ENV echo "Board :" $BOARD echo "Package name:" $BOARD_PACKAGE_NAME +echo "Board v. :" $BOARD_VERSION echo "Specific Lib:" $LIB echo "" diff --git a/README.md b/README.md index 782ed6f7..6edbe012 100644 --- a/README.md +++ b/README.md @@ -46,7 +46,7 @@ _Note: Multi language build is not supported._ * Open Arduino and navigate to File -> Preferences -> Settings * To the text field `"Additional Boards Manager URLSs"` add `https://raw.githubusercontent.com/prusa3d/Arduino_Boards/master/IDE_Board_Manager/package_prusa3d_index.json` -* Open Board manager (`Tools->Board->Board manager`), and install `Prusa Research AVR MK3 RAMBo EINSy board` +* Open Board manager (`Tools->Board->Board manager`), and install `Prusa Research AVR Boards by Prusa Research` **c.** Modify compiler flags in `platform.txt` file From 301d64042bcb1a68744da60ccda02d549b37b578 Mon Sep 17 00:00:00 2001 From: Yuri D'Elia Date: Fri, 27 Dec 2019 19:29:02 +0100 Subject: [PATCH 012/158] Set fsensor_watch_runout earlier to prevent re-entry Do not set/clear fsensor_watch_runout within fsensor_oq_meassure_start which is used outside of fsensor_update where it could have a different starting value. Set it within fsensor_stop_and_save_print to immediately prevent re-entry. --- Firmware/fsensor.cpp | 11 ++++++----- 1 file changed, 6 insertions(+), 5 deletions(-) diff --git a/Firmware/fsensor.cpp b/Firmware/fsensor.cpp index 1c28d025..b9b1f068 100755 --- a/Firmware/fsensor.cpp +++ b/Firmware/fsensor.cpp @@ -124,14 +124,16 @@ unsigned long nIRsensorLastTime; void fsensor_stop_and_save_print(void) { printf_P(PSTR("fsensor_stop_and_save_print\n")); - stop_and_save_print_to_ram(0, 0); //XYZE - no change + stop_and_save_print_to_ram(0, 0); + fsensor_watch_runout = false; } void fsensor_restore_print_and_continue(void) { printf_P(PSTR("fsensor_restore_print_and_continue\n")); + fsensor_watch_runout = true; fsensor_err_cnt = 0; - restore_print_from_ram_and_continue(0); //XYZ = orig, E - no change + restore_print_from_ram_and_continue(0); } // fsensor_checkpoint_print cuts the current print job at the current position, @@ -379,7 +381,6 @@ void fsensor_oq_meassure_start(uint8_t skip) fsensor_oq_sh_sum = 0; pat9125_update(); pat9125_y = 0; - fsensor_watch_runout = false; fsensor_oq_meassure = true; } @@ -391,7 +392,6 @@ void fsensor_oq_meassure_stop(void) printf_P(_N(" st_sum=%u yd_sum=%u er_sum=%u er_max=%hhu\n"), fsensor_oq_st_sum, fsensor_oq_yd_sum, fsensor_oq_er_sum, fsensor_oq_er_max); printf_P(_N(" yd_min=%u yd_max=%u yd_avg=%u sh_avg=%u\n"), fsensor_oq_yd_min, fsensor_oq_yd_max, (uint16_t)((uint32_t)fsensor_oq_yd_sum * fsensor_chunk_len / fsensor_oq_st_sum), (uint16_t)(fsensor_oq_sh_sum / fsensor_oq_samples)); fsensor_oq_meassure = false; - fsensor_watch_runout = true; fsensor_err_cnt = 0; } @@ -578,12 +578,13 @@ void fsensor_update(void) #ifdef PAT9125 if (fsensor_enabled && fsensor_watch_runout && (fsensor_err_cnt > FSENSOR_ERR_MAX)) { + fsensor_stop_and_save_print(); + bool autoload_enabled_tmp = fsensor_autoload_enabled; fsensor_autoload_enabled = false; bool oq_meassure_enabled_tmp = fsensor_oq_meassure_enabled; fsensor_oq_meassure_enabled = true; - fsensor_stop_and_save_print(); fsensor_err_cnt = 0; fsensor_oq_meassure_start(0); From fe4c00fb8a8ff32fcafecb2a730e432a7f065607 Mon Sep 17 00:00:00 2001 From: Yuri D'Elia Date: Fri, 27 Dec 2019 19:35:08 +0100 Subject: [PATCH 013/158] Lift the extruder when checking for the filament This avoids leaving marks on the print --- Firmware/fsensor.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/Firmware/fsensor.cpp b/Firmware/fsensor.cpp index b9b1f068..02f7d572 100755 --- a/Firmware/fsensor.cpp +++ b/Firmware/fsensor.cpp @@ -585,6 +585,11 @@ void fsensor_update(void) bool oq_meassure_enabled_tmp = fsensor_oq_meassure_enabled; fsensor_oq_meassure_enabled = true; + // move the nozzle away while checking the filament + current_position[Z_AXIS] += 0.8; + if(current_position[Z_AXIS] > Z_MAX_POS) current_position[Z_AXIS] = Z_MAX_POS; + plan_buffer_line_curposXYZE(max_feedrate[Z_AXIS], active_extruder); + st_synchronize(); fsensor_err_cnt = 0; fsensor_oq_meassure_start(0); From 97170ed68dbfd5660f28f2f286d94bafee74d939 Mon Sep 17 00:00:00 2001 From: Yuri D'Elia Date: Fri, 27 Dec 2019 19:37:20 +0100 Subject: [PATCH 014/158] Do not call process_commands() within fsensor_update() Plan moves directly to reduce the required stack size. --- Firmware/fsensor.cpp | 19 +++++++------------ 1 file changed, 7 insertions(+), 12 deletions(-) diff --git a/Firmware/fsensor.cpp b/Firmware/fsensor.cpp index 02f7d572..f9875fa6 100755 --- a/Firmware/fsensor.cpp +++ b/Firmware/fsensor.cpp @@ -591,20 +591,15 @@ void fsensor_update(void) plan_buffer_line_curposXYZE(max_feedrate[Z_AXIS], active_extruder); st_synchronize(); + // check the filament in isolation fsensor_err_cnt = 0; fsensor_oq_meassure_start(0); - - enquecommand_front_P((PSTR("G1 E-3 F200"))); - process_commands(); - KEEPALIVE_STATE(IN_HANDLER); - cmdqueue_pop_front(); - st_synchronize(); - - enquecommand_front_P((PSTR("G1 E3 F200"))); - process_commands(); - KEEPALIVE_STATE(IN_HANDLER); - cmdqueue_pop_front(); - st_synchronize(); + float e_tmp = current_position[E_AXIS]; + current_position[E_AXIS] -= 3; + plan_buffer_line_curposXYZE(200/60, active_extruder); + current_position[E_AXIS] = e_tmp; + plan_buffer_line_curposXYZE(200/60, active_extruder); + st_synchronize(); uint8_t err_cnt = fsensor_err_cnt; fsensor_oq_meassure_stop(); From bd80ee88a0f0c8d5a354f7c81a8551d9ee297f5d Mon Sep 17 00:00:00 2001 From: Yuri D'Elia Date: Sat, 28 Dec 2019 18:50:42 +0100 Subject: [PATCH 015/158] Set the IN_HANDLER busy state while checking the filament --- Firmware/fsensor.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/Firmware/fsensor.cpp b/Firmware/fsensor.cpp index f9875fa6..0113317e 100755 --- a/Firmware/fsensor.cpp +++ b/Firmware/fsensor.cpp @@ -579,6 +579,7 @@ void fsensor_update(void) if (fsensor_enabled && fsensor_watch_runout && (fsensor_err_cnt > FSENSOR_ERR_MAX)) { fsensor_stop_and_save_print(); + KEEPALIVE_STATE(IN_HANDLER); bool autoload_enabled_tmp = fsensor_autoload_enabled; fsensor_autoload_enabled = false; From 186f8816000f0c8632fe3c8cfe0aac8c0b13d4b1 Mon Sep 17 00:00:00 2001 From: Yuri D'Elia Date: Sun, 29 Dec 2019 22:08:44 +0100 Subject: [PATCH 016/158] Avoid calling fsensor_update() one level earlier Move the common checks between filament sensors out of fsensor_update(). Disable the runout check if a saved state is already present (this check was missing in the PAT9125 variant) as this is currently not supported. Note that the CHECK_FSENSOR looks completely redundant besides e_active(). --- Firmware/Marlin_main.cpp | 3 ++- Firmware/fsensor.cpp | 4 ++-- 2 files changed, 4 insertions(+), 3 deletions(-) diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index 4970091e..fc395900 100755 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -8606,7 +8606,8 @@ if(0) #ifdef PAT9125 fsensor_autoload_check_stop(); #endif //PAT9125 - fsensor_update(); + if (fsensor_enabled && !saved_printing) + fsensor_update(); } } } diff --git a/Firmware/fsensor.cpp b/Firmware/fsensor.cpp index 0113317e..a7dbce97 100755 --- a/Firmware/fsensor.cpp +++ b/Firmware/fsensor.cpp @@ -576,7 +576,7 @@ void fsensor_enque_M600(){ void fsensor_update(void) { #ifdef PAT9125 - if (fsensor_enabled && fsensor_watch_runout && (fsensor_err_cnt > FSENSOR_ERR_MAX)) + if (fsensor_watch_runout && (fsensor_err_cnt > FSENSOR_ERR_MAX)) { fsensor_stop_and_save_print(); KEEPALIVE_STATE(IN_HANDLER); @@ -621,7 +621,7 @@ void fsensor_update(void) fsensor_enque_M600(); } #else //PAT9125 - if (CHECK_FSENSOR && fsensor_enabled && ir_sensor_detected) + if (CHECK_FSENSOR && ir_sensor_detected) { if(digitalRead(IR_SENSOR_PIN)) { // IR_SENSOR_PIN ~ H From e6ba9e633c9eaeea7eef5d9ba876c380503dd19a Mon Sep 17 00:00:00 2001 From: Alex Voinea Date: Tue, 21 Jan 2020 14:50:53 +0200 Subject: [PATCH 017/158] Adjusted hotend, bed and Ambient mintemp values --- Firmware/variants/1_75mm_MK3-EINSy10a-E3Dv6full.h | 8 ++++---- Firmware/variants/1_75mm_MK3S-EINSy10a-E3Dv6full.h | 8 ++++---- 2 files changed, 8 insertions(+), 8 deletions(-) diff --git a/Firmware/variants/1_75mm_MK3-EINSy10a-E3Dv6full.h b/Firmware/variants/1_75mm_MK3-EINSy10a-E3Dv6full.h index 400d098f..a2c0c3d8 100644 --- a/Firmware/variants/1_75mm_MK3-EINSy10a-E3Dv6full.h +++ b/Firmware/variants/1_75mm_MK3-EINSy10a-E3Dv6full.h @@ -151,8 +151,8 @@ // this value is litlebit higher that real limit, because ambient termistor is on the board and is temperated from it, // temperature inside the case is around 31C for ambient temperature 25C, when the printer is powered on long time and idle // the real limit is 15C (same as MINTEMP limit), this is because 15C is end of scale for both used thermistors (bed, heater) -#define MINTEMP_MINAMBIENT 25 -#define MINTEMP_MINAMBIENT_RAW 978 +#define MINTEMP_MINAMBIENT 10 +#define MINTEMP_MINAMBIENT_RAW 1002 #define DEBUG_DCODE3 @@ -282,14 +282,14 @@ *------------------------------------*/ // Mintemps -#define HEATER_0_MINTEMP 15 +#define HEATER_0_MINTEMP 10 #define HEATER_1_MINTEMP 5 #define HEATER_2_MINTEMP 5 #define HEATER_MINTEMP_DELAY 15000 // [ms] ! if changed, check maximal allowed value @ ShortTimer #if HEATER_MINTEMP_DELAY>USHRT_MAX #error "Check maximal allowed value @ ShortTimer (see HEATER_MINTEMP_DELAY definition)" #endif -#define BED_MINTEMP 15 +#define BED_MINTEMP 10 #define BED_MINTEMP_DELAY 50000 // [ms] ! if changed, check maximal allowed value @ ShortTimer #if BED_MINTEMP_DELAY>USHRT_MAX #error "Check maximal allowed value @ ShortTimer (see BED_MINTEMP_DELAY definition)" diff --git a/Firmware/variants/1_75mm_MK3S-EINSy10a-E3Dv6full.h b/Firmware/variants/1_75mm_MK3S-EINSy10a-E3Dv6full.h index 48ed9139..1c92bfbc 100644 --- a/Firmware/variants/1_75mm_MK3S-EINSy10a-E3Dv6full.h +++ b/Firmware/variants/1_75mm_MK3S-EINSy10a-E3Dv6full.h @@ -153,8 +153,8 @@ // this value is litlebit higher that real limit, because ambient termistor is on the board and is temperated from it, // temperature inside the case is around 31C for ambient temperature 25C, when the printer is powered on long time and idle // the real limit is 15C (same as MINTEMP limit), this is because 15C is end of scale for both used thermistors (bed, heater) -#define MINTEMP_MINAMBIENT 25 -#define MINTEMP_MINAMBIENT_RAW 978 +#define MINTEMP_MINAMBIENT 10 +#define MINTEMP_MINAMBIENT_RAW 1002 #define DEBUG_DCODE3 @@ -284,14 +284,14 @@ *------------------------------------*/ // Mintemps -#define HEATER_0_MINTEMP 15 +#define HEATER_0_MINTEMP 10 #define HEATER_1_MINTEMP 5 #define HEATER_2_MINTEMP 5 #define HEATER_MINTEMP_DELAY 15000 // [ms] ! if changed, check maximal allowed value @ ShortTimer #if HEATER_MINTEMP_DELAY>USHRT_MAX #error "Check maximal allowed value @ ShortTimer (see HEATER_MINTEMP_DELAY definition)" #endif -#define BED_MINTEMP 15 +#define BED_MINTEMP 10 #define BED_MINTEMP_DELAY 50000 // [ms] ! if changed, check maximal allowed value @ ShortTimer #if BED_MINTEMP_DELAY>USHRT_MAX #error "Check maximal allowed value @ ShortTimer (see BED_MINTEMP_DELAY definition)" From 67decb466d478c487dfa6192f8f8cafb787faf06 Mon Sep 17 00:00:00 2001 From: Yuri D'Elia Date: Tue, 21 Jan 2020 16:24:19 +0100 Subject: [PATCH 018/158] Avoid another call to st_get_position_mm current_position is already filled by planner_abort_hard. --- 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 211384f9..a3cf6440 100755 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -10549,7 +10549,7 @@ void uvlo_() planner_abort_hard(); // Store the current extruder position. - eeprom_update_float((float*)(EEPROM_UVLO_CURRENT_POSITION_E), st_get_position_mm(E_AXIS)); + eeprom_update_float((float*)(EEPROM_UVLO_CURRENT_POSITION_E), current_position[E_AXIS]); eeprom_update_byte((uint8_t*)EEPROM_UVLO_E_ABS, axis_relative_modes[3]?0:1); // Clean the input command queue. cmdqueue_reset(); From e8f05d06684a6c8818b11fba334bbb36d2e8fcf5 Mon Sep 17 00:00:00 2001 From: Yuri D'Elia Date: Tue, 21 Jan 2020 16:26:16 +0100 Subject: [PATCH 019/158] Heat both nozzle/bed together while recovering a print --- Firmware/Marlin_main.cpp | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index a3cf6440..267bbe58 100755 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -10777,10 +10777,13 @@ void recover_print(uint8_t automatic) { // Home X and Y axes. Homing just X and Y shall not touch the babystep and the world2machine transformation status. enquecommand_P(PSTR("G28 X Y")); // Set the target bed and nozzle temperatures and wait. - sprintf_P(cmd, PSTR("M109 S%d"), target_temperature[active_extruder]); + sprintf_P(cmd, PSTR("M104 S%d"), target_temperature[active_extruder]); enquecommand(cmd); sprintf_P(cmd, PSTR("M190 S%d"), target_temperature_bed); enquecommand(cmd); + sprintf_P(cmd, PSTR("M109 S%d"), target_temperature[active_extruder]); + enquecommand(cmd); + enquecommand_P(PSTR("M83")); //E axis relative mode //enquecommand_P(PSTR("G1 E5 F120")); //Extrude some filament to stabilize pessure // If not automatically recoreverd (long power loss), extrude extra filament to stabilize From 84376301228aaaa0e2f02a0ab1c960a32af9f271 Mon Sep 17 00:00:00 2001 From: Yuri D'Elia Date: Tue, 21 Jan 2020 16:29:12 +0100 Subject: [PATCH 020/158] Inhibit serial processing in uvlo_ Do not process serial commands when re-enabling the global isr. While printing via USB and a power panic is triggered, *any* extra command should be ignored. Abuse the "saved_printing" variable to inhibit serial processing. --- Firmware/Marlin_main.cpp | 17 ++++++++++------- 1 file changed, 10 insertions(+), 7 deletions(-) diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index 267bbe58..9777aa26 100755 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -10551,15 +10551,18 @@ void uvlo_() // Store the current extruder position. eeprom_update_float((float*)(EEPROM_UVLO_CURRENT_POSITION_E), current_position[E_AXIS]); eeprom_update_byte((uint8_t*)EEPROM_UVLO_E_ABS, axis_relative_modes[3]?0:1); - // Clean the input command queue. + + // Clean the input command queue, inhibit serial processing using saved_printing cmdqueue_reset(); card.sdprinting = false; -// card.closefile(); - // Enable stepper driver interrupt to move Z axis. - // This should be fine as the planner and command queues are empty and the SD card printing is disabled. - //FIXME one may want to disable serial lines at this point of time to avoid interfering with the command queue, - // though it should not happen that the command queue is touched as the plan_buffer_line always succeed without blocking. - sei(); +// card.closefile(); + saved_printing = true; + + // Enable stepper driver interrupt to move Z axis. This should be fine as the planner and + // command queues are empty, SD card printing is disabled, usb is inhibited. + sei(); + + // retract plan_buffer_line( current_position[X_AXIS], current_position[Y_AXIS], From 9ac80f73f2cc4d1d206c370ebef7bf74526137d6 Mon Sep 17 00:00:00 2001 From: Yuri D'Elia Date: Tue, 21 Jan 2020 16:34:09 +0100 Subject: [PATCH 021/158] Remove an useless/duplicate Z move Likely a result of a merge --- Firmware/Marlin_main.cpp | 37 +++++++++++++------------------------ 1 file changed, 13 insertions(+), 24 deletions(-) diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index 9777aa26..674fff8d 100755 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -10563,37 +10563,26 @@ void uvlo_() sei(); // retract - plan_buffer_line( - current_position[X_AXIS], - current_position[Y_AXIS], - current_position[Z_AXIS], - current_position[E_AXIS] - default_retraction, - 95, active_extruder); - - st_synchronize(); - disable_e0(); - - 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) / cs.axis_steps_per_unit[Z_AXIS], - current_position[E_AXIS] - default_retraction, - 40, active_extruder); + plan_buffer_line(current_position[X_AXIS], + current_position[Y_AXIS], + current_position[Z_AXIS], + current_position[E_AXIS] - default_retraction, + 95, active_extruder); st_synchronize(); disable_e0(); - 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) / cs.axis_steps_per_unit[Z_AXIS], - current_position[E_AXIS] - default_retraction, - 40, active_extruder); + // Move Z up and to the next 0th full step. + 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) / cs.axis_steps_per_unit[Z_AXIS], + current_position[E_AXIS] - default_retraction, + 40, active_extruder); st_synchronize(); + disable_z(); - disable_e0(); - // Move Z up to the next 0th full step. // Write the file position. eeprom_update_dword((uint32_t*)(EEPROM_FILE_POSITION), sd_position); + // Store the mesh bed leveling offsets. This is 2*7*7=98 bytes, which takes 98*3.4us=333us in worst case. for (int8_t mesh_point = 0; mesh_point < MESH_NUM_X_POINTS * MESH_NUM_Y_POINTS; ++ mesh_point) { uint8_t ix = mesh_point % MESH_NUM_X_POINTS; // from 0 to MESH_NUM_X_POINTS - 1 From 4c8f1e8b892f335ec14b39244e26ed3e53e01753 Mon Sep 17 00:00:00 2001 From: Yuri D'Elia Date: Tue, 21 Jan 2020 16:36:34 +0100 Subject: [PATCH 022/158] Use eeprom_update_word instead of EEPROM_save_B --- Firmware/Marlin_main.cpp | 11 ++++++----- 1 file changed, 6 insertions(+), 5 deletions(-) diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index 674fff8d..eb7a179f 100755 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -10509,7 +10509,6 @@ void uvlo_() tmc2130_set_current_r(E_AXIS, 20); #endif //TMC2130 - // Indicate that the interrupt has been triggered. // SERIAL_ECHOLNPGM("UVLO"); @@ -10591,17 +10590,19 @@ void uvlo_() int16_t v = mbl.active ? int16_t(floor(mbl.z_values[iy][ix] * 1000.f + 0.5f)) : 0; eeprom_update_word((uint16_t*)(EEPROM_UVLO_MESH_BED_LEVELING_FULL +2*mesh_point), *reinterpret_cast(&v)); } - // Read out the current Z motor microstep counter. This will be later used + + // Write the current Z motor microstep counter. This will be later used // for reaching the zero full step before powering off. eeprom_update_word((uint16_t*)(EEPROM_UVLO_Z_MICROSTEPS), z_microsteps); - // Store the current position. + // Store the current position. eeprom_update_float((float*)(EEPROM_UVLO_CURRENT_POSITION + 0), current_position[X_AXIS]); eeprom_update_float((float*)(EEPROM_UVLO_CURRENT_POSITION + 4), current_position[Y_AXIS]); eeprom_update_float((float*)EEPROM_UVLO_CURRENT_POSITION_Z , current_position[Z_AXIS]); + // Store the current feed rate, temperatures, fan speed and extruder multipliers (flow rates) eeprom_update_word((uint16_t*)EEPROM_UVLO_FEEDRATE, feedrate_bckp); - EEPROM_save_B(EEPROM_UVLO_FEEDMULTIPLY, &feedmultiply); + eeprom_update_word((uint16_t*)EEPROM_UVLO_FEEDMULTIPLY, feedmultiply); eeprom_update_byte((uint8_t*)EEPROM_UVLO_TARGET_HOTEND, target_temperature[active_extruder]); eeprom_update_byte((uint8_t*)EEPROM_UVLO_TARGET_BED, target_temperature_bed); eeprom_update_byte((uint8_t*)EEPROM_UVLO_FAN_SPEED, fanSpeed); @@ -10897,7 +10898,7 @@ void restore_print_from_eeprom() { fan_speed_rec = eeprom_read_byte((uint8_t*)EEPROM_UVLO_FAN_SPEED); feedrate_rec = eeprom_read_word((uint16_t*)EEPROM_UVLO_FEEDRATE); - EEPROM_read_B(EEPROM_UVLO_FEEDMULTIPLY, &feedmultiply_rec); + feedmultiply_rec = eeprom_read_word((uint16_t*)EEPROM_UVLO_FEEDMULTIPLY); SERIAL_ECHOPGM("Feedrate:"); MYSERIAL.print(feedrate_rec); SERIAL_ECHOPGM(", feedmultiply:"); From 7f3d4a8491acabbbb139a41e4c5bff7e4dad9d3f Mon Sep 17 00:00:00 2001 From: Yuri D'Elia Date: Tue, 21 Jan 2020 16:39:39 +0100 Subject: [PATCH 023/158] Restore the last E axis position correctly after powerpanic - Initially restore the last E position from the eeprom in any case, not just when using absolute mode (although unnecessary: since it will be reset later), fixing a possible unitialized position and crash during recovery (thanks to @leptun) - Remove useless extra calls to put the extruder in relative mode: the extruder already starts in relative mode and is later switched to absolute. - Replace incorrect calls to STRINGIFY with sprintf_P - Retract after pressure has been restored in uvlo_tiny, to be consistent with a regular uvlo (remove the bogus double unretract as a result). - Set the real E position prior to the panic *after* the retraction, using the now-fixed G92. --- Firmware/Marlin_main.cpp | 41 ++++++++++++++++++++-------------------- 1 file changed, 21 insertions(+), 20 deletions(-) diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index eb7a179f..61ab1031 100755 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -10778,12 +10778,15 @@ void recover_print(uint8_t automatic) { enquecommand(cmd); enquecommand_P(PSTR("M83")); //E axis relative mode - //enquecommand_P(PSTR("G1 E5 F120")); //Extrude some filament to stabilize pessure - // If not automatically recoreverd (long power loss), extrude extra filament to stabilize - if(automatic == 0){ - enquecommand_P(PSTR("G1 E5 F120")); //Extrude some filament to stabilize pessure - } - enquecommand_P(PSTR("G1 E" STRINGIFY(-default_retraction)" F480")); + + // If not automatically recoreverd (long power loss) + if(automatic == 0){ + //Extrude some filament to stabilize the pressure + enquecommand_P(PSTR("G1 E5 F120")); + // Retract to be consistent with a short pause + sprintf_P(cmd, PSTR("G1 E%-0.3f F2700"), default_retraction); + enquecommand(cmd); + } printf_P(_N("After waiting for temp:\nCurrent pos X_AXIS:%.3f\nCurrent pos Y_AXIS:%.3f\n"), current_position[X_AXIS], current_position[Y_AXIS]); @@ -10794,7 +10797,6 @@ void recover_print(uint8_t automatic) { void recover_machine_state_after_power_panic(bool bTiny) { - char cmd[30]; // 1) Recover the logical cordinates at the time of the power panic. // The logical XY coordinates are needed to recover the machine Z coordinate corrected by the mesh bed leveling. current_position[X_AXIS] = eeprom_read_float((float*)(EEPROM_UVLO_CURRENT_POSITION + 0)); @@ -10829,12 +10831,9 @@ void recover_machine_state_after_power_panic(bool bTiny) 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")); - dtostrf(current_position[E_AXIS], 6, 3, cmd + strlen(cmd)); - enquecommand(cmd); - } + + // Recover last E axis position + current_position[E_AXIS] = eeprom_read_float((float*)(EEPROM_UVLO_CURRENT_POSITION_E)); memcpy(destination, current_position, sizeof(destination)); @@ -10929,8 +10928,6 @@ void restore_print_from_eeprom() { uint32_t position = eeprom_read_dword((uint32_t*)(EEPROM_FILE_POSITION)); SERIAL_ECHOPGM("Position read from eeprom:"); MYSERIAL.println(position); - // E axis relative mode. - enquecommand_P(PSTR("M83")); // Move to the XY print position in logical coordinates, where the print has been killed. strcpy_P(cmd, PSTR("G1 X")); strcat(cmd, ftostr32(eeprom_read_float((float*)(EEPROM_UVLO_CURRENT_POSITION + 0)))); strcat_P(cmd, PSTR(" Y")); strcat(cmd, ftostr32(eeprom_read_float((float*)(EEPROM_UVLO_CURRENT_POSITION + 4)))); @@ -10942,16 +10939,20 @@ void restore_print_from_eeprom() { strcpy_P(cmd, PSTR("G1 Z")); strcat(cmd, ftostr32(eeprom_read_float((float*)(EEPROM_UVLO_CURRENT_POSITION_Z)))); enquecommand(cmd); // Unretract. - enquecommand_P(PSTR("G1 E" STRINGIFY(2*default_retraction)" F480")); + sprintf_P(cmd, PSTR("G1 E%0.3f F2700"), default_retraction); + enquecommand(cmd); + // Recover final E axis position and mode + float pos_e = eeprom_read_float((float*)(EEPROM_UVLO_CURRENT_POSITION_E)); + sprintf_P(cmd, PSTR("G92 E")); + dtostrf(pos_e, 6, 3, cmd + strlen(cmd)); + enquecommand(cmd); + if (eeprom_read_byte((uint8_t*)EEPROM_UVLO_E_ABS)) + enquecommand_P(PSTR("M82")); //E axis abslute mode // Set the feedrates saved at the power panic. sprintf_P(cmd, PSTR("G1 F%d"), feedrate_rec); enquecommand(cmd); sprintf_P(cmd, PSTR("M220 S%d"), feedmultiply_rec); enquecommand(cmd); - if (eeprom_read_byte((uint8_t*)EEPROM_UVLO_E_ABS)) - { - enquecommand_P(PSTR("M82")); //E axis abslute mode - } // Set the fan speed saved at the power panic. strcpy_P(cmd, PSTR("M106 S")); strcat(cmd, itostr3(int(fan_speed_rec))); From 73527d6069c5a4b6d75d8150887640c0ec2f4f6f Mon Sep 17 00:00:00 2001 From: MRprusa3d Date: Wed, 22 Jan 2020 04:45:13 +0100 Subject: [PATCH 024/158] selfTest workflow optimalization --- Firmware/ultralcd.cpp | 14 ++++++-------- 1 file changed, 6 insertions(+), 8 deletions(-) diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index 5d291f35..38471b81 100755 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -7541,26 +7541,24 @@ bool lcd_selftest() int _progress = 0; bool _result = true; bool _swapped_fan = false; +#if IR_SENSOR_ANALOG + bool bAction; + bAction=lcd_show_fullscreen_message_yes_no_and_wait_P(_i("Is the filament unloaded?"),false,true); + if(!bAction) + return(false); +#endif //IR_SENSOR_ANALOG lcd_wait_for_cool_down(); lcd_clear(); lcd_set_cursor(0, 0); lcd_puts_P(_i("Self test start "));////MSG_SELFTEST_START c=20 #ifdef TMC2130 FORCE_HIGH_POWER_START; #endif // TMC2130 -#if !IR_SENSOR_ANALOG _delay(2000); -#endif //!IR_SENSOR_ANALOG FORCE_BL_ON_START; _delay(2000); KEEPALIVE_STATE(IN_HANDLER); -#if IR_SENSOR_ANALOG - bool bAction; - bAction=lcd_show_fullscreen_message_yes_no_and_wait_P(_i("Is filament unloaded?"),false,true); - if(!bAction) - return(false); -#endif //IR_SENSOR_ANALOG _progress = lcd_selftest_screen(TestScreen::ExtruderFan, _progress, 3, true, 2000); #if (defined(FANCHECK) && defined(TACH_0)) From 4055977a95fde87d7d78763e02c5838e9c48bbf0 Mon Sep 17 00:00:00 2001 From: Alex Voinea Date: Sat, 25 Jan 2020 11:41:27 +0200 Subject: [PATCH 025/158] Do not clear axis known position when Z is set to silent Also removed unused (forgotten) variable. --- 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 211384f9..70cbd6d7 100755 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -11563,7 +11563,7 @@ if(!(bEnableForce_z||eeprom_read_byte((uint8_t*)EEPROM_SILENT))) void disable_force_z() { - uint16_t z_microsteps=0; + // uint16_t z_microsteps=0; if(!bEnableForce_z) return; // motor already disabled (may be ;-p ) @@ -11576,7 +11576,7 @@ void disable_force_z() tmc2130_init(true); #endif // TMC2130 - axis_known_position[Z_AXIS]=false; + // axis_known_position[Z_AXIS]=false; } From 53101819701f010cb215e5b50cbfb026084fa870 Mon Sep 17 00:00:00 2001 From: Yuri D'Elia Date: Wed, 22 Jan 2020 19:39:55 +0100 Subject: [PATCH 026/158] Cancel a recovering print when using the LCD "Stop" Also clear the UVLO flag when using lcd_print_stop. This prevents an aborted print which has been cancelled while unparking (just prior to recover) to come back again at the next startup. --- Firmware/Marlin_main.cpp | 1 + 1 file changed, 1 insertion(+) diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index 61ab1031..67b85b94 100755 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -11249,6 +11249,7 @@ void restore_print_from_ram_and_continue(float e_move) // Cancel the state related to a currently saved print void cancel_saved_printing() { + eeprom_update_byte((uint8_t*)EEPROM_UVLO, 0); saved_target[0] = SAVED_TARGET_UNSET; saved_printing_type = PRINTING_TYPE_NONE; saved_printing = false; From ec8b5aaa341cbfd02bf952ba16f36a50a902e816 Mon Sep 17 00:00:00 2001 From: Yuri D'Elia Date: Sun, 26 Jan 2020 14:01:18 +0100 Subject: [PATCH 027/158] Do not attempt to "zero-phase" the microstep counter If the motors are off-phase, this is more likely to "bump" them to an incorrect/reverse full-step, doing worse. We need to ensure the motors are already positioned on a fullstep during power panic instead. Remove the PSU_DELTA exception: Z _always_ needs to be powered here. --- Firmware/Marlin_main.cpp | 23 +++-------------------- 1 file changed, 3 insertions(+), 20 deletions(-) diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index 67b85b94..f5bccffe 100755 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -1327,29 +1327,12 @@ void setup() SET_OUTPUT(CONTROLLERFAN_PIN); //Set pin used for driver cooling fan #endif - setup_homepin(); -#ifdef TMC2130 - - if (1) { - // try to run to zero phase before powering the Z motor. - // Move in negative direction - WRITE(Z_DIR_PIN,INVERT_Z_DIR); - // Round the current micro-micro steps to micro steps. - for (uint16_t phase = (tmc2130_rd_MSCNT(Z_AXIS) + 8) >> 4; phase > 0; -- phase) { - // Until the phase counter is reset to zero. - WRITE(Z_STEP_PIN, !INVERT_Z_STEP_PIN); - _delay(2); - WRITE(Z_STEP_PIN, INVERT_Z_STEP_PIN); - _delay(2); - } - } -#endif //TMC2130 - -#if defined(Z_AXIS_ALWAYS_ON) && !defined(PSU_Delta) - enable_z(); +#if defined(Z_AXIS_ALWAYS_ON) + enable_z(); #endif + farm_mode = eeprom_read_byte((uint8_t*)EEPROM_FARM_MODE); EEPROM_read_B(EEPROM_FARM_NUMBER, &farm_no); if ((farm_mode == 0xFF && farm_no == 0) || (farm_no == static_cast(0xFFFF))) farm_mode = false; //if farm_mode has not been stored to eeprom yet and farm number is set to zero or EEPROM is fresh, deactivate farm mode From ec5cbf73b90070fa9ce58cfc9628dd72f8cb03ea Mon Sep 17 00:00:00 2001 From: Yuri D'Elia Date: Sun, 26 Jan 2020 14:24:53 +0100 Subject: [PATCH 028/158] During PP keep the watchdog waiting for longer When the printer is connected to a USB host during a PP (and the host does not lose power), the rambo can linger for longer, sometimes for long enough to recover the print state. Drain some more power. --- Firmware/Marlin_main.cpp | 17 +++++++++-------- 1 file changed, 9 insertions(+), 8 deletions(-) diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index f5bccffe..b3b0376c 100755 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -10625,10 +10625,11 @@ void uvlo_() plan_buffer_line_curposXYZE(500, active_extruder); st_synchronize(); #endif -wdt_enable(WDTO_500MS); -WRITE(BEEPER,HIGH); -while(1) - ; + + // burn all that residual power + wdt_enable(WDTO_1S); + WRITE(BEEPER,HIGH); + while(1); } @@ -10672,10 +10673,10 @@ eeprom_update_byte((uint8_t*)EEPROM_UVLO,2); // Increment power failure counter eeprom_update_byte((uint8_t*)EEPROM_POWER_COUNT, eeprom_read_byte((uint8_t*)EEPROM_POWER_COUNT) + 1); eeprom_update_word((uint16_t*)EEPROM_POWER_COUNT_TOT, eeprom_read_word((uint16_t*)EEPROM_POWER_COUNT_TOT) + 1); -wdt_enable(WDTO_500MS); -WRITE(BEEPER,HIGH); -while(1) - ; + // burn all that residual power + wdt_enable(WDTO_1S); + WRITE(BEEPER,HIGH); + while(1); } #endif //UVLO_SUPPORT From 0702e0de6e1cc22a3c8af6d0d40f35e23564a2b6 Mon Sep 17 00:00:00 2001 From: Yuri D'Elia Date: Sun, 26 Jan 2020 17:12:27 +0100 Subject: [PATCH 029/158] Use world2machine instead of repeating code --- Firmware/planner.cpp | 9 +-------- 1 file changed, 1 insertion(+), 8 deletions(-) diff --git a/Firmware/planner.cpp b/Firmware/planner.cpp index 8c26cef9..197b3d9f 100644 --- a/Firmware/planner.cpp +++ b/Firmware/planner.cpp @@ -1345,14 +1345,7 @@ void plan_set_position(float x, float y, float z, const float &e) apply_rotation_xyz(plan_bed_level_matrix, x, y, z); #endif // ENABLE_AUTO_BED_LEVELING - // Apply the machine correction matrix. - if (world2machine_correction_mode != WORLD2MACHINE_CORRECTION_NONE) - { - float tmpx = x; - float tmpy = y; - x = world2machine_rotation_and_skew[0][0] * tmpx + world2machine_rotation_and_skew[0][1] * tmpy + world2machine_shift[0]; - y = world2machine_rotation_and_skew[1][0] * tmpx + world2machine_rotation_and_skew[1][1] * tmpy + world2machine_shift[1]; - } + world2machine(x, y); position[X_AXIS] = lround(x*cs.axis_steps_per_unit[X_AXIS]); position[Y_AXIS] = lround(y*cs.axis_steps_per_unit[Y_AXIS]); From 11a0e95f60313f6162d6b94e0d0cc31395aeb825 Mon Sep 17 00:00:00 2001 From: Yuri D'Elia Date: Sun, 26 Jan 2020 17:16:15 +0100 Subject: [PATCH 030/158] Re-enable the code that moves the extruder during PP There is frequently plenty of power left during a PP. Take advantage of it by moving the extruder to either side of the axis to detach completely the nozzle from the print. Re-enable Z during this move to avoid losing the current step. --- Firmware/Marlin_main.cpp | 11 +++++------ 1 file changed, 5 insertions(+), 6 deletions(-) diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index b3b0376c..3fdff1a9 100755 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -10617,18 +10617,17 @@ void uvlo_() // Increment power failure counter eeprom_update_byte((uint8_t*)EEPROM_POWER_COUNT, eeprom_read_byte((uint8_t*)EEPROM_POWER_COUNT) + 1); eeprom_update_word((uint16_t*)EEPROM_POWER_COUNT_TOT, eeprom_read_word((uint16_t*)EEPROM_POWER_COUNT_TOT) + 1); - printf_P(_N("UVLO - end %d\n"), _millis() - time_start); -#if 0 - // Move the print head to the side of the print until all the power stored in the power supply capacitors is depleted. + printf_P(_N("UVLO - end %d\n"), _millis() - time_start); + WRITE(BEEPER,HIGH); + + // All is set: with all the juice left, try to move extruder away to detach the nozzle completely from the print + enable_z(); current_position[X_AXIS] = (current_position[X_AXIS] < 0.5f * (X_MIN_POS + X_MAX_POS)) ? X_MIN_POS : X_MAX_POS; plan_buffer_line_curposXYZE(500, active_extruder); st_synchronize(); -#endif - // burn all that residual power wdt_enable(WDTO_1S); - WRITE(BEEPER,HIGH); while(1); } From eb2ca78167fbec4ded3731a00f9cad921adbea39 Mon Sep 17 00:00:00 2001 From: Yuri D'Elia Date: Sun, 26 Jan 2020 17:35:50 +0100 Subject: [PATCH 031/158] Rewrite uvlo handling for accurate Z re/positioning - In both uvlo_ and uvlo_tiny, calculate Z usteps properly and adjust the Z position to a true fullstep before disabling the motor. This avoids shifs during recovery. - In uvlo_tiny, instead of moving up indefinitely, adjust Z just once using the smallest move possible (new def UVLO_TINY_Z_AXIS_SHIFT) - Perform all the uvlo/recovery processing in physical coordinates and MBL off: there should be no automatic Z movement! - Disable heaters in both handlers to conserve more power. - Add timing information to uvlo_tiny too. - During recovery, to switch between physical and logical positioning introduce a new "PRUSA MBL" gcode as most of the procedure is enqueued, and no existing gcode was available. --- Firmware/Marlin.h | 5 +- Firmware/Marlin_main.cpp | 256 ++++++++++-------- Firmware/eeprom.h | 4 +- .../variants/1_75mm_MK3-EINSy10a-E3Dv6full.h | 4 + .../variants/1_75mm_MK3S-EINSy10a-E3Dv6full.h | 6 +- 5 files changed, 158 insertions(+), 117 deletions(-) diff --git a/Firmware/Marlin.h b/Firmware/Marlin.h index 19e5df57..58b3351d 100755 --- a/Firmware/Marlin.h +++ b/Firmware/Marlin.h @@ -445,9 +445,8 @@ void setup_uvlo_interrupt(); void setup_fan_interrupt(); #endif -//extern void recover_machine_state_after_power_panic(); -extern void recover_machine_state_after_power_panic(bool bTiny); -extern void restore_print_from_eeprom(); +extern bool recover_machine_state_after_power_panic(); +extern void restore_print_from_eeprom(bool mbl_was_active); extern void position_menu(); extern void print_world_coordinates(); diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index 3fdff1a9..c2439d74 100755 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -3838,6 +3838,17 @@ void process_commands() } else if(code_seen("FR")) { // PRUSA FR // Factory full reset factory_reset(0); + } else if(code_seen("MBL")) { // PRUSA MBL + // Change the MBL status without changing the logical Z position. + if(code_seen("V")) { + bool value = code_value_short(); + st_synchronize(); + if(value != mbl.active) { + mbl.active = value; + // Use plan_set_z_position to reset the physical values + plan_set_z_position(current_position[Z_AXIS]); + } + } //-// /* @@ -10492,15 +10503,11 @@ void uvlo_() tmc2130_set_current_r(E_AXIS, 20); #endif //TMC2130 - // Indicate that the interrupt has been triggered. - // SERIAL_ECHOLNPGM("UVLO"); - - // Read out the current Z motor microstep counter. This will be later used - // for reaching the zero full step before powering off. - uint16_t z_microsteps = 0; -#ifdef TMC2130 - z_microsteps = tmc2130_rd_MSCNT(Z_TMC2130_CS); -#endif //TMC2130 + // Stop all heaters + uint8_t saved_target_temperature_bed = target_temperature_bed; + uint8_t saved_target_temperature_ext = target_temperature[active_extruder]; + setAllTargetHotends(0); + setTargetBed(0); // Calculate the file position, from which to resume this print. long sd_position = sdpos_atomic; //atomic sd position of last command added in queue @@ -10525,40 +10532,52 @@ void uvlo_() feedrate_bckp = feedrate; } + // From this point on and up to the print recovery, Z should not move during X/Y travels and + // should be controlled precisely. Reset the MBL status before planner_abort_hard in order to + // get the physical Z for further manipulation. + bool mbl_was_active = mbl.active; + mbl.active = false; + // After this call, the planner queue is emptied and the current_position is set to a current logical coordinate. // The logical coordinate will likely differ from the machine coordinate if the skew calibration and mesh bed leveling // are in action. planner_abort_hard(); - // Store the current extruder position. + // Store the print logical Z position, which we need to recover (a slight error here would be + // recovered on the next Gcode instruction, while a physical location error would not) + float logical_z = current_position[Z_AXIS]; + if(mbl_was_active) logical_z -= mbl.get_z(st_get_position_mm(X_AXIS), st_get_position_mm(Y_AXIS)); + eeprom_update_float((float*)EEPROM_UVLO_CURRENT_POSITION_Z, logical_z); + + // Store the print E position before we lose track eeprom_update_float((float*)(EEPROM_UVLO_CURRENT_POSITION_E), current_position[E_AXIS]); eeprom_update_byte((uint8_t*)EEPROM_UVLO_E_ABS, axis_relative_modes[3]?0:1); // Clean the input command queue, inhibit serial processing using saved_printing cmdqueue_reset(); card.sdprinting = false; -// card.closefile(); saved_printing = true; // Enable stepper driver interrupt to move Z axis. This should be fine as the planner and // command queues are empty, SD card printing is disabled, usb is inhibited. sei(); - // retract - plan_buffer_line(current_position[X_AXIS], - current_position[Y_AXIS], - current_position[Z_AXIS], - current_position[E_AXIS] - default_retraction, - 95, active_extruder); + // Retract + current_position[E_AXIS] -= default_retraction; + plan_buffer_line_curposXYZE(95, active_extruder); st_synchronize(); disable_e0(); - // Move Z up and to the next 0th full step. - 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) / cs.axis_steps_per_unit[Z_AXIS], - current_position[E_AXIS] - default_retraction, - 40, active_extruder); + // Read out the current Z motor microstep counter to move the axis up towards + // a full step before powering off. NOTE: we need to ensure to schedule more + // than "dropsegments" steps in order to move (this is always the case here + // due to UVLO_Z_AXIS_SHIFT being used) + uint16_t z_res = tmc2130_get_res(Z_AXIS); + uint16_t z_microsteps = tmc2130_rd_MSCNT(Z_AXIS); + current_position[Z_AXIS] += float(1024 - z_microsteps) + / (z_res * cs.axis_steps_per_unit[Z_AXIS]) + + UVLO_Z_AXIS_SHIFT; + plan_buffer_line_curposXYZE(homing_feedrate[Z_AXIS]/60, active_extruder); st_synchronize(); disable_z(); @@ -10570,24 +10589,24 @@ void uvlo_() uint8_t ix = mesh_point % MESH_NUM_X_POINTS; // from 0 to MESH_NUM_X_POINTS - 1 uint8_t iy = mesh_point / MESH_NUM_X_POINTS; // Scale the z value to 1u resolution. - int16_t v = mbl.active ? int16_t(floor(mbl.z_values[iy][ix] * 1000.f + 0.5f)) : 0; + int16_t v = mbl_was_active ? int16_t(floor(mbl.z_values[iy][ix] * 1000.f + 0.5f)) : 0; eeprom_update_word((uint16_t*)(EEPROM_UVLO_MESH_BED_LEVELING_FULL +2*mesh_point), *reinterpret_cast(&v)); } - // Write the current Z motor microstep counter. This will be later used - // for reaching the zero full step before powering off. + // Write the _final_ Z position and motor microstep counter (unused). + eeprom_update_float((float*)EEPROM_UVLO_TINY_CURRENT_POSITION_Z, current_position[Z_AXIS]); + z_microsteps = tmc2130_rd_MSCNT(Z_AXIS); eeprom_update_word((uint16_t*)(EEPROM_UVLO_Z_MICROSTEPS), z_microsteps); // Store the current position. eeprom_update_float((float*)(EEPROM_UVLO_CURRENT_POSITION + 0), current_position[X_AXIS]); eeprom_update_float((float*)(EEPROM_UVLO_CURRENT_POSITION + 4), current_position[Y_AXIS]); - eeprom_update_float((float*)EEPROM_UVLO_CURRENT_POSITION_Z , current_position[Z_AXIS]); // Store the current feed rate, temperatures, fan speed and extruder multipliers (flow rates) eeprom_update_word((uint16_t*)EEPROM_UVLO_FEEDRATE, feedrate_bckp); eeprom_update_word((uint16_t*)EEPROM_UVLO_FEEDMULTIPLY, feedmultiply); - eeprom_update_byte((uint8_t*)EEPROM_UVLO_TARGET_HOTEND, target_temperature[active_extruder]); - eeprom_update_byte((uint8_t*)EEPROM_UVLO_TARGET_BED, target_temperature_bed); + eeprom_update_byte((uint8_t*)EEPROM_UVLO_TARGET_HOTEND, saved_target_temperature_ext); + eeprom_update_byte((uint8_t*)EEPROM_UVLO_TARGET_BED, saved_target_temperature_bed); eeprom_update_byte((uint8_t*)EEPROM_UVLO_FAN_SPEED, fanSpeed); eeprom_update_float((float*)(EEPROM_EXTRUDER_MULTIPLIER_0), extruder_multiplier[0]); #if EXTRUDERS > 1 @@ -10611,9 +10630,6 @@ void uvlo_() // Finaly store the "power outage" flag. if(sd_print) eeprom_update_byte((uint8_t*)EEPROM_UVLO, 1); - st_synchronize(); - printf_P(_N("stps%d\n"), tmc2130_rd_MSCNT(Z_AXIS)); - // Increment power failure counter eeprom_update_byte((uint8_t*)EEPROM_POWER_COUNT, eeprom_read_byte((uint8_t*)EEPROM_POWER_COUNT) + 1); eeprom_update_word((uint16_t*)EEPROM_POWER_COUNT_TOT, eeprom_read_word((uint16_t*)EEPROM_POWER_COUNT_TOT) + 1); @@ -10634,44 +10650,68 @@ void uvlo_() void uvlo_tiny() { -uint16_t z_microsteps=0; + unsigned long time_start = _millis(); + + // Conserve power as soon as possible. + disable_x(); + disable_y(); + disable_e0(); -// Conserve power as soon as possible. -disable_x(); -disable_y(); -disable_e0(); - #ifdef TMC2130 -tmc2130_set_current_h(Z_AXIS, 20); -tmc2130_set_current_r(Z_AXIS, 20); + tmc2130_set_current_h(Z_AXIS, 20); + tmc2130_set_current_r(Z_AXIS, 20); #endif //TMC2130 -// Read out the current Z motor microstep counter -#ifdef TMC2130 -z_microsteps=tmc2130_rd_MSCNT(Z_TMC2130_CS); -#endif //TMC2130 -planner_abort_hard(); + // Stop all heaters + setAllTargetHotends(0); + setTargetBed(0); -//save current position only in case, where the printer is moving on Z axis, which is only when EEPROM_UVLO is 1 -//EEPROM_UVLO is 1 after normal uvlo or after recover_print(), when the extruder is moving on Z axis after rehome -if(eeprom_read_byte((uint8_t*)EEPROM_UVLO)!=2){ - eeprom_update_float((float*)(EEPROM_UVLO_TINY_CURRENT_POSITION_Z), current_position[Z_AXIS]); - eeprom_update_word((uint16_t*)(EEPROM_UVLO_TINY_Z_MICROSTEPS),z_microsteps); -} + // When power is interrupted on the _first_ recovery an attempt can be made to raise the + // extruder, causing the Z position to change. Similarly, when recovering, the Z position is + // lowered. In such cases we cannot just save Z, we need to re-align the steppers to a fullstep. + // Disable MBL (if not already) to work with physical coordinates. + mbl.active = false; + planner_abort_hard(); -//after multiple power panics current Z axis is unknow -//in this case we set EEPROM_UVLO_TINY_CURRENT_POSITION_Z to last know position which is EEPROM_UVLO_CURRENT_POSITION_Z -if(eeprom_read_float((float*)EEPROM_UVLO_TINY_CURRENT_POSITION_Z) < 0.001f){ - eeprom_update_float((float*)(EEPROM_UVLO_TINY_CURRENT_POSITION_Z), eeprom_read_float((float*)EEPROM_UVLO_CURRENT_POSITION_Z)); - eeprom_update_word((uint16_t*)(EEPROM_UVLO_TINY_Z_MICROSTEPS), eeprom_read_word((uint16_t*)EEPROM_UVLO_Z_MICROSTEPS)); -} + // Allow for small roundoffs to be ignored + if(abs(current_position[Z_AXIS] - eeprom_read_float((float*)(EEPROM_UVLO_TINY_CURRENT_POSITION_Z))) >= 1.f/cs.axis_steps_per_unit[Z_AXIS]) + { + // Clean the input command queue, inhibit serial processing using saved_printing + cmdqueue_reset(); + card.sdprinting = false; + saved_printing = true; -// Finaly store the "power outage" flag. -eeprom_update_byte((uint8_t*)EEPROM_UVLO,2); + // Enable stepper driver interrupt to move Z axis. This should be fine as the planner and + // command queues are empty, SD card printing is disabled, usb is inhibited. + sei(); + + // The axis was moved: adjust Z as done on a regular UVLO. + uint16_t z_res = tmc2130_get_res(Z_AXIS); + uint16_t z_microsteps = tmc2130_rd_MSCNT(Z_AXIS); + current_position[Z_AXIS] += float(1024 - z_microsteps) + / (z_res * cs.axis_steps_per_unit[Z_AXIS]) + + UVLO_TINY_Z_AXIS_SHIFT; + plan_buffer_line_curposXYZE(homing_feedrate[Z_AXIS]/60, active_extruder); + st_synchronize(); + disable_z(); + + // Update Z position + eeprom_update_float((float*)(EEPROM_UVLO_TINY_CURRENT_POSITION_Z), current_position[Z_AXIS]); + + // Update the _final_ Z motor microstep counter (unused). + z_microsteps = tmc2130_rd_MSCNT(Z_AXIS); + eeprom_update_word((uint16_t*)(EEPROM_UVLO_Z_MICROSTEPS), z_microsteps); + } + + // Update the the "power outage" flag. + eeprom_update_byte((uint8_t*)EEPROM_UVLO,2); + + // Increment power failure counter + eeprom_update_byte((uint8_t*)EEPROM_POWER_COUNT, eeprom_read_byte((uint8_t*)EEPROM_POWER_COUNT) + 1); + eeprom_update_word((uint16_t*)EEPROM_POWER_COUNT_TOT, eeprom_read_word((uint16_t*)EEPROM_POWER_COUNT_TOT) + 1); + + printf_P(_N("UVLO_TINY - end %d\n"), _millis() - time_start); -// Increment power failure counter -eeprom_update_byte((uint8_t*)EEPROM_POWER_COUNT, eeprom_read_byte((uint8_t*)EEPROM_POWER_COUNT) + 1); -eeprom_update_word((uint16_t*)EEPROM_POWER_COUNT_TOT, eeprom_read_word((uint16_t*)EEPROM_POWER_COUNT_TOT) + 1); // burn all that residual power wdt_enable(WDTO_1S); WRITE(BEEPER,HIGH); @@ -10744,13 +10784,16 @@ void recover_print(uint8_t automatic) { lcd_update(2); lcd_setstatuspgm(_i("Recovering print "));////MSG_RECOVERING_PRINT c=20 r=1 - bool bTiny=(eeprom_read_byte((uint8_t*)EEPROM_UVLO)==2); - recover_machine_state_after_power_panic(bTiny); //recover position, temperatures and extrude_multipliers - // Lift the print head, so one may remove the excess priming material. - if(!bTiny&&(current_position[Z_AXIS]<25)) - enquecommand_P(PSTR("G1 Z25 F800")); + // Recover position, temperatures and extrude_multipliers + bool mbl_was_active = recover_machine_state_after_power_panic(); - // Home X and Y axes. Homing just X and Y shall not touch the babystep and the world2machine transformation status. + // Attempt to lift the print head on the first recovery, so one may remove the excess priming material. + bool raise_z = (eeprom_read_byte((uint8_t*)EEPROM_UVLO) == 1); + if(raise_z && (current_position[Z_AXIS]<25)) + enquecommand_P(PSTR("G1 Z25 F800")); + + // Home X and Y axes. Homing just X and Y shall not touch the babystep and the world2machine + // transformation status. G28 will not touch Z when MBL is off. enquecommand_P(PSTR("G28 X Y")); // Set the target bed and nozzle temperatures and wait. sprintf_P(cmd, PSTR("M104 S%d"), target_temperature[active_extruder]); @@ -10774,19 +10817,19 @@ void recover_print(uint8_t automatic) { printf_P(_N("After waiting for temp:\nCurrent pos X_AXIS:%.3f\nCurrent pos Y_AXIS:%.3f\n"), current_position[X_AXIS], current_position[Y_AXIS]); // Restart the print. - restore_print_from_eeprom(); + restore_print_from_eeprom(mbl_was_active); printf_P(_N("Current pos Z_AXIS:%.3f\nCurrent pos E_AXIS:%.3f\n"), current_position[Z_AXIS], current_position[E_AXIS]); } -void recover_machine_state_after_power_panic(bool bTiny) +bool recover_machine_state_after_power_panic() { - // 1) Recover the logical cordinates at the time of the power panic. - // The logical XY coordinates are needed to recover the machine Z coordinate corrected by the mesh bed leveling. - current_position[X_AXIS] = eeprom_read_float((float*)(EEPROM_UVLO_CURRENT_POSITION + 0)); - current_position[Y_AXIS] = eeprom_read_float((float*)(EEPROM_UVLO_CURRENT_POSITION + 4)); + // 1) Preset some dummy values for the XY axes + current_position[X_AXIS] = 0; + current_position[Y_AXIS] = 0; - // 2) Restore the mesh bed leveling offsets. This is 2*7*7=98 bytes, which takes 98*3.4us=333us in worst case. - mbl.active = false; + // 2) Restore the mesh bed leveling offsets, but not the MBL status. + // This is 2*7*7=98 bytes, which takes 98*3.4us=333us in worst case. + bool mbl_was_active = false; for (int8_t mesh_point = 0; mesh_point < MESH_NUM_X_POINTS * MESH_NUM_Y_POINTS; ++ mesh_point) { uint8_t ix = mesh_point % MESH_NUM_X_POINTS; // from 0 to MESH_NUM_X_POINTS - 1 uint8_t iy = mesh_point / MESH_NUM_X_POINTS; @@ -10794,26 +10837,13 @@ void recover_machine_state_after_power_panic(bool bTiny) int16_t v; eeprom_read_block(&v, (void*)(EEPROM_UVLO_MESH_BED_LEVELING_FULL+2*mesh_point), 2); if (v != 0) - mbl.active = true; + mbl_was_active = true; mbl.z_values[iy][ix] = float(v) * 0.001f; } - // Recover the logical coordinate of the Z axis at the time of the power panic. + // Recover the physical coordinate of the Z axis at the time of the power panic. // 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)) - + float((1024 - eeprom_read_word((uint16_t*)(EEPROM_UVLO_TINY_Z_MICROSTEPS)) - + 7) >> 4) / cs.axis_steps_per_unit[Z_AXIS]; - - //after multiple power panics the print is slightly in the air so get it little bit down. - //Not exactly sure why is this happening, but it has something to do with bed leveling and world2machine coordinates - current_position[Z_AXIS] -= 0.4*mbl.get_z(current_position[X_AXIS], current_position[Y_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) / cs.axis_steps_per_unit[Z_AXIS]; - } + current_position[Z_AXIS] = eeprom_read_float((float*)(EEPROM_UVLO_TINY_CURRENT_POSITION_Z)); // Recover last E axis position current_position[E_AXIS] = eeprom_read_float((float*)(EEPROM_UVLO_CURRENT_POSITION_E)); @@ -10832,17 +10862,13 @@ void recover_machine_state_after_power_panic(bool bTiny) // The baby stepping value is used to reset the physical Z axis when rehoming the Z axis. babystep_load(); - // 5) Set the physical positions from the logical positions using the world2machine transformation and the active bed leveling. + // 5) Set the physical positions from the logical positions using the world2machine transformation + // This is only done to inizialize Z/E axes with physical locations, since X/Y are unknown. plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]); - // 6) Power up the motors, mark their positions as known. - //FIXME Verfiy, whether the X and Y axes should be powered up here, as they will later be re-homed anyway. - axis_known_position[X_AXIS] = true; enable_x(); - axis_known_position[Y_AXIS] = true; enable_y(); - axis_known_position[Z_AXIS] = true; enable_z(); - - SERIAL_ECHOPGM("recover_machine_state_after_power_panic, initial "); - print_physical_coordinates(); + // 6) Power up the Z motors, mark their positions as known. + axis_known_position[Z_AXIS] = true; + enable_z(); // 7) Recover the target temperatures. target_temperature[active_extruder] = eeprom_read_byte((uint8_t*)EEPROM_UVLO_TARGET_HOTEND); @@ -10867,9 +10893,11 @@ void recover_machine_state_after_power_panic(bool bTiny) #ifdef LIN_ADVANCE extruder_advance_K = eeprom_read_float((float*)EEPROM_UVLO_LA_K); #endif + + return mbl_was_active; } -void restore_print_from_eeprom() { +void restore_print_from_eeprom(bool mbl_was_active) { int feedrate_rec; int feedmultiply_rec; uint8_t fan_speed_rec; @@ -10910,17 +10938,23 @@ void restore_print_from_eeprom() { enquecommand(cmd); uint32_t position = eeprom_read_dword((uint32_t*)(EEPROM_FILE_POSITION)); SERIAL_ECHOPGM("Position read from eeprom:"); - MYSERIAL.println(position); - // Move to the XY print position in logical coordinates, where the print has been killed. - strcpy_P(cmd, PSTR("G1 X")); strcat(cmd, ftostr32(eeprom_read_float((float*)(EEPROM_UVLO_CURRENT_POSITION + 0)))); - strcat_P(cmd, PSTR(" Y")); strcat(cmd, ftostr32(eeprom_read_float((float*)(EEPROM_UVLO_CURRENT_POSITION + 4)))); - strcat_P(cmd, PSTR(" F2000")); + MYSERIAL.println(position); + + // Move to the XY print position in logical coordinates, where the print has been killed, but + // without shifting Z along the way. This requires performing the move without mbl. + sprintf_P(cmd, PSTR("G1 X%f Y%f F2000"), + eeprom_read_float((float*)(EEPROM_UVLO_CURRENT_POSITION + 0)), + eeprom_read_float((float*)(EEPROM_UVLO_CURRENT_POSITION + 4))); enquecommand(cmd); - //moving on Z axis ahead, set EEPROM_UVLO to 1, so normal uvlo can fire - eeprom_update_byte((uint8_t*)EEPROM_UVLO,1); - // Move the Z axis down to the print, in logical coordinates. - strcpy_P(cmd, PSTR("G1 Z")); strcat(cmd, ftostr32(eeprom_read_float((float*)(EEPROM_UVLO_CURRENT_POSITION_Z)))); + + // Enable MBL and switch to logical positioning + if (mbl_was_active) + enquecommand_P(PSTR("PRUSA MBL V1")); + + // Move the Z axis down to the print, in logical coordinates. + sprintf_P(cmd, PSTR("G1 Z%f"), eeprom_read_float((float*)(EEPROM_UVLO_CURRENT_POSITION_Z))); enquecommand(cmd); + // Unretract. sprintf_P(cmd, PSTR("G1 E%0.3f F2700"), default_retraction); enquecommand(cmd); diff --git a/Firmware/eeprom.h b/Firmware/eeprom.h index 5a9d7d81..c50dc94e 100644 --- a/Firmware/eeprom.h +++ b/Firmware/eeprom.h @@ -79,7 +79,7 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP #define EEPROM_FAN_CHECK_ENABLED (EEPROM_UVLO_FAN_SPEED - 1) #define EEPROM_UVLO_MESH_BED_LEVELING (EEPROM_FAN_CHECK_ENABLED - 9*2) -#define EEPROM_UVLO_Z_MICROSTEPS (EEPROM_UVLO_MESH_BED_LEVELING - 2) +#define EEPROM_UVLO_Z_MICROSTEPS (EEPROM_UVLO_MESH_BED_LEVELING - 2) // uint16_t (could be removed) #define EEPROM_UVLO_E_ABS (EEPROM_UVLO_Z_MICROSTEPS - 1) #define EEPROM_UVLO_CURRENT_POSITION_E (EEPROM_UVLO_E_ABS - 4) //float for current position in E @@ -167,7 +167,7 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP // #define EEPROM_UVLO_TINY_CURRENT_POSITION_Z (EEPROM_EXTRUDEMULTIPLY-4) // float -#define EEPROM_UVLO_TINY_Z_MICROSTEPS (EEPROM_UVLO_TINY_CURRENT_POSITION_Z-2) // uint16 +#define EEPROM_UVLO_TINY_Z_MICROSTEPS (EEPROM_UVLO_TINY_CURRENT_POSITION_Z-2) // uint16 (unused) // Sound Mode //#define EEPROM_SOUND_MODE (EEPROM_EXTRUDEMULTIPLY-1) // uint8 diff --git a/Firmware/variants/1_75mm_MK3-EINSy10a-E3Dv6full.h b/Firmware/variants/1_75mm_MK3-EINSy10a-E3Dv6full.h index 400d098f..53bfb4bf 100644 --- a/Firmware/variants/1_75mm_MK3-EINSy10a-E3Dv6full.h +++ b/Firmware/variants/1_75mm_MK3-EINSy10a-E3Dv6full.h @@ -618,6 +618,10 @@ // The following example, 12 * (4 * 16 / 400) = 12 * 0.16mm = 1.92mm. //#define UVLO_Z_AXIS_SHIFT 1.92 #define UVLO_Z_AXIS_SHIFT 0.64 +// When powered off during PP recovery, the Z axis position can still be re-adjusted. In this case +// we just need to shift to the nearest fullstep, but we need a move which is at least +// "dropsegments" steps long. All the above rules still need to apply. +#define UVLO_TINY_Z_AXIS_SHIFT 0.16 // If power panic occured, and the current temperature is higher then target temperature before interrupt minus this offset, print will be recovered automatically. #define AUTOMATIC_UVLO_BED_TEMP_OFFSET 5 diff --git a/Firmware/variants/1_75mm_MK3S-EINSy10a-E3Dv6full.h b/Firmware/variants/1_75mm_MK3S-EINSy10a-E3Dv6full.h index 48ed9139..253fe0ec 100644 --- a/Firmware/variants/1_75mm_MK3S-EINSy10a-E3Dv6full.h +++ b/Firmware/variants/1_75mm_MK3S-EINSy10a-E3Dv6full.h @@ -620,7 +620,11 @@ // The following example, 12 * (4 * 16 / 400) = 12 * 0.16mm = 1.92mm. //#define UVLO_Z_AXIS_SHIFT 1.92 #define UVLO_Z_AXIS_SHIFT 0.64 -// If power panic occured, and the current temperature is higher then target temperature before interrupt minus this offset, print will be recovered automatically. +// When powered off during PP recovery, the Z axis position can still be re-adjusted. In this case +// we just need to shift to the nearest fullstep, but we need a move which is at least +// "dropsegments" steps long. All the above rules still need to apply. +#define UVLO_TINY_Z_AXIS_SHIFT 0.16 +// If power panic occured, and the current temperature is higher then target temperature before interrupt minus this offset, print will be recovered automatically. #define AUTOMATIC_UVLO_BED_TEMP_OFFSET 5 #define HEATBED_V2 From 50a9fe003a5524cfae0023b605c96577831d2a1b Mon Sep 17 00:00:00 2001 From: Yuri D'Elia Date: Mon, 27 Jan 2020 11:08:28 +0100 Subject: [PATCH 032/158] Bump the unparking speed to 50mm/s (same as M600 recovery) --- 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 c2439d74..1d782194 100755 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -10942,7 +10942,7 @@ void restore_print_from_eeprom(bool mbl_was_active) { // Move to the XY print position in logical coordinates, where the print has been killed, but // without shifting Z along the way. This requires performing the move without mbl. - sprintf_P(cmd, PSTR("G1 X%f Y%f F2000"), + sprintf_P(cmd, PSTR("G1 X%f Y%f F3000"), eeprom_read_float((float*)(EEPROM_UVLO_CURRENT_POSITION + 0)), eeprom_read_float((float*)(EEPROM_UVLO_CURRENT_POSITION + 4))); enquecommand(cmd); From 5d8857371132b311c76d07c19be548a73281b8f0 Mon Sep 17 00:00:00 2001 From: Yuri D'Elia Date: Mon, 27 Jan 2020 14:59:18 +0100 Subject: [PATCH 033/158] Save/restore hotend temperatures above 255C in PowerPanic Use 2 bytes to store extruder temperature during UVLO. Re-use the storage of EEPROM_UVLO_TINY_Z_MICROSTEPS which has been freed by previous changes. Fixes #2303 --- Firmware/Marlin_main.cpp | 6 +++--- Firmware/eeprom.h | 10 ++++------ 2 files changed, 7 insertions(+), 9 deletions(-) diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index 1d782194..a204f9f0 100755 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -10505,7 +10505,7 @@ void uvlo_() // Stop all heaters uint8_t saved_target_temperature_bed = target_temperature_bed; - uint8_t saved_target_temperature_ext = target_temperature[active_extruder]; + uint16_t saved_target_temperature_ext = target_temperature[active_extruder]; setAllTargetHotends(0); setTargetBed(0); @@ -10605,7 +10605,7 @@ void uvlo_() // Store the current feed rate, temperatures, fan speed and extruder multipliers (flow rates) eeprom_update_word((uint16_t*)EEPROM_UVLO_FEEDRATE, feedrate_bckp); eeprom_update_word((uint16_t*)EEPROM_UVLO_FEEDMULTIPLY, feedmultiply); - eeprom_update_byte((uint8_t*)EEPROM_UVLO_TARGET_HOTEND, saved_target_temperature_ext); + eeprom_update_word((uint16_t*)EEPROM_UVLO_TARGET_HOTEND, saved_target_temperature_ext); eeprom_update_byte((uint8_t*)EEPROM_UVLO_TARGET_BED, saved_target_temperature_bed); eeprom_update_byte((uint8_t*)EEPROM_UVLO_FAN_SPEED, fanSpeed); eeprom_update_float((float*)(EEPROM_EXTRUDER_MULTIPLIER_0), extruder_multiplier[0]); @@ -10871,7 +10871,7 @@ bool recover_machine_state_after_power_panic() enable_z(); // 7) Recover the target temperatures. - target_temperature[active_extruder] = eeprom_read_byte((uint8_t*)EEPROM_UVLO_TARGET_HOTEND); + target_temperature[active_extruder] = eeprom_read_word((uint16_t*)EEPROM_UVLO_TARGET_HOTEND); target_temperature_bed = eeprom_read_byte((uint8_t*)EEPROM_UVLO_TARGET_BED); // 8) Recover extruder multipilers diff --git a/Firmware/eeprom.h b/Firmware/eeprom.h index c50dc94e..f0544f39 100644 --- a/Firmware/eeprom.h +++ b/Firmware/eeprom.h @@ -72,8 +72,8 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP #define EEPROM_FILENAME (EEPROM_UVLO_CURRENT_POSITION - 8) //8chars to store filename without extension #define EEPROM_FILE_POSITION (EEPROM_FILENAME - 4) //32 bit for uint32_t file position #define EEPROM_UVLO_CURRENT_POSITION_Z (EEPROM_FILE_POSITION - 4) //float for current position in Z -#define EEPROM_UVLO_TARGET_HOTEND (EEPROM_UVLO_CURRENT_POSITION_Z - 1) -#define EEPROM_UVLO_TARGET_BED (EEPROM_UVLO_TARGET_HOTEND - 1) +#define EEPROM_UVLO_UNUSED_001 (EEPROM_UVLO_CURRENT_POSITION_Z - 1) // uint8_t (unused) +#define EEPROM_UVLO_TARGET_BED (EEPROM_UVLO_UNUSED_001 - 1) #define EEPROM_UVLO_FEEDRATE (EEPROM_UVLO_TARGET_BED - 2) //uint16_t #define EEPROM_UVLO_FAN_SPEED (EEPROM_UVLO_FEEDRATE - 1) #define EEPROM_FAN_CHECK_ENABLED (EEPROM_UVLO_FAN_SPEED - 1) @@ -165,13 +165,11 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP #define EEPROM_EXTRUDER_MULTIPLIER_2 (EEPROM_EXTRUDER_MULTIPLIER_1 - 4) //float #define EEPROM_EXTRUDEMULTIPLY (EEPROM_EXTRUDER_MULTIPLIER_2 - 2) // uint16 -// #define EEPROM_UVLO_TINY_CURRENT_POSITION_Z (EEPROM_EXTRUDEMULTIPLY-4) // float -#define EEPROM_UVLO_TINY_Z_MICROSTEPS (EEPROM_UVLO_TINY_CURRENT_POSITION_Z-2) // uint16 (unused) +#define EEPROM_UVLO_TARGET_HOTEND (EEPROM_UVLO_TINY_CURRENT_POSITION_Z-2) // uint16 // Sound Mode -//#define EEPROM_SOUND_MODE (EEPROM_EXTRUDEMULTIPLY-1) // uint8 -#define EEPROM_SOUND_MODE (EEPROM_UVLO_TINY_Z_MICROSTEPS-1) // uint8 +#define EEPROM_SOUND_MODE (EEPROM_UVLO_TARGET_HOTEND-1) // uint8 #define EEPROM_AUTO_DEPLETE (EEPROM_SOUND_MODE-1) //bool #define EEPROM_FSENS_OQ_MEASS_ENABLED (EEPROM_AUTO_DEPLETE - 1) //bool From 3da20db02404f3654631bf99d8c4d8aea0e8c709 Mon Sep 17 00:00:00 2001 From: Yuri D'Elia Date: Mon, 27 Jan 2020 18:50:17 +0100 Subject: [PATCH 034/158] Really poweroff Z motors when PSU_Delta is defined enable/disable_z behave differently when PSU_Delta is defined. During powerpanic and kill however we do *really* need to save energy and poweroff the motors. Rename enable/disable_z as poweron/poweroff_z and define some aliases so that we can use the low-level function where needed. --- Firmware/Marlin.h | 35 +++++++++++++++++------------------ Firmware/Marlin_main.cpp | 8 ++++---- 2 files changed, 21 insertions(+), 22 deletions(-) diff --git a/Firmware/Marlin.h b/Firmware/Marlin.h index 58b3351d..a0b3c19b 100755 --- a/Firmware/Marlin.h +++ b/Firmware/Marlin.h @@ -146,40 +146,39 @@ void manage_inactivity(bool ignore_stepper_queue=false); #if defined(Z_ENABLE_PIN) && Z_ENABLE_PIN > -1 #if defined(Z_AXIS_ALWAYS_ON) #ifdef Z_DUAL_STEPPER_DRIVERS - #define enable_z() { WRITE(Z_ENABLE_PIN, Z_ENABLE_ON); WRITE(Z2_ENABLE_PIN, Z_ENABLE_ON); } - #define disable_z() { WRITE(Z_ENABLE_PIN,!Z_ENABLE_ON); WRITE(Z2_ENABLE_PIN,!Z_ENABLE_ON); axis_known_position[Z_AXIS] = false; } + #define poweron_z() { WRITE(Z_ENABLE_PIN, Z_ENABLE_ON); WRITE(Z2_ENABLE_PIN, Z_ENABLE_ON); } + #define poweroff_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 poweron_z() WRITE(Z_ENABLE_PIN, Z_ENABLE_ON) + #define poweroff_z() {} #endif #else #ifdef Z_DUAL_STEPPER_DRIVERS - #define enable_z() { WRITE(Z_ENABLE_PIN, Z_ENABLE_ON); WRITE(Z2_ENABLE_PIN, Z_ENABLE_ON); } - #define disable_z() { WRITE(Z_ENABLE_PIN,!Z_ENABLE_ON); WRITE(Z2_ENABLE_PIN,!Z_ENABLE_ON); axis_known_position[Z_AXIS] = false; } + #define poweron_z() { WRITE(Z_ENABLE_PIN, Z_ENABLE_ON); WRITE(Z2_ENABLE_PIN, Z_ENABLE_ON); } + #define poweroff_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() { WRITE(Z_ENABLE_PIN,!Z_ENABLE_ON); axis_known_position[Z_AXIS] = false; } + #define poweron_z() WRITE(Z_ENABLE_PIN, Z_ENABLE_ON) + #define poweroff_z() { WRITE(Z_ENABLE_PIN,!Z_ENABLE_ON); axis_known_position[Z_AXIS] = false; } #endif #endif #else - #define enable_z() {} - #define disable_z() {} + #define poweron_z() {} + #define poweroff_z() {} #endif -#ifdef PSU_Delta +#ifndef PSU_Delta + #define enable_z() poweron_z() + #define disable_z() poweroff_z() +#else void init_force_z(); void check_force_z(); - #undef disable_z - #define disable_z() disable_force_z() - void disable_force_z(); - #undef enable_z - #define enable_z() enable_force_z() void enable_force_z(); + void disable_force_z(); + #define enable_z() enable_force_z() + #define disable_z() disable_force_z() #endif // PSU_Delta - - //#if defined(Z_ENABLE_PIN) && Z_ENABLE_PIN > -1 //#ifdef Z_DUAL_STEPPER_DRIVERS //#define enable_z() { WRITE(Z_ENABLE_PIN, Z_ENABLE_ON); WRITE(Z2_ENABLE_PIN, Z_ENABLE_ON); } diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index a204f9f0..c80199a2 100755 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -9595,7 +9595,7 @@ void kill(const char *full_screen_message, unsigned char id) disable_x(); // SERIAL_ECHOLNPGM("kill - disable Y"); disable_y(); - disable_z(); + poweroff_z(); disable_e0(); disable_e1(); disable_e2(); @@ -10579,7 +10579,7 @@ void uvlo_() + UVLO_Z_AXIS_SHIFT; plan_buffer_line_curposXYZE(homing_feedrate[Z_AXIS]/60, active_extruder); st_synchronize(); - disable_z(); + poweroff_z(); // Write the file position. eeprom_update_dword((uint32_t*)(EEPROM_FILE_POSITION), sd_position); @@ -10638,7 +10638,7 @@ void uvlo_() WRITE(BEEPER,HIGH); // All is set: with all the juice left, try to move extruder away to detach the nozzle completely from the print - enable_z(); + poweron_z(); current_position[X_AXIS] = (current_position[X_AXIS] < 0.5f * (X_MIN_POS + X_MAX_POS)) ? X_MIN_POS : X_MAX_POS; plan_buffer_line_curposXYZE(500, active_extruder); st_synchronize(); @@ -10693,7 +10693,7 @@ void uvlo_tiny() + UVLO_TINY_Z_AXIS_SHIFT; plan_buffer_line_curposXYZE(homing_feedrate[Z_AXIS]/60, active_extruder); st_synchronize(); - disable_z(); + poweroff_z(); // Update Z position eeprom_update_float((float*)(EEPROM_UVLO_TINY_CURRENT_POSITION_Z), current_position[Z_AXIS]); From 3e70b73a1fb21f76267ffb68957656bee42cfccc Mon Sep 17 00:00:00 2001 From: DRracer Date: Mon, 27 Jan 2020 19:02:15 +0100 Subject: [PATCH 035/158] Remove unnecessary delay in lcd_selftest, which occured there as a result of merge. --- Firmware/ultralcd.cpp | 5 +---- 1 file changed, 1 insertion(+), 4 deletions(-) diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index 5d291f35..df9000c4 100755 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -7547,13 +7547,10 @@ bool lcd_selftest() #ifdef TMC2130 FORCE_HIGH_POWER_START; #endif // TMC2130 + FORCE_BL_ON_START; #if !IR_SENSOR_ANALOG _delay(2000); #endif //!IR_SENSOR_ANALOG - - FORCE_BL_ON_START; - - _delay(2000); KEEPALIVE_STATE(IN_HANDLER); #if IR_SENSOR_ANALOG bool bAction; From 200cdde1af99ffc3d3c981f6d431cf0bc936ca2d Mon Sep 17 00:00:00 2001 From: Yuri D'Elia Date: Tue, 28 Jan 2020 21:50:12 +0100 Subject: [PATCH 036/158] Setup the UVLO interrupt later during initialization Do not allow uvlo_tiny() to trigger before the previous print has already been recovered. A quick repeated power failure could cause uvlo_tiny to overwrite the Z position before it has been correctly recovered. --- Firmware/Marlin_main.cpp | 12 +++++------- 1 file changed, 5 insertions(+), 7 deletions(-) diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index c80199a2..fbfb39f2 100755 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -1298,10 +1298,6 @@ void setup() st_init(); // Initialize stepper, this enables interrupts! -#ifdef UVLO_SUPPORT - setup_uvlo_interrupt(); -#endif //UVLO_SUPPORT - #ifdef TMC2130 tmc2130_mode = silentMode?TMC2130_MODE_SILENT:TMC2130_MODE_NORMAL; update_mode_profile(); @@ -1596,12 +1592,14 @@ void setup() lcd_update(2); lcd_setstatuspgm(_T(WELCOME_MSG)); } - } - - } + + // Only arm the uvlo interrupt _after_ a recovering print has been initialized and + // the entire state machine initialized. + setup_uvlo_interrupt(); #endif //UVLO_SUPPORT + fCheckModeInit(); fSetMmuMode(mmu_enabled); KEEPALIVE_STATE(NOT_BUSY); From b46dc59fad9bf26534ac8e9d40e17c4404b2362d Mon Sep 17 00:00:00 2001 From: Yuri D'Elia Date: Wed, 29 Jan 2020 16:06:54 +0100 Subject: [PATCH 037/158] Refuse to start a print if power is lost before arming uvlo If power has been lost during startup already a falling edge would be skipped, causing the print to continue and lose its state without being able to save again. Check for a low line after arming the interrupt and simply wait for reset. --- Firmware/Marlin_main.cpp | 25 ++++++++++++++++++------- 1 file changed, 18 insertions(+), 7 deletions(-) diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index fbfb39f2..5eb8d48b 100755 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -10480,6 +10480,14 @@ void serialecho_temperatures() { } #ifdef UVLO_SUPPORT +void uvlo_drain_reset() +{ + // burn all that residual power + wdt_enable(WDTO_1S); + WRITE(BEEPER,HIGH); + while(1); +} + void uvlo_() { @@ -10709,11 +10717,7 @@ void uvlo_tiny() eeprom_update_word((uint16_t*)EEPROM_POWER_COUNT_TOT, eeprom_read_word((uint16_t*)EEPROM_POWER_COUNT_TOT) + 1); printf_P(_N("UVLO_TINY - end %d\n"), _millis() - time_start); - - // burn all that residual power - wdt_enable(WDTO_1S); - WRITE(BEEPER,HIGH); - while(1); + uvlo_drain_reset(); } #endif //UVLO_SUPPORT @@ -10760,12 +10764,19 @@ void setup_uvlo_interrupt() { DDRE &= ~(1 << 4); //input pin PORTE &= ~(1 << 4); //no internal pull-up - //sensing falling edge + // sensing falling edge EICRB |= (1 << 0); EICRB &= ~(1 << 1); - //enable INT4 interrupt + // enable INT4 interrupt EIMSK |= (1 << 4); + + // check if power was lost before we armed the interrupt + if(!(PINE & (1 << 4))) + { + SERIAL_ECHOLNPGM("INT4"); + uvlo_drain_reset(); + } } ISR(INT4_vect) { From 4fd913ddf3f7170456cbdf195c332a75f8f2012f Mon Sep 17 00:00:00 2001 From: Alex Voinea Date: Wed, 29 Jan 2020 17:45:47 +0200 Subject: [PATCH 038/158] Remove commented out code --- Firmware/Marlin_main.cpp | 4 ---- 1 file changed, 4 deletions(-) diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index 70cbd6d7..1dc45eab 100755 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -11563,8 +11563,6 @@ if(!(bEnableForce_z||eeprom_read_byte((uint8_t*)EEPROM_SILENT))) void disable_force_z() { - // uint16_t z_microsteps=0; - if(!bEnableForce_z) return; // motor already disabled (may be ;-p ) bEnableForce_z=false; @@ -11575,8 +11573,6 @@ void disable_force_z() update_mode_profile(); tmc2130_init(true); #endif // TMC2130 - - // axis_known_position[Z_AXIS]=false; } From 2b46fdac2d0251041cb89f96ae16e7e19e17473c Mon Sep 17 00:00:00 2001 From: Yuri D'Elia Date: Wed, 29 Jan 2020 17:56:26 +0100 Subject: [PATCH 039/158] Only trigger a quick reset if there's a pending saved state Thanks to @leptun --- 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 5eb8d48b..169effb8 100755 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -10772,7 +10772,7 @@ void setup_uvlo_interrupt() { EIMSK |= (1 << 4); // check if power was lost before we armed the interrupt - if(!(PINE & (1 << 4))) + if(!(PINE & (1 << 4)) && eeprom_read_byte((uint8_t*)EEPROM_UVLO)) { SERIAL_ECHOLNPGM("INT4"); uvlo_drain_reset(); From 02d1525445b81002cc591738d69cbdb05988ee18 Mon Sep 17 00:00:00 2001 From: Yuri D'Elia Date: Wed, 29 Jan 2020 21:08:56 +0100 Subject: [PATCH 040/158] Display "POWER PANIC DETECTED" when possible Both during early init and in uvlo_tiny, display "POWER PANIC DETECTED" if enough charge is left. This is not worth doing in regular uvlo_, as we want to give full priority to the X motor --- Firmware/Marlin_main.cpp | 2 ++ Firmware/messages.c | 1 + Firmware/messages.h | 1 + 3 files changed, 4 insertions(+) diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index 169effb8..20a269af 100755 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -10485,6 +10485,8 @@ void uvlo_drain_reset() // burn all that residual power wdt_enable(WDTO_1S); WRITE(BEEPER,HIGH); + lcd_clear(); + lcd_puts_at_P(0, 1, MSG_POWERPANIC_DETECTED); while(1); } diff --git a/Firmware/messages.c b/Firmware/messages.c index 68bad5ff..2b113673 100644 --- a/Firmware/messages.c +++ b/Firmware/messages.c @@ -171,3 +171,4 @@ const char MSG_M112_KILL[] PROGMEM_N1 = "M112 called. Emergency Stop."; ////c=20 #ifdef LA_LIVE_K const char MSG_ADVANCE_K[] PROGMEM_N1 = "Advance K:"; ////c=13 #endif +const char MSG_POWERPANIC_DETECTED[] PROGMEM_N1 = "POWER PANIC DETECTED"; ////c=20 diff --git a/Firmware/messages.h b/Firmware/messages.h index 678524ab..7cc240d3 100644 --- a/Firmware/messages.h +++ b/Firmware/messages.h @@ -170,6 +170,7 @@ extern const char MSG_FANCHECK_EXTRUDER[]; extern const char MSG_FANCHECK_PRINT[]; extern const char MSG_M112_KILL[]; extern const char MSG_ADVANCE_K[]; +extern const char MSG_POWERPANIC_DETECTED[]; #if defined(__cplusplus) } From a5198e32a3d041024fbf327d0e380bbd69543a5f Mon Sep 17 00:00:00 2001 From: Alex Voinea Date: Wed, 29 Jan 2020 22:44:19 +0200 Subject: [PATCH 041/158] Just keep the current state. ON or OFF. No switching allowed --- Firmware/heatbed_pwm.cpp | 16 ++++++---------- 1 file changed, 6 insertions(+), 10 deletions(-) diff --git a/Firmware/heatbed_pwm.cpp b/Firmware/heatbed_pwm.cpp index 1e467c4e..612cf3c8 100755 --- a/Firmware/heatbed_pwm.cpp +++ b/Firmware/heatbed_pwm.cpp @@ -139,19 +139,15 @@ ISR(TIMER0_OVF_vect) // timer compare interrupt service routine break; case States::ONE: // state ONE - we'll either stay in ONE or change to FALL OCR0B = 255; + if (bedPWMDisabled) return; slowCounter += slowInc; // this does software timer_clk/256 or less - if (!bedPWMDisabled){ //disable heating as soon as possible - if( slowCounter < pwm ){ - return; - } - if( (soft_pwm_bed << 1) >= (255 - slowInc - 1) ){ //@@TODO simplify & explain - // if slowInc==2, soft_pwm == 251 will be the first to do short drops to zero. 252 will keep full heating - return; // want full duty for the next ONE cycle again - so keep on heating and just wait for the next timer ovf - } - } - else if (pwm > 200){ //if duty cycle is high and BED PWM is disabled keep heater on. Prevents overcooling + if( slowCounter < pwm ){ return; } + if( (soft_pwm_bed << 1) >= (255 - slowInc - 1) ){ //@@TODO simplify & explain + // if slowInc==2, soft_pwm == 251 will be the first to do short drops to zero. 252 will keep full heating + return; // want full duty for the next ONE cycle again - so keep on heating and just wait for the next timer ovf + } // otherwise moving towards FALL // @@TODO it looks like ONE_TO_FALL isn't necessary, there are no artefacts at all state = States::ONE;//_TO_FALL; From 755230e2e750880de393586946dfa0c26a15737c Mon Sep 17 00:00:00 2001 From: Alex Voinea Date: Wed, 29 Jan 2020 22:47:28 +0200 Subject: [PATCH 042/158] fix small mistake --- Firmware/heatbed_pwm.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Firmware/heatbed_pwm.cpp b/Firmware/heatbed_pwm.cpp index 612cf3c8..4552bf96 100755 --- a/Firmware/heatbed_pwm.cpp +++ b/Firmware/heatbed_pwm.cpp @@ -95,7 +95,7 @@ ISR(TIMER0_OVF_vect) // timer compare interrupt service routine { switch(state){ case States::ZERO_START: - if (bedPWMDisabled) break; + if (bedPWMDisabled) return; pwm = soft_pwm_bed << 1;// expecting soft_pwm_bed to be 7bit! if( pwm != 0 ){ state = States::ZERO; // do nothing, let it tick once again after the 30Hz period From b86aafb56e2dd3b2ec162b7130ec28890ec908f4 Mon Sep 17 00:00:00 2001 From: Alex Voinea Date: Wed, 29 Jan 2020 23:03:20 +0200 Subject: [PATCH 043/158] Documentation --- Firmware/heatbed_pwm.cpp | 10 ++++++++-- 1 file changed, 8 insertions(+), 2 deletions(-) diff --git a/Firmware/heatbed_pwm.cpp b/Firmware/heatbed_pwm.cpp index 4552bf96..e8551501 100755 --- a/Firmware/heatbed_pwm.cpp +++ b/Firmware/heatbed_pwm.cpp @@ -45,6 +45,12 @@ // If there are any change requirements in the future, the signal must be checked with an osciloscope again, // ad-hoc changes may completely screw things up! +// 2020-01-29 update: we are introducing a new option to the automaton that will allow us to force the output state +// to either full ON or OFF. This is so that interference during the MBL probing is minimal. +// To accomplish this goal we use bedPWMDisabled. It is only supposed to be used for brief periods of time as to +// not make the bed temperature too unstable. Also, careful consideration should be used when using this +// option as leaving this enabled will also keep the bed output in the state it stopped in. + ///! Definition off finite automaton states enum class States : uint8_t { ZERO_START = 0,///< entry point of the automaton - reads the soft_pwm_bed value for the next whole PWM cycle @@ -95,7 +101,7 @@ ISR(TIMER0_OVF_vect) // timer compare interrupt service routine { switch(state){ case States::ZERO_START: - if (bedPWMDisabled) return; + if (bedPWMDisabled) return; // stay in the OFF state and do not change the output pin pwm = soft_pwm_bed << 1;// expecting soft_pwm_bed to be 7bit! if( pwm != 0 ){ state = States::ZERO; // do nothing, let it tick once again after the 30Hz period @@ -139,7 +145,7 @@ ISR(TIMER0_OVF_vect) // timer compare interrupt service routine break; case States::ONE: // state ONE - we'll either stay in ONE or change to FALL OCR0B = 255; - if (bedPWMDisabled) return; + if (bedPWMDisabled) return; // stay in the ON state and do not change the output pin slowCounter += slowInc; // this does software timer_clk/256 or less if( slowCounter < pwm ){ return; From 8c2902a6605cacbc35232b3f6f1c49f9ca12a20f Mon Sep 17 00:00:00 2001 From: leptun Date: Wed, 2 Oct 2019 17:34:09 +0300 Subject: [PATCH 044/158] Revert "Mesh bed leveling testing" This reverts commit 28e812d91fe2b4633c9427abdf554e5a9449dd17. --- Firmware/Marlin_main.cpp | 10 +++++++--- Firmware/mesh_bed_calibration.cpp | 8 ++++---- 2 files changed, 11 insertions(+), 7 deletions(-) diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index e14dd2e3..fbfb39f2 100755 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -4973,7 +4973,11 @@ if(eSoundMode!=e_SOUND_MODE_SILENT) z_offset_u = eeprom_read_word((uint16_t*)(EEPROM_BED_CALIBRATION_Z_JITTER + 2 * (ix + iy * 3 - 1))); } z0 = mbl.z_values[0][0] + *reinterpret_cast(&z_offset_u) * 0.01; - // printf_P(PSTR("Bed leveling, point: %d, calibration Z stored in eeprom: %d, calibration z: %f \n"), mesh_point, z_offset_u, z0); + #ifdef SUPPORT_VERBOSITY + if (verbosity_level >= 1) { + printf_P(PSTR("Bed leveling, point: %d, calibration Z stored in eeprom: %d, calibration z: %f \n"), mesh_point, z_offset_u, z0); + } + #endif // SUPPORT_VERBOSITY } // Move Z up to MESH_HOME_Z_SEARCH. @@ -5000,7 +5004,7 @@ if(eSoundMode!=e_SOUND_MODE_SILENT) world2machine_clamp(current_position[X_AXIS], current_position[Y_AXIS]); #endif // SUPPORT_VERBOSITY - printf_P(PSTR("after clamping: [%f;%f]\n"), current_position[X_AXIS], current_position[Y_AXIS]); + //printf_P(PSTR("after clamping: [%f;%f]\n"), current_position[X_AXIS], current_position[Y_AXIS]); plan_buffer_line_curposXYZE(XY_AXIS_FEEDRATE, active_extruder); st_synchronize(); @@ -5011,7 +5015,7 @@ if(eSoundMode!=e_SOUND_MODE_SILENT) break; } if (init_z_bckp - current_position[Z_AXIS] < 0.1f) { //broken cable or initial Z coordinate too low. Go to MESH_HOME_Z_SEARCH and repeat last step (z-probe) again to distinguish between these two cases. - printf_P(PSTR("Another attempt! Current Z position: %f\n"), current_position[Z_AXIS]); + //printf_P(PSTR("Another attempt! Current Z position: %f\n"), current_position[Z_AXIS]); current_position[Z_AXIS] = MESH_HOME_Z_SEARCH; plan_buffer_line_curposXYZE(Z_LIFT_FEEDRATE, active_extruder); st_synchronize(); diff --git a/Firmware/mesh_bed_calibration.cpp b/Firmware/mesh_bed_calibration.cpp index fed100e6..88cbc671 100644 --- a/Firmware/mesh_bed_calibration.cpp +++ b/Firmware/mesh_bed_calibration.cpp @@ -991,7 +991,7 @@ inline bool find_bed_induction_sensor_point_z(float minimum_z, uint8_t n_iter, i update_current_position_z(); //printf_P(PSTR("Zs: %f, Z: %f, delta Z: %f"), z_bckp, current_position[Z_AXIS], (z_bckp - current_position[Z_AXIS])); if (abs(current_position[Z_AXIS] - z_bckp) < 0.025) { - printf_P(PSTR("PINDA triggered immediately, move Z higher and repeat measurement\n")); + //printf_P(PSTR("PINDA triggered immediately, move Z higher and repeat measurement\n")); current_position[Z_AXIS] += 0.5; go_to_current(homing_feedrate[Z_AXIS]/60); current_position[Z_AXIS] = minimum_z; @@ -1019,10 +1019,10 @@ inline bool find_bed_induction_sensor_point_z(float minimum_z, uint8_t n_iter, i float dz = i?abs(current_position[Z_AXIS] - (z / i)):0; z += current_position[Z_AXIS]; //printf_P(PSTR("Z[%d] = %d, dz=%d\n"), i, (int)(current_position[Z_AXIS] * 1000), (int)(dz * 1000)); - printf_P(PSTR("Z- measurement deviation from avg value %f um\n"), dz); + //printf_P(PSTR("Z- measurement deviation from avg value %f um\n"), dz); if (dz > 0.05) { //deviation > 50um if (high_deviation_occured == false) { //first occurence may be caused in some cases by mechanic resonance probably especially if printer is placed on unstable surface - printf_P(PSTR("high dev. first occurence\n")); + //printf_P(PSTR("high dev. first occurence\n")); delay_keep_alive(500); //damping //start measurement from the begining, but this time with higher movements in Z axis which should help to reduce mechanical resonance high_deviation_occured = true; @@ -1033,7 +1033,7 @@ inline bool find_bed_induction_sensor_point_z(float minimum_z, uint8_t n_iter, i goto error; } } - printf_P(PSTR("PINDA triggered at %f\n"), current_position[Z_AXIS]); + //printf_P(PSTR("PINDA triggered at %f\n"), current_position[Z_AXIS]); } current_position[Z_AXIS] = z; if (n_iter > 1) From 571906a494ac07d3450854b15b3068ecc5eb0655 Mon Sep 17 00:00:00 2001 From: Yuri D'Elia Date: Tue, 28 Jan 2020 21:55:16 +0100 Subject: [PATCH 045/158] Do not update saved_target if there's no current_block There is a chance that current_block can be NULL despite the queue being non-empty. This can happen early after a block has been queued, but before the isr has picked it up for processing, and/or when the current block is at the last step and is being discarded. Check for current_block directly to avoid this race. --- 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 20a269af..9d00d42b 100755 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -10529,7 +10529,7 @@ void uvlo_() // save the global state at planning time uint16_t feedrate_bckp; - if (blocks_queued()) + if (current_block) { memcpy(saved_target, current_block->gcode_target, sizeof(saved_target)); feedrate_bckp = current_block->gcode_feedrate; @@ -11129,7 +11129,7 @@ void stop_and_save_print_to_ram(float z_move, float e_move) #endif // save the global state at planning time - if (blocks_queued()) + if (current_block) { memcpy(saved_target, current_block->gcode_target, sizeof(saved_target)); saved_feedrate2 = current_block->gcode_feedrate; From 1db024f17af6ed22f7836ebb553f6b7fe5215227 Mon Sep 17 00:00:00 2001 From: Yuri D'Elia Date: Tue, 28 Jan 2020 22:03:38 +0100 Subject: [PATCH 046/158] Always raise the extruder 25mm during power recovery Avoids oozed material (drooping more than ~1mm) to scrape and potentially detach the print. --- Firmware/Marlin_main.cpp | 11 +++++++---- 1 file changed, 7 insertions(+), 4 deletions(-) diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index 9d00d42b..abd4c368 100755 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -10798,10 +10798,13 @@ void recover_print(uint8_t automatic) { // Recover position, temperatures and extrude_multipliers bool mbl_was_active = recover_machine_state_after_power_panic(); - // Attempt to lift the print head on the first recovery, so one may remove the excess priming material. - bool raise_z = (eeprom_read_byte((uint8_t*)EEPROM_UVLO) == 1); - if(raise_z && (current_position[Z_AXIS]<25)) - enquecommand_P(PSTR("G1 Z25 F800")); + // Lift the print head 25mm, first to avoid collisions with oozed material with the print, + // and second also so one may remove the excess priming material. + if(eeprom_read_byte((uint8_t*)EEPROM_UVLO) == 1) + { + sprintf_P(cmd, PSTR("G1 Z%.3f F800"), current_position[Z_AXIS] + 25); + enquecommand(cmd); + } // Home X and Y axes. Homing just X and Y shall not touch the babystep and the world2machine // transformation status. G28 will not touch Z when MBL is off. From 886c2fdc4ebf18c9ca175068525fa4218c5637e4 Mon Sep 17 00:00:00 2001 From: Alex Voinea Date: Thu, 30 Jan 2020 17:24:32 +0200 Subject: [PATCH 047/158] Show correct fixed message --- Firmware/temperature.cpp | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/Firmware/temperature.cpp b/Firmware/temperature.cpp index 17512254..7517978b 100755 --- a/Firmware/temperature.cpp +++ b/Firmware/temperature.cpp @@ -2003,6 +2003,8 @@ void check_max_temp() //! number of repeating the same state with consecutive step() calls //! used to slow down text switching struct alert_automaton_mintemp { + const char *m2; + alert_automaton_mintemp(const char *m2):m2(m2){} private: enum { ALERT_AUTOMATON_SPEED_DIV = 5 }; enum class States : uint8_t { Init = 0, TempAboveMintemp, ShowPleaseRestart, ShowMintemp }; @@ -2022,7 +2024,6 @@ public: //! @param current_temp current hotend/bed temperature (for computing simple hysteresis) //! @param mintemp minimal temperature including hysteresis to check current_temp against void step(float current_temp, float mintemp){ - static const char m2[] PROGMEM = "MINTEMP fixed"; static const char m1[] PROGMEM = "Please restart"; switch(state){ case States::Init: // initial state - check hysteresis @@ -2050,8 +2051,9 @@ public: } } }; - -static alert_automaton_mintemp alert_automaton_hotend, alert_automaton_bed; +static const char m2hotend[] PROGMEM = "MINTEMP HEATER fixed"; +static const char m2bed[] PROGMEM = "MINTEMP BED fixed"; +static alert_automaton_mintemp alert_automaton_hotend(m2hotend), alert_automaton_bed(m2bed); void check_min_temp_heater0() { From 857f9d8d9e6f707b41888be0d221de5a80cae697 Mon Sep 17 00:00:00 2001 From: 3d-gussner <3d.gussner@gmail.com> Date: Fri, 31 Jan 2020 14:47:44 +0100 Subject: [PATCH 048/158] Hard reset and readded change --- Firmware/language.h | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/Firmware/language.h b/Firmware/language.h index 36c18dba..1e4137bf 100644 --- a/Firmware/language.h +++ b/Firmware/language.h @@ -6,7 +6,9 @@ #include "config.h" #include -//#include +#ifdef DEBUG_SEC_LANG + #include +#endif //DEBUG_SEC_LANG #define PROTOCOL_VERSION "1.0" From 84ecf96be50a3af450bff5d506962ef0a0158f57 Mon Sep 17 00:00:00 2001 From: Yuri D'Elia Date: Fri, 31 Jan 2020 15:08:24 +0100 Subject: [PATCH 049/158] Do not clear last print fail stats prematurely M24 was always cleaning the last print failstats. But because M24 is used to restore a print after power failure (by setting the seek offset), it would also reset the stats incorrectly after resuming. Check for the file index position and reset the stats only when a print is started from the beginning of the file. Apply the same logic to M32 and similarly handle the LA10->15 conversion (do not re-apply the adjustment for a resumed print). --- Firmware/Marlin_main.cpp | 24 ++++++++++++++++++------ 1 file changed, 18 insertions(+), 6 deletions(-) diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index cd4ee63f..62f93fae 100755 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -5576,10 +5576,15 @@ if(eSoundMode!=e_SOUND_MODE_SILENT) lcd_resume_print(); else { - failstats_reset_print(); + if (!card.get_sdpos()) + { + // A new print has started from scratch, reset stats + failstats_reset_print(); #ifndef LA_NOCOMPAT - la10c_reset(); + la10c_reset(); #endif + } + card.startFileprint(); starttime=_millis(); } @@ -5689,12 +5694,19 @@ if(eSoundMode!=e_SOUND_MODE_SILENT) if(code_seen('S')) if(strchr_pointer Date: Fri, 31 Jan 2020 15:27:19 +0100 Subject: [PATCH 050/158] Fix copy paste issues D2 D5 Fixed copy paste --- Firmware/Dcodes.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Firmware/Dcodes.cpp b/Firmware/Dcodes.cpp index 0a514262..ee62087d 100644 --- a/Firmware/Dcodes.cpp +++ b/Firmware/Dcodes.cpp @@ -255,7 +255,7 @@ void dcode_1() ### D2 - Read/Write RAM D3: Read/Write RAM This command can be used without any additional parameters. It will read the entire RAM. - D3 [ A | C | X ] + D2 [ A | C | X ] - `A` - Address (0x0000-0x1fff) - `C` - Count (0x0001-0x2000) @@ -355,7 +355,7 @@ void dcode_4() ### D5 - Read/Write FLASH D5: Read/Write Flash This command can be used without any additional parameters. It will read the 1kb FLASH. - D3 [ A | C | X | E ] + D5 [ A | C | X | E ] - `A` - Address (0x00000-0x3ffff) - `C` - Count (0x0001-0x2000) From a355fdd00d8a3287144d09056c45df94b5043b72 Mon Sep 17 00:00:00 2001 From: 3d-gussner <3d.gussner@gmail.com> Date: Fri, 31 Jan 2020 15:40:07 +0100 Subject: [PATCH 051/158] And another one sorry --- Firmware/Dcodes.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Firmware/Dcodes.cpp b/Firmware/Dcodes.cpp index ee62087d..70ffe2c4 100644 --- a/Firmware/Dcodes.cpp +++ b/Firmware/Dcodes.cpp @@ -252,7 +252,7 @@ void dcode_1() /*! * - ### D2 - Read/Write RAM D3: Read/Write RAM + ### D2 - Read/Write RAM D2: Read/Write RAM This command can be used without any additional parameters. It will read the entire RAM. D2 [ A | C | X ] From fd42361236060319313f56a3a02652a7726baff2 Mon Sep 17 00:00:00 2001 From: DRracer Date: Fri, 31 Jan 2020 16:55:40 +0100 Subject: [PATCH 052/158] Update ultralcd.cpp do delay(2000) everytime, even if IR_SENSOR_ANALOG --- Firmware/ultralcd.cpp | 2 -- 1 file changed, 2 deletions(-) diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index dc93fe53..1045f831 100755 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -7554,9 +7554,7 @@ bool lcd_selftest() FORCE_HIGH_POWER_START; #endif // TMC2130 FORCE_BL_ON_START; -#if !IR_SENSOR_ANALOG _delay(2000); -#endif //!IR_SENSOR_ANALOG KEEPALIVE_STATE(IN_HANDLER); _progress = lcd_selftest_screen(TestScreen::ExtruderFan, _progress, 3, true, 2000); From d6522a643c3a9169681f6a345645942e752543ef Mon Sep 17 00:00:00 2001 From: DRracer Date: Fri, 31 Jan 2020 16:57:18 +0100 Subject: [PATCH 053/158] Update ultralcd.cpp indent --- Firmware/ultralcd.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index 1045f831..03a1d44a 100755 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -7554,7 +7554,7 @@ bool lcd_selftest() FORCE_HIGH_POWER_START; #endif // TMC2130 FORCE_BL_ON_START; - _delay(2000); + _delay(2000); KEEPALIVE_STATE(IN_HANDLER); _progress = lcd_selftest_screen(TestScreen::ExtruderFan, _progress, 3, true, 2000); From 3bbc14382103e711f6b5b304e7522f25aeb85f28 Mon Sep 17 00:00:00 2001 From: Yuri D'Elia Date: Sun, 2 Feb 2020 18:01:06 +0100 Subject: [PATCH 054/158] Fix build with LA_LIVE_K Do not check for LA_LIVE_K in messages.c (Configuration_adv.h is not included here). Rely on the linker to drop the symbol when LA_LIVE_K is disabled. --- Firmware/messages.c | 2 -- 1 file changed, 2 deletions(-) diff --git a/Firmware/messages.c b/Firmware/messages.c index 2b113673..4e229ba7 100644 --- a/Firmware/messages.c +++ b/Firmware/messages.c @@ -168,7 +168,5 @@ const char MSG_OCTOPRINT_CANCEL[] PROGMEM_N1 = "// action:cancel"; //// const char MSG_FANCHECK_EXTRUDER[] PROGMEM_N1 = "Err: EXTR. FAN ERROR"; ////c=20 const char MSG_FANCHECK_PRINT[] PROGMEM_N1 = "Err: PRINT FAN ERROR"; ////c=20 const char MSG_M112_KILL[] PROGMEM_N1 = "M112 called. Emergency Stop."; ////c=20 -#ifdef LA_LIVE_K const char MSG_ADVANCE_K[] PROGMEM_N1 = "Advance K:"; ////c=13 -#endif const char MSG_POWERPANIC_DETECTED[] PROGMEM_N1 = "POWER PANIC DETECTED"; ////c=20 From 47db75d5fda29dabf2f6b8749c3180677fb99ca5 Mon Sep 17 00:00:00 2001 From: Yuri D'Elia Date: Sun, 2 Feb 2020 18:02:57 +0100 Subject: [PATCH 055/158] Fix overflow and infloop with LA15 and low step rates When calculating the advance tick interval, be sure to check for integer overflow. Very low step rates can result in values exceeding uint16_t causing premature LA tick delivery. An overflow resulting in zero would also block in an infinite loop within advance_spread(). Even though such rates are worthless in terms of compensation and often result in 0 extra ticks as well, do not disable LA for the block (as doing so would reset the count for short segments) and do not check for zero in multiple paces either. Saturate the interval instead, delaying any further tick to the next block. --- Firmware/planner.cpp | 17 ++++++++++++----- 1 file changed, 12 insertions(+), 5 deletions(-) diff --git a/Firmware/planner.cpp b/Firmware/planner.cpp index 197b3d9f..57d7b89b 100644 --- a/Firmware/planner.cpp +++ b/Firmware/planner.cpp @@ -1137,17 +1137,24 @@ Having the real displacement of the head, we can calculate the total movement le // still need to replicate the *exact* same step grouping policy (see below) float advance_speed = (extruder_advance_K * e_D_ratio * block->acceleration * cs.axis_steps_per_unit[E_AXIS]); if (advance_speed > MAX_STEP_FREQUENCY) advance_speed = MAX_STEP_FREQUENCY; - block->advance_rate = (F_CPU / 8.0) / advance_speed; - if (block->advance_rate > 20000) { - block->advance_rate = (block->advance_rate >> 2)&0x3fff; + float advance_rate = (F_CPU / 8.0) / advance_speed; + if (advance_speed > 20000) { + block->advance_rate = advance_rate * 4; block->advance_step_loops = 4; } - else if (block->advance_rate > 10000) { - block->advance_rate = (block->advance_rate >> 1)&0x7fff; + else if (advance_speed > 10000) { + block->advance_rate = advance_rate * 2; block->advance_step_loops = 2; } else + { + // never overflow the internal accumulator with very low rates + if (advance_rate < UINT16_MAX) + block->advance_rate = advance_rate; + else + block->advance_rate = UINT16_MAX; block->advance_step_loops = 1; + } #ifdef LA_DEBUG if (block->advance_step_loops > 2) From 4b85664b27abacbfe89ada22c2b54b0bd1abd526 Mon Sep 17 00:00:00 2001 From: Yuri D'Elia Date: Mon, 3 Feb 2020 14:28:54 +0100 Subject: [PATCH 056/158] Raise default extruder jerk to 4.5 This should be the new default for LA1.5 for direct drive printers and newer PrusaSlicer profiles too (hopefully). --- Firmware/Configuration.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Firmware/Configuration.h b/Firmware/Configuration.h index 2f2ea7d8..694247fb 100644 --- a/Firmware/Configuration.h +++ b/Firmware/Configuration.h @@ -424,7 +424,7 @@ your extruder heater takes 2 minutes to hit the target on heating. #define DEFAULT_XJERK 10 // (mm/sec) #define DEFAULT_YJERK 10 // (mm/sec) #define DEFAULT_ZJERK 0.4 // (mm/sec) -#define DEFAULT_EJERK 2.5 // (mm/sec) +#define DEFAULT_EJERK 4.5 // (mm/sec) //=========================================================================== //=============================Additional Features=========================== From 453f5dd8744383c2d1481228db91099037b103fe Mon Sep 17 00:00:00 2001 From: Yuri D'Elia Date: Mon, 3 Feb 2020 15:37:11 +0100 Subject: [PATCH 057/158] Adjust E-jerk in LA10 compatibility mode When upgrading K values of a LA1.0 print, also adjust E-jerk settings (<2) if permissible according to current accell limits. The same is also true when jerk is set mid-print via 'M205 E'. Existing values are always restored when switching to another compatibility mode. TODO: Since this is stateful, we will need to save the current print mode / acceleration and jerk in the eeprom for this to survive a power panic (see prusa3d#2456). --- Firmware/Marlin_main.cpp | 14 +++++++++++--- Firmware/la10compat.cpp | 42 +++++++++++++++++++++++++++++++++++++++- Firmware/la10compat.h | 9 ++++++++- 3 files changed, 60 insertions(+), 5 deletions(-) diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index cd4ee63f..92f3bd30 100755 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -7075,9 +7075,17 @@ Sigma_Exit: 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; + if(code_seen('E')) + { + float e = code_value(); +#ifndef LA_NOCOMPAT + + e = la10c_jerk(e); +#endif + cs.max_jerk[E_AXIS] = e; + } + 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; diff --git a/Firmware/la10compat.cpp b/Firmware/la10compat.cpp index d54e5ace..5b851bc3 100644 --- a/Firmware/la10compat.cpp +++ b/Firmware/la10compat.cpp @@ -2,13 +2,24 @@ #include "Marlin.h" -static LA10C_MODE la10c_mode = LA10C_UNKNOWN; +static LA10C_MODE la10c_mode = LA10C_UNKNOWN; // Current LA compatibility mode +static float la10c_orig_jerk = 0; // Unadjusted/saved e-jerk + + +LA10C_MODE la10c_mode_get() +{ + return la10c_mode; +} void la10c_mode_change(LA10C_MODE mode) { if(mode == la10c_mode) return; + // always restore to the last unadjusted E-jerk value + if(la10c_orig_jerk) + cs.max_jerk[E_AXIS] = la10c_orig_jerk; + SERIAL_ECHOPGM("LA10C: Linear Advance mode: "); switch(mode) { @@ -17,6 +28,9 @@ void la10c_mode_change(LA10C_MODE mode) case LA10C_LA10: SERIAL_ECHOLNPGM("1.0"); break; } la10c_mode = mode; + + // adjust the E-jerk if needed + cs.max_jerk[E_AXIS] = la10c_jerk(cs.max_jerk[E_AXIS]); } @@ -46,3 +60,29 @@ float la10c_value(float k) else return (k >= 0? la10c_convert(k): -1); } + + +float la10c_jerk(float j) +{ + la10c_orig_jerk = j; + + if(la10c_mode != LA10C_LA10) + return j; + + // check for a compatible range of values prior to convert (be sure that + // a higher E-jerk would still be compatible wrt the E accell range) + if(j < 4.5 && cs.max_acceleration_units_per_sq_second_normal[E_AXIS] < 2000) + return j; + + // bring low E-jerk values into equivalent LA 1.5 values by + // flattening the response in the (1-4.5) range using a piecewise + // function. Is it truly worth to preserve the difference between + // 1.5/2.5 E-jerk for LA1.0? Probably not, but we try nonetheless. + j = j < 1.0? j * 3.625: + j < 4.5? j * 0.25 + 3.375: + j; + + SERIAL_ECHOPGM("LA10C: Adjusted E-Jerk: "); + SERIAL_ECHOLN(j); + return j; +} diff --git a/Firmware/la10compat.h b/Firmware/la10compat.h index e6ffbc37..5116eb27 100644 --- a/Firmware/la10compat.h +++ b/Firmware/la10compat.h @@ -5,6 +5,9 @@ // compatbility mode is active the K factor is converted to a LA15 // equivalent (that is, the return value is always a LA15 value). // +// E-jerk<2 is also bumped in LA10 mode to restore the the printing speed +// to values comparable to existing settings. +// // Once the interpretation mode has been set it is kept until the mode // is explicitly reset. This is done to handle transparent fallback for // old firmware revisions in combination with the following gcode @@ -31,9 +34,13 @@ enum __attribute__((packed)) LA10C_MODE LA10C_LA10 = 2 }; -// Explicitly set/reset the interpretation mode for la10c_value() +// Explicitly set/get/reset the interpretation mode for la10c_value() void la10c_mode_change(LA10C_MODE mode); +LA10C_MODE la10c_mode_get(); static inline void la10c_reset() { la10c_mode_change(LA10C_UNKNOWN); } // Return a LA15 K value according to the supplied value and mode float la10c_value(float k); + +// Return an updated LA15 E-jerk value according to the current mode +float la10c_jerk(float j); From 1f482adf557160f2417bb4e6235f460767740b07 Mon Sep 17 00:00:00 2001 From: Alex Voinea Date: Mon, 3 Feb 2020 18:40:46 +0200 Subject: [PATCH 058/158] Improved lcd_menu_statistics() implementation --- Firmware/ultralcd.cpp | 50 ++++++++++++++++++------------------------- 1 file changed, 21 insertions(+), 29 deletions(-) diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index 38471b81..42848b78 100755 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -2794,9 +2794,9 @@ static void lcd_LoadFilament() //! //! @code{.unparsed} //! |01234567890123456789| -//! |Filament used: | c=18 r=1 -//! | 00.00m | -//! |Print time: | c=18 r=1 +//! |Filament used: | c=19 r=1 +//! | 0000.00m | +//! |Print time: | c=19 r=1 //! | 00h 00m 00s | //! ---------------------- //! @endcode @@ -2805,29 +2805,30 @@ static void lcd_LoadFilament() //! //! @code{.unparsed} //! |01234567890123456789| -//! |Total filament : | c=18 r=1 -//! | 000.00 m | -//! |Total print time : | c=18 r=1 -//! | 00d :00h :00 m | +//! |Total filament: | c=19 r=1 +//! | 0000.00m | +//! |Total print time: | c=19 r=1 +//! | 00d 00h 00m | //! ---------------------- //! @endcode //! @todo Positioning of the messages and values on LCD aren't fixed to their exact place. This causes issues with translations. Translations missing for "d"days, "h"ours, "m"inutes", "s"seconds". void lcd_menu_statistics() { + lcd_timeoutToStatus.stop(); //infinite timeout if (IS_SD_PRINTING) { const float _met = ((float)total_filament_used) / (100000.f); const uint32_t _t = (_millis() - starttime) / 1000ul; - const int _h = _t / 3600; - const int _m = (_t - (_h * 3600ul)) / 60ul; - const int _s = _t - ((_h * 3600ul) + (_m * 60ul)); + const uint32_t _h = _t / 3600; + const uint8_t _m = (_t - (_h * 3600ul)) / 60ul; + const uint8_t _s = _t - ((_h * 3600ul) + (_m * 60ul)); - lcd_clear(); + lcd_home(); lcd_printf_P(_N( "%S:\n" - "%17.2fm \n" + "%18.2fm \n" "%S:\n" - "%2dh %02dm %02ds" + "%10ldh %02hhdm %02hhds" ), _i("Filament used"), _met, ////c=18 r=1 _i("Print time"), _h, _m, _s); ////c=18 r=1 @@ -2840,29 +2841,20 @@ void lcd_menu_statistics() uint8_t _hours, _minutes; uint32_t _days; float _filament_m = (float)_filament/100; -// int _filament_km = (_filament >= 100000) ? _filament / 100000 : 0; -// if (_filament_km > 0) _filament_m = _filament - (_filament_km * 100000); _days = _time / 1440; _hours = (_time - (_days * 1440)) / 60; _minutes = _time - ((_days * 1440) + (_hours * 60)); - lcd_clear(); + lcd_home(); lcd_printf_P(_N( "%S:\n" - "%17.2fm \n" + "%18.2fm \n" "%S:\n" - "%7ldd :%2hhdh :%02hhdm" - ), _i("Total filament"), _filament_m, _i("Total print time"), _days, _hours, _minutes); - KEEPALIVE_STATE(PAUSED_FOR_USER); - while (!lcd_clicked()) - { - manage_heater(); - manage_inactivity(true); - _delay(100); - } - KEEPALIVE_STATE(NOT_BUSY); - lcd_quick_feedback(); - menu_back(); + "%10ldd %02hhdh %02hhdm" + ), + _i("Total filament"), _filament_m, + _i("Total print time"), _days, _hours, _minutes); + menu_back_if_clicked_fb(); } } From 3ae5fa70cabc3f96c5093a07374458756977317f Mon Sep 17 00:00:00 2001 From: Alex Voinea Date: Mon, 3 Feb 2020 19:20:43 +0200 Subject: [PATCH 059/158] Fix comments --- Firmware/ultralcd.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index 42848b78..cefd9b8c 100755 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -2830,8 +2830,8 @@ void lcd_menu_statistics() "%S:\n" "%10ldh %02hhdm %02hhds" ), - _i("Filament used"), _met, ////c=18 r=1 - _i("Print time"), _h, _m, _s); ////c=18 r=1 + _i("Filament used"), _met, ////c=19 r=1 + _i("Print time"), _h, _m, _s); ////c=19 r=1 menu_back_if_clicked_fb(); } else @@ -2852,8 +2852,8 @@ void lcd_menu_statistics() "%S:\n" "%10ldd %02hhdh %02hhdm" ), - _i("Total filament"), _filament_m, - _i("Total print time"), _days, _hours, _minutes); + _i("Total filament"), _filament_m, ////c=19 r=1 + _i("Total print time"), _days, _hours, _minutes); ////c=19 r=1 menu_back_if_clicked_fb(); } } From f23dd6bed4c1c5e6b1617723a0971dea1cfbb189 Mon Sep 17 00:00:00 2001 From: 3d-gussner <3d.gussner@gmail.com> Date: Tue, 4 Feb 2020 10:16:44 +0100 Subject: [PATCH 060/158] Hard reset to prusa3d/mk3 and added changes --- build.sh | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/build.sh b/build.sh index 907b1e03..d44a4d89 100755 --- a/build.sh +++ b/build.sh @@ -1,5 +1,5 @@ #!/bin/bash -BUILD_ENV="1.0.6" +BUILD_ENV="1.0.6.1" SCRIPT_PATH="$( cd "$(dirname "$0")" ; pwd -P )" if [ ! -d "build-env" ]; then @@ -8,7 +8,8 @@ fi cd build-env || exit 2 if [ ! -f "PF-build-env-Linux64-$BUILD_ENV.zip" ]; then - wget https://github.com/mkbel/PF-build-env/releases/download/$BUILD_ENV/PF-build-env-Linux64-$BUILD_ENV.zip || exit 3 + #wget https://github.com/3d-gussner/PF-build-env-1/releases/download/$BUILD_ENV-Linux64/PF-build-env-Linux64-$BUILD_ENV.zip || exit 3 + wget https://github.com/prusa3d/PF-build-env/releases/download/$BUILD_ENV-Linux64/PF-build-env-Linux64-$BUILD_ENV.zip || exit 3 fi if [ ! -d "../../PF-build-env-$BUILD_ENV" ]; then From f1ccfd481ac8f6c5a0bae3779ff73df060bc1c92 Mon Sep 17 00:00:00 2001 From: Alex Voinea Date: Tue, 4 Feb 2020 17:30:44 +0200 Subject: [PATCH 061/158] HEATER -> HOTEND --- Firmware/temperature.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Firmware/temperature.cpp b/Firmware/temperature.cpp index 7517978b..54a782b0 100755 --- a/Firmware/temperature.cpp +++ b/Firmware/temperature.cpp @@ -2051,7 +2051,7 @@ public: } } }; -static const char m2hotend[] PROGMEM = "MINTEMP HEATER fixed"; +static const char m2hotend[] PROGMEM = "MINTEMP HOTEND fixed"; static const char m2bed[] PROGMEM = "MINTEMP BED fixed"; static alert_automaton_mintemp alert_automaton_hotend(m2hotend), alert_automaton_bed(m2bed); From e8ce5e140e98bb3de1b690bb6aed014a276acd41 Mon Sep 17 00:00:00 2001 From: Yuri D'Elia Date: Sat, 1 Jun 2019 22:06:55 +0200 Subject: [PATCH 062/158] FS: Detect runout earlier --- Firmware/fsensor.cpp | 7 ++----- 1 file changed, 2 insertions(+), 5 deletions(-) diff --git a/Firmware/fsensor.cpp b/Firmware/fsensor.cpp index fce8f6fe..f4cb647a 100755 --- a/Firmware/fsensor.cpp +++ b/Firmware/fsensor.cpp @@ -19,7 +19,7 @@ //! @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 +#define FSENSOR_ERR_MAX 9 //!< filament sensor maximum error count for runout detection //! @} //! @name Optical quality measurement parameters @@ -453,10 +453,7 @@ ISR(FSENSOR_INT_PIN_VECT) { if (pat9125_y < 0) { - if (fsensor_err_cnt) - fsensor_err_cnt += 2; - else - fsensor_err_cnt++; + fsensor_err_cnt++; } else if (pat9125_y > 0) { From 8fb8ff4bf43eb371217ba9b80b4ea64cf8f7cee0 Mon Sep 17 00:00:00 2001 From: Yuri D'Elia Date: Sun, 2 Jun 2019 18:00:31 +0200 Subject: [PATCH 063/158] Include fsensor recovery stats in the last print stats --- Firmware/Marlin_main.cpp | 1 + Firmware/fsensor.cpp | 5 +++++ Firmware/fsensor.h | 1 + Firmware/ultralcd.cpp | 13 ++++++++----- 4 files changed, 15 insertions(+), 5 deletions(-) diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index 43e3081f..0a1e5439 100755 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -634,6 +634,7 @@ void crashdet_cancel() void failstats_reset_print() { + fsensor_softfail = 0; eeprom_update_byte((uint8_t *)EEPROM_CRASH_COUNT_X, 0); eeprom_update_byte((uint8_t *)EEPROM_CRASH_COUNT_Y, 0); eeprom_update_byte((uint8_t *)EEPROM_FERROR_COUNT, 0); diff --git a/Firmware/fsensor.cpp b/Firmware/fsensor.cpp index f4cb647a..19c8b1f8 100755 --- a/Firmware/fsensor.cpp +++ b/Firmware/fsensor.cpp @@ -83,6 +83,8 @@ uint8_t fsensor_autoload_c; uint32_t fsensor_autoload_last_millis; // uint8_t fsensor_autoload_sum; +// +uint8_t fsensor_softfail = 0; //! @} @@ -598,7 +600,10 @@ void fsensor_update(void) fsensor_oq_meassure_enabled = oq_meassure_enabled_tmp; if (!err) + { printf_P(PSTR("fsensor_err_cnt = 0\n")); + ++fsensor_softfail; + } else fsensor_enque_M600(); } diff --git a/Firmware/fsensor.h b/Firmware/fsensor.h index 5ed7f7fc..fba131db 100755 --- a/Firmware/fsensor.h +++ b/Firmware/fsensor.h @@ -14,6 +14,7 @@ extern bool fsensor_enabled; extern bool fsensor_not_responding; //enable/disable quality meassurement extern bool fsensor_oq_meassure_enabled; +extern uint8_t fsensor_softfail; //! @name save restore printing diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index cefd9b8c..0461ff80 100755 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -1796,11 +1796,14 @@ static void lcd_menu_fails_stats_print() uint8_t crashX = eeprom_read_byte((uint8_t*)EEPROM_CRASH_COUNT_X); uint8_t crashY = eeprom_read_byte((uint8_t*)EEPROM_CRASH_COUNT_Y); lcd_home(); - lcd_printf_P(failStatsFmt, - _i("Last print failures"), ////c=20 r=1 - _i("Power failures"), power, ////c=14 r=1 - _i("Filam. runouts"), filam, ////c=14 r=1 - _i("Crash"), crashX, crashY); ////c=7 r=1 + lcd_printf_P(PSTR("%S\n" + " %S %-3d\n" + " %S H %-3d S %-3d\n" + " %S X %-3d Y %-3d"), + _i("Last print failures"), + _i("Power failures"), power, + _i("Runouts"), filam, fsensor_softfail, + _i("Crash"), crashX, crashY); menu_back_if_clicked_fb(); } From ce74b746f14cf8ea54be925b154838cf0cb0de47 Mon Sep 17 00:00:00 2001 From: Yuri D'Elia Date: Mon, 3 Jun 2019 17:31:19 +0200 Subject: [PATCH 064/158] FS: Trigger a runout with repeated soft-failures (clog?) --- Firmware/fsensor.cpp | 28 +++++++++++++++++++++------- 1 file changed, 21 insertions(+), 7 deletions(-) diff --git a/Firmware/fsensor.cpp b/Firmware/fsensor.cpp index 19c8b1f8..7daea8da 100755 --- a/Firmware/fsensor.cpp +++ b/Firmware/fsensor.cpp @@ -20,6 +20,9 @@ //! @{ #define FSENSOR_CHUNK_LEN 0.64F //!< filament sensor chunk length 0.64mm #define FSENSOR_ERR_MAX 9 //!< filament sensor maximum error count for runout detection + +#define FSENSOR_SOFTERR_CMAX 3 //!< number of contiguous soft failures before a triggering a runout +#define FSENSOR_SOFTERR_DELTA 30000 //!< maximum interval (ms) to consider soft failures contiguous //! @} //! @name Optical quality measurement parameters @@ -85,6 +88,8 @@ uint32_t fsensor_autoload_last_millis; uint8_t fsensor_autoload_sum; // uint8_t fsensor_softfail = 0; +uint8_t fsensor_softfail_ccnt = 0; +unsigned long fsensor_softfail_last = 0; //! @} @@ -596,16 +601,25 @@ void fsensor_update(void) err |= (fsensor_oq_yd_sum < (4 * FSENSOR_OQ_MIN_YD)); fsensor_restore_print_and_continue(); - fsensor_autoload_enabled = autoload_enabled_tmp; - fsensor_oq_meassure_enabled = oq_meassure_enabled_tmp; + fsensor_autoload_enabled = autoload_enabled_tmp; + fsensor_oq_meassure_enabled = oq_meassure_enabled_tmp; - if (!err) + unsigned long now = _millis(); + if (!err && (now - fsensor_softfail_last) > FSENSOR_SOFTERR_DELTA) + fsensor_softfail_ccnt = 0; + if (!err && fsensor_softfail_ccnt <= FSENSOR_SOFTERR_CMAX) { - printf_P(PSTR("fsensor_err_cnt = 0\n")); + printf_P(PSTR("fsensor_err_cnt = 0\n")); ++fsensor_softfail; - } - else - fsensor_enque_M600(); + ++fsensor_softfail_ccnt; + fsensor_softfail_last = now; + } + else + { + fsensor_softfail_ccnt = 0; + fsensor_softfail_last = 0; + fsensor_enque_M600(); + } } #else //PAT9125 if (CHECK_FSENSOR && ir_sensor_detected) From d47363d85a5a813e86af8458bacc0f4970904615 Mon Sep 17 00:00:00 2001 From: Yuri D'Elia Date: Wed, 5 Feb 2020 14:23:41 +0100 Subject: [PATCH 065/158] Update the filament axis resolution when E resolution is changed The filament sensor "chunk lenght" needs to be updated every time the E axis resolution is changed in order to trigger at the same distance. Introduce a new function fsensor_set_axis_steps_per_unit() and use it consistent during init, in M92 and M350. --- Firmware/Marlin_main.cpp | 6 ++++-- Firmware/fsensor.cpp | 7 ++++++- Firmware/fsensor.h | 3 +++ 3 files changed, 13 insertions(+), 3 deletions(-) diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index 0a1e5439..047b7082 100755 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -6673,7 +6673,7 @@ Sigma_Exit: { if(code_seen(axis_codes[i])) { - if(i == 3) { // E + if(i == E_AXIS) { // E 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. @@ -6682,6 +6682,7 @@ Sigma_Exit: axis_steps_per_sqr_second[i] *= factor; } cs.axis_steps_per_unit[i] = value; + fsensor_set_axis_steps_per_unit(value); } else { cs.axis_steps_per_unit[i] = code_value(); @@ -8429,7 +8430,6 @@ Sigma_Exit: res_valid |= (i == E_AXIS) && ((res_new == 64) || (res_new == 128)); // resolutions valid for E only if (res_valid) { - st_synchronize(); uint16_t res = tmc2130_get_res(i); tmc2130_set_res(i, res_new); @@ -8446,6 +8446,8 @@ Sigma_Exit: cs.axis_steps_per_unit[i] /= fac; position[i] /= fac; } + if (i == E_AXIS) + fsensor_set_axis_steps_per_unit(cs.axis_steps_per_unit[i]); } } } diff --git a/Firmware/fsensor.cpp b/Firmware/fsensor.cpp index 7daea8da..297460d6 100755 --- a/Firmware/fsensor.cpp +++ b/Firmware/fsensor.cpp @@ -149,6 +149,11 @@ void fsensor_checkpoint_print(void) restore_print_from_ram_and_continue(0); } +void fsensor_set_axis_steps_per_unit(float u) +{ + fsensor_chunk_len = (int16_t)(FSENSOR_CHUNK_LEN * u); +} + void fsensor_init(void) { #ifdef PAT9125 @@ -161,7 +166,7 @@ void fsensor_init(void) #ifdef PAT9125 uint8_t oq_meassure_enabled = eeprom_read_byte((uint8_t*)EEPROM_FSENS_OQ_MEASS_ENABLED); fsensor_oq_meassure_enabled = (oq_meassure_enabled == 1)?true:false; - fsensor_chunk_len = (int16_t)(FSENSOR_CHUNK_LEN * cs.axis_steps_per_unit[E_AXIS]); + fsensor_set_axis_steps_per_unit(cs.axis_steps_per_unit[E_AXIS]); if (!pat9125) { diff --git a/Firmware/fsensor.h b/Firmware/fsensor.h index fba131db..0c791d41 100755 --- a/Firmware/fsensor.h +++ b/Firmware/fsensor.h @@ -29,6 +29,9 @@ extern void fsensor_checkpoint_print(void); //! initialize extern void fsensor_init(void); +//! update axis resolution +extern void fsensor_set_axis_steps_per_unit(float u); + //! @name enable/disable //! @{ extern bool fsensor_enable(bool bUpdateEEPROM=true); From 6fbd632c844c527bb0812e36bc03318097d54087 Mon Sep 17 00:00:00 2001 From: Yuri D'Elia Date: Wed, 5 Feb 2020 15:17:19 +0100 Subject: [PATCH 066/158] Isolate all PAT9125-specific code, fix build on !MK3 variants - Hide all prototypes related to PAT9125 to force all callers to check for the proper sensor, since the handling differences are substantial - Remove unneeded lenght accounting from the stepper isr as as consequence. - Keep detailed soft failure counts for the MK3 on the "last print failures" status screen, but fix build on variants without a PAT9125 by fixing the lcd stats function. --- Firmware/Marlin_main.cpp | 8 +++++++- Firmware/fsensor.cpp | 32 ++++++++++++++++++++------------ Firmware/fsensor.h | 15 ++++++++++----- Firmware/stepper.cpp | 14 +++++++------- Firmware/ultralcd.cpp | 25 ++++++++++++++++++------- 5 files changed, 62 insertions(+), 32 deletions(-) diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index 047b7082..1dcb8938 100755 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -634,13 +634,15 @@ void crashdet_cancel() void failstats_reset_print() { - fsensor_softfail = 0; eeprom_update_byte((uint8_t *)EEPROM_CRASH_COUNT_X, 0); eeprom_update_byte((uint8_t *)EEPROM_CRASH_COUNT_Y, 0); eeprom_update_byte((uint8_t *)EEPROM_FERROR_COUNT, 0); eeprom_update_byte((uint8_t *)EEPROM_POWER_COUNT, 0); eeprom_update_byte((uint8_t *)EEPROM_MMU_FAIL, 0); eeprom_update_byte((uint8_t *)EEPROM_MMU_LOAD_FAIL, 0); +#if defined(FILAMENT_SENSOR) && defined(PAT9125) + fsensor_softfail = 0; +#endif } @@ -6682,7 +6684,9 @@ Sigma_Exit: axis_steps_per_sqr_second[i] *= factor; } cs.axis_steps_per_unit[i] = value; +#if defined(FILAMENT_SENSOR) && defined(PAT9125) fsensor_set_axis_steps_per_unit(value); +#endif } else { cs.axis_steps_per_unit[i] = code_value(); @@ -8446,8 +8450,10 @@ Sigma_Exit: cs.axis_steps_per_unit[i] /= fac; position[i] /= fac; } +#if defined(FILAMENT_SENSOR) && defined(PAT9125) if (i == E_AXIS) fsensor_set_axis_steps_per_unit(cs.axis_steps_per_unit[i]); +#endif } } } diff --git a/Firmware/fsensor.cpp b/Firmware/fsensor.cpp index 297460d6..c1f9f27b 100755 --- a/Firmware/fsensor.cpp +++ b/Firmware/fsensor.cpp @@ -47,25 +47,32 @@ const char ERRMSG_PAT9125_NOT_RESP[] PROGMEM = "PAT9125 not responding (%d)!\n"; #define FSENSOR_INT_PIN_PCMSK_BIT PCINT13 // PinChange Interrupt / PinChange Enable Mask @ PJ4 #define FSENSOR_INT_PIN_PCICR_BIT PCIE1 // PinChange Interrupt Enable / Flag @ PJ4 -//uint8_t fsensor_int_pin = FSENSOR_INT_PIN; -uint8_t fsensor_int_pin_old = 0; -int16_t fsensor_chunk_len = 0; - //! enabled = initialized and sampled every chunk event bool fsensor_enabled = true; //! runout watching is done in fsensor_update (called from main loop) bool fsensor_watch_runout = true; //! not responding - is set if any communication error occurred during initialization or readout bool fsensor_not_responding = false; + +#ifdef PAT9125 +uint8_t fsensor_int_pin_old = 0; +//! optical checking "chunk lenght" (already in steps) +int16_t fsensor_chunk_len = 0; //! enable/disable quality meassurement bool fsensor_oq_meassure_enabled = false; - //! number of errors, updated in ISR uint8_t fsensor_err_cnt = 0; //! 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) int16_t fsensor_dy_old = 0; +//! count of total sensor "soft" failures (filament status checks) +uint8_t fsensor_softfail = 0; +//! timestamp of last soft failure +unsigned long fsensor_softfail_last = 0; +//! count of soft failures within the configured time +uint8_t fsensor_softfail_ccnt = 0; +#endif //! log flag: 0=log disabled, 1=log enabled uint8_t fsensor_log = 1; @@ -78,6 +85,8 @@ uint8_t fsensor_log = 1; bool fsensor_autoload_enabled = true; //! autoload watching enable/disable flag bool fsensor_watch_autoload = false; + +#ifdef PAT9125 // uint16_t fsensor_autoload_y; // @@ -86,11 +95,8 @@ uint8_t fsensor_autoload_c; uint32_t fsensor_autoload_last_millis; // uint8_t fsensor_autoload_sum; -// -uint8_t fsensor_softfail = 0; -uint8_t fsensor_softfail_ccnt = 0; -unsigned long fsensor_softfail_last = 0; //! @} +#endif //! @name filament optical quality measurement variables @@ -136,7 +142,9 @@ void fsensor_restore_print_and_continue(void) { printf_P(PSTR("fsensor_restore_print_and_continue\n")); fsensor_watch_runout = true; +#ifdef PAT9125 fsensor_err_cnt = 0; +#endif restore_print_from_ram_and_continue(0); } @@ -368,6 +376,7 @@ bool fsensor_check_autoload(void) return false; } +#ifdef PAT9125 void fsensor_oq_meassure_set(bool State) { fsensor_oq_meassure_enabled = State; @@ -439,7 +448,7 @@ bool fsensor_oq_result(void) printf_P(_N("fsensor_oq_result %S\n"), (res?_OK:_NG)); return res; } -#ifdef PAT9125 + ISR(FSENSOR_INT_PIN_VECT) { if (mmu_enabled || ir_sensor_detected) return; @@ -538,8 +547,6 @@ void fsensor_setup_interrupt(void) PCICR |= bit(FSENSOR_INT_PIN_PCICR_BIT); // enable corresponding PinChangeInterrupt (set of pins) } -#endif //PAT9125 - void fsensor_st_block_chunk(int cnt) { if (!fsensor_enabled) return; @@ -551,6 +558,7 @@ void fsensor_st_block_chunk(int cnt) else {PIN_VAL(FSENSOR_INT_PIN, HIGH);} } } +#endif //PAT9125 //! Common code for enqueing M600 and supplemental codes into the command queue. diff --git a/Firmware/fsensor.h b/Firmware/fsensor.h index 0c791d41..373200dc 100755 --- a/Firmware/fsensor.h +++ b/Firmware/fsensor.h @@ -6,16 +6,16 @@ #include "config.h" -//! minimum meassured chunk length in steps -extern int16_t fsensor_chunk_len; // enable/disable flag extern bool fsensor_enabled; // not responding flag extern bool fsensor_not_responding; -//enable/disable quality meassurement -extern bool fsensor_oq_meassure_enabled; +#ifdef PAT9125 +// optical checking "chunk lenght" (already in steps) +extern int16_t fsensor_chunk_len; +// count of soft failures extern uint8_t fsensor_softfail; - +#endif //! @name save restore printing //! @{ @@ -29,8 +29,10 @@ extern void fsensor_checkpoint_print(void); //! initialize extern void fsensor_init(void); +#ifdef PAT9125 //! update axis resolution extern void fsensor_set_axis_steps_per_unit(float u); +#endif //! @name enable/disable //! @{ @@ -56,8 +58,10 @@ extern void fsensor_autoload_check_stop(void); extern bool fsensor_check_autoload(void); //! @} +#ifdef PAT9125 //! @name optical quality measurement support //! @{ +extern bool fsensor_oq_meassure_enabled; extern void fsensor_oq_meassure_set(bool State); extern void fsensor_oq_meassure_start(uint8_t skip); extern void fsensor_oq_meassure_stop(void); @@ -74,6 +78,7 @@ extern void fsensor_st_block_chunk(int cnt); // to drain fsensor_st_cnt anyway at the beginning of the new block. #define fsensor_st_block_begin(rev) fsensor_st_block_chunk(0) //! @} +#endif //PAT9125 #if IR_SENSOR_ANALOG diff --git a/Firmware/stepper.cpp b/Firmware/stepper.cpp index 74625a63..93b3d039 100644 --- a/Firmware/stepper.cpp +++ b/Firmware/stepper.cpp @@ -36,9 +36,9 @@ #include "tmc2130.h" #endif //TMC2130 -#ifdef FILAMENT_SENSOR +#if defined(FILAMENT_SENSOR) && defined(PAT9125) #include "fsensor.h" -int fsensor_counter = 0; //counter for e-steps +int fsensor_counter; //counter for e-steps #endif //FILAMENT_SENSOR #include "mmu.h" @@ -421,9 +421,9 @@ FORCE_INLINE void stepper_next_block() #endif /* LIN_ADVANCE */ count_direction[E_AXIS] = 1; } -#ifdef FILAMENT_SENSOR - fsensor_counter = 0; - fsensor_st_block_begin(count_direction[E_AXIS] < 0); +#if defined(FILAMENT_SENSOR) && defined(PAT9125) + fsensor_counter = 0; + fsensor_st_block_begin(count_direction[E_AXIS] < 0); #endif //FILAMENT_SENSOR } else { @@ -973,13 +973,13 @@ FORCE_INLINE void advance_isr_scheduler() { WRITE_NC(E0_STEP_PIN, !INVERT_E_STEP_PIN); e_steps += (rev? 1: -1); WRITE_NC(E0_STEP_PIN, INVERT_E_STEP_PIN); -#ifdef FILAMENT_SENSOR +#if defined(FILAMENT_SENSOR) && defined(PAT9125) fsensor_counter += (rev? -1: 1); #endif } while(--max_ticks); -#ifdef FILAMENT_SENSOR +#if defined(FILAMENT_SENSOR) && defined(PAT9125) if (abs(fsensor_counter) >= fsensor_chunk_len) { fsensor_st_block_chunk(fsensor_counter); diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index 0461ff80..fc39b140 100755 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -1796,14 +1796,23 @@ static void lcd_menu_fails_stats_print() uint8_t crashX = eeprom_read_byte((uint8_t*)EEPROM_CRASH_COUNT_X); uint8_t crashY = eeprom_read_byte((uint8_t*)EEPROM_CRASH_COUNT_Y); lcd_home(); +#ifndef PAT9125 + lcd_printf_P(failStatsFmt, + _i("Last print failures"), ////c=20 r=1 + _i("Power failures"), power, ////c=14 r=1 + _i("Filam. runouts"), filam, ////c=14 r=1 + _i("Crash"), crashX, crashY); ////c=7 r=1 +#else + // On the MK3 include detailed PAT9125 statistics about soft failures lcd_printf_P(PSTR("%S\n" - " %S %-3d\n" - " %S H %-3d S %-3d\n" - " %S X %-3d Y %-3d"), - _i("Last print failures"), - _i("Power failures"), power, - _i("Runouts"), filam, fsensor_softfail, - _i("Crash"), crashX, crashY); + " %-16.16S%-3d\n" + " %-7.7S H %-3d S %-3d\n" + " %-7.7S X %-3d Y %-3d"), + _i("Last print failures"), ////c=20 r=1 + _i("Power failures"), power, ////c=14 r=1 + _i("Runouts"), filam, fsensor_softfail, //c=7 r=1 + _i("Crash"), crashX, crashY); ////c=7 r=1 +#endif menu_back_if_clicked_fb(); } @@ -2234,10 +2243,12 @@ void lcd_set_filament_autoload() { fsensor_autoload_set(!fsensor_autoload_enabled); } +#if defined(FILAMENT_SENSOR) && defined(PAT9125) void lcd_set_filament_oq_meass() { fsensor_oq_meassure_set(!fsensor_oq_meassure_enabled); } +#endif FilamentAction eFilamentAction=FilamentAction::None; // must be initialized as 'non-autoLoad' From 5c4235b886b678335146bee4dca85ad7635ff497 Mon Sep 17 00:00:00 2001 From: Yuri D'Elia Date: Wed, 5 Feb 2020 15:38:39 +0100 Subject: [PATCH 067/158] Correctly reset the PAT9125 filament counters When the error count is cleared, the cumulative deltas as well as the segment lenght which is kept inside the stepper isr need to be reset. Introduce a helper function fsensor_reset_err_cnt to clear all the required variables in one place which can be used in most cases (the only exceptions being quality measument). Introduce a new function st_reset_fsensor to also clear the segment lenght within the isr. --- Firmware/fsensor.cpp | 38 ++++++++++++++++++++++---------------- Firmware/stepper.cpp | 12 ++++++++++-- Firmware/stepper.h | 5 ++++- 3 files changed, 36 insertions(+), 19 deletions(-) diff --git a/Firmware/fsensor.cpp b/Firmware/fsensor.cpp index c1f9f27b..3c42a342 100755 --- a/Firmware/fsensor.cpp +++ b/Firmware/fsensor.cpp @@ -138,12 +138,28 @@ void fsensor_stop_and_save_print(void) fsensor_watch_runout = false; } +#ifdef PAT9125 +// Reset all internal counters to zero, including stepper callbacks +void fsensor_reset_err_cnt() +{ + fsensor_err_cnt = 0; + pat9125_y = 0; + st_reset_fsensor(); +} + +void fsensor_set_axis_steps_per_unit(float u) +{ + fsensor_chunk_len = (int16_t)(FSENSOR_CHUNK_LEN * u); +} +#endif + + void fsensor_restore_print_and_continue(void) { printf_P(PSTR("fsensor_restore_print_and_continue\n")); fsensor_watch_runout = true; #ifdef PAT9125 - fsensor_err_cnt = 0; + fsensor_reset_err_cnt(); #endif restore_print_from_ram_and_continue(0); } @@ -157,11 +173,6 @@ void fsensor_checkpoint_print(void) restore_print_from_ram_and_continue(0); } -void fsensor_set_axis_steps_per_unit(float u) -{ - fsensor_chunk_len = (int16_t)(FSENSOR_CHUNK_LEN * u); -} - void fsensor_init(void) { #ifdef PAT9125 @@ -214,7 +225,7 @@ bool fsensor_enable(bool bUpdateEEPROM) fsensor_enabled = pat9125 ? true : false; fsensor_watch_runout = true; fsensor_oq_meassure = false; - fsensor_err_cnt = 0; + fsensor_reset_err_cnt(); fsensor_dy_old = 0; eeprom_update_byte((uint8_t*)EEPROM_FSENSOR, fsensor_enabled ? 0x01 : 0x00); FSensorStateMenu = fsensor_enabled ? 1 : 0; @@ -295,12 +306,11 @@ void fsensor_autoload_check_start(void) fsensor_autoload_last_millis = _millis(); fsensor_watch_runout = false; fsensor_watch_autoload = true; - fsensor_err_cnt = 0; } + void fsensor_autoload_check_stop(void) { - // puts_P(_N("fsensor_autoload_check_stop\n")); if (!fsensor_enabled) return; // puts_P(_N("fsensor_autoload_check_stop 1\n")); @@ -311,7 +321,7 @@ void fsensor_autoload_check_stop(void) fsensor_autoload_sum = 0; fsensor_watch_autoload = false; fsensor_watch_runout = true; - fsensor_err_cnt = 0; + fsensor_reset_err_cnt(); } #endif //PAT9125 @@ -410,7 +420,6 @@ void fsensor_oq_meassure_stop(void) printf_P(_N(" st_sum=%u yd_sum=%u er_sum=%u er_max=%hhu\n"), fsensor_oq_st_sum, fsensor_oq_yd_sum, fsensor_oq_er_sum, fsensor_oq_er_max); printf_P(_N(" yd_min=%u yd_max=%u yd_avg=%u sh_avg=%u\n"), fsensor_oq_yd_min, fsensor_oq_yd_max, (uint16_t)((uint32_t)fsensor_oq_yd_sum * fsensor_chunk_len / fsensor_oq_st_sum), (uint16_t)(fsensor_oq_sh_sum / fsensor_oq_samples)); fsensor_oq_meassure = false; - fsensor_err_cnt = 0; } const char _OK[] PROGMEM = "OK"; @@ -595,7 +604,7 @@ void fsensor_update(void) st_synchronize(); // check the filament in isolation - fsensor_err_cnt = 0; + fsensor_reset_err_cnt(); fsensor_oq_meassure_start(0); float e_tmp = current_position[E_AXIS]; current_position[E_AXIS] -= 3; @@ -603,13 +612,10 @@ void fsensor_update(void) current_position[E_AXIS] = e_tmp; plan_buffer_line_curposXYZE(200/60, active_extruder); st_synchronize(); - - uint8_t err_cnt = fsensor_err_cnt; fsensor_oq_meassure_stop(); bool err = false; - err |= (err_cnt > 1); - + err |= (fsensor_err_cnt > 1); err |= (fsensor_oq_er_sum > 2); err |= (fsensor_oq_yd_sum < (4 * FSENSOR_OQ_MIN_YD)); diff --git a/Firmware/stepper.cpp b/Firmware/stepper.cpp index 93b3d039..93e4ad8f 100644 --- a/Firmware/stepper.cpp +++ b/Firmware/stepper.cpp @@ -1357,8 +1357,6 @@ void quickStop() } #ifdef BABYSTEPPING - - void babystep(const uint8_t axis,const bool direction) { //MUST ONLY BE CALLED BY A ISR, it depends on that no other ISR interrupts this @@ -1594,3 +1592,13 @@ void microstep_readings() #endif } #endif //TMC2130 + + +#if defined(FILAMENT_SENSOR) && defined(PAT9125) +void st_reset_fsensor() +{ + CRITICAL_SECTION_START; + fsensor_counter = 0; + CRITICAL_SECTION_END; +} +#endif //FILAMENT_SENSOR diff --git a/Firmware/stepper.h b/Firmware/stepper.h index 7c41743c..7fdf426f 100644 --- a/Firmware/stepper.h +++ b/Firmware/stepper.h @@ -92,7 +92,10 @@ void microstep_readings(); #ifdef BABYSTEPPING void babystep(const uint8_t axis,const bool direction); // perform a short step with a single stepper motor, outside of any convention #endif - +#if defined(FILAMENT_SENSOR) && defined(PAT9125) +// reset the internal filament sensor state +void st_reset_fsensor(); +#endif #endif From 34f43d73898b74e58c37f5fa439ebb581589a07d Mon Sep 17 00:00:00 2001 From: vintagepc <53943260+vintagepc@users.noreply.github.com> Date: Wed, 5 Feb 2020 21:41:31 -0500 Subject: [PATCH 068/158] Update mmu.cpp Fix runout if filament is unknown --- Firmware/mmu.cpp | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/Firmware/mmu.cpp b/Firmware/mmu.cpp index b3465828..85beeb61 100755 --- a/Firmware/mmu.cpp +++ b/Firmware/mmu.cpp @@ -383,8 +383,9 @@ void mmu_loop(void) //printf_P(PSTR("Eact: %d\n"), int(e_active())); if (!mmu_finda && CHECK_FSENSOR && fsensor_enabled) { fsensor_checkpoint_print(); - ad_markDepleted(mmu_extruder); - if (lcd_autoDepleteEnabled() && !ad_allDepleted()) + if (mmu_extruder != MMU_FILAMENT_UNKNOWN) // Can't deplete unknown extruder. + ad_markDepleted(mmu_extruder); + if (lcd_autoDepleteEnabled() && !ad_allDepleted() && mmu_extruder != MMU_FILAMENT_UNKNOWN) // Can't auto if F=? { enquecommand_front_P(PSTR("M600 AUTO")); //save print and run M600 command } From e84f82a6757ec3bfe3a9473b71f145775f631bae Mon Sep 17 00:00:00 2001 From: Yuri D'Elia Date: Wed, 5 Feb 2020 15:46:45 +0100 Subject: [PATCH 069/158] Rewrite filament sensor PAT9125 error handling Rewrite the logic behind the "chunking"/error count behind the PAT9125. Basic idea: check the _direction_ of movement returned by the optical sensor and compare it to the direction of the stepper. To avoid doing this continuosly (and because the optical sensor doesn't necessarily have the accuracy to track small distances), do so in chunks. Each time a chunk doesn't match the expected direction, increase the error count. Several improvements were done to the previous code: - Increase the chunk window: this ensures that a filament with poor response returns an usable direction, while also moving the average return values from the sensor in the middle of the 12 bits available for maximum effectiveness. - Since the returned values are more reliable, reduce the error count (1.25mm*4 = ~5mm before runout detection) - Track _both_ positive and negative movement, although only trigger errors during extrusion (necessary due to several assumptions made in the mmu/unloading code) - Do not reset the counters for each block: accumulate distances correctly, allowing detection of any block lenght. --- Firmware/config.h | 3 +- Firmware/fsensor.cpp | 104 +++++++++++++++++++++---------------------- Firmware/stepper.cpp | 1 - 3 files changed, 53 insertions(+), 55 deletions(-) diff --git a/Firmware/config.h b/Firmware/config.h index 241a2f20..5c8f7cd9 100644 --- a/Firmware/config.h +++ b/Firmware/config.h @@ -34,7 +34,8 @@ //#define PAT9125_I2C_ADDR 0x79 //ID=HI //#define PAT9125_I2C_ADDR 0x73 //ID=NC #define PAT9125_XRES 0 -#define PAT9125_YRES 240 +#define PAT9125_YRES 240 // maximum resolution (5*X cpi) +#define PAT9124_YRES_MM (5*PAT9125_YRES/25.4) // counts per mm //SM4 configuration #define SM4_DEFDELAY 500 //default step delay [us] diff --git a/Firmware/fsensor.cpp b/Firmware/fsensor.cpp index 3c42a342..ea171906 100755 --- a/Firmware/fsensor.cpp +++ b/Firmware/fsensor.cpp @@ -18,8 +18,8 @@ //! @name Basic parameters //! @{ -#define FSENSOR_CHUNK_LEN 0.64F //!< filament sensor chunk length 0.64mm -#define FSENSOR_ERR_MAX 9 //!< filament sensor maximum error count for runout detection +#define FSENSOR_CHUNK_LEN 1.25 //!< filament sensor chunk length (mm) +#define FSENSOR_ERR_MAX 4 //!< filament sensor maximum error/chunk count for runout detection #define FSENSOR_SOFTERR_CMAX 3 //!< number of contiguous soft failures before a triggering a runout #define FSENSOR_SOFTERR_DELTA 30000 //!< maximum interval (ms) to consider soft failures contiguous @@ -64,8 +64,6 @@ bool fsensor_oq_meassure_enabled = false; uint8_t fsensor_err_cnt = 0; //! 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) -int16_t fsensor_dy_old = 0; //! count of total sensor "soft" failures (filament status checks) uint8_t fsensor_softfail = 0; //! timestamp of last soft failure @@ -226,7 +224,6 @@ bool fsensor_enable(bool bUpdateEEPROM) fsensor_watch_runout = true; fsensor_oq_meassure = false; fsensor_reset_err_cnt(); - fsensor_dy_old = 0; eeprom_update_byte((uint8_t*)EEPROM_FSENSOR, fsensor_enabled ? 0x01 : 0x00); FSensorStateMenu = fsensor_enabled ? 1 : 0; } @@ -477,53 +474,56 @@ ISR(FSENSOR_INT_PIN_VECT) fsensor_not_responding = true; printf_P(ERRMSG_PAT9125_NOT_RESP, 1); } + if (st_cnt != 0) - { //movement - if (st_cnt > 0) //positive movement - { - if (pat9125_y < 0) - { - fsensor_err_cnt++; - } - else if (pat9125_y > 0) - { - if (fsensor_err_cnt) - fsensor_err_cnt--; - } - else //(pat9125_y == 0) - if (((fsensor_dy_old <= 0) || (fsensor_err_cnt)) && (st_cnt > (fsensor_chunk_len >> 1))) - fsensor_err_cnt++; - if (fsensor_oq_meassure) - { - if (fsensor_oq_skipchunk) - { - fsensor_oq_skipchunk--; - fsensor_err_cnt = 0; - } - else - { - if (st_cnt == fsensor_chunk_len) - { - if (pat9125_y > 0) if (fsensor_oq_yd_min > pat9125_y) fsensor_oq_yd_min = (fsensor_oq_yd_min + pat9125_y) / 2; - if (pat9125_y >= 0) if (fsensor_oq_yd_max < pat9125_y) fsensor_oq_yd_max = (fsensor_oq_yd_max + pat9125_y) / 2; - } - fsensor_oq_samples++; - fsensor_oq_st_sum += st_cnt; - if (pat9125_y > 0) fsensor_oq_yd_sum += pat9125_y; - if (fsensor_err_cnt > old_err_cnt) - fsensor_oq_er_sum += (fsensor_err_cnt - old_err_cnt); - if (fsensor_oq_er_max < fsensor_err_cnt) - fsensor_oq_er_max = fsensor_err_cnt; - fsensor_oq_sh_sum += pat9125_s; - } - } - } - else //negative movement - { - } - } - else - { //no movement + { + // movement was planned, check for sensor movement + int8_t st_dir = st_cnt >= 0; + int8_t pat9125_dir = pat9125_y >= 0; + + if (pat9125_y == 0) + { + // no movement detected: increase error count only when extruding, since fast retracts + // cannot always be seen. We also need to ensure that no runout is generated while + // retracting as it's not currently handled everywhere + if (st_dir) ++fsensor_err_cnt; + } + else if (pat9125_dir != st_dir) + { + // detected direction opposite of motor movement + if (st_dir) ++fsensor_err_cnt; + } + else if (pat9125_dir == st_dir) + { + // direction agreeing with planned movement + if (fsensor_err_cnt) --fsensor_err_cnt; + } + + if (st_dir && fsensor_oq_meassure) + { + // extruding with quality assessment + if (fsensor_oq_skipchunk) + { + fsensor_oq_skipchunk--; + fsensor_err_cnt = 0; + } + else + { + if (st_cnt == fsensor_chunk_len) + { + if (pat9125_y > 0) if (fsensor_oq_yd_min > pat9125_y) fsensor_oq_yd_min = (fsensor_oq_yd_min + pat9125_y) / 2; + if (pat9125_y >= 0) if (fsensor_oq_yd_max < pat9125_y) fsensor_oq_yd_max = (fsensor_oq_yd_max + pat9125_y) / 2; + } + fsensor_oq_samples++; + fsensor_oq_st_sum += st_cnt; + if (pat9125_y > 0) fsensor_oq_yd_sum += pat9125_y; + if (fsensor_err_cnt > old_err_cnt) + fsensor_oq_er_sum += (fsensor_err_cnt - old_err_cnt); + if (fsensor_oq_er_max < fsensor_err_cnt) + fsensor_oq_er_max = fsensor_err_cnt; + fsensor_oq_sh_sum += pat9125_s; + } + } } #ifdef DEBUG_FSENSOR_LOG @@ -534,9 +534,7 @@ ISR(FSENSOR_INT_PIN_VECT) } #endif //DEBUG_FSENSOR_LOG - fsensor_dy_old = pat9125_y; pat9125_y = 0; - _lock = false; return; } diff --git a/Firmware/stepper.cpp b/Firmware/stepper.cpp index 93e4ad8f..6e0937cf 100644 --- a/Firmware/stepper.cpp +++ b/Firmware/stepper.cpp @@ -422,7 +422,6 @@ FORCE_INLINE void stepper_next_block() count_direction[E_AXIS] = 1; } #if defined(FILAMENT_SENSOR) && defined(PAT9125) - fsensor_counter = 0; fsensor_st_block_begin(count_direction[E_AXIS] < 0); #endif //FILAMENT_SENSOR } From 1eddc40ed46cb74192e792ba2326e9ac174aa157 Mon Sep 17 00:00:00 2001 From: Yuri D'Elia Date: Wed, 5 Feb 2020 22:05:04 +0100 Subject: [PATCH 070/158] Comment existing code --- Firmware/fsensor.cpp | 5 +++++ 1 file changed, 5 insertions(+) diff --git a/Firmware/fsensor.cpp b/Firmware/fsensor.cpp index ea171906..2cf336a6 100755 --- a/Firmware/fsensor.cpp +++ b/Firmware/fsensor.cpp @@ -460,12 +460,17 @@ ISR(FSENSOR_INT_PIN_VECT) if (mmu_enabled || ir_sensor_detected) return; if (!((fsensor_int_pin_old ^ FSENSOR_INT_PIN_PIN_REG) & FSENSOR_INT_PIN_MASK)) return; fsensor_int_pin_old = FSENSOR_INT_PIN_PIN_REG; + + // prevent isr re-entry static bool _lock = false; if (_lock) return; _lock = true; + + // fetch fsensor_st_cnt atomically int st_cnt = fsensor_st_cnt; fsensor_st_cnt = 0; sei(); + uint8_t old_err_cnt = fsensor_err_cnt; uint8_t pat9125_res = fsensor_oq_meassure?pat9125_update():pat9125_update_y(); if (!pat9125_res) From 3af35844e11c95147befa708c3f75f7546ef90dd Mon Sep 17 00:00:00 2001 From: Yuri D'Elia Date: Wed, 5 Feb 2020 22:05:24 +0100 Subject: [PATCH 071/158] Remove redundant check (always trigger the fsensor isr) Since fsensor_st_block_chunk is already called on fsensor_chunk_size boundaries, there's no need to check a second time. --- Firmware/fsensor.cpp | 10 ++++------ 1 file changed, 4 insertions(+), 6 deletions(-) diff --git a/Firmware/fsensor.cpp b/Firmware/fsensor.cpp index 2cf336a6..41d9a506 100755 --- a/Firmware/fsensor.cpp +++ b/Firmware/fsensor.cpp @@ -563,12 +563,10 @@ void fsensor_st_block_chunk(int cnt) { if (!fsensor_enabled) return; fsensor_st_cnt += cnt; - if (abs(fsensor_st_cnt) >= fsensor_chunk_len) - { -// !!! bit toggling (PINxn <- 1) (for PinChangeInterrupt) does not work for some MCU pins - if (PIN_GET(FSENSOR_INT_PIN)) {PIN_VAL(FSENSOR_INT_PIN, LOW);} - else {PIN_VAL(FSENSOR_INT_PIN, HIGH);} - } + + // !!! bit toggling (PINxn <- 1) (for PinChangeInterrupt) does not work for some MCU pins + if (PIN_GET(FSENSOR_INT_PIN)) {PIN_VAL(FSENSOR_INT_PIN, LOW);} + else {PIN_VAL(FSENSOR_INT_PIN, HIGH);} } #endif //PAT9125 From cdc17e8da1b88a6fd10fec6e7a875f3e5caf30c5 Mon Sep 17 00:00:00 2001 From: Yuri D'Elia Date: Wed, 5 Feb 2020 22:06:56 +0100 Subject: [PATCH 072/158] Read all 12 bits correctly from PAT9125 DELTA_* registers Widen ucXL/ucYL/ucXYH types to 16 bits, since the following shifts will otherwise truncate the results. --- Firmware/pat9125.c | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/Firmware/pat9125.c b/Firmware/pat9125.c index 7b7353dd..5b17345c 100644 --- a/Firmware/pat9125.c +++ b/Firmware/pat9125.c @@ -183,9 +183,9 @@ uint8_t pat9125_update(void) if (pat9125_PID1 == 0xff) return 0; if (ucMotion & 0x80) { - uint8_t ucXL = pat9125_rd_reg(PAT9125_DELTA_XL); - uint8_t ucYL = pat9125_rd_reg(PAT9125_DELTA_YL); - uint8_t ucXYH = pat9125_rd_reg(PAT9125_DELTA_XYH); + uint16_t ucXL = pat9125_rd_reg(PAT9125_DELTA_XL); + uint16_t ucYL = pat9125_rd_reg(PAT9125_DELTA_YL); + uint16_t ucXYH = pat9125_rd_reg(PAT9125_DELTA_XYH); if (pat9125_PID1 == 0xff) return 0; int16_t iDX = ucXL | ((ucXYH << 4) & 0xf00); int16_t iDY = ucYL | ((ucXYH << 8) & 0xf00); @@ -207,8 +207,8 @@ uint8_t pat9125_update_y(void) if (pat9125_PID1 == 0xff) return 0; if (ucMotion & 0x80) { - uint8_t ucYL = pat9125_rd_reg(PAT9125_DELTA_YL); - uint8_t ucXYH = pat9125_rd_reg(PAT9125_DELTA_XYH); + uint16_t ucYL = pat9125_rd_reg(PAT9125_DELTA_YL); + uint16_t ucXYH = pat9125_rd_reg(PAT9125_DELTA_XYH); if (pat9125_PID1 == 0xff) return 0; int16_t iDY = ucYL | ((ucXYH << 8) & 0xf00); if (iDY & 0x800) iDY -= 4096; From 3be859ece951c6c4bdeb8ed112c7e14a439636d6 Mon Sep 17 00:00:00 2001 From: Yuri D'Elia Date: Thu, 6 Feb 2020 13:48:23 +0100 Subject: [PATCH 073/158] FS: Improve reliability on speeds with poor optical tracking Depending on the filament surface and moving speed, the PAT9125 sensor can stop being able to track movement. In such cases, instead of triggering false errors and/or relying on previous states, read and use the exposure data off the sensor and increase error counts only for poorly exposed images instead, which is a good indicator of a far-away (or missing!) tracking surface. --- Firmware/fsensor.cpp | 23 +++++++++++++++++++---- Firmware/pat9125.c | 14 ++++---------- Firmware/pat9125.h | 6 +++--- 3 files changed, 26 insertions(+), 17 deletions(-) diff --git a/Firmware/fsensor.cpp b/Firmware/fsensor.cpp index 41d9a506..9e7b2f6c 100755 --- a/Firmware/fsensor.cpp +++ b/Firmware/fsensor.cpp @@ -488,10 +488,25 @@ ISR(FSENSOR_INT_PIN_VECT) if (pat9125_y == 0) { - // no movement detected: increase error count only when extruding, since fast retracts - // cannot always be seen. We also need to ensure that no runout is generated while - // retracting as it's not currently handled everywhere - if (st_dir) ++fsensor_err_cnt; + if (st_dir) + { + // no movement detected: we might be within a blind sensor range, + // update the frame and shutter parameters we didn't earlier + if (!fsensor_oq_meassure) + pat9125_update_bs(); + + // increment the error count only if underexposed: filament likely missing + if ((pat9125_b < 80) && (pat9125_s > 10)) + { + // check for a dark frame (<30% avg brightness) with long exposure + ++fsensor_err_cnt; + } + else + { + // good frame, filament likely present + if(fsensor_err_cnt) --fsensor_err_cnt; + } + } } else if (pat9125_dir != st_dir) { diff --git a/Firmware/pat9125.c b/Firmware/pat9125.c index 5b17345c..ae291c21 100644 --- a/Firmware/pat9125.c +++ b/Firmware/pat9125.c @@ -219,19 +219,13 @@ uint8_t pat9125_update_y(void) return 0; } -uint8_t pat9125_update_y2(void) +uint8_t pat9125_update_bs(void) { if ((pat9125_PID1 == 0x31) && (pat9125_PID2 == 0x91)) { - uint8_t ucMotion = pat9125_rd_reg(PAT9125_MOTION); - if (pat9125_PID1 == 0xff) return 0; //NOACK error - if (ucMotion & 0x80) - { - int8_t dy = pat9125_rd_reg(PAT9125_DELTA_YL); - if (pat9125_PID1 == 0xff) return 0; //NOACK error - pat9125_y -= dy; //negative number, because direction switching does not work - } - return 1; + pat9125_b = pat9125_rd_reg(PAT9125_FRAME); + pat9125_s = pat9125_rd_reg(PAT9125_SHUTTER); + if (pat9125_PID1 == 0xff) return 0; } return 0; } diff --git a/Firmware/pat9125.h b/Firmware/pat9125.h index 6d36a82e..12f7fe94 100755 --- a/Firmware/pat9125.h +++ b/Firmware/pat9125.h @@ -19,9 +19,9 @@ extern uint8_t pat9125_b; extern uint8_t pat9125_s; extern uint8_t pat9125_init(void); -extern uint8_t pat9125_update(void); -extern uint8_t pat9125_update_y(void); -extern uint8_t pat9125_update_y2(void); +extern uint8_t pat9125_update(void); // update all sensor data +extern uint8_t pat9125_update_y(void); // update _y only +extern uint8_t pat9125_update_bs(void); // update _b/_s only #if defined(__cplusplus) From bd0544fe9e028ffb32d3696533340dc0319152b4 Mon Sep 17 00:00:00 2001 From: Yuri D'Elia Date: Thu, 6 Feb 2020 14:44:43 +0100 Subject: [PATCH 074/158] FS: Use two different speeds when checking for runout When doing a PAT9125 "soft check", use two different speeds between retraction and extrusion. This increases the chances that we can track the surface. --- Firmware/fsensor.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Firmware/fsensor.cpp b/Firmware/fsensor.cpp index 9e7b2f6c..7f291d7a 100755 --- a/Firmware/fsensor.cpp +++ b/Firmware/fsensor.cpp @@ -624,7 +624,7 @@ void fsensor_update(void) fsensor_oq_meassure_start(0); float e_tmp = current_position[E_AXIS]; current_position[E_AXIS] -= 3; - plan_buffer_line_curposXYZE(200/60, active_extruder); + plan_buffer_line_curposXYZE(250/60, active_extruder); current_position[E_AXIS] = e_tmp; plan_buffer_line_curposXYZE(200/60, active_extruder); st_synchronize(); From 853bb79b6b4ac485537fd410f432229a9c45817f Mon Sep 17 00:00:00 2001 From: Yuri D'Elia Date: Thu, 6 Feb 2020 16:39:08 +0100 Subject: [PATCH 075/158] Return correct status from pat9125_update_bs --- Firmware/pat9125.c | 1 + 1 file changed, 1 insertion(+) diff --git a/Firmware/pat9125.c b/Firmware/pat9125.c index ae291c21..de4693d2 100644 --- a/Firmware/pat9125.c +++ b/Firmware/pat9125.c @@ -226,6 +226,7 @@ uint8_t pat9125_update_bs(void) pat9125_b = pat9125_rd_reg(PAT9125_FRAME); pat9125_s = pat9125_rd_reg(PAT9125_SHUTTER); if (pat9125_PID1 == 0xff) return 0; + return 1; } return 0; } From 9e45b5d41e49ec6abe3b62263745ef741fca9167 Mon Sep 17 00:00:00 2001 From: Yuri D'Elia Date: Thu, 6 Feb 2020 18:01:54 +0100 Subject: [PATCH 076/158] Improve PAT9125 filament / optical quality checks Tune the "soft" filament recheck to be more in-line with the latest changes. Relax the thresholds so that a poorly tracking filament that managed to trigger a recheck can still pass as long as /some/ motion is detected. Hide the unused fsensor_oq_result() behind the FSENSOR_QUALITY define, which is likely broken currently anyway. Cleanup and simplify all the OQ defines. --- Firmware/fsensor.cpp | 23 +++++++++++------------ 1 file changed, 11 insertions(+), 12 deletions(-) diff --git a/Firmware/fsensor.cpp b/Firmware/fsensor.cpp index 7f291d7a..4894d29c 100755 --- a/Firmware/fsensor.cpp +++ b/Firmware/fsensor.cpp @@ -27,13 +27,10 @@ //! @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 +#define FSENSOR_OQ_MAX_ES 2 //!< maximum sum of error blocks during filament recheck +#define FSENSOR_OQ_MIN_YD 2 //!< minimum yd sum during filament check (counts per inch) +#define FSENSOR_OQ_MIN_BR 80 //!< minimum brightness value +#define FSENSOR_OQ_MAX_SH 10 //!< maximum shutter value //! @} const char ERRMSG_PAT9125_NOT_RESP[] PROGMEM = "PAT9125 not responding (%d)!\n"; @@ -401,7 +398,7 @@ void fsensor_oq_meassure_start(uint8_t skip) fsensor_oq_yd_sum = 0; fsensor_oq_er_sum = 0; fsensor_oq_er_max = 0; - fsensor_oq_yd_min = FSENSOR_OQ_MAX_YD; + fsensor_oq_yd_min = INT16_MAX; fsensor_oq_yd_max = 0; fsensor_oq_sh_sum = 0; pat9125_update(); @@ -419,6 +416,7 @@ void fsensor_oq_meassure_stop(void) fsensor_oq_meassure = false; } +#ifdef FSENSOR_QUALITY const char _OK[] PROGMEM = "OK"; const char _NG[] PROGMEM = "NG!"; @@ -454,6 +452,7 @@ bool fsensor_oq_result(void) printf_P(_N("fsensor_oq_result %S\n"), (res?_OK:_NG)); return res; } +#endif //FSENSOR_QUALITY ISR(FSENSOR_INT_PIN_VECT) { @@ -496,7 +495,7 @@ ISR(FSENSOR_INT_PIN_VECT) pat9125_update_bs(); // increment the error count only if underexposed: filament likely missing - if ((pat9125_b < 80) && (pat9125_s > 10)) + if ((pat9125_b < FSENSOR_OQ_MIN_BR) && (pat9125_s > FSENSOR_OQ_MAX_SH)) { // check for a dark frame (<30% avg brightness) with long exposure ++fsensor_err_cnt; @@ -631,9 +630,9 @@ void fsensor_update(void) fsensor_oq_meassure_stop(); bool err = false; - err |= (fsensor_err_cnt > 1); - err |= (fsensor_oq_er_sum > 2); - err |= (fsensor_oq_yd_sum < (4 * FSENSOR_OQ_MIN_YD)); + err |= (fsensor_err_cnt > 0); // final error count is non-zero + err |= (fsensor_oq_er_sum > FSENSOR_OQ_MAX_ES); // total error count is above limit + err |= (fsensor_oq_yd_sum < FSENSOR_OQ_MIN_YD); // total measured distance is below limit fsensor_restore_print_and_continue(); fsensor_autoload_enabled = autoload_enabled_tmp; From f1618bfbd687e40147d382fb5c0e83a2899d1f04 Mon Sep 17 00:00:00 2001 From: Yuri D'Elia Date: Thu, 6 Feb 2020 22:41:47 +0100 Subject: [PATCH 077/158] Initialize current_position correctly during startup Just after setting up the w2m matrix, call "clamp_to_software_endstops" on the current_position (initially [0,0,0]) to move it to the effective minimal position, which is usually [0,0,non-zero] due to MIN_Z and the negative probe offset. This is required to calculate correctly the first relative move: planning X+10 would unexpectedly calculate a Z shift otherwise. --- Firmware/Marlin_main.cpp | 9 ++++++++- 1 file changed, 8 insertions(+), 1 deletion(-) diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index 43e3081f..e33ad37c 100755 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -1310,10 +1310,17 @@ void setup() setup_photpin(); servo_init(); + // Reset the machine correction matrix. // It does not make sense to load the correction matrix until the machine is homed. world2machine_reset(); - + + // Initialize current_position accounting for software endstops to + // avoid unexpected initial shifts on the first move + clamp_to_software_endstops(current_position); + plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], + current_position[Z_AXIS], current_position[E_AXIS]); + #ifdef FILAMENT_SENSOR fsensor_init(); #endif //FILAMENT_SENSOR From 1384e783bfb422afe25bc88b8705203ecc6b26e4 Mon Sep 17 00:00:00 2001 From: vintagepc <53943260+vintagepc@users.noreply.github.com> Date: Fri, 7 Feb 2020 16:14:33 -0500 Subject: [PATCH 078/158] Force high power mode when running belt test --- Firmware/ultralcd.cpp | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index cefd9b8c..4e0057ac 100755 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -7455,6 +7455,11 @@ void lcd_belttest() { int _progress = 0; bool _result = true; + + #ifdef TMC2130 // Belttest requires high power mode. Enable it. + FORCE_HIGH_POWER_START; + #endif + uint16_t X = eeprom_read_word((uint16_t*)(EEPROM_BELTSTATUS_X)); uint16_t Y = eeprom_read_word((uint16_t*)(EEPROM_BELTSTATUS_Y)); lcd_belttest_print(_i("Checking X..."), X, Y); @@ -7482,6 +7487,10 @@ void lcd_belttest() lcd_belttest_print(_i("Done"), X, Y); + #ifdef TMC2130 + FORCE_HIGH_POWER_END; + #endif + KEEPALIVE_STATE(NOT_BUSY); _delay(3000); } From 721b27fcb6984d11f009ea77d21a93923e2397aa Mon Sep 17 00:00:00 2001 From: vintagepc <53943260+vintagepc@users.noreply.github.com> Date: Sat, 8 Feb 2020 12:33:23 -0500 Subject: [PATCH 079/158] Reorg/cleanup Removed unused progress variable reorganized flow to avoid early returns (ensures forced high power mode is disabled regardless of outcome) --- Firmware/ultralcd.cpp | 27 ++++++++++----------------- 1 file changed, 10 insertions(+), 17 deletions(-) diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index 4e0057ac..a4b52477 100755 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -7453,7 +7453,6 @@ void lcd_belttest_print(const char* msg, uint16_t X, uint16_t Y) } void lcd_belttest() { - int _progress = 0; bool _result = true; #ifdef TMC2130 // Belttest requires high power mode. Enable it. @@ -7466,26 +7465,20 @@ void lcd_belttest() _delay(2000); KEEPALIVE_STATE(IN_HANDLER); - + _result = lcd_selfcheck_axis_sg(X_AXIS); X = eeprom_read_word((uint16_t*)(EEPROM_BELTSTATUS_X)); - if (!_result){ - lcd_belttest_print(_i("Error"), X, Y); - return; + if (_result){ + lcd_belttest_print(_i("Checking Y..."), X, Y); + _result = lcd_selfcheck_axis_sg(Y_AXIS); + Y = eeprom_read_word((uint16_t*)(EEPROM_BELTSTATUS_Y)); } - - lcd_belttest_print(_i("Checking Y..."), X, Y); - _result = lcd_selfcheck_axis_sg(Y_AXIS); - Y = eeprom_read_word((uint16_t*)(EEPROM_BELTSTATUS_Y)); - - if (!_result){ + + if (!_result) { lcd_belttest_print(_i("Error"), X, Y); - lcd_clear(); - return; - } - - - lcd_belttest_print(_i("Done"), X, Y); + } else { + lcd_belttest_print(_i("Done"), X, Y); + } #ifdef TMC2130 FORCE_HIGH_POWER_END; From e4b1a1e9c4d265a7b76a74ea172efdfd4f6859f2 Mon Sep 17 00:00:00 2001 From: vintagepc <53943260+vintagepc@users.noreply.github.com> Date: Sun, 9 Feb 2020 21:39:48 -0500 Subject: [PATCH 080/158] Remove delay for belttest, similar to #2439 There's a separate PR to remove the first delay in the selftest. (#2439). Mirroring that to the belt test function, which I suspect also inherited it. --- Firmware/ultralcd.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index a4b52477..af6399f3 100755 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -7463,7 +7463,6 @@ void lcd_belttest() uint16_t Y = eeprom_read_word((uint16_t*)(EEPROM_BELTSTATUS_Y)); lcd_belttest_print(_i("Checking X..."), X, Y); - _delay(2000); KEEPALIVE_STATE(IN_HANDLER); _result = lcd_selfcheck_axis_sg(X_AXIS); From a4458fb57b6ea78569c3b9cb49e6e468545d59ba Mon Sep 17 00:00:00 2001 From: vintagepc <53943260+vintagepc@users.noreply.github.com> Date: Tue, 11 Feb 2020 18:33:40 -0500 Subject: [PATCH 081/158] Removed duplicate #defines cleaned up display routine --- Firmware/ultralcd.cpp | 39 +++++++++++++-------------------------- 1 file changed, 13 insertions(+), 26 deletions(-) diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index af6399f3..7321d70e 100755 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -7436,52 +7436,39 @@ static void lcd_belttest_v() lcd_belttest(); menu_back_if_clicked(); } -void lcd_belttest_print(const char* msg, uint16_t X, uint16_t Y) -{ - lcd_clear(); - lcd_printf_P( - _N( - "%S:\n" - "%S\n" - "X:%d\n" - "Y:%d" - ), - _i("Belt status"), - msg, - X,Y - ); -} + void lcd_belttest() { bool _result = true; - #ifdef TMC2130 // Belttest requires high power mode. Enable it. - FORCE_HIGH_POWER_START; - #endif + // Belttest requires high power mode. Enable it. + FORCE_HIGH_POWER_START; uint16_t X = eeprom_read_word((uint16_t*)(EEPROM_BELTSTATUS_X)); uint16_t Y = eeprom_read_word((uint16_t*)(EEPROM_BELTSTATUS_Y)); - lcd_belttest_print(_i("Checking X..."), X, Y); + lcd_puts_at_P(0,0,_i("Checking X...")); KEEPALIVE_STATE(IN_HANDLER); _result = lcd_selfcheck_axis_sg(X_AXIS); X = eeprom_read_word((uint16_t*)(EEPROM_BELTSTATUS_X)); + lcd_set_cursor(0,1), lcd_printf_P(PSTR("X: %d "),X); // Trailing space for done/error spacing if !_result if (_result){ - lcd_belttest_print(_i("Checking Y..."), X, Y); + lcd_printf_P(_i("Done")); + lcd_puts_at_P(0,2,_i("Checking Y...")); _result = lcd_selfcheck_axis_sg(Y_AXIS); Y = eeprom_read_word((uint16_t*)(EEPROM_BELTSTATUS_Y)); + lcd_set_cursor(0,3), lcd_printf_P(PSTR("Y: %d "),Y); } - if (!_result) { - lcd_belttest_print(_i("Error"), X, Y); + if (!_result) { // If error on X, error appears after X measurement, else done or error after Y measurement. + lcd_printf_P(_i("Error")); } else { - lcd_belttest_print(_i("Done"), X, Y); + lcd_printf_P(_i("Done")); } - #ifdef TMC2130 - FORCE_HIGH_POWER_END; - #endif + lcd_puts_at_P(19,3,char(2)); // Checkmark + FORCE_HIGH_POWER_END; KEEPALIVE_STATE(NOT_BUSY); _delay(3000); From 278bb032d797843dc84ba0b4332b8fc65a5d3b37 Mon Sep 17 00:00:00 2001 From: vintagepc <53943260+vintagepc@users.noreply.github.com> Date: Tue, 11 Feb 2020 18:37:26 -0500 Subject: [PATCH 082/158] Change to raise_z_above() --- Firmware/ultralcd.cpp | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index 7321d70e..3dbb6831 100755 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -7797,9 +7797,7 @@ static bool lcd_selfcheck_axis_sg(unsigned char axis) { enable_endstops(true); if (axis == X_AXIS) { //there is collision between cables and PSU cover in X axis if Z coordinate is too low - - current_position[Z_AXIS] += 17; - plan_buffer_line_curposXYZE(manual_feedrate[0] / 60, active_extruder); + raise_z_above(17,true); tmc2130_home_enter(Z_AXIS_MASK); st_synchronize(); tmc2130_home_exit(); From 5abee3d3e51acaabe2ec25f1ab717c3a835c3590 Mon Sep 17 00:00:00 2001 From: vintagepc <53943260+vintagepc@users.noreply.github.com> Date: Tue, 11 Feb 2020 19:44:26 -0500 Subject: [PATCH 083/158] Better display handling --- Firmware/ultralcd.cpp | 42 ++++++++++++++++++++---------------------- 1 file changed, 20 insertions(+), 22 deletions(-) diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index 3dbb6831..ed1b91d4 100755 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -7439,39 +7439,37 @@ static void lcd_belttest_v() void lcd_belttest() { - bool _result = true; - + lcd_clear(); // Belttest requires high power mode. Enable it. FORCE_HIGH_POWER_START; uint16_t X = eeprom_read_word((uint16_t*)(EEPROM_BELTSTATUS_X)); uint16_t Y = eeprom_read_word((uint16_t*)(EEPROM_BELTSTATUS_Y)); - lcd_puts_at_P(0,0,_i("Checking X...")); - + lcd_puts_at_P(0,0,_i("Checking X axis ")); // share message with selftest + lcd_set_cursor(0,1), lcd_printf_P(PSTR("X: %d "),X); KEEPALIVE_STATE(IN_HANDLER); - _result = lcd_selfcheck_axis_sg(X_AXIS); - X = eeprom_read_word((uint16_t*)(EEPROM_BELTSTATUS_X)); - lcd_set_cursor(0,1), lcd_printf_P(PSTR("X: %d "),X); // Trailing space for done/error spacing if !_result - if (_result){ - lcd_printf_P(_i("Done")); - lcd_puts_at_P(0,2,_i("Checking Y...")); - _result = lcd_selfcheck_axis_sg(Y_AXIS); - Y = eeprom_read_word((uint16_t*)(EEPROM_BELTSTATUS_Y)); + // N.B: it doesn't make sense to handle !lcd_selfcheck...() because selftest_sg throws its own error screen + // that clobbers ours, with more info than we could provide. So on fail we just fall through to take us back to status. + if (lcd_selfcheck_axis_sg(X_AXIS)){ + X = eeprom_read_word((uint16_t*)(EEPROM_BELTSTATUS_X)); + lcd_printf_P(PSTR("-> %d"),X); // Show new X value next to old one. + lcd_puts_at_P(0,2,_i("Checking Y axis ")); lcd_set_cursor(0,3), lcd_printf_P(PSTR("Y: %d "),Y); + if (lcd_selfcheck_axis_sg(Y_AXIS)) + { + Y = eeprom_read_word((uint16_t*)(EEPROM_BELTSTATUS_Y)); + lcd_printf_P(PSTR("-> %d"),Y); + lcd_set_custom_characters_nextpage(); + lcd_set_cursor(19, 3); + lcd_print(char(2)); + lcd_wait_for_click_delay(10); + } } - - if (!_result) { // If error on X, error appears after X measurement, else done or error after Y measurement. - lcd_printf_P(_i("Error")); - } else { - lcd_printf_P(_i("Done")); - } - - lcd_puts_at_P(19,3,char(2)); // Checkmark + FORCE_HIGH_POWER_END; - KEEPALIVE_STATE(NOT_BUSY); - _delay(3000); + lcd_set_custom_characters(); // restore status screen chars. } #endif //TMC2130 From 04588ee5cba673979737c9317e86e7082c318f73 Mon Sep 17 00:00:00 2001 From: Thelvaen Date: Wed, 12 Feb 2020 13:25:16 +0100 Subject: [PATCH 084/158] removing sudo for normal build --- README.md | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/README.md b/README.md index 54070dce..9d62d9ae 100644 --- a/README.md +++ b/README.md @@ -21,7 +21,7 @@ - For MK3 --> skip to step 3. - If you have a different printer model, follow step [2.b](#2b) from Windows build -3. Run `sudo ./build.sh` +3. Run `./build.sh` - Output hex file is at `"PrusaFirmware/lang/firmware.hex"` . In the same folder you can hex files for other languages as well. 4. Connect your printer and flash with PrusaSlicer ( Configuration --> Flash printer firmware ) or Slic3r PE. From 1aaefffdb04a94f9ea451f05d2437983f3172c39 Mon Sep 17 00:00:00 2001 From: vintagepc <53943260+vintagepc@users.noreply.github.com> Date: Tue, 11 Feb 2020 18:37:26 -0500 Subject: [PATCH 085/158] Change to raise_z_above() --- Firmware/ultralcd.cpp | 4 +--- 1 file changed, 1 insertion(+), 3 deletions(-) diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index af6399f3..5c7def25 100755 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -7810,9 +7810,7 @@ static bool lcd_selfcheck_axis_sg(unsigned char axis) { enable_endstops(true); if (axis == X_AXIS) { //there is collision between cables and PSU cover in X axis if Z coordinate is too low - - current_position[Z_AXIS] += 17; - plan_buffer_line_curposXYZE(manual_feedrate[0] / 60, active_extruder); + raise_z_above(17,true); tmc2130_home_enter(Z_AXIS_MASK); st_synchronize(); tmc2130_home_exit(); From f234ef2104cbf7808a8aa21bfa745165ce42e3d1 Mon Sep 17 00:00:00 2001 From: DRracer Date: Fri, 14 Feb 2020 09:09:15 +0100 Subject: [PATCH 086/158] Use combined creation/modification file time stamps for sorting --- Firmware/cardreader.cpp | 29 +++++++++++++++++++---------- Firmware/cardreader.h | 4 +++- 2 files changed, 22 insertions(+), 11 deletions(-) diff --git a/Firmware/cardreader.cpp b/Firmware/cardreader.cpp index 545316d3..1c2cbf3c 100644 --- a/Firmware/cardreader.cpp +++ b/Firmware/cardreader.cpp @@ -136,8 +136,17 @@ void CardReader::lsDive(const char *prepend, SdFile parent, const char * const m SERIAL_ECHOPGM("Access date: "); MYSERIAL.println(p.lastAccessDate); SERIAL_ECHOLNPGM("");*/ - modificationDate = p.lastWriteDate; - modificationTime = p.lastWriteTime; + crmodDate = p.lastWriteDate; + crmodTime = p.lastWriteTime; + // There are scenarios when simple modification time is not enough (on MS Windows) + // For example - extract an old g-code from an archive onto the SD card. + // In such case the creation time is current time (which is correct), but the modification time + // stays the same - i.e. old. + // Therefore let's pick the most recent timestamp from both creation and modification timestamps + if( crmodDate < p.creationDate || ( crmodDate == p.creationDate && crmodTime < p.creationTime ) ){ + crmodDate = p.creationDate; + crmodTime = p.creationTime; + } //writeDate = p.lastAccessDate; if (match != NULL) { if (strcasecmp(match, filename) == 0) return; @@ -773,8 +782,8 @@ void CardReader::presort() { // retaining only two filenames at a time. This is very // slow but is safest and uses minimal RAM. char name1[LONG_FILENAME_LENGTH + 1]; - uint16_t modification_time_bckp; - uint16_t modification_date_bckp; + uint16_t crmod_time_bckp; + uint16_t crmod_date_bckp; #endif position = 0; @@ -800,8 +809,8 @@ void CardReader::presort() { #else // Copy filenames into the static array strcpy(sortnames[i], LONGEST_FILENAME); - modification_time[i] = modificationTime; - modification_date[i] = modificationDate; + modification_time[i] = crmodTime; + modification_date[i] = crmodDate; #if SDSORT_CACHE_NAMES strcpy(sortshort[i], filename); #endif @@ -830,8 +839,8 @@ void CardReader::presort() { (modification_date[o1] < modification_date [o2])) #else #define _SORT_CMP_NODIR() (strcasecmp(name1, name2) > 0) //true if lowercase(name1) > lowercase(name2) - #define _SORT_CMP_TIME_NODIR() (((modification_date_bckp == modificationDate) && (modification_time_bckp > modificationTime)) || \ - (modification_date_bckp > modificationDate)) + #define _SORT_CMP_TIME_NODIR() (((crmod_date_bckp == crmodDate) && (crmod_time_bckp > crmodTime)) || \ + (crmod_date_bckp > crmodDate)) #endif @@ -882,8 +891,8 @@ void CardReader::presort() { counter++; getfilename_simple(positions[o1]); strcpy(name1, LONGEST_FILENAME); // save (or getfilename below will trounce it) - modification_date_bckp = modificationDate; - modification_time_bckp = modificationTime; + crmod_date_bckp = crmodDate; + crmod_time_bckp = crmodTime; #if HAS_FOLDER_SORTING bool dir1 = filenameIsDir; #endif diff --git a/Firmware/cardreader.h b/Firmware/cardreader.h index 9a7d0f69..12e83d96 100644 --- a/Firmware/cardreader.h +++ b/Firmware/cardreader.h @@ -75,7 +75,9 @@ public: bool sdprinting ; bool cardOK ; char filename[13]; - uint16_t modificationTime, modificationDate; + // There are scenarios when simple modification time is not enough (on MS Windows) + // Therefore these timestamps hold the most recent one of creation/modification date/times + uint16_t crmodTime, crmodDate; uint32_t cluster, position; char longFilename[LONG_FILENAME_LENGTH]; bool filenameIsDir; From 2e18a48b8778308e1ebf1782dbf95df51dff59fe Mon Sep 17 00:00:00 2001 From: DRracer Date: Mon, 17 Feb 2020 16:47:56 +0100 Subject: [PATCH 087/158] Version changed (3.9.0-RC1 build 3272) --- Firmware/Configuration.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Firmware/Configuration.h b/Firmware/Configuration.h index 694247fb..98923ef4 100644 --- a/Firmware/Configuration.h +++ b/Firmware/Configuration.h @@ -16,8 +16,8 @@ extern uint16_t nPrinterType; extern PGM_P sPrinterName; // Firmware version -#define FW_VERSION "3.9.0" -#define FW_COMMIT_NR 3175 +#define FW_VERSION "3.9.0-RC1" +#define FW_COMMIT_NR 3272 // 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 From e06beb61c30785fb93f314120fb91ad155795b9c Mon Sep 17 00:00:00 2001 From: vintagepc <53943260+vintagepc@users.noreply.github.com> Date: Fri, 21 Feb 2020 18:14:13 -0500 Subject: [PATCH 088/158] Ditch charswitch, show ... for measuring --- Firmware/ultralcd.cpp | 12 +++++------- 1 file changed, 5 insertions(+), 7 deletions(-) diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index ed1b91d4..2ecf7ddc 100755 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -7446,30 +7446,28 @@ void lcd_belttest() uint16_t X = eeprom_read_word((uint16_t*)(EEPROM_BELTSTATUS_X)); uint16_t Y = eeprom_read_word((uint16_t*)(EEPROM_BELTSTATUS_Y)); lcd_puts_at_P(0,0,_i("Checking X axis ")); // share message with selftest - lcd_set_cursor(0,1), lcd_printf_P(PSTR("X: %d "),X); + lcd_set_cursor(0,1), lcd_printf_P(PSTR("X: %d -> ..."),X); KEEPALIVE_STATE(IN_HANDLER); // N.B: it doesn't make sense to handle !lcd_selfcheck...() because selftest_sg throws its own error screen // that clobbers ours, with more info than we could provide. So on fail we just fall through to take us back to status. if (lcd_selfcheck_axis_sg(X_AXIS)){ X = eeprom_read_word((uint16_t*)(EEPROM_BELTSTATUS_X)); - lcd_printf_P(PSTR("-> %d"),X); // Show new X value next to old one. + lcd_set_cursor(9,1), lcd_printf_P(PSTR("%d"),X); // Show new X value next to old one. lcd_puts_at_P(0,2,_i("Checking Y axis ")); - lcd_set_cursor(0,3), lcd_printf_P(PSTR("Y: %d "),Y); + lcd_set_cursor(0,3), lcd_printf_P(PSTR("Y: %d -> ..."),Y); if (lcd_selfcheck_axis_sg(Y_AXIS)) { Y = eeprom_read_word((uint16_t*)(EEPROM_BELTSTATUS_Y)); - lcd_printf_P(PSTR("-> %d"),Y); - lcd_set_custom_characters_nextpage(); + lcd_set_cursor(9,3),lcd_printf_P(PSTR("%d"),Y); lcd_set_cursor(19, 3); - lcd_print(char(2)); + lcd_print(LCD_STR_UPLEVEL); lcd_wait_for_click_delay(10); } } FORCE_HIGH_POWER_END; KEEPALIVE_STATE(NOT_BUSY); - lcd_set_custom_characters(); // restore status screen chars. } #endif //TMC2130 From ec5e54de25ec8d0c08726b880f0c26be9b4dedf5 Mon Sep 17 00:00:00 2001 From: MRprusa3d Date: Mon, 2 Mar 2020 17:52:25 +0100 Subject: [PATCH 089/158] state fixing --- Firmware/Marlin_main.cpp | 29 ++++++++++++++++++++++ Firmware/config.h | 4 ++-- Firmware/ultralcd.cpp | 52 ++++++++++++++++++++++++++++++++++++---- Firmware/ultralcd.h | 3 +++ 4 files changed, 81 insertions(+), 7 deletions(-) diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index 211384f9..6f74d5a7 100755 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -9439,6 +9439,8 @@ static void handleSafetyTimer() } #endif //SAFETYTIMER +extern bool bMenuDetect; / -> .h +extern void lcd_status_screen(); / -> .h & 'static' void manage_inactivity(bool ignore_stepper_queue/*=false*/) //default argument set in Marlin.h { bool bInhibitFlag; @@ -9451,11 +9453,38 @@ bool bInhibitFlag; #endif // PAT9125 #ifdef IR_SENSOR bInhibitFlag=(menu_menu==lcd_menu_show_sensors_state); // Support::SensorInfo menu active +//MYSERIAL.print("inhibit :: "); +//MYSERIAL.println(bInhibitFlag); +// & IR_SENSOR_ANALOG ??? +//bInhibitFlag|=(menu_menu==lcd_detect_IRsensor); // Settings::HWsetup::FSdetect menu active +//.bInhibitFlag=bInhibitFlag||(menu_menu==lcd_detect_IRsensor); // Settings::HWsetup::FSdetect menu active +bInhibitFlag=bInhibitFlag||bMenuDetect; // Settings::HWsetup::FSdetect menu active +//MYSERIAL.print(" :: "); +//MYSERIAL.println(bInhibitFlag); +//MYSERIAL.println(current_voltage_raw_IR); #endif // IR_SENSOR if ((mcode_in_progress != 600) && (eFilamentAction != FilamentAction::AutoLoad) && (!bInhibitFlag)) //M600 not in progress, preHeat @ autoLoad menu not active, Support::ExtruderInfo/SensorInfo menu not active { if (!moves_planned() && !IS_SD_PRINTING && !is_usb_printing && (lcd_commands_type != LcdCommands::Layer1Cal) && ! eeprom_read_byte((uint8_t*)EEPROM_WIZARD_ACTIVE)) { +// ***** +// & IR_SENSOR_ANALOG ??? +bool bTemp; +bTemp=current_voltage_raw_IR>14000; // nahradit prumerem @ vicero hodnot +bTemp=bTemp&&(target_temperature[0]==0); // & bed (& dalsi extrudery) +bTemp=bTemp&&(menu_menu==lcd_status_screen); +bTemp=bTemp&&((oFsensorPCB==ClFsensorPCB::_Old)||(oFsensorPCB==ClFsensorPCB::_Undef)); +bTemp=bTemp&&fsensor_enabled; +if(bTemp) + { + MYSERIAL.println(current_voltage_raw_IR); + MYSERIAL.println("!!!!! -> 03b !!!!!"); + oFsensorPCB=ClFsensorPCB::_Rev03b; + //bTemp=lcd_show_fullscreen_message_yes_no_and_wait_P(_i("?potvrdit?"),false,true); + //MYSERIAL.println(bTemp); + lcd_setstatuspgm(_i("!!! -> 03b !!!")); + } +// ***** if (fsensor_check_autoload()) { #ifdef PAT9125 diff --git a/Firmware/config.h b/Firmware/config.h index 241a2f20..e6d81fe9 100644 --- a/Firmware/config.h +++ b/Firmware/config.h @@ -55,8 +55,8 @@ #define W25X20CL_SPSR SPI_SPSR(W25X20CL_SPI_RATE) //LANG - Multi-language support -//define LANG_MODE 0 // primary language only -#define LANG_MODE 1 // sec. language support +#define LANG_MODE 0 // primary language only +//#define LANG_MODE 1 // sec. language support #define LANG_SIZE_RESERVED 0x3000 // reserved space for secondary language (12288 bytes) diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index 38471b81..6c5fc3e2 100755 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -114,7 +114,8 @@ static const char* lcd_display_message_fullscreen_nonBlocking_P(const char *msg, // void copy_and_scalePID_d(); /* Different menus */ -static void lcd_status_screen(); +//-//static void lcd_status_screen(); + void lcd_status_screen(); #if (LANG_MODE != 0) static void lcd_language_menu(); #endif @@ -236,7 +237,8 @@ static bool lcd_selftest_fsensor(); #endif //PAT9125 static bool selftest_irsensor(); #if IR_SENSOR_ANALOG -static bool lcd_selftest_IRsensor(); +static bool lcd_selftest_IRsensor(bool bStandalone = false); +//-//static lcd_detect_IRsensor(); #endif //IR_SENSOR_ANALOG static void lcd_selftest_error(TestError error, const char *_error_1, const char *_error_2); static void lcd_colorprint_change(); @@ -2146,6 +2148,23 @@ static void lcd_support_menu() MENU_ITEM_BACK_P(_i("Date:"));////MSG_DATE c=17 r=1 MENU_ITEM_BACK_P(PSTR(__DATE__)); + MENU_ITEM_BACK_P(STR_SEPARATOR); + MENU_ITEM_BACK_P(PSTR("Fil. sensor v.:")); + switch(oFsensorPCB) + { + case ClFsensorPCB::_Old: + MENU_ITEM_BACK_P(PSTR(" 03 or older")); + break; + case ClFsensorPCB::_Rev03b: + MENU_ITEM_BACK_P(PSTR(" 03b or newer")); + break; + case ClFsensorPCB::_Undef: + MENU_ITEM_BACK_P(PSTR(" N/A")); + break; + default: + MENU_ITEM_BACK_P(PSTR(" unknown")); + } + MENU_ITEM_BACK_P(STR_SEPARATOR); if (mmu_enabled) { @@ -5697,6 +5716,7 @@ void lcd_hw_setup_menu(void) // can not be "static" #if IR_SENSOR_ANALOG FSENSOR_ACTION_NA; + MENU_ITEM_FUNCTION_P(PSTR("FS Detect"), lcd_detect_IRsensor); #endif //IR_SENSOR_ANALOG MENU_END(); } @@ -7496,7 +7516,7 @@ void lcd_belttest() #endif //TMC2130 #if IR_SENSOR_ANALOG -static bool lcd_selftest_IRsensor() +static bool lcd_selftest_IRsensor(bool bStandalone) { bool bAction; bool bPCBrev03b; @@ -7509,7 +7529,8 @@ volt_IR=VOLT_DIV_REF*((float)volt_IR_int/(1023*OVERSAMPLENR)); printf_P(PSTR("Measured filament sensor high level: %4.2fV\n"),volt_IR); if(volt_IR_int<((int)IRsensor_Hmin_TRESHOLD)) { - lcd_selftest_error(TestError::FsensorLevel,"HIGH",""); + if(!bStandalone) + lcd_selftest_error(TestError::FsensorLevel,"HIGH",""); return(false); } lcd_show_fullscreen_message_and_wait_P(_i("Please insert filament (but not load them!) into extruder and then press the knob.")); @@ -7518,7 +7539,8 @@ volt_IR=VOLT_DIV_REF*((float)volt_IR_int/(1023*OVERSAMPLENR)); printf_P(PSTR("Measured filament sensor low level: %4.2fV\n"),volt_IR); if(volt_IR_int>((int)IRsensor_Lmax_TRESHOLD)) { - lcd_selftest_error(TestError::FsensorLevel,"LOW",""); + if(!bStandalone) + lcd_selftest_error(TestError::FsensorLevel,"LOW",""); return(false); } if((bPCBrev03b?1:0)!=(uint8_t)oFsensorPCB) // safer then "(uint8_t)bPCBrev03b" @@ -7529,6 +7551,26 @@ if((bPCBrev03b?1:0)!=(uint8_t)oFsensorPCB) // safer then "(uint8_t)bPCBre } return(true); } + +bool bMenuDetect=false; +//static void lcd_detect_IRsensor() +void lcd_detect_IRsensor() +{ +bool bAction; + +bMenuDetect=true; +bAction=lcd_show_fullscreen_message_yes_no_and_wait_P(_i("Is the filament unloaded?"),false,true); +if(!bAction) + { + lcd_show_fullscreen_message_and_wait_P(_i("... vyjmi & opakuj ...")); + return; + } +bAction=lcd_selftest_IRsensor(true); +if(bAction) + lcd_show_fullscreen_message_and_wait_P(_i("... povedlo se - VYJMI!!! ...")); +else lcd_show_fullscreen_message_and_wait_P(_i("... NEpovedlo se - VYJMI!!!...")); +bMenuDetect=false; +} #endif //IR_SENSOR_ANALOG static void lcd_selftest_v() diff --git a/Firmware/ultralcd.h b/Firmware/ultralcd.h index 9e0c35b0..c9a9d65d 100755 --- a/Firmware/ultralcd.h +++ b/Firmware/ultralcd.h @@ -57,6 +57,9 @@ void lcd_menu_statistics(); void lcd_menu_extruder_info(); // NOT static due to using inside "Marlin_main" module ("manage_inactivity()") void lcd_menu_show_sensors_state(); // NOT static due to using inside "Marlin_main" module ("manage_inactivity()") + + void lcd_detect_IRsensor(); // NOT static due to using inside "Marlin_main" module ("manage_inactivity()") + #ifdef TMC2130 bool lcd_crash_detect_enabled(); void lcd_crash_detect_enable(); From 2a9504b20a5a6db30550e8c22cd1b28fe1eed3d6 Mon Sep 17 00:00:00 2001 From: MRprusa3d Date: Mon, 2 Mar 2020 19:07:23 +0100 Subject: [PATCH 090/158] !!! for testing only !!! filament sensor auto-detection --- Firmware/Marlin_main.cpp | 49 ++++++++++++++++------------------------ Firmware/config.h | 4 ++-- Firmware/ultralcd.cpp | 27 +++++++++++----------- Firmware/ultralcd.h | 7 ++++-- 4 files changed, 40 insertions(+), 47 deletions(-) diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index 6f74d5a7..7ecbe0e9 100755 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -9439,12 +9439,11 @@ static void handleSafetyTimer() } #endif //SAFETYTIMER -extern bool bMenuDetect; / -> .h -extern void lcd_status_screen(); / -> .h & 'static' void manage_inactivity(bool ignore_stepper_queue/*=false*/) //default argument set in Marlin.h { -bool bInhibitFlag; #ifdef FILAMENT_SENSOR +bool bInhibitFlag; + if (mmu_enabled == false) { //-// if (mcode_in_progress != 600) //M600 not in progress @@ -9453,38 +9452,28 @@ bool bInhibitFlag; #endif // PAT9125 #ifdef IR_SENSOR bInhibitFlag=(menu_menu==lcd_menu_show_sensors_state); // Support::SensorInfo menu active -//MYSERIAL.print("inhibit :: "); -//MYSERIAL.println(bInhibitFlag); -// & IR_SENSOR_ANALOG ??? -//bInhibitFlag|=(menu_menu==lcd_detect_IRsensor); // Settings::HWsetup::FSdetect menu active -//.bInhibitFlag=bInhibitFlag||(menu_menu==lcd_detect_IRsensor); // Settings::HWsetup::FSdetect menu active -bInhibitFlag=bInhibitFlag||bMenuDetect; // Settings::HWsetup::FSdetect menu active -//MYSERIAL.print(" :: "); -//MYSERIAL.println(bInhibitFlag); -//MYSERIAL.println(current_voltage_raw_IR); +#ifdef IR_SENSOR_ANALOG + bInhibitFlag=bInhibitFlag||bMenuFSDetect; // Settings::HWsetup::FSdetect menu active +#endif // IR_SENSOR_ANALOG #endif // IR_SENSOR if ((mcode_in_progress != 600) && (eFilamentAction != FilamentAction::AutoLoad) && (!bInhibitFlag)) //M600 not in progress, preHeat @ autoLoad menu not active, Support::ExtruderInfo/SensorInfo menu not active { if (!moves_planned() && !IS_SD_PRINTING && !is_usb_printing && (lcd_commands_type != LcdCommands::Layer1Cal) && ! eeprom_read_byte((uint8_t*)EEPROM_WIZARD_ACTIVE)) { -// ***** -// & IR_SENSOR_ANALOG ??? -bool bTemp; -bTemp=current_voltage_raw_IR>14000; // nahradit prumerem @ vicero hodnot -bTemp=bTemp&&(target_temperature[0]==0); // & bed (& dalsi extrudery) -bTemp=bTemp&&(menu_menu==lcd_status_screen); -bTemp=bTemp&&((oFsensorPCB==ClFsensorPCB::_Old)||(oFsensorPCB==ClFsensorPCB::_Undef)); -bTemp=bTemp&&fsensor_enabled; -if(bTemp) - { - MYSERIAL.println(current_voltage_raw_IR); - MYSERIAL.println("!!!!! -> 03b !!!!!"); - oFsensorPCB=ClFsensorPCB::_Rev03b; - //bTemp=lcd_show_fullscreen_message_yes_no_and_wait_P(_i("?potvrdit?"),false,true); - //MYSERIAL.println(bTemp); - lcd_setstatuspgm(_i("!!! -> 03b !!!")); - } -// ***** +#ifdef IR_SENSOR_ANALOG + bool bTemp=current_voltage_raw_IR>14000; // nahradit prumerem @ vicero hodnot + bTemp=bTemp&&(target_temperature[0]==0); // & bed (& dalsi extrudery) + bTemp=bTemp&&(menu_menu==lcd_status_screen); + bTemp=bTemp&&((oFsensorPCB==ClFsensorPCB::_Old)||(oFsensorPCB==ClFsensorPCB::_Undef)); + bTemp=bTemp&&fsensor_enabled; + if(bTemp) + { + oFsensorPCB=ClFsensorPCB::_Rev03b; +// eeprom_update_byte((uint8_t*)EEPROM_FSENSOR_PCB,(uint8_t)oFsensorPCB); + printf_P(PSTR("Filament sensor board change detected: revision 03b or newer\n")); + lcd_setstatuspgm(_i("FS rev. 03b or newer")); + } +#endif // IR_SENSOR_ANALOG if (fsensor_check_autoload()) { #ifdef PAT9125 diff --git a/Firmware/config.h b/Firmware/config.h index e6d81fe9..ab93d798 100644 --- a/Firmware/config.h +++ b/Firmware/config.h @@ -55,8 +55,8 @@ #define W25X20CL_SPSR SPI_SPSR(W25X20CL_SPI_RATE) //LANG - Multi-language support -#define LANG_MODE 0 // primary language only -//#define LANG_MODE 1 // sec. language support +//#define LANG_MODE 0 // primary language only +#define LANG_MODE 1 // sec. language support #define LANG_SIZE_RESERVED 0x3000 // reserved space for secondary language (12288 bytes) diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index 6c5fc3e2..a2acd1b9 100755 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -68,6 +68,10 @@ uint8_t SilentModeMenu_MMU = 1; //activate mmu unit stealth mode int8_t FSensorStateMenu = 1; +#if IR_SENSOR_ANALOG +bool bMenuFSDetect=false; +#endif //IR_SENSOR_ANALOG + #ifdef SDCARD_SORT_ALPHA bool presort_flag = false; @@ -114,8 +118,7 @@ static const char* lcd_display_message_fullscreen_nonBlocking_P(const char *msg, // void copy_and_scalePID_d(); /* Different menus */ -//-//static void lcd_status_screen(); - void lcd_status_screen(); +//static void lcd_status_screen(); // NOT static due to using inside "Marlin_main" module ("manage_inactivity()") #if (LANG_MODE != 0) static void lcd_language_menu(); #endif @@ -237,8 +240,8 @@ static bool lcd_selftest_fsensor(); #endif //PAT9125 static bool selftest_irsensor(); #if IR_SENSOR_ANALOG -static bool lcd_selftest_IRsensor(bool bStandalone = false); -//-//static lcd_detect_IRsensor(); +static bool lcd_selftest_IRsensor(bool bStandalone=false); +static void lcd_detect_IRsensor(); #endif //IR_SENSOR_ANALOG static void lcd_selftest_error(TestError error, const char *_error_1, const char *_error_2); static void lcd_colorprint_change(); @@ -977,7 +980,7 @@ void lcdui_print_status_screen(void) } // Main status screen. It's up to the implementation specific part to show what is needed. As this is very display dependent -static void lcd_status_screen() +void lcd_status_screen() // NOT static due to using inside "Marlin_main" module ("manage_inactivity()") { if (firstrun == 1) { @@ -7552,24 +7555,22 @@ if((bPCBrev03b?1:0)!=(uint8_t)oFsensorPCB) // safer then "(uint8_t)bPCBre return(true); } -bool bMenuDetect=false; -//static void lcd_detect_IRsensor() -void lcd_detect_IRsensor() +static void lcd_detect_IRsensor() { bool bAction; -bMenuDetect=true; +bMenuFSDetect=true; // inhibits some code inside "manage_inactivity()" bAction=lcd_show_fullscreen_message_yes_no_and_wait_P(_i("Is the filament unloaded?"),false,true); if(!bAction) { - lcd_show_fullscreen_message_and_wait_P(_i("... vyjmi & opakuj ...")); + lcd_show_fullscreen_message_and_wait_P(_i("... so unload the filament and repeat action!")); return; } bAction=lcd_selftest_IRsensor(true); if(bAction) - lcd_show_fullscreen_message_and_wait_P(_i("... povedlo se - VYJMI!!! ...")); -else lcd_show_fullscreen_message_and_wait_P(_i("... NEpovedlo se - VYJMI!!!...")); -bMenuDetect=false; + lcd_show_fullscreen_message_and_wait_P(_i("PCB check successful - withdraw the filament now!")); +else lcd_show_fullscreen_message_and_wait_P(_i("PCB check unsuccessful - withdraw the filament now!")); +bMenuFSDetect=false; // de-inhibits some code inside "manage_inactivity()" } #endif //IR_SENSOR_ANALOG diff --git a/Firmware/ultralcd.h b/Firmware/ultralcd.h index c9a9d65d..ca64659a 100755 --- a/Firmware/ultralcd.h +++ b/Firmware/ultralcd.h @@ -55,11 +55,10 @@ extern bool lcd_selftest(); void lcd_menu_statistics(); +void lcd_status_screen(); // NOT static due to using inside "Marlin_main" module ("manage_inactivity()") void lcd_menu_extruder_info(); // NOT static due to using inside "Marlin_main" module ("manage_inactivity()") void lcd_menu_show_sensors_state(); // NOT static due to using inside "Marlin_main" module ("manage_inactivity()") - void lcd_detect_IRsensor(); // NOT static due to using inside "Marlin_main" module ("manage_inactivity()") - #ifdef TMC2130 bool lcd_crash_detect_enabled(); void lcd_crash_detect_enable(); @@ -141,6 +140,10 @@ extern uint8_t farm_status; #define SILENT_MODE_OFF SILENT_MODE_POWER #endif +#if IR_SENSOR_ANALOG +extern bool bMenuFSDetect; +#endif //IR_SENSOR_ANALOG + extern int8_t SilentModeMenu; extern uint8_t SilentModeMenu_MMU; From 0eaa4edfee5ce1b76c279c809cc0f4e02935ace4 Mon Sep 17 00:00:00 2001 From: MRprusa3d Date: Mon, 2 Mar 2020 21:18:11 +0100 Subject: [PATCH 091/158] configuration update --- Firmware/Marlin_main.cpp | 5 +++-- Firmware/ultralcd.cpp | 2 ++ 2 files changed, 5 insertions(+), 2 deletions(-) diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index 7ecbe0e9..cbf42c9a 100755 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -46,6 +46,7 @@ //-// #include "Configuration.h" #include "Marlin.h" +#include "config.h" #ifdef ENABLE_AUTO_BED_LEVELING #include "vector_3.h" @@ -9452,7 +9453,7 @@ bool bInhibitFlag; #endif // PAT9125 #ifdef IR_SENSOR bInhibitFlag=(menu_menu==lcd_menu_show_sensors_state); // Support::SensorInfo menu active -#ifdef IR_SENSOR_ANALOG +#if IR_SENSOR_ANALOG bInhibitFlag=bInhibitFlag||bMenuFSDetect; // Settings::HWsetup::FSdetect menu active #endif // IR_SENSOR_ANALOG #endif // IR_SENSOR @@ -9460,7 +9461,7 @@ bool bInhibitFlag; { if (!moves_planned() && !IS_SD_PRINTING && !is_usb_printing && (lcd_commands_type != LcdCommands::Layer1Cal) && ! eeprom_read_byte((uint8_t*)EEPROM_WIZARD_ACTIVE)) { -#ifdef IR_SENSOR_ANALOG +#if IR_SENSOR_ANALOG bool bTemp=current_voltage_raw_IR>14000; // nahradit prumerem @ vicero hodnot bTemp=bTemp&&(target_temperature[0]==0); // & bed (& dalsi extrudery) bTemp=bTemp&&(menu_menu==lcd_status_screen); diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index a2acd1b9..845ab3fd 100755 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -2151,6 +2151,7 @@ static void lcd_support_menu() MENU_ITEM_BACK_P(_i("Date:"));////MSG_DATE c=17 r=1 MENU_ITEM_BACK_P(PSTR(__DATE__)); +#if IR_SENSOR_ANALOG MENU_ITEM_BACK_P(STR_SEPARATOR); MENU_ITEM_BACK_P(PSTR("Fil. sensor v.:")); switch(oFsensorPCB) @@ -2167,6 +2168,7 @@ static void lcd_support_menu() default: MENU_ITEM_BACK_P(PSTR(" unknown")); } +#endif // IR_SENSOR_ANALOG MENU_ITEM_BACK_P(STR_SEPARATOR); if (mmu_enabled) From f09323a78f6c3db246c99c62fef4999e791385c1 Mon Sep 17 00:00:00 2001 From: MRprusa3d Date: Tue, 3 Mar 2020 14:57:45 +0100 Subject: [PATCH 092/158] heaters-checking update --- Firmware/Marlin_main.cpp | 2 +- Firmware/temperature.cpp | 8 ++++++++ Firmware/temperature.h | 5 +++++ 3 files changed, 14 insertions(+), 1 deletion(-) diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index cbf42c9a..dd1a9e72 100755 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -9463,7 +9463,7 @@ bool bInhibitFlag; { #if IR_SENSOR_ANALOG bool bTemp=current_voltage_raw_IR>14000; // nahradit prumerem @ vicero hodnot - bTemp=bTemp&&(target_temperature[0]==0); // & bed (& dalsi extrudery) + bTemp=bTemp&&(!CHECK_ALL_HEATERS); bTemp=bTemp&&(menu_menu==lcd_status_screen); bTemp=bTemp&&((oFsensorPCB==ClFsensorPCB::_Old)||(oFsensorPCB==ClFsensorPCB::_Undef)); bTemp=bTemp&&fsensor_enabled; diff --git a/Firmware/temperature.cpp b/Firmware/temperature.cpp index 88674cf9..b8c4fc27 100755 --- a/Firmware/temperature.cpp +++ b/Firmware/temperature.cpp @@ -210,6 +210,14 @@ static void temp_runaway_check(int _heater_id, float _target_temperature, float static void temp_runaway_stop(bool isPreheat, bool isBed); #endif +// return "false", if all extruder-heaters are 'off' (ie. "true", if any heater is 'on') +bool checkAllHotends(void) +{ + bool result=false; + for(int i=0;i Date: Thu, 5 Mar 2020 11:22:35 +0200 Subject: [PATCH 093/158] Decouple XYZ relative from E relative. --- Firmware/Configuration_adv.h | 1 - Firmware/Marlin.h | 2 +- Firmware/Marlin_main.cpp | 26 +++++++++++--------------- Firmware/mmu.cpp | 6 +++--- Firmware/ultralcd.cpp | 5 +---- 5 files changed, 16 insertions(+), 24 deletions(-) diff --git a/Firmware/Configuration_adv.h b/Firmware/Configuration_adv.h index d25b345c..ab927424 100644 --- a/Firmware/Configuration_adv.h +++ b/Firmware/Configuration_adv.h @@ -152,7 +152,6 @@ #define Z_HOME_RETRACT_MM 2 //#define QUICK_HOME //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially. -#define AXIS_RELATIVE_MODES {0, 0, 0, 0} #define MAX_STEP_FREQUENCY 40000 // Max step frequency for Ultimaker (5000 pps / half step). Toshiba steppers are 4x slower, but Prusa3D does not use those. //By default pololu step drivers require an active high signal. However, some high power drivers require an active low signal as step. #define INVERT_X_STEP_PIN 0 diff --git a/Firmware/Marlin.h b/Firmware/Marlin.h index a0b3c19b..363407e2 100755 --- a/Firmware/Marlin.h +++ b/Firmware/Marlin.h @@ -294,7 +294,7 @@ void setPwmFrequency(uint8_t pin, int val); extern bool fans_check_enabled; extern float homing_feedrate[]; -extern bool axis_relative_modes[]; +extern uint8_t axis_relative_modes; extern float feedrate; extern int feedmultiply; extern int extrudemultiply; // Sets extrude multiply factor (in percent) for all extruders diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index 1dcb8938..0d3fce5b 100755 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -178,9 +178,7 @@ float default_retraction = DEFAULT_RETRACTION; float homing_feedrate[] = HOMING_FEEDRATE; -// Currently only the extruder axis may be switched to a relative mode. -// Other axes are always absolute or relative based on the common relative_mode flag. -bool axis_relative_modes[] = AXIS_RELATIVE_MODES; +uint8_t axis_relative_modes; int feedmultiply=100; //100->1 200->2 int extrudemultiply=100; //100->1 200->2 int extruder_multiply[EXTRUDERS] = {100 @@ -5367,21 +5365,19 @@ if(eSoundMode!=e_SOUND_MODE_SILENT) /*! ### G90 - Switch off relative mode G90: Set to Absolute Positioning - All coordinates from now on are absolute relative to the origin of the machine. E axis is also switched to absolute mode. + All coordinates from now on are absolute relative to the origin of the machine. */ case 90: { - for(uint8_t i = 0; i != NUM_AXIS; ++i) - axis_relative_modes[i] = false; + axis_relative_modes &= ~(X_AXIS_MASK | Y_AXIS_MASK | Z_AXIS_MASK); } break; /*! ### G91 - Switch on relative mode G91: Set to Relative Positioning - All coordinates from now on are relative to the last position. E axis is also switched to relative mode. + All coordinates from now on are relative to the last position. */ case 91: { - for(uint8_t i = 0; i != NUM_AXIS; ++i) - axis_relative_modes[i] = true; + axis_relative_modes |= X_AXIS_MASK | Y_AXIS_MASK | Z_AXIS_MASK; } break; @@ -6558,7 +6554,7 @@ Sigma_Exit: Makes the extruder interpret extrusion as absolute positions. */ case 82: - axis_relative_modes[E_AXIS] = false; + axis_relative_modes &= ~E_AXIS_MASK; break; /*! @@ -6566,7 +6562,7 @@ Sigma_Exit: Makes the extruder interpret extrusion values as relative positions. */ case 83: - axis_relative_modes[E_AXIS] = true; + axis_relative_modes |= E_AXIS_MASK; break; /*! @@ -9190,7 +9186,7 @@ void get_coordinates() for(int8_t i=0; i < NUM_AXIS; i++) { if(code_seen(axis_codes[i])) { - bool relative = axis_relative_modes[i]; + bool relative = axis_relative_modes & (1 << i); destination[i] = (float)code_value(); if (i == E_AXIS) { float emult = extruder_multiplier[active_extruder]; @@ -10589,7 +10585,7 @@ void uvlo_() // Store the print E position before we lose track eeprom_update_float((float*)(EEPROM_UVLO_CURRENT_POSITION_E), current_position[E_AXIS]); - eeprom_update_byte((uint8_t*)EEPROM_UVLO_E_ABS, axis_relative_modes[3]?0:1); + eeprom_update_byte((uint8_t*)EEPROM_UVLO_E_ABS, (axis_relative_modes & E_AXIS_MASK)?0:1); // Clean the input command queue, inhibit serial processing using saved_printing cmdqueue_reset(); @@ -11178,7 +11174,7 @@ void stop_and_save_print_to_ram(float z_move, float e_move) saved_feedmultiply2 = feedmultiply; //save feedmultiply saved_active_extruder = active_extruder; //save active_extruder saved_extruder_temperature = degTargetHotend(active_extruder); - saved_extruder_relative_mode = axis_relative_modes[E_AXIS]; + saved_extruder_relative_mode = axis_relative_modes & E_AXIS_MASK; saved_fanSpeed = fanSpeed; cmdqueue_reset(); //empty cmdqueue card.sdprinting = false; @@ -11260,7 +11256,7 @@ void restore_print_from_ram_and_continue(float e_move) wait_for_heater(_millis(), saved_active_extruder); heating_status = 2; } - axis_relative_modes[E_AXIS] = saved_extruder_relative_mode; + axis_relative_modes ^= (-saved_extruder_relative_mode ^ axis_relative_modes) & E_AXIS_MASK; float e = saved_pos[E_AXIS] - e_move; plan_set_e_position(e); diff --git a/Firmware/mmu.cpp b/Firmware/mmu.cpp index b3465828..aaa09f70 100755 --- a/Firmware/mmu.cpp +++ b/Firmware/mmu.cpp @@ -795,8 +795,8 @@ 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; + const bool saved_e_relative_mode = axis_relative_modes & E_AXIS_MASK; + if (!saved_e_relative_mode) axis_relative_modes |= E_AXIS_MASK; if (ir_sensor_detected) { current_position[E_AXIS] += 3.0f; @@ -820,7 +820,7 @@ void mmu_load_to_nozzle() feedrate = 871; plan_buffer_line_curposXYZE(feedrate / 60, active_extruder); st_synchronize(); - if (!saved_e_relative_mode) axis_relative_modes[E_AXIS] = false; + if (!saved_e_relative_mode) axis_relative_modes &= ~E_AXIS_MASK; } void mmu_M600_wait_and_beep() { diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index fc39b140..d991bb5e 100755 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -7349,10 +7349,7 @@ void lcd_print_stop() planner_abort_hard(); //needs to be done since plan_buffer_line resets waiting_inside_plan_buffer_line_print_aborted to false. Also copies current to destination. - axis_relative_modes[X_AXIS] = false; - axis_relative_modes[Y_AXIS] = false; - axis_relative_modes[Z_AXIS] = false; - axis_relative_modes[E_AXIS] = true; + axis_relative_modes = E_AXIS_MASK; //XYZ absolute, E relative isPrintPaused = false; //clear isPrintPaused flag to allow starting next print after pause->stop scenario. } From 890c1372980588c48d3933b4b9a22e468b5b2b44 Mon Sep 17 00:00:00 2001 From: Alex Voinea Date: Thu, 5 Mar 2020 11:29:16 +0200 Subject: [PATCH 094/158] Initialize all axis as absolute at the beginning. --- 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 0d3fce5b..a606403a 100755 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -178,7 +178,7 @@ float default_retraction = DEFAULT_RETRACTION; float homing_feedrate[] = HOMING_FEEDRATE; -uint8_t axis_relative_modes; +uint8_t axis_relative_modes = 0; int feedmultiply=100; //100->1 200->2 int extrudemultiply=100; //100->1 200->2 int extruder_multiply[EXTRUDERS] = {100 From f71bbfe95e5eab4d52af21f455a93bdfe2d417ab Mon Sep 17 00:00:00 2001 From: MRprusa3d Date: Tue, 10 Mar 2020 00:11:17 +0100 Subject: [PATCH 095/158] tresholds specification, steady delay --- Firmware/Marlin_main.cpp | 21 ++++++++++++++++----- 1 file changed, 16 insertions(+), 5 deletions(-) diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index dd1a9e72..6b5f2470 100755 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -9440,10 +9440,14 @@ static void handleSafetyTimer() } #endif //SAFETYTIMER +#define FS_CHECK_COUNT 15 void manage_inactivity(bool ignore_stepper_queue/*=false*/) //default argument set in Marlin.h { #ifdef FILAMENT_SENSOR bool bInhibitFlag; +#if IR_SENSOR_ANALOG +static uint8_t nFSCheckCount=0; +#endif // IR_SENSOR_ANALOG if (mmu_enabled == false) { @@ -9462,18 +9466,25 @@ bool bInhibitFlag; if (!moves_planned() && !IS_SD_PRINTING && !is_usb_printing && (lcd_commands_type != LcdCommands::Layer1Cal) && ! eeprom_read_byte((uint8_t*)EEPROM_WIZARD_ACTIVE)) { #if IR_SENSOR_ANALOG - bool bTemp=current_voltage_raw_IR>14000; // nahradit prumerem @ vicero hodnot + bool bTemp=current_voltage_raw_IR>IRsensor_Hmin_TRESHOLD; + bTemp=bTemp&¤t_voltage_raw_IRFS_CHECK_COUNT) + { + nFSCheckCount=0; // not necessary + oFsensorPCB=ClFsensorPCB::_Rev03b; +// eeprom_update_byte((uint8_t*)EEPROM_FSENSOR_PCB,(uint8_t)oFsensorPCB); + printf_P(PSTR("Filament sensor board change detected: revision 03b or newer\n")); + lcd_setstatuspgm(_i("FS rev. 03b or newer")); + } } + else nFSCheckCount=0; #endif // IR_SENSOR_ANALOG if (fsensor_check_autoload()) { From ff479afd88ba612db7a5bbfc26c4fa190efc4aa5 Mon Sep 17 00:00:00 2001 From: MRprusa3d Date: Tue, 10 Mar 2020 15:51:48 +0100 Subject: [PATCH 096/158] version for testing / final review --- Firmware/Marlin_main.cpp | 2 +- Firmware/ultralcd.cpp | 8 +++++--- 2 files changed, 6 insertions(+), 4 deletions(-) diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index 6b5f2470..d0ee5a3b 100755 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -9479,7 +9479,7 @@ static uint8_t nFSCheckCount=0; { nFSCheckCount=0; // not necessary oFsensorPCB=ClFsensorPCB::_Rev03b; -// eeprom_update_byte((uint8_t*)EEPROM_FSENSOR_PCB,(uint8_t)oFsensorPCB); + eeprom_update_byte((uint8_t*)EEPROM_FSENSOR_PCB,(uint8_t)oFsensorPCB); printf_P(PSTR("Filament sensor board change detected: revision 03b or newer\n")); lcd_setstatuspgm(_i("FS rev. 03b or newer")); } diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index 845ab3fd..c23f2a23 100755 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -7586,7 +7586,8 @@ bool lcd_selftest() int _progress = 0; bool _result = true; bool _swapped_fan = false; -#if IR_SENSOR_ANALOG +//#if IR_SENSOR_ANALOG +#if (0) bool bAction; bAction=lcd_show_fullscreen_message_yes_no_and_wait_P(_i("Is the filament unloaded?"),false,true); if(!bAction) @@ -7598,7 +7599,7 @@ bool lcd_selftest() #ifdef TMC2130 FORCE_HIGH_POWER_START; #endif // TMC2130 - _delay(2000); +// _delay(2000); FORCE_BL_ON_START; @@ -7795,7 +7796,8 @@ bool lcd_selftest() _progress = lcd_selftest_screen(TestScreen::FsensorOk, _progress, 3, true, 2000); //fil sensor OK } #endif //PAT9125 -#if IR_SENSOR_ANALOG +//#if IR_SENSOR_ANALOG +#if (0) _progress = lcd_selftest_screen(TestScreen::Fsensor, _progress, 3, true, 2000); //check filament sensor _result = lcd_selftest_IRsensor(); if (_result) From 2818316366f424a04f22ea522141f7cc2fc472d7 Mon Sep 17 00:00:00 2001 From: 3d-gussner <3d.gussner@gmail.com> Date: Thu, 12 Mar 2020 12:34:33 +0100 Subject: [PATCH 097/158] Started EEPROM Table doxygen documentation --- Firmware/Marlin_main.cpp | 4 +- Firmware/eeprom.h | 114 +++++++++++++++++++++++++++++++++++++++ 2 files changed, 116 insertions(+), 2 deletions(-) diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index 1dcb8938..d0a4122f 100755 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -9124,8 +9124,8 @@ Sigma_Exit: #### End of D-Codes */ - /** @defgroup GCodes G-Code List - */ +/** @defgroup GCodes G-Code List +*/ // --------------------------------------------------- diff --git a/Firmware/eeprom.h b/Firmware/eeprom.h index f0544f39..7f431d24 100644 --- a/Firmware/eeprom.h +++ b/Firmware/eeprom.h @@ -1,3 +1,11 @@ + +/** + * @file + */ + /** \ingroup eeprom_table */ + //! _This is a EEPROM table of currently implemented in Prusa firmware (dynamically generated from doxygen)._ + + #ifndef EEPROM_H #define EEPROM_H @@ -26,6 +34,110 @@ typedef struct #ifdef __cplusplus static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEPROM_SHEETS_SIZEOF."); #endif +/** @defgroup eeprom_table EEPROM Table + * + + --------------------------------------------------------------------------------- + EEPROM 8-bit Empty value = 0xFFh 255 + + EEPROM 16-bit Empty value = 0xFFFFh 65535 + + --------------------------------------------------------------------------------- + How can you use the debug codes? + - Serial terminal like Putty. + - Octoprint does support D-codes + - _Pronterface_ does not support D-codes + + + --------------------------------------------------------------------------------- + + + +
EEPROM Table
Adress begin Bit/Type Name Valid values Default/FactoryResetDescription Debug code +
0x0FFFh 4095ucharEEPROM_SILENT 00h 0 ??? TMC Stealth mode off / miniRambo Power mode D3 Ax0fff C1 +
01h 1 TMC Stealth mode on / miniRambo Silent mode +
02h 2 Auto mode +
0x0FFEh 4094ucharEEPROM_LANG 00h 0 00h 0 English / LANG_ID_PRI D3 Ax0ffe C1 +
01h 1 Other language LANG_ID_SEC +
0x0FFCh 4092 uint16 EEPROM_BABYSTEP_X ??? ffh 255 Babystep for X axis _unsued_ D3 Ax0ffc C2 +
0x0FFAh 4090 uint16 EEPROM_BABYSTEP_Y ??? ffh 222 Babystep for Y axis _unsued_ D3 Ax0ffa C2 +
0x0FF8h 4088uint16EEPROM_BABYSTEP_Z ??? ffh 255 Babystep for Z axis _lagacy_ D3 Ax0ff8 C2 +
multiple values stored now in EEPROM_Sheets_base +
0x0FF7h 4087uint8EEPROM_CALIBRATION_STATUS 00h 0 ffh 255 Unknown D3 Ax0ff7 C1 +
01h 1 Calibrated +
E6h 230 needs Live Z adjustment +
F0h 240 needs Z calibration +
FAh 250 needs XYZ calibration +
FFh 255 Assbemled _default_ +
0x0FF5h 4085 uint16 EEPROM_BABYSTEP_Z0 ??? ??? Babystep for Z ??? D3 Ax0ff5 C2 +
0x0FF1h 4081 uint32 EEPROM_FILAMENTUSED ??? 00h 0 Filament used in meters D3 Ax0ff1 C4 +
0x0FEDh 4077 uint32 EEPROM_TOTALTIME ??? 00h 0 Total print time D3 Ax0fed C4 +
0x0FE5h 4069floatEEPROM_BED_CALIBRATION_CENTER ??? ??? ??? D3 Ax0fe5 C8 +
??? +
0x0FDDh 4061floatEEPROM_BED_CALIBRATION_VEC_X ??? ??? ??? D3 Ax0fdd C8 +
??? +
0x0FD5h 4053floatEEPROM_BED_CALIBRATION_VEC_Y ??? ??? ??? D3 Ax0fd5 C8 +
??? +
0x0FC5h 4037int16EEPROM_BED_CALIBRATION_Z_JITTER??? ??? ??? D3 Ax0fc5 C16 +
??? +
??? +
??? +
??? +
??? +
??? +
??? +
0x0FC4h 4036boolEEPROM_FARM_MODE 00h 0 00h 0 Prusa farm mode off D3 Ax0fc4 C1 +
ffh 255 Prusa farm mode on +
0x0FC1h 4033 int16 EEPROM_FARM_NUMBER ??? ff ff ffh Prusa farm number D3 Ax0fc1 C3 +
0x0FC0h 4032boolEEPROM_BED_CORRECTION_VALID 00h 0 00h 0 Bed correction invalid D3 Ax0fc0 C1 +
ffh 255 Bed correction valid +
0x0FBFh 4031charEEPROM_BED_CORRECTION_LEFT 00h FFh 00h 0 Bed manual correction left D3 Ax0fbf C1 +
At this moment limited to +-100um +
0x0FBEh 4030charEEPROM_BED_CORRECTION_RIGHT 00h FFh 00h 0 Bed manual correction right D3 Ax0fbe C1 +
At this moment limited to +-100um +
0x0FBDh 4029charEEPROM_BED_CORRECTION_FRONT 00h FFh 00h 0 Bed manual correction front D3 Ax0fbd C1 +
At this moment limited to +-100um +
0x0FBCh 4028charEEPROM_BED_CORRECTION_BACK 00h FFh 00h 0 Bed manual correction back D3 Ax0fbc C1 +
At this moment limited to +-100um +
0x0FBBh 4027boolEEPROM_TOSHIBA_FLASH_AIR_COMPATIBLITY 00h 0 00h 0 Toshiba Air off D3 Ax0fbb C1 +
ffh 255 Toshiba Air oon +
0x0FBAh 4026 uchar EEPROM_PRINT_FLAG ??? ??? _unsued_ D3 Ax0fba C1 +
0x0FB0h 4016int16EEPROM_PROBE_TEMP_SHIFT ??? ??? ??? D3 Ax0fb0 C10 +
??? +
??? +
??? +
??? +
0x0FAFh 4015boolEEPROM_TEMP_CAL_ACTIVE 00h 0 00h 0 PINDA Temp cal. inactive D3 Ax0faf C1 +
FFh 255 PINDA Temp cal. active +
0x0FA7h 4007uint32EEPROM_BOWDEN_LENGTH ??? ff 00 ff ffh Bowden length D3 Ax0fae C8 +
ff ff ff ffh +
0x0FA6h 4006uint8EEPROM_CALIBRATION_STATUS_PINDA 00h 0 ffh 255 PINDA Temp not calibrated D3 Ax0fa6 C1 +
01h 1 PINDA Temp calibrated +
0x0FA5h 4005uint8EEPROM_UVLO 00h 0 ffh 255 Power Panic flag inactive D3 Ax0fa5 C1 +
01h 1 Power Panic flag active +
02h 2 Power Panic flag ??? +
0x0F9Dh 3997floatEEPROM_UVLO_CURRENT_POSITION ??? ffh 255 Power Panic position D3 Ax0f9d C8 +
??? +
0x0F95h 3989charEEPROM_FILENAME ??? ffh 255 Power Panic Filename D3 Ax0f95 C8 +
??? +
??? +
??? +
??? +
??? +
??? +
??? +
0x0F91h 39851 unit32 EEPROM_FILE_POSITION ??? ff ff ff ffh Power Panic File Postion D3 Ax0f91 C4 +
0x0F8Dh 3981 float EEPROM_UVLO_CURRENT_POSITION_Z ??? ff ff ff ffh Power Panic Z Position D3 Ax0f8d C4 +
0x0F8Ch 3980???EEPROM_UVLO_UNUSED_001 ??? ffh 255 Power Panic UNUSED D3 Ax0f8c C1 +
0x0F8Bh 3979uint8EEPROM_UVLO_TARGET_BED ??? ffh 255 Power Panic Bed temperature D3 Ax0f8b C1 +
0x0F89h 3977uint16EEPROM_UVLO_FEEDRATE ??? ff ffh 65535 Power Panic Feedrate D3 Ax0f89 C2 +
0x0F88h 3976uint8EEPROM_UVLO_FAN_SPEED ??? ffh 255 Power Panic Fan speed D3 Ax0f88 C1 +
0x0F87h 3975uint8EEPROM_FAN_CHECK_ENABLED 00h 0 Fan Check disabled D3 Ax0f87 C1 +
01h 1 ffh 255 Fan Check enabled (exception ffh=01h) + + +
+*/ #define EEPROM_EMPTY_VALUE 0xFF #define EEPROM_EMPTY_VALUE16 0xFFFF @@ -230,6 +342,7 @@ static Sheets * const EEPROM_Sheets_base = (Sheets*)(EEPROM_SHEETS_BASE); // Magic string, indicating that the current or the previous firmware running was the Prusa3D firmware. #define EEPROM_FIRMWARE_PRUSA_MAGIC 0 + #ifdef __cplusplus #include "ConfigurationStore.h" static_assert(EEPROM_FIRMWARE_VERSION_END < 20, "Firmware version EEPROM address conflicts with EEPROM_M500_base"); @@ -256,3 +369,4 @@ void eeprom_switch_to_next_sheet(); #endif #endif // EEPROM_H + From 4d40ed67f67bda91ab1c8e87266191ffeece9ef3 Mon Sep 17 00:00:00 2001 From: 3d-gussner <3d.gussner@gmail.com> Date: Thu, 12 Mar 2020 12:36:48 +0100 Subject: [PATCH 098/158] remove LF --- Firmware/eeprom.h | 2 -- 1 file changed, 2 deletions(-) diff --git a/Firmware/eeprom.h b/Firmware/eeprom.h index 7f431d24..07cb2a9c 100644 --- a/Firmware/eeprom.h +++ b/Firmware/eeprom.h @@ -342,7 +342,6 @@ static Sheets * const EEPROM_Sheets_base = (Sheets*)(EEPROM_SHEETS_BASE); // Magic string, indicating that the current or the previous firmware running was the Prusa3D firmware. #define EEPROM_FIRMWARE_PRUSA_MAGIC 0 - #ifdef __cplusplus #include "ConfigurationStore.h" static_assert(EEPROM_FIRMWARE_VERSION_END < 20, "Firmware version EEPROM address conflicts with EEPROM_M500_base"); @@ -369,4 +368,3 @@ void eeprom_switch_to_next_sheet(); #endif #endif // EEPROM_H - From c8fc5b2fed52a813532c3f469162bc966216f685 Mon Sep 17 00:00:00 2001 From: 3d-gussner <3d.gussner@gmail.com> Date: Fri, 20 Mar 2020 10:44:12 +0100 Subject: [PATCH 099/158] Simpler tabel syntax --- Firmware/eeprom.h | 172 +++++++++++++++++++++++----------------------- 1 file changed, 85 insertions(+), 87 deletions(-) diff --git a/Firmware/eeprom.h b/Firmware/eeprom.h index 07cb2a9c..9322ca0f 100644 --- a/Firmware/eeprom.h +++ b/Firmware/eeprom.h @@ -50,95 +50,93 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP --------------------------------------------------------------------------------- - - - -
EEPROM Table
Adress begin Bit/Type Name Valid values Default/FactoryResetDescription Debug code -
0x0FFFh 4095ucharEEPROM_SILENT 00h 0 ??? TMC Stealth mode off / miniRambo Power mode D3 Ax0fff C1 -
01h 1 TMC Stealth mode on / miniRambo Silent mode -
02h 2 Auto mode -
0x0FFEh 4094ucharEEPROM_LANG 00h 0 00h 0 English / LANG_ID_PRI D3 Ax0ffe C1 -
01h 1 Other language LANG_ID_SEC -
0x0FFCh 4092 uint16 EEPROM_BABYSTEP_X ??? ffh 255 Babystep for X axis _unsued_ D3 Ax0ffc C2 -
0x0FFAh 4090 uint16 EEPROM_BABYSTEP_Y ??? ffh 222 Babystep for Y axis _unsued_ D3 Ax0ffa C2 -
0x0FF8h 4088uint16EEPROM_BABYSTEP_Z ??? ffh 255 Babystep for Z axis _lagacy_ D3 Ax0ff8 C2 -
multiple values stored now in EEPROM_Sheets_base -
0x0FF7h 4087uint8EEPROM_CALIBRATION_STATUS 00h 0 ffh 255 Unknown D3 Ax0ff7 C1 -
01h 1 Calibrated -
E6h 230 needs Live Z adjustment -
F0h 240 needs Z calibration -
FAh 250 needs XYZ calibration -
FFh 255 Assbemled _default_ -
0x0FF5h 4085 uint16 EEPROM_BABYSTEP_Z0 ??? ??? Babystep for Z ??? D3 Ax0ff5 C2 -
0x0FF1h 4081 uint32 EEPROM_FILAMENTUSED ??? 00h 0 Filament used in meters D3 Ax0ff1 C4 -
0x0FEDh 4077 uint32 EEPROM_TOTALTIME ??? 00h 0 Total print time D3 Ax0fed C4 -
0x0FE5h 4069floatEEPROM_BED_CALIBRATION_CENTER ??? ??? ??? D3 Ax0fe5 C8 -
??? -
0x0FDDh 4061floatEEPROM_BED_CALIBRATION_VEC_X ??? ??? ??? D3 Ax0fdd C8 -
??? -
0x0FD5h 4053floatEEPROM_BED_CALIBRATION_VEC_Y ??? ??? ??? D3 Ax0fd5 C8 -
??? -
0x0FC5h 4037int16EEPROM_BED_CALIBRATION_Z_JITTER??? ??? ??? D3 Ax0fc5 C16 -
??? -
??? -
??? -
??? -
??? -
??? -
??? -
0x0FC4h 4036boolEEPROM_FARM_MODE 00h 0 00h 0 Prusa farm mode off D3 Ax0fc4 C1 -
ffh 255 Prusa farm mode on -
0x0FC1h 4033 int16 EEPROM_FARM_NUMBER ??? ff ff ffh Prusa farm number D3 Ax0fc1 C3 -
0x0FC0h 4032boolEEPROM_BED_CORRECTION_VALID 00h 0 00h 0 Bed correction invalid D3 Ax0fc0 C1 -
ffh 255 Bed correction valid -
0x0FBFh 4031charEEPROM_BED_CORRECTION_LEFT 00h FFh 00h 0 Bed manual correction left D3 Ax0fbf C1 -
At this moment limited to +-100um -
0x0FBEh 4030charEEPROM_BED_CORRECTION_RIGHT 00h FFh 00h 0 Bed manual correction right D3 Ax0fbe C1 -
At this moment limited to +-100um -
0x0FBDh 4029charEEPROM_BED_CORRECTION_FRONT 00h FFh 00h 0 Bed manual correction front D3 Ax0fbd C1 -
At this moment limited to +-100um -
0x0FBCh 4028charEEPROM_BED_CORRECTION_BACK 00h FFh 00h 0 Bed manual correction back D3 Ax0fbc C1 -
At this moment limited to +-100um -
0x0FBBh 4027boolEEPROM_TOSHIBA_FLASH_AIR_COMPATIBLITY 00h 0 00h 0 Toshiba Air off D3 Ax0fbb C1 -
ffh 255 Toshiba Air oon -
0x0FBAh 4026 uchar EEPROM_PRINT_FLAG ??? ??? _unsued_ D3 Ax0fba C1 -
0x0FB0h 4016int16EEPROM_PROBE_TEMP_SHIFT ??? ??? ??? D3 Ax0fb0 C10 -
??? -
??? -
??? -
??? -
0x0FAFh 4015boolEEPROM_TEMP_CAL_ACTIVE 00h 0 00h 0 PINDA Temp cal. inactive D3 Ax0faf C1 -
FFh 255 PINDA Temp cal. active -
0x0FA7h 4007uint32EEPROM_BOWDEN_LENGTH ??? ff 00 ff ffh Bowden length D3 Ax0fae C8 -
ff ff ff ffh -
0x0FA6h 4006uint8EEPROM_CALIBRATION_STATUS_PINDA 00h 0 ffh 255 PINDA Temp not calibrated D3 Ax0fa6 C1 -
01h 1 PINDA Temp calibrated -
0x0FA5h 4005uint8EEPROM_UVLO 00h 0 ffh 255 Power Panic flag inactive D3 Ax0fa5 C1 -
01h 1 Power Panic flag active -
02h 2 Power Panic flag ??? -
0x0F9Dh 3997floatEEPROM_UVLO_CURRENT_POSITION ??? ffh 255 Power Panic position D3 Ax0f9d C8 -
??? -
0x0F95h 3989charEEPROM_FILENAME ??? ffh 255 Power Panic Filename D3 Ax0f95 C8 -
??? -
??? -
??? -
??? -
??? -
??? -
??? -
0x0F91h 39851 unit32 EEPROM_FILE_POSITION ??? ff ff ff ffh Power Panic File Postion D3 Ax0f91 C4 -
0x0F8Dh 3981 float EEPROM_UVLO_CURRENT_POSITION_Z ??? ff ff ff ffh Power Panic Z Position D3 Ax0f8d C4 -
0x0F8Ch 3980???EEPROM_UVLO_UNUSED_001 ??? ffh 255 Power Panic UNUSED D3 Ax0f8c C1 -
0x0F8Bh 3979uint8EEPROM_UVLO_TARGET_BED ??? ffh 255 Power Panic Bed temperature D3 Ax0f8b C1 -
0x0F89h 3977uint16EEPROM_UVLO_FEEDRATE ??? ff ffh 65535 Power Panic Feedrate D3 Ax0f89 C2 -
0x0F88h 3976uint8EEPROM_UVLO_FAN_SPEED ??? ffh 255 Power Panic Fan speed D3 Ax0f88 C1 -
0x0F87h 3975uint8EEPROM_FAN_CHECK_ENABLED 00h 0 Fan Check disabled D3 Ax0f87 C1 -
01h 1 ffh 255 Fan Check enabled (exception ffh=01h) + + ## EEPROM Tabel + +| Adress begin | Bit/Type | Name | Valid values | Default/FactoryReset | Description | Debug code +| :--: | :--: | :--: | :--: | :--: | :--: | :--: +| 0x0FFFh 4095 | uchar | EEPROM_SILENT | 00h 0 | ffh 255 | TMC Stealth mode off / miniRambo Power mode | D3 Ax0fff C1 +| ^ | ^ | ^ | 01h 1 | ^ | TMC Stealth mode on / miniRambo Silent mode | ^ +| 0x0FFEh 4094 | uchar | EEPROM_LANG | 00h 0 | ffh 255 | English / LANG_ID_PRI | D3 Ax0ffe C1 +| ^ | ^ | ^ | 01h 1 | ^ | Other language LANG_ID_SEC | ^ +| 0x0FFCh 4092 | uint16 | EEPROM_BABYSTEP_X | ??? | ffh 255 | Babystep for X axis _unsued_ | D3 Ax0ffc C2 +| 0x0FFAh 4090 | uint16 | EEPROM_BABYSTEP_Y | ??? | ffh 255 | Babystep for Y axis _unsued_ | D3 Ax0ffa C2 +| 0x0FF8h 4088 | uint16 | EEPROM_BABYSTEP_Z | ??? | ffh 255 | Babystep for Z axis _lagacy_ | D3 Ax0ff8 C2 +| ^ | ^ | ^ | ^ | ^ | multiple values stored now in EEPROM_Sheets_base | ^ +| 0x0FF7h 4087 | uint8 | EEPROM_CALIBRATION_STATUS | 00h 0 | ffh 255 | Unknown | D3 Ax0ff7 C1 +| ^ | ^ | ^ | 01h 1 | ^ | Calibrated | ^ +| ^ | ^ | ^ | E6h 230 | ^ | needs Live Z adjustment | ^ +| ^ | ^ | ^ | F0h 240 | ^ | needs Z calibration | ^ +| ^ | ^ | ^ | FAh 250 | ^ | needs XYZ calibration | ^ +| ^ | ^ | ^ | FFh 255 | ^ | Assbemled _default_ | ^ +| 0x0FF5h 4085 | uint16 | EEPROM_BABYSTEP_Z0 | ??? | ??? | Babystep for Z ??? | D3 Ax0ff5 C2 +| 0x0FF1h 4081 | uint32 | EEPROM_FILAMENTUSED | ??? | 00h 0 | Filament used in meters | D3 Ax0ff1 C4 +| 0x0FEDh 4077 | uint32 | EEPROM_TOTALTIME | ??? | 00h 0 | Total print time | D3 Ax0fed C4 +| 0x0FE5h 4069 | float | EEPROM_BED_CALIBRATION_CENTER | ??? | ??? | ??? | D3 Ax0fe5 C8 +| ^ | ^ | ^ | ??? | ??? | ??? | ^ +| 0x0FDDh 4061 | float | EEPROM_BED_CALIBRATION_VEC_X | ??? | ??? | ??? | D3 Ax0fdd C8 +| ^ | ^ | ^ | ??? | ??? | ??? | ^ +| 0x0FD5h 4053 | float | EEPROM_BED_CALIBRATION_VEC_Y | ??? | ??? | ??? | D3 Ax0fd5 C8 +| ^ | ^ | ^ | ??? | ??? | ??? | ^ +| 0x0FC5h 4037 | int16 | EEPROM_BED_CALIBRATION_Z_JITTER | ??? | ??? | ??? | D3 Ax0fc5 C16 +| ^ | ^ | ^ | ??? | ??? | ??? | ^ +| ^ | ^ | ^ | ??? | ??? | ??? | ^ +| ^ | ^ | ^ | ??? | ??? | ??? | ^ +| ^ | ^ | ^ | ??? | ??? | ??? | ^ +| ^ | ^ | ^ | ??? | ??? | ??? | ^ +| ^ | ^ | ^ | ??? | ??? | ??? | ^ +| ^ | ^ | ^ | ??? | ??? | ??? | ^ +| 0x0FC4h 4036 | bool | EEPROM_FARM_MODE | 00h 0 | 00h 0 | Prusa farm mode off | D3 Ax0fc4 C1 +| ^ | ^ | ^ | ??? | ffh 255 | Prusa farm mode on | ^ +| 0x0FC1h 4033 | int16 | EEPROM_FARM_NUMBER | ??? | ff ff ffh | Prusa farm number | D3 Ax0fc1 C3 +| 0x0FC0h 4032 | bool | EEPROM_BED_CORRECTION_VALID | 00h 0 | 00h 0 | Bed correction invalid | D3 Ax0fc0 C1 +| ^ | ^ | ^ | ffh 255 | | Bed correction valid ^ | ^ +| 0x0FBFh 4031 | char | EEPROM_BED_CORRECTION_LEFT | 00h FFh | 00h 0 | Bed manual correction left | D3 Ax0fbf C1 +| ^ | ^ | ^ | ??? | ??? | At this moment limited to +-100um | ^ +| 0x0FBEh 4030 | char | EEPROM_BED_CORRECTION_RIGHT | 00h FFh | 00h 0 | Bed manual correction right | D3 Ax0fbe C1 +| ^ | ^ | ^ | ??? | ??? | At this moment limited to +-100um | ^ +| 0x0FBDh 4029 | char | EEPROM_BED_CORRECTION_FRONT | 00h FFh | 00h 0 | Bed manual correction front | D3 Ax0fbd C1 +| ^ | ^ | ^ | ??? | ??? | At this moment limited to +-100um | ^ +| 0x0FBCh 4028 | char | EEPROM_BED_CORRECTION_BACK | 00h FFh | 00h 0 | Bed manual correction back | D3 Ax0fbc C1 +| ^ | ^ | ^ | ??? | ??? | At this moment limited to +-100um | ^ +| 0x0FBBh 4027 | bool | EEPROM_TOSHIBA_FLASH_AIR_COMPATIBLITY | 00h 0 | 00h 0 | Toshiba Air off | D3 Ax0fbb C1 +| ^ | ^ | ^ | ??? | ffh 255 | Toshiba Air oon | ^ +| 0x0FBAh 4026 | uchar | EEPROM_PRINT_FLAG | ??? | ??? | _unsued_ | D3 Ax0fba C1 +| 0x0FB0h 4016 | int16 | EEPROM_PROBE_TEMP_SHIFT | ??? | ??? | ??? | D3 Ax0fb0 C10 +| ^ | ^ | ^ | ??? | ??? | ??? | ^ +| ^ | ^ | ^ | ??? | ??? | ??? | ^ +| ^ | ^ | ^ | ??? | ??? | ??? | ^ +| ^ | ^ | ^ | ??? | ??? | ??? | ^ +| 0x0FAFh 4015 | bool | EEPROM_TEMP_CAL_ACTIVE | 00h 0 | 00h 0 | PINDA Temp cal. inactive | D3 Ax0faf C1 +| ^ | ^ | ^ | ffh 255 | ^ | PINDA Temp cal. active | ^ +| 0x0FA7h 4007 | uint32 | EEPROM_BOWDEN_LENGTH | ??? | ff 00 ff ffh | Bowden length | D3 Ax0fae C8 +| ^ | ^ | ^ | ??? | ff ff ff ffh | ^ | ^ +| 0x0FA6h 4006 | uint8 | EEPROM_CALIBRATION_STATUS_PINDA | 00h 0 | ffh 255 | PINDA Temp not calibrated | D3 Ax0fa6 C1 +| ^ | ^ | ^ | 01h 1 | ^ | PINDA Temp calibrated | ^ +| 0x0FA5h 4005 | uint8 | EEPROM_UVLO | 00h 0 | ffh 255 | Power Panic flag inactive | D3 Ax0fa5 C1 +| ^ | ^ | ^ | 01h 1 | ^ | Power Panic flag active | ^ +| ^ | ^ | ^ | 02h 2 | ^ | Power Panic flag ??? | ^ +| 0x0F9Dh 3997 | float | EEPROM_UVLO_CURRENT_POSITION | ??? | ffh 255 | Power Panic position | D3 Ax0f9d C8 +| ^ | ^ | ^ | ??? | ^ | ^ | ^ +| 0x0F95h 3989 | char | EEPROM_FILENAME | ??? | ffh 255 | Power Panic Filename | D3 Ax0f95 C8 +| ^ | ^ | ^ | ??? | ^ | ^ | ^ +| ^ | ^ | ^ | ??? | ^ | ^ | ^ +| ^ | ^ | ^ | ??? | ^ | ^ | ^ +| ^ | ^ | ^ | ??? | ^ | ^ | ^ +| ^ | ^ | ^ | ??? | ^ | ^ | ^ +| ^ | ^ | ^ | ??? | ^ | ^ | ^ +| ^ | ^ | ^ | ??? | ^ | ^ | ^ +| 0x0F91h 39851 | unit32 | EEPROM_FILE_POSITION | ??? | ff ff ff ffh | Power Panic File Postion | D3 Ax0f91 C4 +| 0x0F8Dh 3981 | float | EEPROM_UVLO_CURRENT_POSITION_Z | ??? | ff ff ff ffh | Power Panic Z Position | D3 Ax0f8d C4 +| 0x0F8Ch 3980 | ??? | EEPROM_UVLO_UNUSED_001 | ??? | ffh 255 | Power Panic UNUSED | D3 Ax0f8c C1 +| 0x0F8Bh 3979 | uint8 | EEPROM_UVLO_TARGET_BED | ??? | ffh 255 | Power Panic Bed temperature | D3 Ax0f8b C1 +| 0x0F89h 3977 | uint16 | EEPROM_UVLO_FEEDRATE | ??? | ff ffh 65535 | Power Panic Feedrate | D3 Ax0f89 C2 +| 0x0F88h 3976 | uint8 | EEPROM_UVLO_FAN_SPEED | ??? | ffh 255 | Power Panic Fan speed | D3 Ax0f88 C1 +| 0x0F87h 3975 | uint8 | EEPROM_FAN_CHECK_ENABLED | 00h 0 | ??? | Fan Check disabled | D3 Ax0f87 C1 +| ^ | ^ | ^ | 01h 1 | ffh 255 | Fan Check enabled (exception ffh=01h) | ^ -
-*/ - + */ #define EEPROM_EMPTY_VALUE 0xFF #define EEPROM_EMPTY_VALUE16 0xFFFF // The total size of the EEPROM is From 2591f8d5931cc722098ae0bee80b1dd0f94ff8fc Mon Sep 17 00:00:00 2001 From: 3d-gussner <3d.gussner@gmail.com> Date: Fri, 20 Mar 2020 12:36:26 +0100 Subject: [PATCH 100/158] Added and tested more... ... have to take a short break --- Firmware/eeprom.h | 202 +++++++++++++++++++++++++++------------------- 1 file changed, 118 insertions(+), 84 deletions(-) diff --git a/Firmware/eeprom.h b/Firmware/eeprom.h index 9322ca0f..d47b0cad 100644 --- a/Firmware/eeprom.h +++ b/Firmware/eeprom.h @@ -53,90 +53,124 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP ## EEPROM Tabel -| Adress begin | Bit/Type | Name | Valid values | Default/FactoryReset | Description | Debug code -| :--: | :--: | :--: | :--: | :--: | :--: | :--: -| 0x0FFFh 4095 | uchar | EEPROM_SILENT | 00h 0 | ffh 255 | TMC Stealth mode off / miniRambo Power mode | D3 Ax0fff C1 -| ^ | ^ | ^ | 01h 1 | ^ | TMC Stealth mode on / miniRambo Silent mode | ^ -| 0x0FFEh 4094 | uchar | EEPROM_LANG | 00h 0 | ffh 255 | English / LANG_ID_PRI | D3 Ax0ffe C1 -| ^ | ^ | ^ | 01h 1 | ^ | Other language LANG_ID_SEC | ^ -| 0x0FFCh 4092 | uint16 | EEPROM_BABYSTEP_X | ??? | ffh 255 | Babystep for X axis _unsued_ | D3 Ax0ffc C2 -| 0x0FFAh 4090 | uint16 | EEPROM_BABYSTEP_Y | ??? | ffh 255 | Babystep for Y axis _unsued_ | D3 Ax0ffa C2 -| 0x0FF8h 4088 | uint16 | EEPROM_BABYSTEP_Z | ??? | ffh 255 | Babystep for Z axis _lagacy_ | D3 Ax0ff8 C2 -| ^ | ^ | ^ | ^ | ^ | multiple values stored now in EEPROM_Sheets_base | ^ -| 0x0FF7h 4087 | uint8 | EEPROM_CALIBRATION_STATUS | 00h 0 | ffh 255 | Unknown | D3 Ax0ff7 C1 -| ^ | ^ | ^ | 01h 1 | ^ | Calibrated | ^ -| ^ | ^ | ^ | E6h 230 | ^ | needs Live Z adjustment | ^ -| ^ | ^ | ^ | F0h 240 | ^ | needs Z calibration | ^ -| ^ | ^ | ^ | FAh 250 | ^ | needs XYZ calibration | ^ -| ^ | ^ | ^ | FFh 255 | ^ | Assbemled _default_ | ^ -| 0x0FF5h 4085 | uint16 | EEPROM_BABYSTEP_Z0 | ??? | ??? | Babystep for Z ??? | D3 Ax0ff5 C2 -| 0x0FF1h 4081 | uint32 | EEPROM_FILAMENTUSED | ??? | 00h 0 | Filament used in meters | D3 Ax0ff1 C4 -| 0x0FEDh 4077 | uint32 | EEPROM_TOTALTIME | ??? | 00h 0 | Total print time | D3 Ax0fed C4 -| 0x0FE5h 4069 | float | EEPROM_BED_CALIBRATION_CENTER | ??? | ??? | ??? | D3 Ax0fe5 C8 -| ^ | ^ | ^ | ??? | ??? | ??? | ^ -| 0x0FDDh 4061 | float | EEPROM_BED_CALIBRATION_VEC_X | ??? | ??? | ??? | D3 Ax0fdd C8 -| ^ | ^ | ^ | ??? | ??? | ??? | ^ -| 0x0FD5h 4053 | float | EEPROM_BED_CALIBRATION_VEC_Y | ??? | ??? | ??? | D3 Ax0fd5 C8 -| ^ | ^ | ^ | ??? | ??? | ??? | ^ -| 0x0FC5h 4037 | int16 | EEPROM_BED_CALIBRATION_Z_JITTER | ??? | ??? | ??? | D3 Ax0fc5 C16 -| ^ | ^ | ^ | ??? | ??? | ??? | ^ -| ^ | ^ | ^ | ??? | ??? | ??? | ^ -| ^ | ^ | ^ | ??? | ??? | ??? | ^ -| ^ | ^ | ^ | ??? | ??? | ??? | ^ -| ^ | ^ | ^ | ??? | ??? | ??? | ^ -| ^ | ^ | ^ | ??? | ??? | ??? | ^ -| ^ | ^ | ^ | ??? | ??? | ??? | ^ -| 0x0FC4h 4036 | bool | EEPROM_FARM_MODE | 00h 0 | 00h 0 | Prusa farm mode off | D3 Ax0fc4 C1 -| ^ | ^ | ^ | ??? | ffh 255 | Prusa farm mode on | ^ -| 0x0FC1h 4033 | int16 | EEPROM_FARM_NUMBER | ??? | ff ff ffh | Prusa farm number | D3 Ax0fc1 C3 -| 0x0FC0h 4032 | bool | EEPROM_BED_CORRECTION_VALID | 00h 0 | 00h 0 | Bed correction invalid | D3 Ax0fc0 C1 -| ^ | ^ | ^ | ffh 255 | | Bed correction valid ^ | ^ -| 0x0FBFh 4031 | char | EEPROM_BED_CORRECTION_LEFT | 00h FFh | 00h 0 | Bed manual correction left | D3 Ax0fbf C1 -| ^ | ^ | ^ | ??? | ??? | At this moment limited to +-100um | ^ -| 0x0FBEh 4030 | char | EEPROM_BED_CORRECTION_RIGHT | 00h FFh | 00h 0 | Bed manual correction right | D3 Ax0fbe C1 -| ^ | ^ | ^ | ??? | ??? | At this moment limited to +-100um | ^ -| 0x0FBDh 4029 | char | EEPROM_BED_CORRECTION_FRONT | 00h FFh | 00h 0 | Bed manual correction front | D3 Ax0fbd C1 -| ^ | ^ | ^ | ??? | ??? | At this moment limited to +-100um | ^ -| 0x0FBCh 4028 | char | EEPROM_BED_CORRECTION_BACK | 00h FFh | 00h 0 | Bed manual correction back | D3 Ax0fbc C1 -| ^ | ^ | ^ | ??? | ??? | At this moment limited to +-100um | ^ -| 0x0FBBh 4027 | bool | EEPROM_TOSHIBA_FLASH_AIR_COMPATIBLITY | 00h 0 | 00h 0 | Toshiba Air off | D3 Ax0fbb C1 -| ^ | ^ | ^ | ??? | ffh 255 | Toshiba Air oon | ^ -| 0x0FBAh 4026 | uchar | EEPROM_PRINT_FLAG | ??? | ??? | _unsued_ | D3 Ax0fba C1 -| 0x0FB0h 4016 | int16 | EEPROM_PROBE_TEMP_SHIFT | ??? | ??? | ??? | D3 Ax0fb0 C10 -| ^ | ^ | ^ | ??? | ??? | ??? | ^ -| ^ | ^ | ^ | ??? | ??? | ??? | ^ -| ^ | ^ | ^ | ??? | ??? | ??? | ^ -| ^ | ^ | ^ | ??? | ??? | ??? | ^ -| 0x0FAFh 4015 | bool | EEPROM_TEMP_CAL_ACTIVE | 00h 0 | 00h 0 | PINDA Temp cal. inactive | D3 Ax0faf C1 -| ^ | ^ | ^ | ffh 255 | ^ | PINDA Temp cal. active | ^ -| 0x0FA7h 4007 | uint32 | EEPROM_BOWDEN_LENGTH | ??? | ff 00 ff ffh | Bowden length | D3 Ax0fae C8 -| ^ | ^ | ^ | ??? | ff ff ff ffh | ^ | ^ -| 0x0FA6h 4006 | uint8 | EEPROM_CALIBRATION_STATUS_PINDA | 00h 0 | ffh 255 | PINDA Temp not calibrated | D3 Ax0fa6 C1 -| ^ | ^ | ^ | 01h 1 | ^ | PINDA Temp calibrated | ^ -| 0x0FA5h 4005 | uint8 | EEPROM_UVLO | 00h 0 | ffh 255 | Power Panic flag inactive | D3 Ax0fa5 C1 -| ^ | ^ | ^ | 01h 1 | ^ | Power Panic flag active | ^ -| ^ | ^ | ^ | 02h 2 | ^ | Power Panic flag ??? | ^ -| 0x0F9Dh 3997 | float | EEPROM_UVLO_CURRENT_POSITION | ??? | ffh 255 | Power Panic position | D3 Ax0f9d C8 -| ^ | ^ | ^ | ??? | ^ | ^ | ^ -| 0x0F95h 3989 | char | EEPROM_FILENAME | ??? | ffh 255 | Power Panic Filename | D3 Ax0f95 C8 -| ^ | ^ | ^ | ??? | ^ | ^ | ^ -| ^ | ^ | ^ | ??? | ^ | ^ | ^ -| ^ | ^ | ^ | ??? | ^ | ^ | ^ -| ^ | ^ | ^ | ??? | ^ | ^ | ^ -| ^ | ^ | ^ | ??? | ^ | ^ | ^ -| ^ | ^ | ^ | ??? | ^ | ^ | ^ -| ^ | ^ | ^ | ??? | ^ | ^ | ^ -| 0x0F91h 39851 | unit32 | EEPROM_FILE_POSITION | ??? | ff ff ff ffh | Power Panic File Postion | D3 Ax0f91 C4 -| 0x0F8Dh 3981 | float | EEPROM_UVLO_CURRENT_POSITION_Z | ??? | ff ff ff ffh | Power Panic Z Position | D3 Ax0f8d C4 -| 0x0F8Ch 3980 | ??? | EEPROM_UVLO_UNUSED_001 | ??? | ffh 255 | Power Panic UNUSED | D3 Ax0f8c C1 -| 0x0F8Bh 3979 | uint8 | EEPROM_UVLO_TARGET_BED | ??? | ffh 255 | Power Panic Bed temperature | D3 Ax0f8b C1 -| 0x0F89h 3977 | uint16 | EEPROM_UVLO_FEEDRATE | ??? | ff ffh 65535 | Power Panic Feedrate | D3 Ax0f89 C2 -| 0x0F88h 3976 | uint8 | EEPROM_UVLO_FAN_SPEED | ??? | ffh 255 | Power Panic Fan speed | D3 Ax0f88 C1 -| 0x0F87h 3975 | uint8 | EEPROM_FAN_CHECK_ENABLED | 00h 0 | ??? | Fan Check disabled | D3 Ax0f87 C1 -| ^ | ^ | ^ | 01h 1 | ffh 255 | Fan Check enabled (exception ffh=01h) | ^ - - - */ +| Adress begin | Bit/Type | Name | Valid values | Default/FactoryReset | Description | Gcode/Function| Debug code +| :--: | :--: | :--: | :--: | :--: | :--: | :--: | :--: +| 0x0FFFh 4095 | uchar | EEPROM_SILENT | 00h 0 | ffh 255 | TMC Stealth mode off / miniRambo Power mode | LCD menu | D3 Ax0fff C1 +| ^ | ^ | ^ | 01h 1 | ^ | TMC Stealth mode on / miniRambo Silent mode | ^ | ^ +| 0x0FFEh 4094 | uchar | EEPROM_LANG | 00h 0 | ffh 255 | English / LANG_ID_PRI | LCD menu | D3 Ax0ffe C1 +| ^ | ^ | ^ | 01h 1 | ^ | Other language LANG_ID_SEC | ^ | ^ +| 0x0FFCh 4092 | uint16 | EEPROM_BABYSTEP_X | ??? | ffh 255 | Babystep for X axis _unsued_ | ??? | D3 Ax0ffc C2 +| 0x0FFAh 4090 | uint16 | EEPROM_BABYSTEP_Y | ??? | ffh 255 | Babystep for Y axis _unsued_ | ^ | D3 Ax0ffa C2 +| 0x0FF8h 4088 | uint16 | EEPROM_BABYSTEP_Z | ??? | ffh 255 | Babystep for Z axis _lagacy_ | ^ | D3 Ax0ff8 C2 +| ^ | ^ | ^ | ^ | ^ | multiple values stored now in EEPROM_Sheets_base | ^ | ^ +| 0x0FF7h 4087 | uint8 | EEPROM_CALIBRATION_STATUS | 00h 0 | ffh 255 | Unknown | ??? | D3 Ax0ff7 C1 +| ^ | ^ | ^ | 01h 1 | ^ | Calibrated | ^ | ^ +| ^ | ^ | ^ | E6h 230 | ^ | needs Live Z adjustment | ^ | ^ +| ^ | ^ | ^ | F0h 240 | ^ | needs Z calibration | ^ | ^ +| ^ | ^ | ^ | FAh 250 | ^ | needs XYZ calibration | ^ | ^ +| ^ | ^ | ^ | FFh 255 | ^ | Assbemled _default_ | ^ | ^ +| 0x0FF5h 4085 | uint16 | EEPROM_BABYSTEP_Z0 | ??? | ??? | Babystep for Z ??? | ??? | D3 Ax0ff5 C2 +| 0x0FF1h 4081 | uint32 | EEPROM_FILAMENTUSED | ??? | 00h 0 | Filament used in meters | ??? | D3 Ax0ff1 C4 +| 0x0FEDh 4077 | uint32 | EEPROM_TOTALTIME | ??? | 00h 0 | Total print time | ??? | D3 Ax0fed C4 +| 0x0FE5h 4069 | float | EEPROM_BED_CALIBRATION_CENTER | ??? | ??? | ??? | ??? | D3 Ax0fe5 C8 +| ^ | ^ | ^ | ??? | ??? | ??? | ^ | ^ +| 0x0FDDh 4061 | float | EEPROM_BED_CALIBRATION_VEC_X | ??? | ??? | ??? | ??? | D3 Ax0fdd C8 +| ^ | ^ | ^ | ??? | ??? | ??? | ^ | ^ +| 0x0FD5h 4053 | float | EEPROM_BED_CALIBRATION_VEC_Y | ??? | ??? | ??? | ??? | D3 Ax0fd5 C8 +| ^ | ^ | ^ | ??? | ??? | ??? | ^ | ^ +| 0x0FC5h 4037 | int16 | EEPROM_BED_CALIBRATION_Z_JITTER | ??? | ??? | ??? | ??? | D3 Ax0fc5 C16 +| ^ | ^ | ^ | ??? | ??? | ??? | ^ | ^ +| ^ | ^ | ^ | ??? | ??? | ??? | ^ | ^ +| ^ | ^ | ^ | ??? | ??? | ??? | ^ | ^ +| ^ | ^ | ^ | ??? | ??? | ??? | ^ | ^ +| ^ | ^ | ^ | ??? | ??? | ??? | ^ | ^ +| ^ | ^ | ^ | ??? | ??? | ??? | ^ | ^ +| ^ | ^ | ^ | ??? | ??? | ??? | ^ | ^ +| 0x0FC4h 4036 | bool | EEPROM_FARM_MODE | 00h 0 | ffh 255 | Prusa farm mode off | G99 | D3 Ax0fc4 C1 +| ^ | ^ | ^ | 01h 1 | ^ | Prusa farm mode on | G98 | ^ +| 0x0FC1h 4033 | int16 | EEPROM_FARM_NUMBER | ??? | ff ff ffh | Prusa farm number | ??? | D3 Ax0fc1 C3 +| 0x0FC0h 4032 | bool | EEPROM_BED_CORRECTION_VALID | 00h 0 | 00h 0 | Bed correction invalid | ??? | D3 Ax0fc0 C1 +| ^ | ^ | ^ | ffh 255 | | Bed correction valid ^ | ??? | ^ +| 0x0FBFh 4031 | char | EEPROM_BED_CORRECTION_LEFT | 00h FFh | 00h 0 | Bed manual correction left | LCD menu | D3 Ax0fbf C1 +| ^ | ^ | ^ | ??? | ??? | At this moment limited to +-100um | ^ | ^ +| 0x0FBEh 4030 | char | EEPROM_BED_CORRECTION_RIGHT | 00h FFh | 00h 0 | Bed manual correction right | LCD menu | D3 Ax0fbe C1 +| ^ | ^ | ^ | ??? | ??? | At this moment limited to +-100um | ^ | ^ +| 0x0FBDh 4029 | char | EEPROM_BED_CORRECTION_FRONT | 00h FFh | 00h 0 | Bed manual correction front | LCD menu | D3 Ax0fbd C1 +| ^ | ^ | ^ | ??? | ??? | At this moment limited to +-100um | ^ | ^ +| 0x0FBCh 4028 | char | EEPROM_BED_CORRECTION_BACK | 00h FFh | 00h 0 | Bed manual correction back | LCD menu | D3 Ax0fbc C1 +| ^ | ^ | ^ | ??? | ??? | At this moment limited to +-100um | ^ | ^ +| 0x0FBBh 4027 | bool | EEPROM_TOSHIBA_FLASH_AIR_COMPATIBLITY | 00h 0 | 00h 0 | Toshiba Air off | LCD menu | D3 Ax0fbb C1 +| ^ | ^ | ^ | ??? | ffh 255 | Toshiba Air oon | ^ | ^ +| 0x0FBAh 4026 | uchar | EEPROM_PRINT_FLAG | ??? | ??? | _unsued_ | ??? | D3 Ax0fba C1 +| 0x0FB0h 4016 | int16 | EEPROM_PROBE_TEMP_SHIFT | ??? | ??? | ??? | ??? | D3 Ax0fb0 C10 +| ^ | ^ | ^ | ??? | ??? | ??? | ^ | ^ +| ^ | ^ | ^ | ??? | ??? | ??? | ^ | ^ +| ^ | ^ | ^ | ??? | ??? | ??? | ^ | ^ +| ^ | ^ | ^ | ??? | ??? | ??? | ^ | ^ +| 0x0FAFh 4015 | bool | EEPROM_TEMP_CAL_ACTIVE | 00h 0 | 00h 0 | PINDA Temp cal. inactive | LCD menu | D3 Ax0faf C1 +| ^ | ^ | ^ | ffh 255 | ^ | PINDA Temp cal. active | ^ | ^ +| 0x0FA7h 4007 | uint32 | EEPROM_BOWDEN_LENGTH | ??? | ff 00 ff ffh | Bowden length | ??? | D3 Ax0fae C8 +| ^ | ^ | ^ | ??? | ff ff ff ffh | ^ | ^ | ^ +| 0x0FA6h 4006 | uint8 | EEPROM_CALIBRATION_STATUS_PINDA | 00h 0 | ffh 255 | PINDA Temp not calibrated | ??? | D3 Ax0fa6 C1 +| ^ | ^ | ^ | 01h 1 | ^ | PINDA Temp calibrated | ^ | ^ +| 0x0FA5h 4005 | uint8 | EEPROM_UVLO | 00h 0 | ffh 255 | Power Panic flag inactive | ??? | D3 Ax0fa5 C1 +| ^ | ^ | ^ | 01h 1 | ^ | Power Panic flag active | ^ | ^ +| ^ | ^ | ^ | 02h 2 | ^ | Power Panic flag ??? | ^ | ^ +| 0x0F9Dh 3997 | float | EEPROM_UVLO_CURRENT_POSITION | ??? | ffh 255 | Power Panic position | ??? | D3 Ax0f9d C8 +| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^ +| 0x0F95h 3989 | char | EEPROM_FILENAME | ??? | ffh 255 | Power Panic Filename | ??? | D3 Ax0f95 C8 +| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^ +| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^ +| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^ +| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^ +| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^ +| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^ +| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^ +| 0x0F91h 39851 | uint32 | EEPROM_FILE_POSITION | ??? | ff ff ff ffh | Power Panic File Postion | ??? | D3 Ax0f91 C4 +| 0x0F8Dh 3981 | float | EEPROM_UVLO_CURRENT_POSITION_Z | ??? | ff ff ff ffh | Power Panic Z Position | ^ | D3 Ax0f8d C4 +| 0x0F8Ch 3980 | ??? | EEPROM_UVLO_UNUSED_001 | ??? | ffh 255 | Power Panic UNUSED | ^ | D3 Ax0f8c C1 +| 0x0F8Bh 3979 | uint8 | EEPROM_UVLO_TARGET_BED | ??? | ffh 255 | Power Panic Bed temperature | ^ | D3 Ax0f8b C1 +| 0x0F89h 3977 | uint16 | EEPROM_UVLO_FEEDRATE | ??? | ff ffh 65535 | Power Panic Feedrate | ^ | D3 Ax0f89 C2 +| 0x0F88h 3976 | uint8 | EEPROM_UVLO_FAN_SPEED | ??? | ffh 255 | Power Panic Fan speed | ^ | D3 Ax0f88 C1 +| 0x0F87h 3975 | uint8 | EEPROM_FAN_CHECK_ENABLED | 00h 0 | ??? | Fan Check disabled | LCD menu | D3 Ax0f87 C1 +| ^ | ^ | ^ | 01h 1 | ffh 255 | Fan Check enabled (exception ffh=01h) | ^ | ^ +| 0x0F75h 3957 | uint16 | EEPROM_UVLO_MESH_BED_LEVELING | ??? | ff ffh 65535 | Power Panic Mesh Bed Leveling | ??? | D3 Ax0f75 C18 +| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^ +| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^ +| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^ +| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^ +| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^ +| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^ +| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^ +| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^ +| 0x0F73h 3955 | uint16 | EEPROM_UVLO_Z_MICROSTEPS | ??? | ff ffh 65535 | Power Panic Z microsteps | ??? | D3 Ax0f73 C2 +| 0x0F72h 3954 | uint8 | EEPROM_UVLO_E_ABS | ??? | ffh 255 | Power Panic ??? position | ??? | D3 Ax0f72 C1 +| 0x0F6Eh 3950 | foat | EEPROM_UVLO_CURRENT_POSITION_E | ??? | ff ff ff ffh | Power Panic E position | ??? | D3 Ax0f6e C4 +| 0x0F69h 3945 | uint8 | EEPROM_CRASH_DET | ffh 255 | ffh 255 | Crash detection enabled | LCD menu | D3 Ax0f69 C5 +| ^ | ^ | ^ | 00h 0 | ^ | Crash detection disabled | LCD menu | ^ +| ^ | ^ | ^ | ??? | ??? | ^ | ??? | ^ +| ^ | ^ | ^ | ??? | ??? | ^ | ??? | ^ +| ^ | ^ | ^ | ??? | ??? | ^ | ??? | ^ +| 0x0F68h 3944 | uint8 | EEPROM_CRASH_COUNT_Y | 00h-ffh 0-255 | ffh 255 | Crashes detected on y axis | ??? | D3 Ax0f68 C1 +| 0x0F67h 3943 | uint8 | EEPROM_FSENSOR | 01h 1 | ffh 255 | Filament sensor enabled | LCD menu | D3 Ax0f67 C1 +| 0x0F65h 3942 | uint8 | EEPROM_CRASH_COUNT_X | 00h-ffh 0-255 | ffh 255 | Crashes detected on x axis | ??? | D3 Ax0f66 C1 +| 0x0F65h 3941 | uint8 | EEPROM_FERROR_COUNT | 00h-ffh 0-255 | ffh 255 | Filament sensor error counter | ??? | D3 Ax0f65 C1 +| 0x0F64h 3940 | uint8 | EEPROM_POWER_COUNT | 00h-ffh 0-255 | ffh 255 | Power failure counter | ??? | D3 Ax0f64 C1 +| 0x0F60h 3936 | float | EEPROM_XYZ_CAL_SKEW | ??? | ff ff ff ffh | XYZ skew value | ??? | D3 Ax0f60 C4 +| 0x0F5Fh 3935 | uint8 | EEPROM_WIZARD_ACTIVE | 00h 0 | ??? | Wizard active | ??? | D3 Ax0f5f C1 +| ^ | ^ | ^ | 01h 1 | ??? | ^ | ^ | ^ +| 0x0F5Dh 3933 | uint16 | EEPROM_BELTSTATUS_X | ??? | ff ffh | X Beltstatus | ??? | D3 Ax0f5d C2 +| 0x0F5Bh 3931 | uint16 | EEPROM_BELTSTATUS_Y | ??? | ff ffh | Y Beltstatus | ??? | D3 Ax0f5b C2 +| 0x0F5Ah 3930 | uint8 | EEPROM_DIR_DEPTH | 00h-ffh 0-255 | ffh 255 | Directory depth | ??? | D3 Ax0f5a C1 +| 0x0F0Ah 3850 | uint8 | EEPROM_DIRS | ??? | ffh 255 | Directories ??? | ??? | D3 Ax0f0a C80 +| 0x0F09h 3849 | uint8 | EEPROM_SD_SORT | 00h 0 | ffh 255 | SD card sort by time | LCD menu | D3 Ax0f09 C1 +| ^ | ^ | ^ | 01h 1 | ^ | SD card sort by alphabet | LCD menu | ^ +| ^ | ^ | ^ | 02h 1 | ^ | SD card not sorted | LCD menu | ^ +| 0x0F08h 3848 | uint8 | EEPROM_SECOND_SERIAL_ACTIVE | 00h 0 | ffh 255 | RPi Port disabled | LCD menu | D3 Ax0f08 C1 +| ^ | ^ | ^ | 01h 1 | ^ | RPi Port enabled | LCD menu | ^ +| 0x0F07h 3847 | uint8 | EEPROM_FSENS_AUTOLOAD_ENABLED | 01h 1 | ffh 255 | Filament autoload enabled | LCD menu | D3 Ax0f07 C1 +| ^ | ^ | ^ | 00h 0 | ^ | Filament autoload disabled | LCD menu | ^ +*/ #define EEPROM_EMPTY_VALUE 0xFF #define EEPROM_EMPTY_VALUE16 0xFFFF // The total size of the EEPROM is From 028a27021baf7bbce9f01ca823434a5073e6114a Mon Sep 17 00:00:00 2001 From: 3d-gussner <3d.gussner@gmail.com> Date: Sun, 22 Mar 2020 14:08:21 +0100 Subject: [PATCH 101/158] All done... hope not I forgot one. I will re-test all `D3 Axyyyy Cz` before creating a PR. --- Firmware/eeprom.h | 168 ++++++++++++++++++++++++++++++++++++++++++++-- 1 file changed, 162 insertions(+), 6 deletions(-) diff --git a/Firmware/eeprom.h b/Firmware/eeprom.h index d47b0cad..f707ce68 100644 --- a/Firmware/eeprom.h +++ b/Firmware/eeprom.h @@ -48,7 +48,8 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP - Octoprint does support D-codes - _Pronterface_ does not support D-codes - + ### !!! D-codes are case sensitive so please don't use upper case A,C or X in the address you want to read !!! + --------------------------------------------------------------------------------- ## EEPROM Tabel @@ -92,15 +93,15 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP | 0x0FC0h 4032 | bool | EEPROM_BED_CORRECTION_VALID | 00h 0 | 00h 0 | Bed correction invalid | ??? | D3 Ax0fc0 C1 | ^ | ^ | ^ | ffh 255 | | Bed correction valid ^ | ??? | ^ | 0x0FBFh 4031 | char | EEPROM_BED_CORRECTION_LEFT | 00h FFh | 00h 0 | Bed manual correction left | LCD menu | D3 Ax0fbf C1 -| ^ | ^ | ^ | ??? | ??? | At this moment limited to +-100um | ^ | ^ +| ^ | ^ | ^ | ??? | ??? | At this moment limited to +-100um | G80 Lxxx | ^ | 0x0FBEh 4030 | char | EEPROM_BED_CORRECTION_RIGHT | 00h FFh | 00h 0 | Bed manual correction right | LCD menu | D3 Ax0fbe C1 -| ^ | ^ | ^ | ??? | ??? | At this moment limited to +-100um | ^ | ^ +| ^ | ^ | ^ | ??? | ??? | At this moment limited to +-100um | G80 Rxxx | ^ | 0x0FBDh 4029 | char | EEPROM_BED_CORRECTION_FRONT | 00h FFh | 00h 0 | Bed manual correction front | LCD menu | D3 Ax0fbd C1 -| ^ | ^ | ^ | ??? | ??? | At this moment limited to +-100um | ^ | ^ +| ^ | ^ | ^ | ??? | ??? | At this moment limited to +-100um | G80 Fxxx | ^ | 0x0FBCh 4028 | char | EEPROM_BED_CORRECTION_BACK | 00h FFh | 00h 0 | Bed manual correction back | LCD menu | D3 Ax0fbc C1 -| ^ | ^ | ^ | ??? | ??? | At this moment limited to +-100um | ^ | ^ +| ^ | ^ | ^ | ??? | ??? | At this moment limited to +-100um | G80 Bxxx | ^ | 0x0FBBh 4027 | bool | EEPROM_TOSHIBA_FLASH_AIR_COMPATIBLITY | 00h 0 | 00h 0 | Toshiba Air off | LCD menu | D3 Ax0fbb C1 -| ^ | ^ | ^ | ??? | ffh 255 | Toshiba Air oon | ^ | ^ +| ^ | ^ | ^ | ??? | ffh 255 | Toshiba Air on | ^ | ^ | 0x0FBAh 4026 | uchar | EEPROM_PRINT_FLAG | ??? | ??? | _unsued_ | ??? | D3 Ax0fba C1 | 0x0FB0h 4016 | int16 | EEPROM_PROBE_TEMP_SHIFT | ??? | ??? | ??? | ??? | D3 Ax0fb0 C10 | ^ | ^ | ^ | ??? | ??? | ??? | ^ | ^ @@ -170,7 +171,162 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP | ^ | ^ | ^ | 01h 1 | ^ | RPi Port enabled | LCD menu | ^ | 0x0F07h 3847 | uint8 | EEPROM_FSENS_AUTOLOAD_ENABLED | 01h 1 | ffh 255 | Filament autoload enabled | LCD menu | D3 Ax0f07 C1 | ^ | ^ | ^ | 00h 0 | ^ | Filament autoload disabled | LCD menu | ^ +| 0x0F05h 3845 | uint16 | EEPROM_CRASH_COUNT_X_TOT | 0000-fffe | ff ffh | Total charshes on x axis | ??? | D3 Ax0f05 C2 +| 0x0F03h 3843 | uint16 | EEPROM_CRASH_COUNT_Y_TOT | 0000-fffe | ff ffh | Total charshes on y axis | ??? | D3 Ax0f03 C2 +| 0x0F01h 3841 | uint16 | EEPROM_FERROR_COUNT_TOT | 0000-fffe | ff ffh | Total filament sensor errors | ??? | D3 Ax0f01 C2 +| 0x0EFFh 3839 | uint16 | EEPROM_POWER_COUNT_TOT | 0000-fffe | ff ffh | Total power failures | ??? | D3 Ax0eff C2 +| 0x0EFEh 3838 | uint8 | EEPROM_TMC2130_HOME_X_ORIGIN | ??? | ffh 255 | ??? | ??? | D3 Ax0efe C1 +| 0x0EFDh 3837 | uint8 | EEPROM MC2130_HOME_X_BSTEPS | ??? | ffh 255 | ??? | ??? | D3 Ax0efd C1 +| 0x0EFCh 3836 | uint8 | EEPROM_TMC2130_HOME_X_FSTEPS | ??? | ffh 255 | ??? | ??? | D3 Ax0efc C1 +| 0x0EFBh 3835 | uint8 | EEPROM_TMC2130_HOME_Y_ORIGIN | ??? | ffh 255 | ??? | ??? | D3 Ax0efb C1 +| 0x0EFAh 3834 | uint8 | EEPROM_TMC2130_HOME_Y_BSTEPS | ??? | ffh 255 | ??? | ??? | D3 Ax0efa C1 +| 0x0EF9h 3833 | uint8 | EEPROM_TMC2130_HOME_Y_FSTEPS | ??? | ffh 255 | ??? | ??? | D3 Ax0ef9 C1 +| 0x0EF8h 3832 | uint8 | EEPROM_TMC2130_HOME_ENABLED | ??? | ffh 255 | ??? | ??? | D3 Ax0ef8 C1 +| 0x0EF7h 3831 | uint8 | EEPROM_TMC2130_WAVE_X_FAC | ??? | ffh 255 | ??? | ??? | D3 Ax0ef7 C1 +| 0x0EF6h 3830 | uint8 | EEPROM_TMC2130_WAVE_Y_FAC | ??? | ffh 255 | ??? | ??? | D3 Ax0ef6 C1 +| 0x0EF5h 3829 | uint8 | EEPROM_TMC2130_WAVE_Z_FAC | ??? | ffh 255 | ??? | ??? | D3 Ax0ef5 C1 +| 0x0EF4h 3828 | uint8 | EEPROM_TMC2130_WAVE_E_FAC | ??? | ffh 255 | ??? | ??? | D3 Ax0ef4 C1 +| 0x0EF3h 3827 | uint8 | EEPROM_TMC2130_X_MRES | ??? | ffh 255 | ??? | ??? | D3 Ax0ef3 C1 +| 0x0EF2h 3826 | uint8 | EEPROM_TMC2130_Y_MRES | ??? | ffh 255 | ??? | ??? | D3 Ax0ef2 C1 +| 0x0EF1h 3825 | uint8 | EEPROM_TMC2130_Z_MRES | ??? | ffh 255 | ??? | ??? | D3 Ax0ef1 C1 +| 0x0EF0h 3824 | uint8 | EEPROM_TMC2130_E_MRES | ??? | ffh 255 | ??? | ??? | D3 Ax0ef0 C1 +| 0x0EEE 3822 | uint16 | EEPROM_PRINTER_TYPE | ??? | ff ffh 65535 | Printer Type | ??? | D3 Ax0eee C2 +| 0x0EEC 3820 | uint16 | EEPROM_BOARD_TYPE | ??? | ff ffh 65535 | Board Type | ??? | D3 Ax0eec C2 +| 0x0EE8 3816 | float | EEPROM_EXTRUDER_MULTIPLIER_0 | ??? | ff ff ff ffh | Power panic Extruder 0 multiplier | ??? | D3 Ax0ee8 C4 +| 0x0EE4 3812 | float | EEPROM_EXTRUDER_MULTIPLIER_1 | ??? | ff ff ff ffh | Power panic Extruder 1 multiplier | ??? | D3 Ax0ee4 C4 +| 0x0EE0 3808 | float | EEPROM_EXTRUDER_MULTIPLIER_2 | ??? | ff ff ff ffh | Power panic Extruder 2 multiplier | ??? | D3 Ax0ee0 C4 +| 0x0EDE 3806 | uint16 | EEPROM_EXTRUDEMULTIPLY | ??? | ff ffh 65535 | Power panic Extruder multiplier | ??? | D3 Ax0ede C2 +| 0x0EDA 3802 | float | EEPROM_UVLO_TINY_CURRENT_POSITION_Z | ??? | ff ff ff ffh | Power panic Z position | ??? | D3 Ax0eda C4 +| 0x0ED8 3800 | uint16 | EEPROM_UVLO_TARGET_HOTEND | ??? | ff ffh 65535 | Power panic traget Hotend temperature | ??? | D3 Ax0ed8 C2 +| 0x0ED7 3799 | uint8 | EEPROM_SOUND_MODE | 00h 0 | ffh 255 | Sound mode loud | ??? | D3 Ax0ed7 C1 +| ^ | ^ | ^ | 01h 1 | ^ | Sound mode once | ^ | ^ +| ^ | ^ | ^ | 02h 1 | ^ | Sound mode silent | ^ | ^ +| ^ | ^ | ^ | 03h 1 | ^ | Sound mode assist | ^ | ^ +| 0x0ED6 3798 | bool | EEPROM_AUTO_DEPLETE | 01h 1 | ffh 255 | MMU2/s autodeplete on | ??? | D3 Ax0ed6 C1 +| ^ | ^ | ^ | 00h 0 | ^ | MMU2/s autodeplete off | ^ | ^ +| 0x0ED5 3797 | bool | EEPROM_FSENS_OQ_MEASS_ENABLED | ??? | ffh 255 | PAT1925 ??? | ??? | D3 Ax0ed5 C1 +| ^ | ^ | ^ | ??? | ^ | PAT1925 ??? | ^ | ^ +| 0x0ED3 3795 | uint16 | EEPROM_MMU_FAIL_TOT | ??? | ff ffh 65535 | MMU2/s total failures | ??? | D3 Ax0ed3 C2 +| 0x0ED2 3794 | uint8 | EEPROM_MMU_FAIL | ??? | ffh 255 | MMU2/s fails during print | ??? | D3 Ax0ed2 C1 +| 0x0ED0 3792 | uint16 | EEPROM_MMU_LOAD_FAIL_TOT | ??? | ff ffh 65535 | MMU2/s total load failures | ??? | D3 Ax0ed0 C2 +| 0x0ECF 3791 | uint8 | EEPROM_MMU_LOAD_FAIL | ??? | ffh 255 | MMU2/s load failures during print | ??? | D3 Ax0ecf C1 +| 0x0ECE 3790 | uint8 | EEPROM_MMU_CUTTER_ENABLED | 00h 0 | ffh 255 | MMU2/s cutter disabled | LCD menu | D3 Ax0ece C1 +| ^ | ^ | ^ | 01h 1 | ^ | MMU2/s cutter enabled | ^ | ^ +| ^ | ^ | ^ | 02h 2 | ^ | MMU2/s cutter always | ^ | ^ +| 0x0DAE 3502 | uint16 | EEPROM_UVLO_MESH_BED_LEVELING_FULL | ??? | ff ffh 65535 | Power panic Mesh bed leveling points | ??? | D3 Ax0dae C288 +| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^ +| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^ +| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^ +| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^ +| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^ +| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^ +| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^ +| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^ +| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^ +| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^ +| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^ +| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^ +| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^ +| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^ +| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^ +| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^ +| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^ +| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^ +| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^ +| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^ +| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^ +| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^ +| 0x0DAD 3501 | uint8 | EEPROM_MBL_TYPE | ??? | ffh 255 | Mesh bed leveling precision _unused atm_ | ??? | D3 Ax0dad C1 +| 0x0DAC 3500 | bool | EEPROM_MBL_MAGNET_ELIMINATION | 01h 1 | ffh 255 | Mesh bed leveling ignore magnets | LCD menu | D3 Ax0dac C1 +| ^ | ^ | ^ | 00h 0 | ^ | Mesh bed leveling NOT ignore magnets | ^ | ^ +| 0x0DAB 3499 | uint8 | EEPROM_MBL_POINTS_NR | 03h 3 | ffh 255 | Mesh bed leveling points 3x3 | LCD menu | D3 Ax0dab C1 +| ^ | ^ | ^ | 07h 7 | ^ | Mesh bed leveling points 7x7 | ^ | ^ +| 0x0DAA 3498 | uint8 | EEPROM_MBL_PROBE_NR | 03h 3 | ffh 255 | MBL 3 times measurements for each point | LCD menu | D3 Ax0daa C1 +| ^ | ^ | ^ | 05h 5 | ^ | MBL 5 times measurements for each point | ^ | ^ +| ^ | ^ | ^ | 01h 1 | ^ | MBL 7 times measurements for each point | ^ | ^ +| 0x0DA9 3497 | uint8 | EEPROM_MMU_STEALTH | 01h 1 | ffh 255 | MMU2/s Silent mode on | ??? | D3 Ax0da9 C1 +| ^ | ^ | ^ | 00h 0 | ^ | MMU2/s Silent mode off | ^ | ^ +| 0x0DA8 3496 | uint8 | EEPROM_CHECK_MODE | 01h 1 | ffh 255 | Check mode for nozzle is warn | LCD menu | D3 Ax0da8 C1 +| ^ | ^ | ^ | 02h 0 | ^ | Check mode for nozzle is strict | ^ | ^ +| ^ | ^ | ^ | 00h 0 | ^ | Check mode for nozzle is none | ^ | ^ +| 0x0DA7 3495 | uint8 | EEPROM_NOZZLE_DIAMETER | 28h 40 | ffh 255 | Nozzle diameter is 40 or 0.40mm | LCD menu | D3 Ax0da7 C1 +| ^ | ^ | ^ | 3ch 60 | ^ | Nozzle diameter is 60 or 0.60mm | ^ | ^ +| ^ | ^ | ^ | 19h 25 | ^ | Nozzle diameter is 25 or 0.25mm | ^ | ^ +| 0x0DA5 3493 | uint16 | EEPROM_NOZZLE_DIAMETER_uM | 9001h | ff ffh 65535 | Nozzle diameter is 400um | LCD menu | D3 Ax0da5 C2 +| ^ | ^ | ^ | 5802h | ^ | Nozzle diameter is 600um | ^ | ^ +| ^ | ^ | ^ | fa00h | ^ | Nozzle diameter is 250um | ^ | ^ +| 0x0DA4 3492 | uint8 | EEPROM_CHECK_MODEL | 01h 1 | ffh 255 | Check mode for printer model is warn | LCD menu | D3 Ax0da4 C1 +| ^ | ^ | ^ | 02h 0 | ^ | Check mode for printer model is strict | ^ | ^ +| ^ | ^ | ^ | 00h 0 | ^ | Check mode for printer model is none | ^ | ^ +| 0x0DA3 3491 | uint8 | EEPROM_CHECK_VERSION | 01h 1 | ffh 255 | Check mode for firmware is warn | LCD menu | D3 Ax0da3 C1 +| ^ | ^ | ^ | 02h 0 | ^ | Check mode for firmware is strict | ^ | ^ +| ^ | ^ | ^ | 00h 0 | ^ | Check mode for firmware is none | ^ | ^ +| 0x0DA2 3490 | uint8 | EEPROM_CHECK_GCODE | 01h 1 | ffh 255 | Check mode for gcode is warn _unused atm_ | LCD menu | D3 Ax0da2 C1 +| ^ | ^ | ^ | 02h 0 | ^ | Check mode for gcode is strict _unused atm_ | ^ | ^ +| ^ | ^ | ^ | 00h 0 | ^ | Check mode for gcode is none _unused atm_ | ^ | ^ +| 0x0D49 3401 | uint16 | EEPROM_SHEETS_BASE | ??? | ffh 255 | ??? | LCD menu | D3 Ax0d49 C89 +| 0x0D49 3401 | char | _1st Sheet block_ | 536d6f6f746831| ffffffffffffff | 1st sheet - Name: _Smooth1_ | ^ | D3 Ax0d49 C7 +| 0x0D50 3408 | uint16 | ^ | 00 00h 0 | ff ffh 65535 | 1st sheet - Z offset | ^ | D3 Ax0d50 C2 +| 0x0D52 3410 | uint8 | ^ | 00h 0 | ffh 255 | 1st sheet - bed temp | ^ | D3 Ax0d52 C1 +| 0x0D53 3411 | uint8 | ^ | 00h 0 | ffh 255 | 1st sheet - PINDA temp | ^ | D3 Ax0d53 C1 +| 0x0D54 3412 | char | _2nd Sheet block_ | 536d6f6f746832| ffffffffffffff | 2nd sheet - Name: _Smooth2_ | ^ | D3 Ax0d54 C7 +| 0x0D5B 3419 | uint16 | ^ | 00 00h 0 | ff ffh 65535 | 2nd sheet - Z offset | ^ | D3 Ax0d5b C2 +| 0x0D5D 3421 | uint8 | ^ | 00h 0 | ffh 255 | 2nd sheet - bed temp | ^ | D3 Ax0d5d C1 +| 0x0D5E 3422 | uint8 | ^ | 00h 0 | ffh 255 | 2nd sheet - PINDA temp | ^ | D3 Ax0d5e C1 +| 0x0D5F 3423 | char | _3rd Sheet block_ | 54657874757231| ffffffffffffff | 3rd sheet - Name: _Textur1_ | ^ | D3 Ax0d5f C7 +| 0x0D66 3430 | uint16 | ^ | 00 00h 0 | ff ffh 65535 | 3rd sheet - Z offset | ^ | D3 Ax0d66 C2 +| 0x0D68 3432 | uint8 | ^ | 00h 0 | ffh 255 | 3rd sheet - bed temp | ^ | D3 Ax0d68 C1 +| 0x0D69 3433 | uint8 | ^ | 00h 0 | ffh 255 | 3rd sheet - PINDA temp | ^ | D3 Ax0d69 C1 +| 0x0D6A 3434 | char | _4th Sheet block_ | 54657874757232| ffffffffffffff | 4th sheet - Name: _Textur2_ | ^ | D3 Ax0d6a C7 +| 0x0D71 3441 | uint16 | ^ | 00 00h 0 | ff ffh 65535 | 4th sheet - Z offset | ^ | D3 Ax0d71 C2 +| 0x0D73 3443 | uint8 | ^ | 00h 0 | ffh 255 | 4th sheet - bed temp | ^ | D3 Ax0d73 C1 +| 0x0D74 3444 | uint8 | ^ | 00h 0 | ffh 255 | 4th sheet - PINDA temp | ^ | D3 Ax0d74 C1 +| 0x0D75 3445 | char | _5th Sheet block_ | 437573746f6d31| ffffffffffffff | 5th sheet - Name: _Custom1_ | ^ | D3 Ax0d75 C7 +| 0x0D7C 3452 | uint16 | ^ | 00 00h 0 | ff ffh 65535 | 5th sheet - Z offset | ^ | D3 Ax0d7c C2 +| 0x0D7E 3454 | uint8 | ^ | 00h 0 | ffh 255 | 5th sheet - bed temp | ^ | D3 Ax0d7e C1 +| 0x0D7F 3455 | uint8 | ^ | 00h 0 | ffh 255 | 5th sheet - PINDA temp | ^ | D3 Ax0d7f C1 +| 0x0D80 3456 | char | _6th Sheet block_ | 437573746f6d32| ffffffffffffff | 6th sheet - Name: _Custom2_ | ^ | D3 Ax0d80 C7 +| 0x0D87 3463 | uint16 | ^ | 00 00h 0 | ff ffh 65535 | 6th sheet - Z offset | ^ | D3 Ax0d87 C2 +| 0x0D89 3465 | uint8 | ^ | 00h 0 | ffh 255 | 6th sheet - bed temp | ^ | D3 Ax0d89 C1 +| 0x0D8A 3466 | uint8 | ^ | 00h 0 | ffh 255 | 6th sheet - PINDA temp | ^ | D3 Ax0d8a C1 +| 0x0D8B 3467 | char | _7th Sheet block_ | 437573746f6d33| ffffffffffffff | 7th sheet - Name: _Custom3_ | ^ | D3 Ax0d8b C7 +| 0x0D92 3474 | uint16 | ^ | 00 00h 0 | ff ffh 65535 | 7th sheet - Z offset | ^ | D3 Ax0d92 C2 +| 0x0D94 3476 | uint8 | ^ | 00h 0 | ffh 255 | 7th sheet - bed temp | ^ | D3 Ax0d94 C1 +| 0x0D95 3477 | uint8 | ^ | 00h 0 | ffh 255 | 7th sheet - PINDA temp | ^ | D3 Ax0d95 C1 +| 0x0D96 3478 | char | _8th Sheet block_ | 437573746f6d34| ffffffffffffff | 8th sheet - Name: _Custom4_ | ^ | D3 Ax0d96 C7 +| 0x0D9D 3485 | uint16 | ^ | 00 00h 0 | ff ffh 65535 | 8th sheet - Z offset | ^ | D3 Ax0d9d C2 +| 0x0D9F 3487 | uint8 | ^ | 00h 0 | ffh 255 | 8th sheet - bed temp | ^ | D3 Ax0d9f C1 +| 0x0DA0 3488 | uint8 | ^ | 00h 0 | ffh 255 | 8th sheet - PINDA temp | ^ | D3 Ax0da0 C1 +| 0x0DA1 3489 | uint8 | ??? | 00h 0 | ffh 255 | ??? | ??? | D3 Ax0da1 C1 +| 0x0D48 3400 | uint8 | EEPROM_FSENSOR_PCB | ??? | ffh 255 | Filament Sensor type old vs new | ??? | D3 Ax0d48 C1 +| ^ | ^ | ^ | ??? | ^ | Filament Sensor type ??? | ^ | ^ +| 0x0D47 3399 | uint8 | EEPROM_FSENSOR_ACTION_NA | 00h 0 | ffh 255 | Filament Sensor action: _Continue_ | LCD menu | D3 Ax0d47 C1 +| ^ | ^ | ^ | 01h 1 | ^ | Filament Sensor action: Pause | ^ | ^ +| 0x0D37 3383 | float | EEPROM_UVLO_SAVED_TARGET | ??? | ff ff ff ffh | Power panic saved target all-axis | ??? | D3 Ax0d37 C16 +| ^ | ^ | ^ | ??? | ^ | Power panic saved target e-axis | ^ | D3 Ax0d43 C4 +| ^ | ^ | ^ | ??? | ^ | Power panic saved target z-axis | ^ | D3 Ax0d3f C4 +| ^ | ^ | ^ | ??? | ^ | Power panic saved target y-axis | ^ | D3 Ax0d3b C4 +| ^ | ^ | ^ | ??? | ^ | Power panic saved target x-axis | ^ | D3 Ax0d37 C4 +| 0x0D35 3381 | uint16 | EEPROM_UVLO_FEEDMULTIPLY | ??? | ff ffh 65355 | Power panic saved feed multiplier | ??? | D3 Ax0d35 C2 +| 0x0D34 3380 | uint8 | EEPROM_BACKLIGHT_LEVEL_HIGH | 00h - ffh | 80h 128 | LCD backlight bright _128_ Dim value to 255 | LCD menu | D3 Ax0d34 C1 +| 0x0D33 3379 | uint8 | EEPROM_BACKLIGHT_LEVEL_LOW | 00h - ffh | 32h 50 | LCD backlight dim _50_ 0 to Bright value | LCD menu | D3 Ax0d33 C1 +| 0x0D32 3378 | uint8 | EEPROM_BACKLIGHT_MODE | 02h 2 | ffh 255 | LCD backlight mode: _Auto_ | LCD menu | D3 Ax0d32 C1 +| ^ | ^ | ^ | 01h 1 | ^ | LCD backlight mode: Bright | ^ | ^ +| ^ | ^ | ^ | 00h 0 | ^ | LCD backlight mode: Dim | ^ | ^ +| 0x0D30 3376 | uint16 | EEPROM_BACKLIGHT_TIMEOUT | 01 00 - ff ff | ff ffh 65535 | LCD backlight timeout: _10_ seconds | LCD menu | D3 Ax0d30 C2 +| 0x0D2C 3372 | float | EEPROM_UVLO_LA_K | ??? | ff ff ff ffh | Power panic saved Linear Advanced K value | ??? | D3 Ax0d2c C4 + + ## End of EEPROM Table + +| Adress begin | Bit/Type | Name | Valid values | Default/FactoryReset | Description | Gcode/Function| Debug code +| :--: | :--: | :--: | :--: | :--: | :--: | :--: | :--: +| 0x0012 18 | uint16 | EEPROM_FIRMWARE_VERSION_END | ??? | ff ffh 65535 | ??? | ??? | D3 Ax0012 C2 +| 0x0010 16 | uint16 | EEPROM_FIRMWARE_VERSION_FLAVOR | ??? | ff ffh 65535 | ??? | ??? | D3 Ax0010 C2 +| 0x000E 14 | uint16 | EEPROM_FIRMWARE_VERSION_REVISION | ??? | ff ffh 65535 | Firmware version revision number DEV/ALPHA/BETA/RC| ??? | D3 Ax000e C2 +| 0x000C 12 | uint16 | EEPROM_FIRMWARE_VERSION_MINOR | ??? | ff ffh 65535 | Firmware version minor number | ??? | D3 Ax000c C2 +| 0x000A 10 | uint16 | EEPROM_FIRMWARE_VERSION_MAJOR | ??? | ff ffh 65535 | Firmware version major number | ??? | D3 Ax000a C2 */ + #define EEPROM_EMPTY_VALUE 0xFF #define EEPROM_EMPTY_VALUE16 0xFFFF // The total size of the EEPROM is From b178252eb9a4737aed95af3bc96a0a01991608dd Mon Sep 17 00:00:00 2001 From: 3d-gussner <3d.gussner@gmail.com> Date: Sun, 22 Mar 2020 15:18:45 +0100 Subject: [PATCH 102/158] Added Italic and Bold to highlight some settings --- Firmware/eeprom.h | 146 ++++++++++++++++++++++++---------------------- 1 file changed, 75 insertions(+), 71 deletions(-) diff --git a/Firmware/eeprom.h b/Firmware/eeprom.h index f707ce68..e149526e 100644 --- a/Firmware/eeprom.h +++ b/Firmware/eeprom.h @@ -42,6 +42,10 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP EEPROM 16-bit Empty value = 0xFFFFh 65535 + _Italic = unsued or default_ + + __Bold = Status__ + --------------------------------------------------------------------------------- How can you use the debug codes? - Serial terminal like Putty. @@ -52,12 +56,11 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP --------------------------------------------------------------------------------- - ## EEPROM Tabel | Adress begin | Bit/Type | Name | Valid values | Default/FactoryReset | Description | Gcode/Function| Debug code -| :--: | :--: | :--: | :--: | :--: | :--: | :--: | :--: -| 0x0FFFh 4095 | uchar | EEPROM_SILENT | 00h 0 | ffh 255 | TMC Stealth mode off / miniRambo Power mode | LCD menu | D3 Ax0fff C1 -| ^ | ^ | ^ | 01h 1 | ^ | TMC Stealth mode on / miniRambo Silent mode | ^ | ^ +| :-- | :-- | :-- | :--: | :--: | :-- | :--: | :--: +| 0x0FFFh 4095 | uchar | EEPROM_SILENT | 00h 0 | ffh 255 | TMC Stealth mode: __off__ / miniRambo Power mode | LCD menu | D3 Ax0fff C1 +| ^ | ^ | ^ | 01h 1 | ^ | TMC Stealth mode: __on__ / miniRambo Silent mode | ^ | ^ | 0x0FFEh 4094 | uchar | EEPROM_LANG | 00h 0 | ffh 255 | English / LANG_ID_PRI | LCD menu | D3 Ax0ffe C1 | ^ | ^ | ^ | 01h 1 | ^ | Other language LANG_ID_SEC | ^ | ^ | 0x0FFCh 4092 | uint16 | EEPROM_BABYSTEP_X | ??? | ffh 255 | Babystep for X axis _unsued_ | ??? | D3 Ax0ffc C2 @@ -87,11 +90,11 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP | ^ | ^ | ^ | ??? | ??? | ??? | ^ | ^ | ^ | ^ | ^ | ??? | ??? | ??? | ^ | ^ | ^ | ^ | ^ | ??? | ??? | ??? | ^ | ^ -| 0x0FC4h 4036 | bool | EEPROM_FARM_MODE | 00h 0 | ffh 255 | Prusa farm mode off | G99 | D3 Ax0fc4 C1 -| ^ | ^ | ^ | 01h 1 | ^ | Prusa farm mode on | G98 | ^ +| 0x0FC4h 4036 | bool | EEPROM_FARM_MODE | 00h 0 | ffh 255 | Prusa farm mode: __off__ | G99 | D3 Ax0fc4 C1 +| ^ | ^ | ^ | 01h 1 | ^ | Prusa farm mode: __on__ | G98 | ^ | 0x0FC1h 4033 | int16 | EEPROM_FARM_NUMBER | ??? | ff ff ffh | Prusa farm number | ??? | D3 Ax0fc1 C3 | 0x0FC0h 4032 | bool | EEPROM_BED_CORRECTION_VALID | 00h 0 | 00h 0 | Bed correction invalid | ??? | D3 Ax0fc0 C1 -| ^ | ^ | ^ | ffh 255 | | Bed correction valid ^ | ??? | ^ +| ^ | ^ | ^ | ffh 255 | | Bed correction valid | ??? | ^ | 0x0FBFh 4031 | char | EEPROM_BED_CORRECTION_LEFT | 00h FFh | 00h 0 | Bed manual correction left | LCD menu | D3 Ax0fbf C1 | ^ | ^ | ^ | ??? | ??? | At this moment limited to +-100um | G80 Lxxx | ^ | 0x0FBEh 4030 | char | EEPROM_BED_CORRECTION_RIGHT | 00h FFh | 00h 0 | Bed manual correction right | LCD menu | D3 Ax0fbe C1 @@ -100,23 +103,23 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP | ^ | ^ | ^ | ??? | ??? | At this moment limited to +-100um | G80 Fxxx | ^ | 0x0FBCh 4028 | char | EEPROM_BED_CORRECTION_BACK | 00h FFh | 00h 0 | Bed manual correction back | LCD menu | D3 Ax0fbc C1 | ^ | ^ | ^ | ??? | ??? | At this moment limited to +-100um | G80 Bxxx | ^ -| 0x0FBBh 4027 | bool | EEPROM_TOSHIBA_FLASH_AIR_COMPATIBLITY | 00h 0 | 00h 0 | Toshiba Air off | LCD menu | D3 Ax0fbb C1 -| ^ | ^ | ^ | ??? | ffh 255 | Toshiba Air on | ^ | ^ +| 0x0FBBh 4027 | bool | EEPROM_TOSHIBA_FLASH_AIR_COMPATIBLITY | 00h 0 | 00h 0 | Toshiba Air: __off__ | LCD menu | D3 Ax0fbb C1 +| ^ | ^ | ^ | ??? | ffh 255 | Toshiba Air: __on__ | ^ | ^ | 0x0FBAh 4026 | uchar | EEPROM_PRINT_FLAG | ??? | ??? | _unsued_ | ??? | D3 Ax0fba C1 | 0x0FB0h 4016 | int16 | EEPROM_PROBE_TEMP_SHIFT | ??? | ??? | ??? | ??? | D3 Ax0fb0 C10 | ^ | ^ | ^ | ??? | ??? | ??? | ^ | ^ | ^ | ^ | ^ | ??? | ??? | ??? | ^ | ^ | ^ | ^ | ^ | ??? | ??? | ??? | ^ | ^ | ^ | ^ | ^ | ??? | ??? | ??? | ^ | ^ -| 0x0FAFh 4015 | bool | EEPROM_TEMP_CAL_ACTIVE | 00h 0 | 00h 0 | PINDA Temp cal. inactive | LCD menu | D3 Ax0faf C1 -| ^ | ^ | ^ | ffh 255 | ^ | PINDA Temp cal. active | ^ | ^ +| 0x0FAFh 4015 | bool | EEPROM_TEMP_CAL_ACTIVE | 00h 0 | 00h 0 | PINDA Temp cal.: __inactive__ | LCD menu | D3 Ax0faf C1 +| ^ | ^ | ^ | ffh 255 | ^ | PINDA Temp cal.: __active__ | ^ | ^ | 0x0FA7h 4007 | uint32 | EEPROM_BOWDEN_LENGTH | ??? | ff 00 ff ffh | Bowden length | ??? | D3 Ax0fae C8 | ^ | ^ | ^ | ??? | ff ff ff ffh | ^ | ^ | ^ -| 0x0FA6h 4006 | uint8 | EEPROM_CALIBRATION_STATUS_PINDA | 00h 0 | ffh 255 | PINDA Temp not calibrated | ??? | D3 Ax0fa6 C1 -| ^ | ^ | ^ | 01h 1 | ^ | PINDA Temp calibrated | ^ | ^ -| 0x0FA5h 4005 | uint8 | EEPROM_UVLO | 00h 0 | ffh 255 | Power Panic flag inactive | ??? | D3 Ax0fa5 C1 -| ^ | ^ | ^ | 01h 1 | ^ | Power Panic flag active | ^ | ^ -| ^ | ^ | ^ | 02h 2 | ^ | Power Panic flag ??? | ^ | ^ +| 0x0FA6h 4006 | uint8 | EEPROM_CALIBRATION_STATUS_PINDA | 00h 0 | ffh 255 | PINDA Temp: __not calibrated__ | ??? | D3 Ax0fa6 C1 +| ^ | ^ | ^ | 01h 1 | ^ | PINDA Temp: __calibrated__ | ^ | ^ +| 0x0FA5h 4005 | uint8 | EEPROM_UVLO | 00h 0 | ffh 255 | Power Panic flag: __inactive__ | ??? | D3 Ax0fa5 C1 +| ^ | ^ | ^ | 01h 1 | ^ | Power Panic flag: __active__ | ^ | ^ +| ^ | ^ | ^ | 02h 2 | ^ | Power Panic flag: __???__ | ^ | ^ | 0x0F9Dh 3997 | float | EEPROM_UVLO_CURRENT_POSITION | ??? | ffh 255 | Power Panic position | ??? | D3 Ax0f9d C8 | ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^ | 0x0F95h 3989 | char | EEPROM_FILENAME | ??? | ffh 255 | Power Panic Filename | ??? | D3 Ax0f95 C8 @@ -129,7 +132,7 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP | ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^ | 0x0F91h 39851 | uint32 | EEPROM_FILE_POSITION | ??? | ff ff ff ffh | Power Panic File Postion | ??? | D3 Ax0f91 C4 | 0x0F8Dh 3981 | float | EEPROM_UVLO_CURRENT_POSITION_Z | ??? | ff ff ff ffh | Power Panic Z Position | ^ | D3 Ax0f8d C4 -| 0x0F8Ch 3980 | ??? | EEPROM_UVLO_UNUSED_001 | ??? | ffh 255 | Power Panic UNUSED | ^ | D3 Ax0f8c C1 +| 0x0F8Ch 3980 | ??? | EEPROM_UVLO_UNUSED_001 | ??? | ffh 255 | Power Panic _unused_ | ^ | D3 Ax0f8c C1 | 0x0F8Bh 3979 | uint8 | EEPROM_UVLO_TARGET_BED | ??? | ffh 255 | Power Panic Bed temperature | ^ | D3 Ax0f8b C1 | 0x0F89h 3977 | uint16 | EEPROM_UVLO_FEEDRATE | ??? | ff ffh 65535 | Power Panic Feedrate | ^ | D3 Ax0f89 C2 | 0x0F88h 3976 | uint8 | EEPROM_UVLO_FAN_SPEED | ??? | ffh 255 | Power Panic Fan speed | ^ | D3 Ax0f88 C1 @@ -147,13 +150,14 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP | 0x0F73h 3955 | uint16 | EEPROM_UVLO_Z_MICROSTEPS | ??? | ff ffh 65535 | Power Panic Z microsteps | ??? | D3 Ax0f73 C2 | 0x0F72h 3954 | uint8 | EEPROM_UVLO_E_ABS | ??? | ffh 255 | Power Panic ??? position | ??? | D3 Ax0f72 C1 | 0x0F6Eh 3950 | foat | EEPROM_UVLO_CURRENT_POSITION_E | ??? | ff ff ff ffh | Power Panic E position | ??? | D3 Ax0f6e C4 -| 0x0F69h 3945 | uint8 | EEPROM_CRASH_DET | ffh 255 | ffh 255 | Crash detection enabled | LCD menu | D3 Ax0f69 C5 -| ^ | ^ | ^ | 00h 0 | ^ | Crash detection disabled | LCD menu | ^ +| 0x0F69h 3945 | uint8 | EEPROM_CRASH_DET | ffh 255 | ffh 255 | Crash detection: __enabled__ | LCD menu | D3 Ax0f69 C5 +| ^ | ^ | ^ | 00h 0 | ^ | Crash detection: __disabled__ | LCD menu | ^ | ^ | ^ | ^ | ??? | ??? | ^ | ??? | ^ | ^ | ^ | ^ | ??? | ??? | ^ | ??? | ^ | ^ | ^ | ^ | ??? | ??? | ^ | ??? | ^ | 0x0F68h 3944 | uint8 | EEPROM_CRASH_COUNT_Y | 00h-ffh 0-255 | ffh 255 | Crashes detected on y axis | ??? | D3 Ax0f68 C1 -| 0x0F67h 3943 | uint8 | EEPROM_FSENSOR | 01h 1 | ffh 255 | Filament sensor enabled | LCD menu | D3 Ax0f67 C1 +| 0x0F67h 3943 | uint8 | EEPROM_FSENSOR | 01h 1 | ffh 255 | Filament sensor: __enabled__ | LCD menu | D3 Ax0f67 C1 +| ^ | ^ | ^ | 00h 0 | ^ | Filament sensor: __disabled__ | LCD menu | ^ | 0x0F65h 3942 | uint8 | EEPROM_CRASH_COUNT_X | 00h-ffh 0-255 | ffh 255 | Crashes detected on x axis | ??? | D3 Ax0f66 C1 | 0x0F65h 3941 | uint8 | EEPROM_FERROR_COUNT | 00h-ffh 0-255 | ffh 255 | Filament sensor error counter | ??? | D3 Ax0f65 C1 | 0x0F64h 3940 | uint8 | EEPROM_POWER_COUNT | 00h-ffh 0-255 | ffh 255 | Power failure counter | ??? | D3 Ax0f64 C1 @@ -164,13 +168,13 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP | 0x0F5Bh 3931 | uint16 | EEPROM_BELTSTATUS_Y | ??? | ff ffh | Y Beltstatus | ??? | D3 Ax0f5b C2 | 0x0F5Ah 3930 | uint8 | EEPROM_DIR_DEPTH | 00h-ffh 0-255 | ffh 255 | Directory depth | ??? | D3 Ax0f5a C1 | 0x0F0Ah 3850 | uint8 | EEPROM_DIRS | ??? | ffh 255 | Directories ??? | ??? | D3 Ax0f0a C80 -| 0x0F09h 3849 | uint8 | EEPROM_SD_SORT | 00h 0 | ffh 255 | SD card sort by time | LCD menu | D3 Ax0f09 C1 -| ^ | ^ | ^ | 01h 1 | ^ | SD card sort by alphabet | LCD menu | ^ -| ^ | ^ | ^ | 02h 1 | ^ | SD card not sorted | LCD menu | ^ -| 0x0F08h 3848 | uint8 | EEPROM_SECOND_SERIAL_ACTIVE | 00h 0 | ffh 255 | RPi Port disabled | LCD menu | D3 Ax0f08 C1 -| ^ | ^ | ^ | 01h 1 | ^ | RPi Port enabled | LCD menu | ^ -| 0x0F07h 3847 | uint8 | EEPROM_FSENS_AUTOLOAD_ENABLED | 01h 1 | ffh 255 | Filament autoload enabled | LCD menu | D3 Ax0f07 C1 -| ^ | ^ | ^ | 00h 0 | ^ | Filament autoload disabled | LCD menu | ^ +| 0x0F09h 3849 | uint8 | EEPROM_SD_SORT | 00h 0 | ffh 255 | SD card sort by: __time__ | LCD menu | D3 Ax0f09 C1 +| ^ | ^ | ^ | 01h 1 | ^ | SD card sort by: __alphabet__ | LCD menu | ^ +| ^ | ^ | ^ | 02h 1 | ^ | SD card: __not sorted__ | LCD menu | ^ +| 0x0F08h 3848 | uint8 | EEPROM_SECOND_SERIAL_ACTIVE | 00h 0 | ffh 255 | RPi Port: __disabled__ | LCD menu | D3 Ax0f08 C1 +| ^ | ^ | ^ | 01h 1 | ^ | RPi Port: __enabled__ | LCD menu | ^ +| 0x0F07h 3847 | uint8 | EEPROM_FSENS_AUTOLOAD_ENABLED | 01h 1 | ffh 255 | Filament autoload: __enabled__ | LCD menu | D3 Ax0f07 C1 +| ^ | ^ | ^ | 00h 0 | ^ | Filament autoload: __disabled__ | LCD menu | ^ | 0x0F05h 3845 | uint16 | EEPROM_CRASH_COUNT_X_TOT | 0000-fffe | ff ffh | Total charshes on x axis | ??? | D3 Ax0f05 C2 | 0x0F03h 3843 | uint16 | EEPROM_CRASH_COUNT_Y_TOT | 0000-fffe | ff ffh | Total charshes on y axis | ??? | D3 Ax0f03 C2 | 0x0F01h 3841 | uint16 | EEPROM_FERROR_COUNT_TOT | 0000-fffe | ff ffh | Total filament sensor errors | ??? | D3 Ax0f01 C2 @@ -198,21 +202,21 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP | 0x0EDE 3806 | uint16 | EEPROM_EXTRUDEMULTIPLY | ??? | ff ffh 65535 | Power panic Extruder multiplier | ??? | D3 Ax0ede C2 | 0x0EDA 3802 | float | EEPROM_UVLO_TINY_CURRENT_POSITION_Z | ??? | ff ff ff ffh | Power panic Z position | ??? | D3 Ax0eda C4 | 0x0ED8 3800 | uint16 | EEPROM_UVLO_TARGET_HOTEND | ??? | ff ffh 65535 | Power panic traget Hotend temperature | ??? | D3 Ax0ed8 C2 -| 0x0ED7 3799 | uint8 | EEPROM_SOUND_MODE | 00h 0 | ffh 255 | Sound mode loud | ??? | D3 Ax0ed7 C1 -| ^ | ^ | ^ | 01h 1 | ^ | Sound mode once | ^ | ^ -| ^ | ^ | ^ | 02h 1 | ^ | Sound mode silent | ^ | ^ -| ^ | ^ | ^ | 03h 1 | ^ | Sound mode assist | ^ | ^ -| 0x0ED6 3798 | bool | EEPROM_AUTO_DEPLETE | 01h 1 | ffh 255 | MMU2/s autodeplete on | ??? | D3 Ax0ed6 C1 -| ^ | ^ | ^ | 00h 0 | ^ | MMU2/s autodeplete off | ^ | ^ +| 0x0ED7 3799 | uint8 | EEPROM_SOUND_MODE | 00h 0 | ffh 255 | Sound mode: __loud__ | ??? | D3 Ax0ed7 C1 +| ^ | ^ | ^ | 01h 1 | ^ | Sound mode: __once__ | ^ | ^ +| ^ | ^ | ^ | 02h 1 | ^ | Sound mode: __silent__ | ^ | ^ +| ^ | ^ | ^ | 03h 1 | ^ | Sound mode: __assist__ | ^ | ^ +| 0x0ED6 3798 | bool | EEPROM_AUTO_DEPLETE | 01h 1 | ffh 255 | MMU2/s autodeplete: __on__ | ??? | D3 Ax0ed6 C1 +| ^ | ^ | ^ | 00h 0 | ^ | MMU2/s autodeplete: __off__ | ^ | ^ | 0x0ED5 3797 | bool | EEPROM_FSENS_OQ_MEASS_ENABLED | ??? | ffh 255 | PAT1925 ??? | ??? | D3 Ax0ed5 C1 | ^ | ^ | ^ | ??? | ^ | PAT1925 ??? | ^ | ^ | 0x0ED3 3795 | uint16 | EEPROM_MMU_FAIL_TOT | ??? | ff ffh 65535 | MMU2/s total failures | ??? | D3 Ax0ed3 C2 | 0x0ED2 3794 | uint8 | EEPROM_MMU_FAIL | ??? | ffh 255 | MMU2/s fails during print | ??? | D3 Ax0ed2 C1 | 0x0ED0 3792 | uint16 | EEPROM_MMU_LOAD_FAIL_TOT | ??? | ff ffh 65535 | MMU2/s total load failures | ??? | D3 Ax0ed0 C2 | 0x0ECF 3791 | uint8 | EEPROM_MMU_LOAD_FAIL | ??? | ffh 255 | MMU2/s load failures during print | ??? | D3 Ax0ecf C1 -| 0x0ECE 3790 | uint8 | EEPROM_MMU_CUTTER_ENABLED | 00h 0 | ffh 255 | MMU2/s cutter disabled | LCD menu | D3 Ax0ece C1 -| ^ | ^ | ^ | 01h 1 | ^ | MMU2/s cutter enabled | ^ | ^ -| ^ | ^ | ^ | 02h 2 | ^ | MMU2/s cutter always | ^ | ^ +| 0x0ECE 3790 | uint8 | EEPROM_MMU_CUTTER_ENABLED | 00h 0 | ffh 255 | MMU2/s cutter: __disabled__ | LCD menu | D3 Ax0ece C1 +| ^ | ^ | ^ | 01h 1 | ^ | MMU2/s cutter: __enabled__ | ^ | ^ +| ^ | ^ | ^ | 02h 2 | ^ | MMU2/s cutter: __always__ | ^ | ^ | 0x0DAE 3502 | uint16 | EEPROM_UVLO_MESH_BED_LEVELING_FULL | ??? | ff ffh 65535 | Power panic Mesh bed leveling points | ??? | D3 Ax0dae C288 | ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^ | ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^ @@ -237,33 +241,33 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP | ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^ | ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^ | 0x0DAD 3501 | uint8 | EEPROM_MBL_TYPE | ??? | ffh 255 | Mesh bed leveling precision _unused atm_ | ??? | D3 Ax0dad C1 -| 0x0DAC 3500 | bool | EEPROM_MBL_MAGNET_ELIMINATION | 01h 1 | ffh 255 | Mesh bed leveling ignore magnets | LCD menu | D3 Ax0dac C1 -| ^ | ^ | ^ | 00h 0 | ^ | Mesh bed leveling NOT ignore magnets | ^ | ^ -| 0x0DAB 3499 | uint8 | EEPROM_MBL_POINTS_NR | 03h 3 | ffh 255 | Mesh bed leveling points 3x3 | LCD menu | D3 Ax0dab C1 -| ^ | ^ | ^ | 07h 7 | ^ | Mesh bed leveling points 7x7 | ^ | ^ -| 0x0DAA 3498 | uint8 | EEPROM_MBL_PROBE_NR | 03h 3 | ffh 255 | MBL 3 times measurements for each point | LCD menu | D3 Ax0daa C1 -| ^ | ^ | ^ | 05h 5 | ^ | MBL 5 times measurements for each point | ^ | ^ -| ^ | ^ | ^ | 01h 1 | ^ | MBL 7 times measurements for each point | ^ | ^ -| 0x0DA9 3497 | uint8 | EEPROM_MMU_STEALTH | 01h 1 | ffh 255 | MMU2/s Silent mode on | ??? | D3 Ax0da9 C1 -| ^ | ^ | ^ | 00h 0 | ^ | MMU2/s Silent mode off | ^ | ^ -| 0x0DA8 3496 | uint8 | EEPROM_CHECK_MODE | 01h 1 | ffh 255 | Check mode for nozzle is warn | LCD menu | D3 Ax0da8 C1 -| ^ | ^ | ^ | 02h 0 | ^ | Check mode for nozzle is strict | ^ | ^ -| ^ | ^ | ^ | 00h 0 | ^ | Check mode for nozzle is none | ^ | ^ -| 0x0DA7 3495 | uint8 | EEPROM_NOZZLE_DIAMETER | 28h 40 | ffh 255 | Nozzle diameter is 40 or 0.40mm | LCD menu | D3 Ax0da7 C1 -| ^ | ^ | ^ | 3ch 60 | ^ | Nozzle diameter is 60 or 0.60mm | ^ | ^ -| ^ | ^ | ^ | 19h 25 | ^ | Nozzle diameter is 25 or 0.25mm | ^ | ^ -| 0x0DA5 3493 | uint16 | EEPROM_NOZZLE_DIAMETER_uM | 9001h | ff ffh 65535 | Nozzle diameter is 400um | LCD menu | D3 Ax0da5 C2 -| ^ | ^ | ^ | 5802h | ^ | Nozzle diameter is 600um | ^ | ^ -| ^ | ^ | ^ | fa00h | ^ | Nozzle diameter is 250um | ^ | ^ -| 0x0DA4 3492 | uint8 | EEPROM_CHECK_MODEL | 01h 1 | ffh 255 | Check mode for printer model is warn | LCD menu | D3 Ax0da4 C1 -| ^ | ^ | ^ | 02h 0 | ^ | Check mode for printer model is strict | ^ | ^ -| ^ | ^ | ^ | 00h 0 | ^ | Check mode for printer model is none | ^ | ^ -| 0x0DA3 3491 | uint8 | EEPROM_CHECK_VERSION | 01h 1 | ffh 255 | Check mode for firmware is warn | LCD menu | D3 Ax0da3 C1 -| ^ | ^ | ^ | 02h 0 | ^ | Check mode for firmware is strict | ^ | ^ -| ^ | ^ | ^ | 00h 0 | ^ | Check mode for firmware is none | ^ | ^ -| 0x0DA2 3490 | uint8 | EEPROM_CHECK_GCODE | 01h 1 | ffh 255 | Check mode for gcode is warn _unused atm_ | LCD menu | D3 Ax0da2 C1 -| ^ | ^ | ^ | 02h 0 | ^ | Check mode for gcode is strict _unused atm_ | ^ | ^ -| ^ | ^ | ^ | 00h 0 | ^ | Check mode for gcode is none _unused atm_ | ^ | ^ +| 0x0DAC 3500 | bool | EEPROM_MBL_MAGNET_ELIMINATION | 01h 1 | ffh 255 | Mesh bed leveling does: __ignores__ magnets | LCD menu | D3 Ax0dac C1 +| ^ | ^ | ^ | 00h 0 | ^ | Mesh bed leveling does: __NOT ignores__ magnets | ^ | ^ +| 0x0DAB 3499 | uint8 | EEPROM_MBL_POINTS_NR | 03h 3 | ffh 255 | Mesh bed leveling points: __3x3__ | LCD menu | D3 Ax0dab C1 +| ^ | ^ | ^ | 07h 7 | ^ | Mesh bed leveling points: __7x7__ | ^ | ^ +| 0x0DAA 3498 | uint8 | EEPROM_MBL_PROBE_NR | 03h 3 | ffh 255 | MBL times measurements for each point: __3__ | LCD menu | D3 Ax0daa C1 +| ^ | ^ | ^ | 05h 5 | ^ | MBL times measurements for each point: __5__ | ^ | ^ +| ^ | ^ | ^ | 01h 1 | ^ | MBL times measurements for each point: __7__ | ^ | ^ +| 0x0DA9 3497 | uint8 | EEPROM_MMU_STEALTH | 01h 1 | ffh 255 | MMU2/s Silent mode: __on__ | ??? | D3 Ax0da9 C1 +| ^ | ^ | ^ | 00h 0 | ^ | MMU2/s Silent mode: __off__ | ^ | ^ +| 0x0DA8 3496 | uint8 | EEPROM_CHECK_MODE | 01h 1 | ffh 255 | Check mode for nozzle is: __warn__ | LCD menu | D3 Ax0da8 C1 +| ^ | ^ | ^ | 02h 0 | ^ | Check mode for nozzle is: __strict__ | ^ | ^ +| ^ | ^ | ^ | 00h 0 | ^ | Check mode for nozzle is: __none__ | ^ | ^ +| 0x0DA7 3495 | uint8 | EEPROM_NOZZLE_DIAMETER | 28h 40 | ffh 255 | Nozzle diameter is: __40 or 0.40mm__ | LCD menu | D3 Ax0da7 C1 +| ^ | ^ | ^ | 3ch 60 | ^ | Nozzle diameter is: __60 or 0.60mm__ | ^ | ^ +| ^ | ^ | ^ | 19h 25 | ^ | Nozzle diameter is: __25 or 0.25mm__ | ^ | ^ +| 0x0DA5 3493 | uint16 | EEPROM_NOZZLE_DIAMETER_uM | 9001h | ff ffh 65535 | Nozzle diameter is: __400um__ | LCD menu | D3 Ax0da5 C2 +| ^ | ^ | ^ | 5802h | ^ | Nozzle diameter is: __600um__ | ^ | ^ +| ^ | ^ | ^ | fa00h | ^ | Nozzle diameter is: __250um__ | ^ | ^ +| 0x0DA4 3492 | uint8 | EEPROM_CHECK_MODEL | 01h 1 | ffh 255 | Check mode for printer model is: __warn__ | LCD menu | D3 Ax0da4 C1 +| ^ | ^ | ^ | 02h 0 | ^ | Check mode for printer model is: __strict__ | ^ | ^ +| ^ | ^ | ^ | 00h 0 | ^ | Check mode for printer model is: __none__ | ^ | ^ +| 0x0DA3 3491 | uint8 | EEPROM_CHECK_VERSION | 01h 1 | ffh 255 | Check mode for firmware is: __warn__ | LCD menu | D3 Ax0da3 C1 +| ^ | ^ | ^ | 02h 0 | ^ | Check mode for firmware is: __strict__ | ^ | ^ +| ^ | ^ | ^ | 00h 0 | ^ | Check mode for firmware is: __none__ | ^ | ^ +| 0x0DA2 3490 | uint8 | EEPROM_CHECK_GCODE | 01h 1 | ffh 255 | Check mode for gcode is: __warn__ _unused atm_ | LCD menu | D3 Ax0da2 C1 +| ^ | ^ | ^ | 02h 0 | ^ | Check mode for gcode is: __strict__ _unused atm_ | ^ | ^ +| ^ | ^ | ^ | 00h 0 | ^ | Check mode for gcode is: __none__ _unused atm_ | ^ | ^ | 0x0D49 3401 | uint16 | EEPROM_SHEETS_BASE | ??? | ffh 255 | ??? | LCD menu | D3 Ax0d49 C89 | 0x0D49 3401 | char | _1st Sheet block_ | 536d6f6f746831| ffffffffffffff | 1st sheet - Name: _Smooth1_ | ^ | D3 Ax0d49 C7 | 0x0D50 3408 | uint16 | ^ | 00 00h 0 | ff ffh 65535 | 1st sheet - Z offset | ^ | D3 Ax0d50 C2 @@ -300,20 +304,20 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP | 0x0DA1 3489 | uint8 | ??? | 00h 0 | ffh 255 | ??? | ??? | D3 Ax0da1 C1 | 0x0D48 3400 | uint8 | EEPROM_FSENSOR_PCB | ??? | ffh 255 | Filament Sensor type old vs new | ??? | D3 Ax0d48 C1 | ^ | ^ | ^ | ??? | ^ | Filament Sensor type ??? | ^ | ^ -| 0x0D47 3399 | uint8 | EEPROM_FSENSOR_ACTION_NA | 00h 0 | ffh 255 | Filament Sensor action: _Continue_ | LCD menu | D3 Ax0d47 C1 -| ^ | ^ | ^ | 01h 1 | ^ | Filament Sensor action: Pause | ^ | ^ +| 0x0D47 3399 | uint8 | EEPROM_FSENSOR_ACTION_NA | 00h 0 | ffh 255 | Filament Sensor action: __Continue__ | LCD menu | D3 Ax0d47 C1 +| ^ | ^ | ^ | 01h 1 | ^ | Filament Sensor action: __Pause__ | ^ | ^ | 0x0D37 3383 | float | EEPROM_UVLO_SAVED_TARGET | ??? | ff ff ff ffh | Power panic saved target all-axis | ??? | D3 Ax0d37 C16 | ^ | ^ | ^ | ??? | ^ | Power panic saved target e-axis | ^ | D3 Ax0d43 C4 | ^ | ^ | ^ | ??? | ^ | Power panic saved target z-axis | ^ | D3 Ax0d3f C4 | ^ | ^ | ^ | ??? | ^ | Power panic saved target y-axis | ^ | D3 Ax0d3b C4 | ^ | ^ | ^ | ??? | ^ | Power panic saved target x-axis | ^ | D3 Ax0d37 C4 | 0x0D35 3381 | uint16 | EEPROM_UVLO_FEEDMULTIPLY | ??? | ff ffh 65355 | Power panic saved feed multiplier | ??? | D3 Ax0d35 C2 -| 0x0D34 3380 | uint8 | EEPROM_BACKLIGHT_LEVEL_HIGH | 00h - ffh | 80h 128 | LCD backlight bright _128_ Dim value to 255 | LCD menu | D3 Ax0d34 C1 -| 0x0D33 3379 | uint8 | EEPROM_BACKLIGHT_LEVEL_LOW | 00h - ffh | 32h 50 | LCD backlight dim _50_ 0 to Bright value | LCD menu | D3 Ax0d33 C1 -| 0x0D32 3378 | uint8 | EEPROM_BACKLIGHT_MODE | 02h 2 | ffh 255 | LCD backlight mode: _Auto_ | LCD menu | D3 Ax0d32 C1 -| ^ | ^ | ^ | 01h 1 | ^ | LCD backlight mode: Bright | ^ | ^ -| ^ | ^ | ^ | 00h 0 | ^ | LCD backlight mode: Dim | ^ | ^ -| 0x0D30 3376 | uint16 | EEPROM_BACKLIGHT_TIMEOUT | 01 00 - ff ff | ff ffh 65535 | LCD backlight timeout: _10_ seconds | LCD menu | D3 Ax0d30 C2 +| 0x0D34 3380 | uint8 | EEPROM_BACKLIGHT_LEVEL_HIGH | 00h - ffh | 80h 128 | LCD backlight bright: __128__ Dim value to 255 | LCD menu | D3 Ax0d34 C1 +| 0x0D33 3379 | uint8 | EEPROM_BACKLIGHT_LEVEL_LOW | 00h - ffh | 32h 50 | LCD backlight dim: __50__ 0 to Bright value | LCD menu | D3 Ax0d33 C1 +| 0x0D32 3378 | uint8 | EEPROM_BACKLIGHT_MODE | 02h 2 | ffh 255 | LCD backlight mode: __Auto__ | LCD menu | D3 Ax0d32 C1 +| ^ | ^ | ^ | 01h 1 | ^ | LCD backlight mode: __Bright__ | ^ | ^ +| ^ | ^ | ^ | 00h 0 | ^ | LCD backlight mode: __Dim__ | ^ | ^ +| 0x0D30 3376 | uint16 | EEPROM_BACKLIGHT_TIMEOUT | 01 00 - ff ff | ff ffh 65535 | LCD backlight timeout: __10__ seconds | LCD menu | D3 Ax0d30 C2 | 0x0D2C 3372 | float | EEPROM_UVLO_LA_K | ??? | ff ff ff ffh | Power panic saved Linear Advanced K value | ??? | D3 Ax0d2c C4 ## End of EEPROM Table From 2778fa9aa049b896645df855484ffa61eae490e4 Mon Sep 17 00:00:00 2001 From: 3d-gussner <3d.gussner@gmail.com> Date: Sun, 22 Mar 2020 15:22:14 +0100 Subject: [PATCH 103/158] Added author and version of document --- Firmware/eeprom.h | 3 +++ 1 file changed, 3 insertions(+) diff --git a/Firmware/eeprom.h b/Firmware/eeprom.h index e149526e..1f9446ca 100644 --- a/Firmware/eeprom.h +++ b/Firmware/eeprom.h @@ -1,6 +1,7 @@ /** * @file + * @author 3d-gussner */ /** \ingroup eeprom_table */ //! _This is a EEPROM table of currently implemented in Prusa firmware (dynamically generated from doxygen)._ @@ -54,6 +55,8 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP ### !!! D-codes are case sensitive so please don't use upper case A,C or X in the address you want to read !!! + Version 0.9 + --------------------------------------------------------------------------------- From 1b0c86cb51248118495f6da70337186ddaa5d044 Mon Sep 17 00:00:00 2001 From: 3d-gussner <3d.gussner@gmail.com> Date: Sun, 22 Mar 2020 15:23:41 +0100 Subject: [PATCH 104/158] minor fix --- Firmware/eeprom.h | 1 - 1 file changed, 1 deletion(-) diff --git a/Firmware/eeprom.h b/Firmware/eeprom.h index 1f9446ca..b4357de3 100644 --- a/Firmware/eeprom.h +++ b/Firmware/eeprom.h @@ -323,7 +323,6 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP | 0x0D30 3376 | uint16 | EEPROM_BACKLIGHT_TIMEOUT | 01 00 - ff ff | ff ffh 65535 | LCD backlight timeout: __10__ seconds | LCD menu | D3 Ax0d30 C2 | 0x0D2C 3372 | float | EEPROM_UVLO_LA_K | ??? | ff ff ff ffh | Power panic saved Linear Advanced K value | ??? | D3 Ax0d2c C4 - ## End of EEPROM Table | Adress begin | Bit/Type | Name | Valid values | Default/FactoryReset | Description | Gcode/Function| Debug code | :--: | :--: | :--: | :--: | :--: | :--: | :--: | :--: From 0c655057413897a6321068d3145b597a4270a34f Mon Sep 17 00:00:00 2001 From: 3d-gussner <3d.gussner@gmail.com> Date: Mon, 23 Mar 2020 07:23:36 +0100 Subject: [PATCH 105/158] Added PRUSA3DFW at 0x0000 --- Firmware/eeprom.h | 1 + 1 file changed, 1 insertion(+) diff --git a/Firmware/eeprom.h b/Firmware/eeprom.h index b4357de3..7f97c355 100644 --- a/Firmware/eeprom.h +++ b/Firmware/eeprom.h @@ -331,6 +331,7 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP | 0x000E 14 | uint16 | EEPROM_FIRMWARE_VERSION_REVISION | ??? | ff ffh 65535 | Firmware version revision number DEV/ALPHA/BETA/RC| ??? | D3 Ax000e C2 | 0x000C 12 | uint16 | EEPROM_FIRMWARE_VERSION_MINOR | ??? | ff ffh 65535 | Firmware version minor number | ??? | D3 Ax000c C2 | 0x000A 10 | uint16 | EEPROM_FIRMWARE_VERSION_MAJOR | ??? | ff ffh 65535 | Firmware version major number | ??? | D3 Ax000a C2 +| 0x0000 0 | char | FW_PRUSA3D_MAGIC | ??? | ffffffffffffffffffff | __`PRUSA3DFW`__ | ??? | D3 Ax0000 C10 */ #define EEPROM_EMPTY_VALUE 0xFF From ea1a2bb3628b193cbe6b76e042c0f5454c9ce13a Mon Sep 17 00:00:00 2001 From: Alex Voinea Date: Mon, 23 Mar 2020 12:37:56 +0200 Subject: [PATCH 106/158] Documentation update --- 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 a606403a..33d0d9eb 100755 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -5365,7 +5365,7 @@ if(eSoundMode!=e_SOUND_MODE_SILENT) /*! ### G90 - Switch off relative mode G90: Set to Absolute Positioning - All coordinates from now on are absolute relative to the origin of the machine. + All coordinates from now on are absolute relative to the origin of the machine. E axis is left intact. */ case 90: { axis_relative_modes &= ~(X_AXIS_MASK | Y_AXIS_MASK | Z_AXIS_MASK); @@ -5374,7 +5374,7 @@ if(eSoundMode!=e_SOUND_MODE_SILENT) /*! ### G91 - Switch on relative mode G91: Set to Relative Positioning - All coordinates from now on are relative to the last position. + All coordinates from now on are relative to the last position. E axis is left intact. */ case 91: { axis_relative_modes |= X_AXIS_MASK | Y_AXIS_MASK | Z_AXIS_MASK; From 32bff79fd67192963f9a8dfa2710f7579bf6fb8e Mon Sep 17 00:00:00 2001 From: 3d-gussner <3d.gussner@gmail.com> Date: Mon, 23 Mar 2020 11:40:07 +0100 Subject: [PATCH 107/158] minor changes + added EEPROM_FREE_NRx ... Some EEPROM allocations do not use the hole allocated space: - EEPROM_FARM_NUMBER is only numeric 000-999 and only uses 2 bytes to store the Farm number BUT allocated 3 bytes. Added EEPROM_FREE_NR1 as free space that can be used - EEPROM_CRASH_DET just changes 1 byte to save it status [on/off] but allocated 5 bytes. Added EEPROM_FREE_NR2 to EEPROM_FREE_NR5 as free space that can be used --- Firmware/eeprom.h | 158 +++++++++++++++++++++++++++------------------- 1 file changed, 93 insertions(+), 65 deletions(-) diff --git a/Firmware/eeprom.h b/Firmware/eeprom.h index 7f97c355..e2b01c37 100644 --- a/Firmware/eeprom.h +++ b/Firmware/eeprom.h @@ -51,11 +51,16 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP How can you use the debug codes? - Serial terminal like Putty. - Octoprint does support D-codes - - _Pronterface_ does not support D-codes + - _Pronterface_ does __not__ support D-codes ### !!! D-codes are case sensitive so please don't use upper case A,C or X in the address you want to read !!! + + #### Usefull tools/links: + To convert hex to ascii https://www.rapidtables.com/convert/number/hex-to-ascii.html - Version 0.9 + To convert hex to dec https://www.rapidtables.com/convert/number/hex-to-decimal.html + + Version: 0.9.1 --------------------------------------------------------------------------------- @@ -66,73 +71,74 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP | ^ | ^ | ^ | 01h 1 | ^ | TMC Stealth mode: __on__ / miniRambo Silent mode | ^ | ^ | 0x0FFEh 4094 | uchar | EEPROM_LANG | 00h 0 | ffh 255 | English / LANG_ID_PRI | LCD menu | D3 Ax0ffe C1 | ^ | ^ | ^ | 01h 1 | ^ | Other language LANG_ID_SEC | ^ | ^ -| 0x0FFCh 4092 | uint16 | EEPROM_BABYSTEP_X | ??? | ffh 255 | Babystep for X axis _unsued_ | ??? | D3 Ax0ffc C2 -| 0x0FFAh 4090 | uint16 | EEPROM_BABYSTEP_Y | ??? | ffh 255 | Babystep for Y axis _unsued_ | ^ | D3 Ax0ffa C2 -| 0x0FF8h 4088 | uint16 | EEPROM_BABYSTEP_Z | ??? | ffh 255 | Babystep for Z axis _lagacy_ | ^ | D3 Ax0ff8 C2 +| 0x0FFCh 4092 | uint16 | EEPROM_BABYSTEP_X | ??? | ff ffh 65535 | Babystep for X axis _unsued_ | ??? | D3 Ax0ffc C2 +| 0x0FFAh 4090 | uint16 | EEPROM_BABYSTEP_Y | ??? | ff ffh 65535 | Babystep for Y axis _unsued_ | ^ | D3 Ax0ffa C2 +| 0x0FF8h 4088 | uint16 | EEPROM_BABYSTEP_Z | ??? | ff ffh 65535 | Babystep for Z axis _lagacy_ | ^ | D3 Ax0ff8 C2 | ^ | ^ | ^ | ^ | ^ | multiple values stored now in EEPROM_Sheets_base | ^ | ^ -| 0x0FF7h 4087 | uint8 | EEPROM_CALIBRATION_STATUS | 00h 0 | ffh 255 | Unknown | ??? | D3 Ax0ff7 C1 +| 0x0FF7h 4087 | uint8 | EEPROM_CALIBRATION_STATUS | ffh 255 | ffh 255 | Assbemled _default_ | ??? | D3 Ax0ff7 C1 | ^ | ^ | ^ | 01h 1 | ^ | Calibrated | ^ | ^ -| ^ | ^ | ^ | E6h 230 | ^ | needs Live Z adjustment | ^ | ^ -| ^ | ^ | ^ | F0h 240 | ^ | needs Z calibration | ^ | ^ -| ^ | ^ | ^ | FAh 250 | ^ | needs XYZ calibration | ^ | ^ -| ^ | ^ | ^ | FFh 255 | ^ | Assbemled _default_ | ^ | ^ -| 0x0FF5h 4085 | uint16 | EEPROM_BABYSTEP_Z0 | ??? | ??? | Babystep for Z ??? | ??? | D3 Ax0ff5 C2 -| 0x0FF1h 4081 | uint32 | EEPROM_FILAMENTUSED | ??? | 00h 0 | Filament used in meters | ??? | D3 Ax0ff1 C4 -| 0x0FEDh 4077 | uint32 | EEPROM_TOTALTIME | ??? | 00h 0 | Total print time | ??? | D3 Ax0fed C4 -| 0x0FE5h 4069 | float | EEPROM_BED_CALIBRATION_CENTER | ??? | ??? | ??? | ??? | D3 Ax0fe5 C8 -| ^ | ^ | ^ | ??? | ??? | ??? | ^ | ^ -| 0x0FDDh 4061 | float | EEPROM_BED_CALIBRATION_VEC_X | ??? | ??? | ??? | ??? | D3 Ax0fdd C8 -| ^ | ^ | ^ | ??? | ??? | ??? | ^ | ^ -| 0x0FD5h 4053 | float | EEPROM_BED_CALIBRATION_VEC_Y | ??? | ??? | ??? | ??? | D3 Ax0fd5 C8 -| ^ | ^ | ^ | ??? | ??? | ??? | ^ | ^ -| 0x0FC5h 4037 | int16 | EEPROM_BED_CALIBRATION_Z_JITTER | ??? | ??? | ??? | ??? | D3 Ax0fc5 C16 -| ^ | ^ | ^ | ??? | ??? | ??? | ^ | ^ -| ^ | ^ | ^ | ??? | ??? | ??? | ^ | ^ -| ^ | ^ | ^ | ??? | ??? | ??? | ^ | ^ -| ^ | ^ | ^ | ??? | ??? | ??? | ^ | ^ -| ^ | ^ | ^ | ??? | ??? | ??? | ^ | ^ -| ^ | ^ | ^ | ??? | ??? | ??? | ^ | ^ -| ^ | ^ | ^ | ??? | ??? | ??? | ^ | ^ +| ^ | ^ | ^ | e6h 230 | ^ | needs Live Z adjustment | ^ | ^ +| ^ | ^ | ^ | f0h 240 | ^ | needs Z calibration | ^ | ^ +| ^ | ^ | ^ | fah 250 | ^ | needs XYZ calibration | ^ | ^ +| ^ | ^ | ^ | 00h 0 | ^ | Unknown | ^ | ^ +| 0x0FF5h 4085 | uint16 | EEPROM_BABYSTEP_Z0 | ??? | ff ffh 65535 | Babystep for Z ??? | ??? | D3 Ax0ff5 C2 +| 0x0FF1h 4081 | uint32 | EEPROM_FILAMENTUSED | ??? | 00 00 00 00h 0 | Filament used in meters | ??? | D3 Ax0ff1 C4 +| 0x0FEDh 4077 | uint32 | EEPROM_TOTALTIME | ??? | 00 00 00 00h 0 | Total print time | ??? | D3 Ax0fed C4 +| 0x0FE5h 4069 | float | EEPROM_BED_CALIBRATION_CENTER | ??? | ff ff ff ffh | ??? | ??? | D3 Ax0fe5 C8 +| ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ +| 0x0FDDh 4061 | float | EEPROM_BED_CALIBRATION_VEC_X | ??? | ff ff ff ffh | ??? | ??? | D3 Ax0fdd C8 +| ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ +| 0x0FD5h 4053 | float | EEPROM_BED_CALIBRATION_VEC_Y | ??? | ff ff ff ffh | ??? | ??? | D3 Ax0fd5 C8 +| ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ +| 0x0FC5h 4037 | int16 | EEPROM_BED_CALIBRATION_Z_JITTER | ??? | ff ffh 65535 | ??? | ??? | D3 Ax0fc5 C16 +| ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ +| ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ +| ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ +| ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ +| ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ +| ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ +| ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ | 0x0FC4h 4036 | bool | EEPROM_FARM_MODE | 00h 0 | ffh 255 | Prusa farm mode: __off__ | G99 | D3 Ax0fc4 C1 | ^ | ^ | ^ | 01h 1 | ^ | Prusa farm mode: __on__ | G98 | ^ -| 0x0FC1h 4033 | int16 | EEPROM_FARM_NUMBER | ??? | ff ff ffh | Prusa farm number | ??? | D3 Ax0fc1 C3 +| 0x0FC3h 4035 | free | _EEPROM_FREE_NR1_ | ??? | ffh 255 | _Free EEPROM space_ | _free space_ | D3 Ax0fc3 C1 +| 0x0FC1h 4033 | ??? | EEPROM_FARM_NUMBER | 000-999 | ff ffh = 00 00 | Prusa farm number _only 0-9 are allowed: 000-999_ | LCD menu | D3 Ax0fc1 C2 | 0x0FC0h 4032 | bool | EEPROM_BED_CORRECTION_VALID | 00h 0 | 00h 0 | Bed correction invalid | ??? | D3 Ax0fc0 C1 | ^ | ^ | ^ | ffh 255 | | Bed correction valid | ??? | ^ -| 0x0FBFh 4031 | char | EEPROM_BED_CORRECTION_LEFT | 00h FFh | 00h 0 | Bed manual correction left | LCD menu | D3 Ax0fbf C1 -| ^ | ^ | ^ | ??? | ??? | At this moment limited to +-100um | G80 Lxxx | ^ -| 0x0FBEh 4030 | char | EEPROM_BED_CORRECTION_RIGHT | 00h FFh | 00h 0 | Bed manual correction right | LCD menu | D3 Ax0fbe C1 -| ^ | ^ | ^ | ??? | ??? | At this moment limited to +-100um | G80 Rxxx | ^ -| 0x0FBDh 4029 | char | EEPROM_BED_CORRECTION_FRONT | 00h FFh | 00h 0 | Bed manual correction front | LCD menu | D3 Ax0fbd C1 -| ^ | ^ | ^ | ??? | ??? | At this moment limited to +-100um | G80 Fxxx | ^ -| 0x0FBCh 4028 | char | EEPROM_BED_CORRECTION_BACK | 00h FFh | 00h 0 | Bed manual correction back | LCD menu | D3 Ax0fbc C1 -| ^ | ^ | ^ | ??? | ??? | At this moment limited to +-100um | G80 Bxxx | ^ +| 0x0FBFh 4031 | char | EEPROM_BED_CORRECTION_LEFT | 00h ffh | 00h 0 | Bed manual correction left | LCD menu | D3 Ax0fbf C1 +| ^ | ^ | ^ | ^ | ^ | At this moment limited to +-100um | G80 Lxxx | ^ +| 0x0FBEh 4030 | char | EEPROM_BED_CORRECTION_RIGHT | 00h ffh | 00h 0 | Bed manual correction right | LCD menu | D3 Ax0fbe C1 +| ^ | ^ | ^ | ^ | ^ | At this moment limited to +-100um | G80 Rxxx | ^ +| 0x0FBDh 4029 | char | EEPROM_BED_CORRECTION_FRONT | 00h ffh | 00h 0 | Bed manual correction front | LCD menu | D3 Ax0fbd C1 +| ^ | ^ | ^ | ^ | ^ | At this moment limited to +-100um | G80 Fxxx | ^ +| 0x0FBCh 4028 | char | EEPROM_BED_CORRECTION_BACK | 00h ffh | 00h 0 | Bed manual correction back | LCD menu | D3 Ax0fbc C1 +| ^ | ^ | ^ | ^ | ^ | At this moment limited to +-100um | G80 Bxxx | ^ | 0x0FBBh 4027 | bool | EEPROM_TOSHIBA_FLASH_AIR_COMPATIBLITY | 00h 0 | 00h 0 | Toshiba Air: __off__ | LCD menu | D3 Ax0fbb C1 -| ^ | ^ | ^ | ??? | ffh 255 | Toshiba Air: __on__ | ^ | ^ +| ^ | ^ | ^ | 01h 1 | ffh 255 | Toshiba Air: __on__ | ^ | ^ | 0x0FBAh 4026 | uchar | EEPROM_PRINT_FLAG | ??? | ??? | _unsued_ | ??? | D3 Ax0fba C1 | 0x0FB0h 4016 | int16 | EEPROM_PROBE_TEMP_SHIFT | ??? | ??? | ??? | ??? | D3 Ax0fb0 C10 -| ^ | ^ | ^ | ??? | ??? | ??? | ^ | ^ -| ^ | ^ | ^ | ??? | ??? | ??? | ^ | ^ -| ^ | ^ | ^ | ??? | ??? | ??? | ^ | ^ -| ^ | ^ | ^ | ??? | ??? | ??? | ^ | ^ +| ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ +| ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ +| ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ +| ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ | 0x0FAFh 4015 | bool | EEPROM_TEMP_CAL_ACTIVE | 00h 0 | 00h 0 | PINDA Temp cal.: __inactive__ | LCD menu | D3 Ax0faf C1 | ^ | ^ | ^ | ffh 255 | ^ | PINDA Temp cal.: __active__ | ^ | ^ | 0x0FA7h 4007 | uint32 | EEPROM_BOWDEN_LENGTH | ??? | ff 00 ff ffh | Bowden length | ??? | D3 Ax0fae C8 -| ^ | ^ | ^ | ??? | ff ff ff ffh | ^ | ^ | ^ +| ^ | ^ | ^ | ^ | ff ff ff ffh | ^ | ^ | ^ | 0x0FA6h 4006 | uint8 | EEPROM_CALIBRATION_STATUS_PINDA | 00h 0 | ffh 255 | PINDA Temp: __not calibrated__ | ??? | D3 Ax0fa6 C1 | ^ | ^ | ^ | 01h 1 | ^ | PINDA Temp: __calibrated__ | ^ | ^ | 0x0FA5h 4005 | uint8 | EEPROM_UVLO | 00h 0 | ffh 255 | Power Panic flag: __inactive__ | ??? | D3 Ax0fa5 C1 | ^ | ^ | ^ | 01h 1 | ^ | Power Panic flag: __active__ | ^ | ^ | ^ | ^ | ^ | 02h 2 | ^ | Power Panic flag: __???__ | ^ | ^ | 0x0F9Dh 3997 | float | EEPROM_UVLO_CURRENT_POSITION | ??? | ffh 255 | Power Panic position | ??? | D3 Ax0f9d C8 -| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^ +| ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ | 0x0F95h 3989 | char | EEPROM_FILENAME | ??? | ffh 255 | Power Panic Filename | ??? | D3 Ax0f95 C8 -| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^ -| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^ -| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^ -| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^ -| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^ -| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^ -| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^ +| ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ +| ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ +| ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ +| ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ +| ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ +| ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ +| ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ | 0x0F91h 39851 | uint32 | EEPROM_FILE_POSITION | ??? | ff ff ff ffh | Power Panic File Postion | ??? | D3 Ax0f91 C4 | 0x0F8Dh 3981 | float | EEPROM_UVLO_CURRENT_POSITION_Z | ??? | ff ff ff ffh | Power Panic Z Position | ^ | D3 Ax0f8d C4 | 0x0F8Ch 3980 | ??? | EEPROM_UVLO_UNUSED_001 | ??? | ffh 255 | Power Panic _unused_ | ^ | D3 Ax0f8c C1 @@ -142,22 +148,23 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP | 0x0F87h 3975 | uint8 | EEPROM_FAN_CHECK_ENABLED | 00h 0 | ??? | Fan Check disabled | LCD menu | D3 Ax0f87 C1 | ^ | ^ | ^ | 01h 1 | ffh 255 | Fan Check enabled (exception ffh=01h) | ^ | ^ | 0x0F75h 3957 | uint16 | EEPROM_UVLO_MESH_BED_LEVELING | ??? | ff ffh 65535 | Power Panic Mesh Bed Leveling | ??? | D3 Ax0f75 C18 -| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^ -| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^ -| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^ -| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^ -| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^ -| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^ -| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^ -| ^ | ^ | ^ | ??? | ^ | ^ | ^ | ^ +| ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ +| ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ +| ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ +| ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ +| ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ +| ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ +| ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ +| ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ | 0x0F73h 3955 | uint16 | EEPROM_UVLO_Z_MICROSTEPS | ??? | ff ffh 65535 | Power Panic Z microsteps | ??? | D3 Ax0f73 C2 | 0x0F72h 3954 | uint8 | EEPROM_UVLO_E_ABS | ??? | ffh 255 | Power Panic ??? position | ??? | D3 Ax0f72 C1 | 0x0F6Eh 3950 | foat | EEPROM_UVLO_CURRENT_POSITION_E | ??? | ff ff ff ffh | Power Panic E position | ??? | D3 Ax0f6e C4 -| 0x0F69h 3945 | uint8 | EEPROM_CRASH_DET | ffh 255 | ffh 255 | Crash detection: __enabled__ | LCD menu | D3 Ax0f69 C5 +| 0x0F6Dh 3949 | ??? | _EEPROM_FREE_NR2_ | ??? | ffh 255 | _Free EEPROM space_ | _free space_ | D3 Ax0f6d C1 +| 0x0F6Ch 3948 | ??? | _EEPROM_FREE_NR3_ | ??? | ffh 255 | _Free EEPROM space_ | _free space_ | D3 Ax0f6c C1 +| 0x0F6Bh 3947 | ??? | _EEPROM_FREE_NR4_ | ??? | ffh 255 | _Free EEPROM space_ | _free space_ | D3 Ax0f6b C1 +| 0x0F6Ah 3946 | ??? | _EEPROM_FREE_NR5_ | ??? | ffh 255 | _Free EEPROM space_ | _free space_ | D3 Ax0f6a C1 +| 0x0F69h 3945 | uint8 | EEPROM_CRASH_DET | ffh 255 | ffh 255 | Crash detection: __enabled__ | LCD menu | D3 Ax0f69 C1 | ^ | ^ | ^ | 00h 0 | ^ | Crash detection: __disabled__ | LCD menu | ^ -| ^ | ^ | ^ | ??? | ??? | ^ | ??? | ^ -| ^ | ^ | ^ | ??? | ??? | ^ | ??? | ^ -| ^ | ^ | ^ | ??? | ??? | ^ | ??? | ^ | 0x0F68h 3944 | uint8 | EEPROM_CRASH_COUNT_Y | 00h-ffh 0-255 | ffh 255 | Crashes detected on y axis | ??? | D3 Ax0f68 C1 | 0x0F67h 3943 | uint8 | EEPROM_FSENSOR | 01h 1 | ffh 255 | Filament sensor: __enabled__ | LCD menu | D3 Ax0f67 C1 | ^ | ^ | ^ | 00h 0 | ^ | Filament sensor: __disabled__ | LCD menu | ^ @@ -198,7 +205,23 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP | 0x0EF1h 3825 | uint8 | EEPROM_TMC2130_Z_MRES | ??? | ffh 255 | ??? | ??? | D3 Ax0ef1 C1 | 0x0EF0h 3824 | uint8 | EEPROM_TMC2130_E_MRES | ??? | ffh 255 | ??? | ??? | D3 Ax0ef0 C1 | 0x0EEE 3822 | uint16 | EEPROM_PRINTER_TYPE | ??? | ff ffh 65535 | Printer Type | ??? | D3 Ax0eee C2 +| ^ | ^ | ^ | 64 00h 100 | ^ | PRINTER_MK1 | ??? | ^ +| ^ | ^ | ^ | c8 00h 200 | ^ | PRINTER_MK2 | ??? | ^ +| ^ | ^ | ^ | c9 00h 201 | ^ | PRINTER_MK2 with MMU1 | ??? | ^ +| ^ | ^ | ^ | ca 00h 202 | ^ | PRINTER_MK2S | ??? | ^ +| ^ | ^ | ^ | cb 00h 203 | ^ | PRINTER_MK2S with MMU1 | ??? | ^ +| ^ | ^ | ^ | fa 00h 250 | ^ | PRINTER_MK2.5 | ??? | ^ +| ^ | ^ | ^ | 1a 4fh 20250 | ^ | PRINTER_MK2.5 with MMU2 | ??? | ^ +| ^ | ^ | ^ | fc 00h 252 | ^ | PRINTER_MK2.5S | ??? | ^ +| ^ | ^ | ^ | 1c 4fh 20250 | ^ | PRINTER_MK2.5S with MMU2S | ??? | ^ +| ^ | ^ | ^ | 0c 12h 300 | ^ | PRINTER_MK3 | ??? | ^ +| ^ | ^ | ^ | 4c 4fh 20300 | ^ | PRINTER_MK3 with MMU2 | ??? | ^ +| ^ | ^ | ^ | 0e 12h 302 | ^ | PRINTER_MK3S | ??? | ^ +| ^ | ^ | ^ | 4e 4fh 20302 | ^ | PRINTER_MK3S with MMU2S | ??? | ^ | 0x0EEC 3820 | uint16 | EEPROM_BOARD_TYPE | ??? | ff ffh 65535 | Board Type | ??? | D3 Ax0eec C2 +| ^ | ^ | ^ | c8 00h 200 | ^ | BOARD_RAMBO_MINI_1_0 | ??? | ^ +| ^ | ^ | ^ | cb 00h 203 | ^ | BOARD_RAMBO_MINI_1_3 | ??? | ^ +| ^ | ^ | ^ | 36 01h 310 | ^ | BOARD_EINSY_1_0a | ??? | ^ | 0x0EE8 3816 | float | EEPROM_EXTRUDER_MULTIPLIER_0 | ??? | ff ff ff ffh | Power panic Extruder 0 multiplier | ??? | D3 Ax0ee8 C4 | 0x0EE4 3812 | float | EEPROM_EXTRUDER_MULTIPLIER_1 | ??? | ff ff ff ffh | Power panic Extruder 1 multiplier | ??? | D3 Ax0ee4 C4 | 0x0EE0 3808 | float | EEPROM_EXTRUDER_MULTIPLIER_2 | ??? | ff ff ff ffh | Power panic Extruder 2 multiplier | ??? | D3 Ax0ee0 C4 @@ -250,7 +273,7 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP | ^ | ^ | ^ | 07h 7 | ^ | Mesh bed leveling points: __7x7__ | ^ | ^ | 0x0DAA 3498 | uint8 | EEPROM_MBL_PROBE_NR | 03h 3 | ffh 255 | MBL times measurements for each point: __3__ | LCD menu | D3 Ax0daa C1 | ^ | ^ | ^ | 05h 5 | ^ | MBL times measurements for each point: __5__ | ^ | ^ -| ^ | ^ | ^ | 01h 1 | ^ | MBL times measurements for each point: __7__ | ^ | ^ +| ^ | ^ | ^ | 01h 1 | ^ | MBL times measurements for each point: __1__ | ^ | ^ | 0x0DA9 3497 | uint8 | EEPROM_MMU_STEALTH | 01h 1 | ffh 255 | MMU2/s Silent mode: __on__ | ??? | D3 Ax0da9 C1 | ^ | ^ | ^ | 00h 0 | ^ | MMU2/s Silent mode: __off__ | ^ | ^ | 0x0DA8 3496 | uint8 | EEPROM_CHECK_MODE | 01h 1 | ffh 255 | Check mode for nozzle is: __warn__ | LCD menu | D3 Ax0da8 C1 @@ -358,7 +381,8 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP // The offsets are saved as 16bit signed int, scaled to tenths of microns. #define EEPROM_BED_CALIBRATION_Z_JITTER (EEPROM_BED_CALIBRATION_VEC_Y-2*8) #define EEPROM_FARM_MODE (EEPROM_BED_CALIBRATION_Z_JITTER-1) -#define EEPROM_FARM_NUMBER (EEPROM_FARM_MODE-3) +#define EEPROM_FREE_NR1 (EEPROM_FARM_MODE-1) +#define EEPROM_FARM_NUMBER (EEPROM_FREE_NR1-2) // Correction of the bed leveling, in micrometers. // Maximum 50 micrometers allowed. @@ -390,8 +414,12 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP #define EEPROM_UVLO_E_ABS (EEPROM_UVLO_Z_MICROSTEPS - 1) #define EEPROM_UVLO_CURRENT_POSITION_E (EEPROM_UVLO_E_ABS - 4) //float for current position in E +#dedine EEPROM_FREE_NR2 (EEPROM_UVLO_CURRENT_POSITION_E - 1) // FREE EEPROM SPACE +#dedine EEPROM_FREE_NR3 (EEPROM_FREE_NR2 - 1) // FREE EEPROM SPACE +#dedine EEPROM_FREE_NR4 (EEPROM_FREE_NR3 - 1) // FREE EEPROM SPACE +#dedine EEPROM_FREE_NR5 (EEPROM_FREE_NR4 - 1) // FREE EEPROM SPACE // Crash detection mode EEPROM setting -#define EEPROM_CRASH_DET (EEPROM_UVLO_CURRENT_POSITION_E - 5) // float (orig EEPROM_UVLO_MESH_BED_LEVELING-12) +#define EEPROM_CRASH_DET (EEPROM_FREE_NR5 - 1) // uint8 (orig EEPROM_UVLO_MESH_BED_LEVELING-12) // Crash detection counter Y (last print) #define EEPROM_CRASH_COUNT_Y (EEPROM_CRASH_DET - 1) // uint8 (orig EEPROM_UVLO_MESH_BED_LEVELING-15) // Filament sensor on/off EEPROM setting From fc793b59d7ce78e15bcc5afdc042bc87026e2a81 Mon Sep 17 00:00:00 2001 From: 3d-gussner <3d.gussner@gmail.com> Date: Mon, 23 Mar 2020 12:02:57 +0100 Subject: [PATCH 108/158] changed default values for bowden length after test --- Firmware/eeprom.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Firmware/eeprom.h b/Firmware/eeprom.h index e2b01c37..f9bdfb81 100644 --- a/Firmware/eeprom.h +++ b/Firmware/eeprom.h @@ -122,8 +122,8 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP | ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ | 0x0FAFh 4015 | bool | EEPROM_TEMP_CAL_ACTIVE | 00h 0 | 00h 0 | PINDA Temp cal.: __inactive__ | LCD menu | D3 Ax0faf C1 | ^ | ^ | ^ | ffh 255 | ^ | PINDA Temp cal.: __active__ | ^ | ^ -| 0x0FA7h 4007 | uint32 | EEPROM_BOWDEN_LENGTH | ??? | ff 00 ff ffh | Bowden length | ??? | D3 Ax0fae C8 -| ^ | ^ | ^ | ^ | ff ff ff ffh | ^ | ^ | ^ +| 0x0FA7h 4007 | uint32 | EEPROM_BOWDEN_LENGTH | ??? | ff 00 00 00h | Bowden length | ??? | D3 Ax0fae C8 +| ^ | ^ | ^ | ^ | 00 00 00 00h | ^ | ^ | ^ | 0x0FA6h 4006 | uint8 | EEPROM_CALIBRATION_STATUS_PINDA | 00h 0 | ffh 255 | PINDA Temp: __not calibrated__ | ??? | D3 Ax0fa6 C1 | ^ | ^ | ^ | 01h 1 | ^ | PINDA Temp: __calibrated__ | ^ | ^ | 0x0FA5h 4005 | uint8 | EEPROM_UVLO | 00h 0 | ffh 255 | Power Panic flag: __inactive__ | ??? | D3 Ax0fa5 C1 From 5c4b3eea877d466d98494669c74ebd3c88b85da7 Mon Sep 17 00:00:00 2001 From: Alex Voinea Date: Mon, 23 Mar 2020 14:57:03 +0200 Subject: [PATCH 109/158] Struct comments --- Firmware/Marlin_main.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index 33d0d9eb..dd1f1b25 100755 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -178,7 +178,11 @@ float default_retraction = DEFAULT_RETRACTION; float homing_feedrate[] = HOMING_FEEDRATE; + +//Although this flag and many others like this could be represented with a struct/bitfield for each axis (more readable and efficient code), the implementation +//would not be standard across all platforms. That being said, the code will continue to use bitmasks for independent axis. uint8_t axis_relative_modes = 0; + int feedmultiply=100; //100->1 200->2 int extrudemultiply=100; //100->1 200->2 int extruder_multiply[EXTRUDERS] = {100 From f4037b9cb4c296b42b1d82399d96eeda26303295 Mon Sep 17 00:00:00 2001 From: 3d-gussner <3d.gussner@gmail.com> Date: Mon, 23 Mar 2020 14:13:24 +0100 Subject: [PATCH 110/158] Fixes after testing --- Firmware/eeprom.h | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/Firmware/eeprom.h b/Firmware/eeprom.h index f9bdfb81..908ba1cd 100644 --- a/Firmware/eeprom.h +++ b/Firmware/eeprom.h @@ -101,7 +101,7 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP | 0x0FC4h 4036 | bool | EEPROM_FARM_MODE | 00h 0 | ffh 255 | Prusa farm mode: __off__ | G99 | D3 Ax0fc4 C1 | ^ | ^ | ^ | 01h 1 | ^ | Prusa farm mode: __on__ | G98 | ^ | 0x0FC3h 4035 | free | _EEPROM_FREE_NR1_ | ??? | ffh 255 | _Free EEPROM space_ | _free space_ | D3 Ax0fc3 C1 -| 0x0FC1h 4033 | ??? | EEPROM_FARM_NUMBER | 000-999 | ff ffh = 00 00 | Prusa farm number _only 0-9 are allowed: 000-999_ | LCD menu | D3 Ax0fc1 C2 +| 0x0FC1h 4033 | ??? | EEPROM_FARM_NUMBER | 000-999 | ff ffh | Prusa farm number _only 0-9 are allowed: 000-999_ | LCD menu | D3 Ax0fc1 C2 | 0x0FC0h 4032 | bool | EEPROM_BED_CORRECTION_VALID | 00h 0 | 00h 0 | Bed correction invalid | ??? | D3 Ax0fc0 C1 | ^ | ^ | ^ | ffh 255 | | Bed correction valid | ??? | ^ | 0x0FBFh 4031 | char | EEPROM_BED_CORRECTION_LEFT | 00h ffh | 00h 0 | Bed manual correction left | LCD menu | D3 Ax0fbf C1 @@ -112,8 +112,8 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP | ^ | ^ | ^ | ^ | ^ | At this moment limited to +-100um | G80 Fxxx | ^ | 0x0FBCh 4028 | char | EEPROM_BED_CORRECTION_BACK | 00h ffh | 00h 0 | Bed manual correction back | LCD menu | D3 Ax0fbc C1 | ^ | ^ | ^ | ^ | ^ | At this moment limited to +-100um | G80 Bxxx | ^ -| 0x0FBBh 4027 | bool | EEPROM_TOSHIBA_FLASH_AIR_COMPATIBLITY | 00h 0 | 00h 0 | Toshiba Air: __off__ | LCD menu | D3 Ax0fbb C1 -| ^ | ^ | ^ | 01h 1 | ffh 255 | Toshiba Air: __on__ | ^ | ^ +| 0x0FBBh 4027 | bool | EEPROM_TOSHIBA_FLASH_AIR_COMPATIBLITY | 00h 0 | ffh 255 | Toshiba Air: __off__ | LCD menu | D3 Ax0fbb C1 +| ^ | ^ | ^ | 01h 1 | ^ | Toshiba Air: __on__ | ^ | ^ | 0x0FBAh 4026 | uchar | EEPROM_PRINT_FLAG | ??? | ??? | _unsued_ | ??? | D3 Ax0fba C1 | 0x0FB0h 4016 | int16 | EEPROM_PROBE_TEMP_SHIFT | ??? | ??? | ??? | ??? | D3 Ax0fb0 C10 | ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ @@ -145,8 +145,8 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP | 0x0F8Bh 3979 | uint8 | EEPROM_UVLO_TARGET_BED | ??? | ffh 255 | Power Panic Bed temperature | ^ | D3 Ax0f8b C1 | 0x0F89h 3977 | uint16 | EEPROM_UVLO_FEEDRATE | ??? | ff ffh 65535 | Power Panic Feedrate | ^ | D3 Ax0f89 C2 | 0x0F88h 3976 | uint8 | EEPROM_UVLO_FAN_SPEED | ??? | ffh 255 | Power Panic Fan speed | ^ | D3 Ax0f88 C1 -| 0x0F87h 3975 | uint8 | EEPROM_FAN_CHECK_ENABLED | 00h 0 | ??? | Fan Check disabled | LCD menu | D3 Ax0f87 C1 -| ^ | ^ | ^ | 01h 1 | ffh 255 | Fan Check enabled (exception ffh=01h) | ^ | ^ +| 0x0F87h 3975 | uint8 | EEPROM_FAN_CHECK_ENABLED | 00h 0 | ??? | Fan Check __disabled__ | LCD menu | D3 Ax0f87 C1 +| ^ | ^ | ^ | 01h 1 | ffh 255 | Fan Check __enabled__ | ^ | ^ | 0x0F75h 3957 | uint16 | EEPROM_UVLO_MESH_BED_LEVELING | ??? | ff ffh 65535 | Power Panic Mesh Bed Leveling | ??? | D3 Ax0f75 C18 | ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ @@ -338,7 +338,7 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP | ^ | ^ | ^ | ??? | ^ | Power panic saved target y-axis | ^ | D3 Ax0d3b C4 | ^ | ^ | ^ | ??? | ^ | Power panic saved target x-axis | ^ | D3 Ax0d37 C4 | 0x0D35 3381 | uint16 | EEPROM_UVLO_FEEDMULTIPLY | ??? | ff ffh 65355 | Power panic saved feed multiplier | ??? | D3 Ax0d35 C2 -| 0x0D34 3380 | uint8 | EEPROM_BACKLIGHT_LEVEL_HIGH | 00h - ffh | 80h 128 | LCD backlight bright: __128__ Dim value to 255 | LCD menu | D3 Ax0d34 C1 +| 0x0D34 3380 | uint8 | EEPROM_BACKLIGHT_LEVEL_HIGH | 00h - ffh | 82h 130 | LCD backlight bright: __128__ Dim value to 255 | LCD menu | D3 Ax0d34 C1 | 0x0D33 3379 | uint8 | EEPROM_BACKLIGHT_LEVEL_LOW | 00h - ffh | 32h 50 | LCD backlight dim: __50__ 0 to Bright value | LCD menu | D3 Ax0d33 C1 | 0x0D32 3378 | uint8 | EEPROM_BACKLIGHT_MODE | 02h 2 | ffh 255 | LCD backlight mode: __Auto__ | LCD menu | D3 Ax0d32 C1 | ^ | ^ | ^ | 01h 1 | ^ | LCD backlight mode: __Bright__ | ^ | ^ From bb43fa9878d41501e41ed9b46f124c0c9691eaf5 Mon Sep 17 00:00:00 2001 From: 3d-gussner <3d.gussner@gmail.com> Date: Mon, 23 Mar 2020 14:51:40 +0100 Subject: [PATCH 111/158] typo dedine doesn't work --- Firmware/eeprom.h | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/Firmware/eeprom.h b/Firmware/eeprom.h index 908ba1cd..ddc920d2 100644 --- a/Firmware/eeprom.h +++ b/Firmware/eeprom.h @@ -414,10 +414,10 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP #define EEPROM_UVLO_E_ABS (EEPROM_UVLO_Z_MICROSTEPS - 1) #define EEPROM_UVLO_CURRENT_POSITION_E (EEPROM_UVLO_E_ABS - 4) //float for current position in E -#dedine EEPROM_FREE_NR2 (EEPROM_UVLO_CURRENT_POSITION_E - 1) // FREE EEPROM SPACE -#dedine EEPROM_FREE_NR3 (EEPROM_FREE_NR2 - 1) // FREE EEPROM SPACE -#dedine EEPROM_FREE_NR4 (EEPROM_FREE_NR3 - 1) // FREE EEPROM SPACE -#dedine EEPROM_FREE_NR5 (EEPROM_FREE_NR4 - 1) // FREE EEPROM SPACE +#define EEPROM_FREE_NR2 (EEPROM_UVLO_CURRENT_POSITION_E - 1) // FREE EEPROM SPACE +#define EEPROM_FREE_NR3 (EEPROM_FREE_NR2 - 1) // FREE EEPROM SPACE +#define EEPROM_FREE_NR4 (EEPROM_FREE_NR3 - 1) // FREE EEPROM SPACE +#define EEPROM_FREE_NR5 (EEPROM_FREE_NR4 - 1) // FREE EEPROM SPACE // Crash detection mode EEPROM setting #define EEPROM_CRASH_DET (EEPROM_FREE_NR5 - 1) // uint8 (orig EEPROM_UVLO_MESH_BED_LEVELING-12) // Crash detection counter Y (last print) From 6979555fab75855b8b3eab656675bfc27cde1231 Mon Sep 17 00:00:00 2001 From: Alex Voinea Date: Mon, 23 Mar 2020 16:30:51 +0200 Subject: [PATCH 112/158] more comments --- Firmware/Marlin_main.cpp | 2 ++ 1 file changed, 2 insertions(+) diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index dd1f1b25..4eed0942 100755 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -181,6 +181,8 @@ float homing_feedrate[] = HOMING_FEEDRATE; //Although this flag and many others like this could be represented with a struct/bitfield for each axis (more readable and efficient code), the implementation //would not be standard across all platforms. That being said, the code will continue to use bitmasks for independent axis. +//Moreover, according to C/C++ standard, the ordering of bits is platform/compiler dependent and the compiler is allowed to align the bits arbitrarily, +//thus bit operations like shifting and masking may stop working and will be very hard to fix. uint8_t axis_relative_modes = 0; int feedmultiply=100; //100->1 200->2 From 6be66fcfcdb388060fb1515e71a276711ff13b3b Mon Sep 17 00:00:00 2001 From: 3d-gussner <3d.gussner@gmail.com> Date: Mon, 23 Mar 2020 15:47:59 +0100 Subject: [PATCH 113/158] fix some typos --- Firmware/eeprom.h | 19 ++++++++++--------- 1 file changed, 10 insertions(+), 9 deletions(-) diff --git a/Firmware/eeprom.h b/Firmware/eeprom.h index ddc920d2..def91133 100644 --- a/Firmware/eeprom.h +++ b/Firmware/eeprom.h @@ -4,6 +4,7 @@ * @author 3d-gussner */ /** \ingroup eeprom_table */ + //! _This is a EEPROM table of currently implemented in Prusa firmware (dynamically generated from doxygen)._ @@ -43,7 +44,7 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP EEPROM 16-bit Empty value = 0xFFFFh 65535 - _Italic = unsued or default_ + _Italic = unused or default_ __Bold = Status__ @@ -55,7 +56,7 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP ### !!! D-codes are case sensitive so please don't use upper case A,C or X in the address you want to read !!! - #### Usefull tools/links: + #### Useful tools/links: To convert hex to ascii https://www.rapidtables.com/convert/number/hex-to-ascii.html To convert hex to dec https://www.rapidtables.com/convert/number/hex-to-decimal.html @@ -65,7 +66,7 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP --------------------------------------------------------------------------------- -| Adress begin | Bit/Type | Name | Valid values | Default/FactoryReset | Description | Gcode/Function| Debug code +| Address begin | Bit/Type | Name | Valid values | Default/FactoryReset | Description | Gcode/Function| Debug code | :-- | :-- | :-- | :--: | :--: | :-- | :--: | :--: | 0x0FFFh 4095 | uchar | EEPROM_SILENT | 00h 0 | ffh 255 | TMC Stealth mode: __off__ / miniRambo Power mode | LCD menu | D3 Ax0fff C1 | ^ | ^ | ^ | 01h 1 | ^ | TMC Stealth mode: __on__ / miniRambo Silent mode | ^ | ^ @@ -75,7 +76,7 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP | 0x0FFAh 4090 | uint16 | EEPROM_BABYSTEP_Y | ??? | ff ffh 65535 | Babystep for Y axis _unsued_ | ^ | D3 Ax0ffa C2 | 0x0FF8h 4088 | uint16 | EEPROM_BABYSTEP_Z | ??? | ff ffh 65535 | Babystep for Z axis _lagacy_ | ^ | D3 Ax0ff8 C2 | ^ | ^ | ^ | ^ | ^ | multiple values stored now in EEPROM_Sheets_base | ^ | ^ -| 0x0FF7h 4087 | uint8 | EEPROM_CALIBRATION_STATUS | ffh 255 | ffh 255 | Assbemled _default_ | ??? | D3 Ax0ff7 C1 +| 0x0FF7h 4087 | uint8 | EEPROM_CALIBRATION_STATUS | ffh 255 | ffh 255 | Assembled _default_ | ??? | D3 Ax0ff7 C1 | ^ | ^ | ^ | 01h 1 | ^ | Calibrated | ^ | ^ | ^ | ^ | ^ | e6h 230 | ^ | needs Live Z adjustment | ^ | ^ | ^ | ^ | ^ | f0h 240 | ^ | needs Z calibration | ^ | ^ @@ -139,7 +140,7 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP | ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ -| 0x0F91h 39851 | uint32 | EEPROM_FILE_POSITION | ??? | ff ff ff ffh | Power Panic File Postion | ??? | D3 Ax0f91 C4 +| 0x0F91h 39851 | uint32 | EEPROM_FILE_POSITION | ??? | ff ff ff ffh | Power Panic File Position | ??? | D3 Ax0f91 C4 | 0x0F8Dh 3981 | float | EEPROM_UVLO_CURRENT_POSITION_Z | ??? | ff ff ff ffh | Power Panic Z Position | ^ | D3 Ax0f8d C4 | 0x0F8Ch 3980 | ??? | EEPROM_UVLO_UNUSED_001 | ??? | ffh 255 | Power Panic _unused_ | ^ | D3 Ax0f8c C1 | 0x0F8Bh 3979 | uint8 | EEPROM_UVLO_TARGET_BED | ??? | ffh 255 | Power Panic Bed temperature | ^ | D3 Ax0f8b C1 @@ -185,8 +186,8 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP | ^ | ^ | ^ | 01h 1 | ^ | RPi Port: __enabled__ | LCD menu | ^ | 0x0F07h 3847 | uint8 | EEPROM_FSENS_AUTOLOAD_ENABLED | 01h 1 | ffh 255 | Filament autoload: __enabled__ | LCD menu | D3 Ax0f07 C1 | ^ | ^ | ^ | 00h 0 | ^ | Filament autoload: __disabled__ | LCD menu | ^ -| 0x0F05h 3845 | uint16 | EEPROM_CRASH_COUNT_X_TOT | 0000-fffe | ff ffh | Total charshes on x axis | ??? | D3 Ax0f05 C2 -| 0x0F03h 3843 | uint16 | EEPROM_CRASH_COUNT_Y_TOT | 0000-fffe | ff ffh | Total charshes on y axis | ??? | D3 Ax0f03 C2 +| 0x0F05h 3845 | uint16 | EEPROM_CRASH_COUNT_X_TOT | 0000-fffe | ff ffh | Total crashes on x axis | ??? | D3 Ax0f05 C2 +| 0x0F03h 3843 | uint16 | EEPROM_CRASH_COUNT_Y_TOT | 0000-fffe | ff ffh | Total crashes on y axis | ??? | D3 Ax0f03 C2 | 0x0F01h 3841 | uint16 | EEPROM_FERROR_COUNT_TOT | 0000-fffe | ff ffh | Total filament sensor errors | ??? | D3 Ax0f01 C2 | 0x0EFFh 3839 | uint16 | EEPROM_POWER_COUNT_TOT | 0000-fffe | ff ffh | Total power failures | ??? | D3 Ax0eff C2 | 0x0EFEh 3838 | uint8 | EEPROM_TMC2130_HOME_X_ORIGIN | ??? | ffh 255 | ??? | ??? | D3 Ax0efe C1 @@ -227,7 +228,7 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP | 0x0EE0 3808 | float | EEPROM_EXTRUDER_MULTIPLIER_2 | ??? | ff ff ff ffh | Power panic Extruder 2 multiplier | ??? | D3 Ax0ee0 C4 | 0x0EDE 3806 | uint16 | EEPROM_EXTRUDEMULTIPLY | ??? | ff ffh 65535 | Power panic Extruder multiplier | ??? | D3 Ax0ede C2 | 0x0EDA 3802 | float | EEPROM_UVLO_TINY_CURRENT_POSITION_Z | ??? | ff ff ff ffh | Power panic Z position | ??? | D3 Ax0eda C4 -| 0x0ED8 3800 | uint16 | EEPROM_UVLO_TARGET_HOTEND | ??? | ff ffh 65535 | Power panic traget Hotend temperature | ??? | D3 Ax0ed8 C2 +| 0x0ED8 3800 | uint16 | EEPROM_UVLO_TARGET_HOTEND | ??? | ff ffh 65535 | Power panic target Hotend temperature | ??? | D3 Ax0ed8 C2 | 0x0ED7 3799 | uint8 | EEPROM_SOUND_MODE | 00h 0 | ffh 255 | Sound mode: __loud__ | ??? | D3 Ax0ed7 C1 | ^ | ^ | ^ | 01h 1 | ^ | Sound mode: __once__ | ^ | ^ | ^ | ^ | ^ | 02h 1 | ^ | Sound mode: __silent__ | ^ | ^ @@ -347,7 +348,7 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP | 0x0D2C 3372 | float | EEPROM_UVLO_LA_K | ??? | ff ff ff ffh | Power panic saved Linear Advanced K value | ??? | D3 Ax0d2c C4 -| Adress begin | Bit/Type | Name | Valid values | Default/FactoryReset | Description | Gcode/Function| Debug code +| Address begin | Bit/Type | Name | Valid values | Default/FactoryReset | Description | Gcode/Function| Debug code | :--: | :--: | :--: | :--: | :--: | :--: | :--: | :--: | 0x0012 18 | uint16 | EEPROM_FIRMWARE_VERSION_END | ??? | ff ffh 65535 | ??? | ??? | D3 Ax0012 C2 | 0x0010 16 | uint16 | EEPROM_FIRMWARE_VERSION_FLAVOR | ??? | ff ffh 65535 | ??? | ??? | D3 Ax0010 C2 From 7cd5d83089b377492fbfc17fc304328e8d138bcc Mon Sep 17 00:00:00 2001 From: 3d-gussner <3d.gussner@gmail.com> Date: Mon, 23 Mar 2020 16:54:35 +0100 Subject: [PATCH 114/158] Added S/P to Default/FactoryReset S = Statistics P = shipping Prepare --- Firmware/eeprom.h | 48 +++++++++++++++++++++++++++-------------------- 1 file changed, 28 insertions(+), 20 deletions(-) diff --git a/Firmware/eeprom.h b/Firmware/eeprom.h index def91133..ec9c57de 100644 --- a/Firmware/eeprom.h +++ b/Firmware/eeprom.h @@ -48,6 +48,14 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP __Bold = Status__ + In Default/FactoryReset column the + + - __S__ Statistics + - __P__ Shipping prep + - __S/P__ Statistics and Shipping prep + + will overwrite existing values to 0 or default. + --------------------------------------------------------------------------------- How can you use the debug codes? - Serial terminal like Putty. @@ -83,8 +91,8 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP | ^ | ^ | ^ | fah 250 | ^ | needs XYZ calibration | ^ | ^ | ^ | ^ | ^ | 00h 0 | ^ | Unknown | ^ | ^ | 0x0FF5h 4085 | uint16 | EEPROM_BABYSTEP_Z0 | ??? | ff ffh 65535 | Babystep for Z ??? | ??? | D3 Ax0ff5 C2 -| 0x0FF1h 4081 | uint32 | EEPROM_FILAMENTUSED | ??? | 00 00 00 00h 0 | Filament used in meters | ??? | D3 Ax0ff1 C4 -| 0x0FEDh 4077 | uint32 | EEPROM_TOTALTIME | ??? | 00 00 00 00h 0 | Total print time | ??? | D3 Ax0fed C4 +| 0x0FF1h 4081 | uint32 | EEPROM_FILAMENTUSED | ??? | 00 00 00 00h 0 __S/P__| Filament used in meters | ??? | D3 Ax0ff1 C4 +| 0x0FEDh 4077 | uint32 | EEPROM_TOTALTIME | ??? | 00 00 00 00h 0 __S/P__| Total print time | ??? | D3 Ax0fed C4 | 0x0FE5h 4069 | float | EEPROM_BED_CALIBRATION_CENTER | ??? | ff ff ff ffh | ??? | ??? | D3 Ax0fe5 C8 | ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ | 0x0FDDh 4061 | float | EEPROM_BED_CALIBRATION_VEC_X | ??? | ff ff ff ffh | ??? | ??? | D3 Ax0fdd C8 @@ -99,10 +107,10 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP | ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ -| 0x0FC4h 4036 | bool | EEPROM_FARM_MODE | 00h 0 | ffh 255 | Prusa farm mode: __off__ | G99 | D3 Ax0fc4 C1 +| 0x0FC4h 4036 | bool | EEPROM_FARM_MODE | 00h 0 | ffh 255 __P__ | Prusa farm mode: __off__ | G99 | D3 Ax0fc4 C1 | ^ | ^ | ^ | 01h 1 | ^ | Prusa farm mode: __on__ | G98 | ^ | 0x0FC3h 4035 | free | _EEPROM_FREE_NR1_ | ??? | ffh 255 | _Free EEPROM space_ | _free space_ | D3 Ax0fc3 C1 -| 0x0FC1h 4033 | ??? | EEPROM_FARM_NUMBER | 000-999 | ff ffh | Prusa farm number _only 0-9 are allowed: 000-999_ | LCD menu | D3 Ax0fc1 C2 +| 0x0FC1h 4033 | ??? | EEPROM_FARM_NUMBER | 000-999 | ff ffh __P__ | Prusa farm number _only 0-9 are allowed: 000-999_ | LCD menu | D3 Ax0fc1 C2 | 0x0FC0h 4032 | bool | EEPROM_BED_CORRECTION_VALID | 00h 0 | 00h 0 | Bed correction invalid | ??? | D3 Ax0fc0 C1 | ^ | ^ | ^ | ffh 255 | | Bed correction valid | ??? | ^ | 0x0FBFh 4031 | char | EEPROM_BED_CORRECTION_LEFT | 00h ffh | 00h 0 | Bed manual correction left | LCD menu | D3 Ax0fbf C1 @@ -166,15 +174,15 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP | 0x0F6Ah 3946 | ??? | _EEPROM_FREE_NR5_ | ??? | ffh 255 | _Free EEPROM space_ | _free space_ | D3 Ax0f6a C1 | 0x0F69h 3945 | uint8 | EEPROM_CRASH_DET | ffh 255 | ffh 255 | Crash detection: __enabled__ | LCD menu | D3 Ax0f69 C1 | ^ | ^ | ^ | 00h 0 | ^ | Crash detection: __disabled__ | LCD menu | ^ -| 0x0F68h 3944 | uint8 | EEPROM_CRASH_COUNT_Y | 00h-ffh 0-255 | ffh 255 | Crashes detected on y axis | ??? | D3 Ax0f68 C1 -| 0x0F67h 3943 | uint8 | EEPROM_FSENSOR | 01h 1 | ffh 255 | Filament sensor: __enabled__ | LCD menu | D3 Ax0f67 C1 +| 0x0F68h 3944 | uint8 | EEPROM_CRASH_COUNT_Y | 00h-ffh 0-255 | ffh 255 __S/P__ | Crashes detected on y axis | ??? | D3 Ax0f68 C1 +| 0x0F67h 3943 | uint8 | EEPROM_FSENSOR | 01h 1 | ffh 255 __P__ | Filament sensor: __enabled__ | LCD menu | D3 Ax0f67 C1 | ^ | ^ | ^ | 00h 0 | ^ | Filament sensor: __disabled__ | LCD menu | ^ -| 0x0F65h 3942 | uint8 | EEPROM_CRASH_COUNT_X | 00h-ffh 0-255 | ffh 255 | Crashes detected on x axis | ??? | D3 Ax0f66 C1 -| 0x0F65h 3941 | uint8 | EEPROM_FERROR_COUNT | 00h-ffh 0-255 | ffh 255 | Filament sensor error counter | ??? | D3 Ax0f65 C1 -| 0x0F64h 3940 | uint8 | EEPROM_POWER_COUNT | 00h-ffh 0-255 | ffh 255 | Power failure counter | ??? | D3 Ax0f64 C1 +| 0x0F65h 3942 | uint8 | EEPROM_CRASH_COUNT_X | 00h-ffh 0-255 | ffh 255 __S/P__ | Crashes detected on x axis | ??? | D3 Ax0f66 C1 +| 0x0F65h 3941 | uint8 | EEPROM_FERROR_COUNT | 00h-ffh 0-255 | ffh 255 __S/P__ | Filament sensor error counter | ??? | D3 Ax0f65 C1 +| 0x0F64h 3940 | uint8 | EEPROM_POWER_COUNT | 00h-ffh 0-255 | ffh 255 __S/P__ | Power failure counter | ??? | D3 Ax0f64 C1 | 0x0F60h 3936 | float | EEPROM_XYZ_CAL_SKEW | ??? | ff ff ff ffh | XYZ skew value | ??? | D3 Ax0f60 C4 -| 0x0F5Fh 3935 | uint8 | EEPROM_WIZARD_ACTIVE | 00h 0 | ??? | Wizard active | ??? | D3 Ax0f5f C1 -| ^ | ^ | ^ | 01h 1 | ??? | ^ | ^ | ^ +| 0x0F5Fh 3935 | uint8 | EEPROM_WIZARD_ACTIVE | 01h 1 | 01h 1 __P__ | Wizard __active__ | ??? | D3 Ax0f5f C1 +| ^ | ^ | ^ | 00h 0 | ^ | Wizard __inactive__ | ^ | ^ | 0x0F5Dh 3933 | uint16 | EEPROM_BELTSTATUS_X | ??? | ff ffh | X Beltstatus | ??? | D3 Ax0f5d C2 | 0x0F5Bh 3931 | uint16 | EEPROM_BELTSTATUS_Y | ??? | ff ffh | Y Beltstatus | ??? | D3 Ax0f5b C2 | 0x0F5Ah 3930 | uint8 | EEPROM_DIR_DEPTH | 00h-ffh 0-255 | ffh 255 | Directory depth | ??? | D3 Ax0f5a C1 @@ -184,12 +192,12 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP | ^ | ^ | ^ | 02h 1 | ^ | SD card: __not sorted__ | LCD menu | ^ | 0x0F08h 3848 | uint8 | EEPROM_SECOND_SERIAL_ACTIVE | 00h 0 | ffh 255 | RPi Port: __disabled__ | LCD menu | D3 Ax0f08 C1 | ^ | ^ | ^ | 01h 1 | ^ | RPi Port: __enabled__ | LCD menu | ^ -| 0x0F07h 3847 | uint8 | EEPROM_FSENS_AUTOLOAD_ENABLED | 01h 1 | ffh 255 | Filament autoload: __enabled__ | LCD menu | D3 Ax0f07 C1 +| 0x0F07h 3847 | uint8 | EEPROM_FSENS_AUTOLOAD_ENABLED | 01h 1 | ffh 255 __P__ | Filament autoload: __enabled__ | LCD menu | D3 Ax0f07 C1 | ^ | ^ | ^ | 00h 0 | ^ | Filament autoload: __disabled__ | LCD menu | ^ -| 0x0F05h 3845 | uint16 | EEPROM_CRASH_COUNT_X_TOT | 0000-fffe | ff ffh | Total crashes on x axis | ??? | D3 Ax0f05 C2 -| 0x0F03h 3843 | uint16 | EEPROM_CRASH_COUNT_Y_TOT | 0000-fffe | ff ffh | Total crashes on y axis | ??? | D3 Ax0f03 C2 -| 0x0F01h 3841 | uint16 | EEPROM_FERROR_COUNT_TOT | 0000-fffe | ff ffh | Total filament sensor errors | ??? | D3 Ax0f01 C2 -| 0x0EFFh 3839 | uint16 | EEPROM_POWER_COUNT_TOT | 0000-fffe | ff ffh | Total power failures | ??? | D3 Ax0eff C2 +| 0x0F05h 3845 | uint16 | EEPROM_CRASH_COUNT_X_TOT | 0000-fffe | ff ffh __S/P__ | Total crashes on x axis | ??? | D3 Ax0f05 C2 +| 0x0F03h 3843 | uint16 | EEPROM_CRASH_COUNT_Y_TOT | 0000-fffe | ff ffh __S/P__ | Total crashes on y axis | ??? | D3 Ax0f03 C2 +| 0x0F01h 3841 | uint16 | EEPROM_FERROR_COUNT_TOT | 0000-fffe | ff ffh __S/P__ | Total filament sensor errors | ??? | D3 Ax0f01 C2 +| 0x0EFFh 3839 | uint16 | EEPROM_POWER_COUNT_TOT | 0000-fffe | ff ffh __S/P__ | Total power failures | ??? | D3 Ax0eff C2 | 0x0EFEh 3838 | uint8 | EEPROM_TMC2130_HOME_X_ORIGIN | ??? | ffh 255 | ??? | ??? | D3 Ax0efe C1 | 0x0EFDh 3837 | uint8 | EEPROM MC2130_HOME_X_BSTEPS | ??? | ffh 255 | ??? | ??? | D3 Ax0efd C1 | 0x0EFCh 3836 | uint8 | EEPROM_TMC2130_HOME_X_FSTEPS | ??? | ffh 255 | ??? | ??? | D3 Ax0efc C1 @@ -237,10 +245,10 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP | ^ | ^ | ^ | 00h 0 | ^ | MMU2/s autodeplete: __off__ | ^ | ^ | 0x0ED5 3797 | bool | EEPROM_FSENS_OQ_MEASS_ENABLED | ??? | ffh 255 | PAT1925 ??? | ??? | D3 Ax0ed5 C1 | ^ | ^ | ^ | ??? | ^ | PAT1925 ??? | ^ | ^ -| 0x0ED3 3795 | uint16 | EEPROM_MMU_FAIL_TOT | ??? | ff ffh 65535 | MMU2/s total failures | ??? | D3 Ax0ed3 C2 -| 0x0ED2 3794 | uint8 | EEPROM_MMU_FAIL | ??? | ffh 255 | MMU2/s fails during print | ??? | D3 Ax0ed2 C1 -| 0x0ED0 3792 | uint16 | EEPROM_MMU_LOAD_FAIL_TOT | ??? | ff ffh 65535 | MMU2/s total load failures | ??? | D3 Ax0ed0 C2 -| 0x0ECF 3791 | uint8 | EEPROM_MMU_LOAD_FAIL | ??? | ffh 255 | MMU2/s load failures during print | ??? | D3 Ax0ecf C1 +| 0x0ED3 3795 | uint16 | EEPROM_MMU_FAIL_TOT | ??? | ff ffh 65535 __S/P__ | MMU2/s total failures | ??? | D3 Ax0ed3 C2 +| 0x0ED2 3794 | uint8 | EEPROM_MMU_FAIL | ??? | ffh 255 __S/P__ | MMU2/s fails during print | ??? | D3 Ax0ed2 C1 +| 0x0ED0 3792 | uint16 | EEPROM_MMU_LOAD_FAIL_TOT | ??? | ff ffh 65535 __S/P__ | MMU2/s total load failures | ??? | D3 Ax0ed0 C2 +| 0x0ECF 3791 | uint8 | EEPROM_MMU_LOAD_FAIL | ??? | ffh 255 __S/P__ | MMU2/s load failures during print | ??? | D3 Ax0ecf C1 | 0x0ECE 3790 | uint8 | EEPROM_MMU_CUTTER_ENABLED | 00h 0 | ffh 255 | MMU2/s cutter: __disabled__ | LCD menu | D3 Ax0ece C1 | ^ | ^ | ^ | 01h 1 | ^ | MMU2/s cutter: __enabled__ | ^ | ^ | ^ | ^ | ^ | 02h 2 | ^ | MMU2/s cutter: __always__ | ^ | ^ From 95a24320f7d7293d686cda94d0f4a6e29709ee98 Mon Sep 17 00:00:00 2001 From: 3d-gussner <3d.gussner@gmail.com> Date: Mon, 23 Mar 2020 17:10:40 +0100 Subject: [PATCH 115/158] Added language factory reset and some other minor fixes --- Firmware/eeprom.h | 11 +++++++---- 1 file changed, 7 insertions(+), 4 deletions(-) diff --git a/Firmware/eeprom.h b/Firmware/eeprom.h index ec9c57de..64bd4a9b 100644 --- a/Firmware/eeprom.h +++ b/Firmware/eeprom.h @@ -50,11 +50,14 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP In Default/FactoryReset column the + - __L__ Language - __S__ Statistics - __P__ Shipping prep - __S/P__ Statistics and Shipping prep will overwrite existing values to 0 or default. + A FactoryReset All Data will overwrite the hole EEPROM with ffh and some values will be initialized automatically, + others need a reset / reboot. --------------------------------------------------------------------------------- How can you use the debug codes? @@ -78,7 +81,7 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP | :-- | :-- | :-- | :--: | :--: | :-- | :--: | :--: | 0x0FFFh 4095 | uchar | EEPROM_SILENT | 00h 0 | ffh 255 | TMC Stealth mode: __off__ / miniRambo Power mode | LCD menu | D3 Ax0fff C1 | ^ | ^ | ^ | 01h 1 | ^ | TMC Stealth mode: __on__ / miniRambo Silent mode | ^ | ^ -| 0x0FFEh 4094 | uchar | EEPROM_LANG | 00h 0 | ffh 255 | English / LANG_ID_PRI | LCD menu | D3 Ax0ffe C1 +| 0x0FFEh 4094 | uchar | EEPROM_LANG | 00h 0 | ffh 255 __L__ | English / LANG_ID_PRI | LCD menu | D3 Ax0ffe C1 | ^ | ^ | ^ | 01h 1 | ^ | Other language LANG_ID_SEC | ^ | ^ | 0x0FFCh 4092 | uint16 | EEPROM_BABYSTEP_X | ??? | ff ffh 65535 | Babystep for X axis _unsued_ | ??? | D3 Ax0ffc C2 | 0x0FFAh 4090 | uint16 | EEPROM_BABYSTEP_Y | ??? | ff ffh 65535 | Babystep for Y axis _unsued_ | ^ | D3 Ax0ffa C2 @@ -87,7 +90,7 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP | 0x0FF7h 4087 | uint8 | EEPROM_CALIBRATION_STATUS | ffh 255 | ffh 255 | Assembled _default_ | ??? | D3 Ax0ff7 C1 | ^ | ^ | ^ | 01h 1 | ^ | Calibrated | ^ | ^ | ^ | ^ | ^ | e6h 230 | ^ | needs Live Z adjustment | ^ | ^ -| ^ | ^ | ^ | f0h 240 | ^ | needs Z calibration | ^ | ^ +| ^ | ^ | ^ | f0h 240 | ^ __P__ | needs Z calibration | ^ | ^ | ^ | ^ | ^ | fah 250 | ^ | needs XYZ calibration | ^ | ^ | ^ | ^ | ^ | 00h 0 | ^ | Unknown | ^ | ^ | 0x0FF5h 4085 | uint16 | EEPROM_BABYSTEP_Z0 | ??? | ff ffh 65535 | Babystep for Z ??? | ??? | D3 Ax0ff5 C2 @@ -107,10 +110,10 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP | ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ | ^ -| 0x0FC4h 4036 | bool | EEPROM_FARM_MODE | 00h 0 | ffh 255 __P__ | Prusa farm mode: __off__ | G99 | D3 Ax0fc4 C1 +| 0x0FC4h 4036 | bool | EEPROM_FARM_MODE | 00h 0 | ffh 255 __P__ | Prusa farm mode: __off__ | G99 | D3 Ax0fc4 C1 | ^ | ^ | ^ | 01h 1 | ^ | Prusa farm mode: __on__ | G98 | ^ | 0x0FC3h 4035 | free | _EEPROM_FREE_NR1_ | ??? | ffh 255 | _Free EEPROM space_ | _free space_ | D3 Ax0fc3 C1 -| 0x0FC1h 4033 | ??? | EEPROM_FARM_NUMBER | 000-999 | ff ffh __P__ | Prusa farm number _only 0-9 are allowed: 000-999_ | LCD menu | D3 Ax0fc1 C2 +| 0x0FC1h 4033 | ??? | EEPROM_FARM_NUMBER | 000-999 | ff ffh / 000 __P__ | Prusa farm number _only 0-9 are allowed: 000-999_ | LCD menu | D3 Ax0fc1 C2 | 0x0FC0h 4032 | bool | EEPROM_BED_CORRECTION_VALID | 00h 0 | 00h 0 | Bed correction invalid | ??? | D3 Ax0fc0 C1 | ^ | ^ | ^ | ffh 255 | | Bed correction valid | ??? | ^ | 0x0FBFh 4031 | char | EEPROM_BED_CORRECTION_LEFT | 00h ffh | 00h 0 | Bed manual correction left | LCD menu | D3 Ax0fbf C1 From 0d00db1c335d42a94ea91e5fa6ba60e3c9d40255 Mon Sep 17 00:00:00 2001 From: 3d-gussner <3d.gussner@gmail.com> Date: Wed, 25 Mar 2020 17:26:27 +0100 Subject: [PATCH 116/158] Some D-codes are case sensitive --- Firmware/Marlin_main.cpp | 38 ++++++++++++++++++++++++++++---------- 1 file changed, 28 insertions(+), 10 deletions(-) diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index 9a8ac81e..413781b6 100755 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -8809,12 +8809,18 @@ Sigma_Exit: This command can be used without any additional parameters. It will read the entire RAM. #### Usage - D3 [ A | C | X ] + D2 [ A | C | X ] #### Parameters - - `A` - Address (0x0000-0x1fff) - - `C` - Count (0x0001-0x2000) + - `A` - Address (x0000-x1fff) + - `C` - Count (1-8192) - `X` - Data + + #### Notes + - The hex address needs to be lowercase without the 0 before the x + - Count is decimal + - The hex data needs to be lowercase + */ case 2: dcode_2(); break; @@ -8829,9 +8835,15 @@ Sigma_Exit: D3 [ A | C | X ] #### Parameters - - `A` - Address (0x0000-0x0fff) - - `C` - Count (0x0001-0x1000) - - `X` - Data + - `A` - Address (x0000-x0fff) + - `C` - Count (1-4096) + - `X` - Data (hex) + + #### Notes + - The hex address needs to be lowercase without the 0 before the x + - Count is decimal + - The hex data needs to be lowercase + */ case 3: dcode_3(); break; @@ -8861,14 +8873,20 @@ Sigma_Exit: This command can be used without any additional parameters. It will read the 1kb FLASH. #### Usage - D3 [ A | C | X | E ] + D5 [ A | C | X | E ] #### Parameters - - `A` - Address (0x00000-0x3ffff) - - `C` - Count (0x0001-0x2000) + - `A` - Address (x00000-x3ffff) + - `C` - Count (1-8192) - `X` - Data - `E` - Erase - */ + + #### Notes + - The hex address needs to be lowercase without the 0 before the x + - Count is decimal + - The hex data needs to be lowercase + + */ case 5: dcode_5(); break; break; From 4c518545f1927e12149f3ae5b14a6189bc961ced Mon Sep 17 00:00:00 2001 From: 3d-gussner <3d.gussner@gmail.com> Date: Wed, 25 Mar 2020 17:33:10 +0100 Subject: [PATCH 117/158] Updated the documentation copy past from Marlin_main.cpp doxygen documentation d-codes --- Firmware/Dcodes.cpp | 279 ++++++++++++++++++++++----------------- Firmware/Marlin_main.cpp | 1 - 2 files changed, 155 insertions(+), 125 deletions(-) diff --git a/Firmware/Dcodes.cpp b/Firmware/Dcodes.cpp index 70ffe2c4..ebf34b4f 100644 --- a/Firmware/Dcodes.cpp +++ b/Firmware/Dcodes.cpp @@ -100,16 +100,22 @@ void print_mem(uint32_t address, uint16_t count, uint8_t type, uint8_t countperl #ifdef DEBUG_DCODE3 #define EEPROM_SIZE 0x1000 /*! - * ### D3 - Read/Write EEPROM D3: Read/Write EEPROM This command can be used without any additional parameters. It will read the entire eeprom. - - D3 [ A | C | X ] - - - `A` - Address (0x0000-0x0fff) - - `C` - Count (0x0001-0x1000) - - `X` - Data - * + #### Usage + + D3 [ A | C | X ] + + #### Parameters + - `A` - Address (x0000-x0fff) + - `C` - Count (1-4096) + - `X` - Data (hex) + + #### Notes + - The hex address needs to be lowercase without the 0 before the x + - Count is decimal + - The hex data needs to be lowercase + */ void dcode_3() { @@ -206,13 +212,13 @@ void dcode__1() #ifdef DEBUG_DCODES /*! - * ### D0 - Reset D0: Reset - - D0 [ B ] - - - `B` - Bootloader - * + #### Usage + + D0 [ B ] + + #### Parameters + - `B` - Bootloader */ void dcode_0() { @@ -251,16 +257,22 @@ void dcode_1() } /*! - * - ### D2 - Read/Write RAM D2: Read/Write RAM + ### D2 - Read/Write RAM D3: Read/Write RAM This command can be used without any additional parameters. It will read the entire RAM. - - D2 [ A | C | X ] - - - `A` - Address (0x0000-0x1fff) - - `C` - Count (0x0001-0x2000) - - `X` - Data - * + #### Usage + + D2 [ A | C | X ] + + #### Parameters + - `A` - Address (x0000-x1fff) + - `C` - Count (1-8192) + - `X` - Data + + #### Notes + - The hex address needs to be lowercase without the 0 before the x + - Count is decimal + - The hex data needs to be lowercase + */ void dcode_2() { @@ -306,17 +318,17 @@ void dcode_2() } /*! - * - ### D4 - Read/Write PIN D4: Read/Write PIN + ### D4 - Read/Write PIN D4: Read/Write PIN To read the digital value of a pin you need only to define the pin number. - - D4 [ P | F | V ] - - - `P` - Pin (0-255) - - `F` - Function in/out (0/1) - - `V` - Value (0/1) - * + #### Usage + + D4 [ P | F | V ] + + #### Parameters + - `P` - Pin (0-255) + - `F` - Function in/out (0/1) + - `V` - Value (0/1) */ void dcode_4() { @@ -351,18 +363,24 @@ void dcode_4() #ifdef DEBUG_DCODE5 /*! - * ### D5 - Read/Write FLASH D5: Read/Write Flash This command can be used without any additional parameters. It will read the 1kb FLASH. - - D5 [ A | C | X | E ] - - - `A` - Address (0x00000-0x3ffff) - - `C` - Count (0x0001-0x2000) - - `X` - Data - - `E` - Erase - * - */ + #### Usage + + D5 [ A | C | X | E ] + + #### Parameters + - `A` - Address (x00000-x3ffff) + - `C` - Count (1-8192) + - `X` - Data + - `E` - Erase + + #### Notes + - The hex address needs to be lowercase without the 0 before the x + - Count is decimal + - The hex data needs to be lowercase + + */ void dcode_5() { printf_P(PSTR("D5 - Read/Write FLASH\n")); @@ -427,24 +445,18 @@ void dcode_5() #ifdef DEBUG_DCODES /*! - * ### D6 - Read/Write external FLASH D6: Read/Write external Flash - Reserved - * - */ + */ void dcode_6() { LOG("D6 - Read/Write external FLASH\n"); } /*! - * ### D7 - Read/Write Bootloader D7: Read/Write Bootloader - Reserved - * - */ + */ void dcode_7() { LOG("D7 - Read/Write Bootloader\n"); @@ -461,16 +473,16 @@ void dcode_7() } /*! - * ### D8 - Read/Write PINDA D8: Read/Write PINDA - - D8 [ ? | ! | P | Z ] - - - `?` - Read PINDA temperature shift values - - `!` - Reset PINDA temperature shift values to default - - `P` - Pinda temperature [C] - - `Z` - Z Offset [mm] - * + #### Usage + + D8 [ ? | ! | P | Z ] + + #### Parameters + - `?` - Read PINDA temperature shift values + - `!` - Reset PINDA temperature shift values to default + - `P` - Pinda temperature [C] + - `Z` - Z Offset [mm] */ void dcode_8() { @@ -514,21 +526,21 @@ void dcode_8() } /*! - * ### D9 - Read ADC D9: Read ADC - - D9 [ I | V ] - - - `I` - ADC channel index - - `0` - Heater 0 temperature - - `1` - Heater 1 temperature - - `2` - Bed temperature - - `3` - PINDA temperature - - `4` - PWR voltage - - `5` - Ambient temperature - - `6` - BED voltage - - `V` Value to be written as simulated - * + #### Usage + + D9 [ I | V ] + + #### Parameters + - `I` - ADC channel index + - `0` - Heater 0 temperature + - `1` - Heater 1 temperature + - `2` - Bed temperature + - `3` - PINDA temperature + - `4` - PWR voltage + - `5` - Ambient temperature + - `6` - BED voltage + - `V` Value to be written as simulated */ const char* dcode_9_ADC_name(uint8_t i) { @@ -604,11 +616,8 @@ void dcode_9() } /*! - * ### D10 - Set XYZ calibration = OK D10: Set XYZ calibration = OK - - * - */ + */ void dcode_10() {//Tell the printer that XYZ calibration went OK LOG("D10 - XYZ calibration = OK\n"); @@ -616,11 +625,10 @@ void dcode_10() } /*! - * ### D12 - Time D12: Time - - * - */ + Writes the actual time in the log file. + */ + void dcode_12() {//Time LOG("D12 - Time\n"); @@ -632,38 +640,61 @@ void dcode_12() #include "planner.h" #include "tmc2130.h" extern void st_synchronize(); -/** - * @brief D2130 Trinamic stepper controller - * D2130[subcommand][value] - * * Axis - * * * 'X' - * * * 'Y' - * * * 'Z' - * * * 'E' - * * command - * * * '0' current off - * * * '1' current on - * * * '+' single step - * * * * value sereval steps - * * * '-' dtto oposite direction - * * * '?' read register - * * * * "mres" - * * * * "step" - * * * * "mscnt" - * * * * "mscuract" - * * * * "wave" - * * * '!' set register - * * * * "mres" - * * * * "step" - * * * * "wave" - * * * * *0, 180..250 meaning: off, 0.9..1.25, recommended value is 1.1 - * * * '@' home calibrate axis - * - * Example: - * D2130E?wave //print extruder microstep linearity compensation curve - * D2130E!wave0 //disable extruder linearity compensation curve, (sine curve is used) - * D2130E!wave220 // (sin(x))^1.1 extruder microstep compensation curve used - */ + /*! + ### D2130 - Trinamic stepper controller D2130: Trinamic stepper controller + @todo Please review by owner of the code. RepRap Wiki Gcode needs to be updated after review of owner as well. + + #### Usage + + D2130 [ Axis | Command | Subcommand | Value ] + + #### Parameters + - Axis + - `X` - X stepper driver + - `Y` - Y stepper driver + - `Z` - Z stepper driver + - `E` - Extruder stepper driver + - Commands + - `0` - Current off + - `1` - Current on + - `+` - Single step + - `-` - Single step oposite direction + - `NNN` - Value sereval steps + - `?` - Read register + - Subcommands for read register + - `mres` - Micro step resolution. More information in datasheet '5.5.2 CHOPCONF – Chopper Configuration' + - `step` - Step + - `mscnt` - Microstep counter. More information in datasheet '5.5 Motor Driver Registers' + - `mscuract` - Actual microstep current for motor. More information in datasheet '5.5 Motor Driver Registers' + - `wave` - Microstep linearity compensation curve + - `!` - Set register + - Subcommands for set register + - `mres` - Micro step resolution + - `step` - Step + - `wave` - Microstep linearity compensation curve + - Values for set register + - `0, 180 --> 250` - Off + - `0.9 --> 1.25` - Valid values (recommended is 1.1) + - `@` - Home calibrate axis + + Examples: + + D2130E?wave + + Print extruder microstep linearity compensation curve + + D2130E!wave0 + + Disable extruder linearity compensation curve, (sine curve is used) + + D2130E!wave220 + + (sin(x))^1.1 extruder microstep compensation curve used + + Notes: + For more information see https://www.trinamic.com/fileadmin/assets/Products/ICs_Documents/TMC2130_datasheet.pdf + * + */ void dcode_2130() { printf_P(PSTR("D2130 - TMC2130\n")); @@ -767,18 +798,18 @@ void dcode_2130() #ifdef PAT9125 /*! - * ### D9125 - PAT9125 filament sensor D9125: PAT9125 filament sensor - - D9125 [ ? | ! | R | X | Y | L ] - - - `?` - Print values - - `!` - Print values - - `R` - Resolution. Not active in code - - `X` - X values - - `Y` - Y values - - `L` - Activate filament sensor log - * + #### Usage + + D9125 [ ? | ! | R | X | Y | L ] + + #### Parameters + - `?` - Print values + - `!` - Print values + - `R` - Resolution. Not active in code + - `X` - X values + - `Y` - Y values + - `L` - Activate filament sensor log */ void dcode_9125() { diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index 413781b6..1a17e40d 100755 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -9105,7 +9105,6 @@ Sigma_Exit: For more information see https://www.trinamic.com/fileadmin/assets/Products/ICs_Documents/TMC2130_datasheet.pdf * */ - case 2130: dcode_2130(); break; #endif //TMC2130 From 82cd1f9f841509a760072ed51fde17885ebaa463 Mon Sep 17 00:00:00 2001 From: 3d-gussner <3d.gussner@gmail.com> Date: Wed, 25 Mar 2020 17:44:43 +0100 Subject: [PATCH 118/158] Typo. thanks @leptun --- Firmware/eeprom.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Firmware/eeprom.h b/Firmware/eeprom.h index 64bd4a9b..bed2d20b 100644 --- a/Firmware/eeprom.h +++ b/Firmware/eeprom.h @@ -56,7 +56,7 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP - __S/P__ Statistics and Shipping prep will overwrite existing values to 0 or default. - A FactoryReset All Data will overwrite the hole EEPROM with ffh and some values will be initialized automatically, + A FactoryReset All Data will overwrite the whole EEPROM with ffh and some values will be initialized automatically, others need a reset / reboot. --------------------------------------------------------------------------------- From 9b394dcbe6ae718856f92058101d8170c0bf40c2 Mon Sep 17 00:00:00 2001 From: 3d-gussner <3d.gussner@gmail.com> Date: Thu, 26 Mar 2020 13:55:23 +0100 Subject: [PATCH 119/158] Update to Version 1.0 --- Firmware/eeprom.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Firmware/eeprom.h b/Firmware/eeprom.h index bed2d20b..17fcf089 100644 --- a/Firmware/eeprom.h +++ b/Firmware/eeprom.h @@ -72,7 +72,7 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP To convert hex to dec https://www.rapidtables.com/convert/number/hex-to-decimal.html - Version: 0.9.1 + Version: 1.0 --------------------------------------------------------------------------------- From 2ceec597a59a765be54c7bac3d89410184857e55 Mon Sep 17 00:00:00 2001 From: 3d-gussner <3d.gussner@gmail.com> Date: Thu, 26 Mar 2020 14:08:35 +0100 Subject: [PATCH 120/158] Fix typo --- Firmware/Dcodes.cpp | 2 +- Firmware/Marlin_main.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Firmware/Dcodes.cpp b/Firmware/Dcodes.cpp index ebf34b4f..79695c9e 100644 --- a/Firmware/Dcodes.cpp +++ b/Firmware/Dcodes.cpp @@ -626,7 +626,7 @@ void dcode_10() /*! ### D12 - Time D12: Time - Writes the actual time in the log file. + Writes the current time in the log file. */ void dcode_12() diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index 1a17e40d..ac0d3b5d 100755 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -8950,7 +8950,7 @@ Sigma_Exit: /*! ### D12 - Time D12: Time - Writes the actual time in the log file. + Writes the current time in the log file. */ #endif //DEBUG_DCODES From 34ac2917ae7d444a8560966eb4f043dd446eaadb Mon Sep 17 00:00:00 2001 From: "D.R.racer" Date: Thu, 26 Mar 2020 14:40:47 +0100 Subject: [PATCH 121/158] fix. warning "Macro expansion producing 'defined' has undefined behavior" update screen layout comments --- Firmware/Marlin_main.cpp | 6 +++--- Firmware/config.h | 6 ++++-- Firmware/fsensor.cpp | 16 +++++++------- Firmware/fsensor.h | 2 +- Firmware/temperature.cpp | 4 ++-- Firmware/temperature.h | 2 +- Firmware/ultralcd.cpp | 45 +++++++++++++++++++--------------------- Firmware/ultralcd.h | 4 ++-- 8 files changed, 42 insertions(+), 43 deletions(-) diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index d0ee5a3b..95ea92e1 100755 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -9445,7 +9445,7 @@ void manage_inactivity(bool ignore_stepper_queue/*=false*/) //default argument s { #ifdef FILAMENT_SENSOR bool bInhibitFlag; -#if IR_SENSOR_ANALOG +#ifdef IR_SENSOR_ANALOG static uint8_t nFSCheckCount=0; #endif // IR_SENSOR_ANALOG @@ -9457,7 +9457,7 @@ static uint8_t nFSCheckCount=0; #endif // PAT9125 #ifdef IR_SENSOR bInhibitFlag=(menu_menu==lcd_menu_show_sensors_state); // Support::SensorInfo menu active -#if IR_SENSOR_ANALOG +#ifdef IR_SENSOR_ANALOG bInhibitFlag=bInhibitFlag||bMenuFSDetect; // Settings::HWsetup::FSdetect menu active #endif // IR_SENSOR_ANALOG #endif // IR_SENSOR @@ -9465,7 +9465,7 @@ static uint8_t nFSCheckCount=0; { if (!moves_planned() && !IS_SD_PRINTING && !is_usb_printing && (lcd_commands_type != LcdCommands::Layer1Cal) && ! eeprom_read_byte((uint8_t*)EEPROM_WIZARD_ACTIVE)) { -#if IR_SENSOR_ANALOG +#ifdef IR_SENSOR_ANALOG bool bTemp=current_voltage_raw_IR>IRsensor_Hmin_TRESHOLD; bTemp=bTemp&¤t_voltage_raw_IR9 #endif -#if IR_SENSOR_ANALOG +#ifdef IR_SENSOR_ANALOG current_voltage_raw_IR = adc_values[ADC_PIN_IDX(VOLT_IR_PIN)]; #endif //IR_SENSOR_ANALOG temp_meas_ready = true; diff --git a/Firmware/temperature.h b/Firmware/temperature.h index ba56e681..94e11a2f 100755 --- a/Firmware/temperature.h +++ b/Firmware/temperature.h @@ -78,7 +78,7 @@ extern int current_voltage_raw_pwr; extern int current_voltage_raw_bed; #endif -#if IR_SENSOR_ANALOG +#ifdef IR_SENSOR_ANALOG extern int current_voltage_raw_IR; #endif //IR_SENSOR_ANALOG diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index c23f2a23..dc4fa56b 100755 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -68,7 +68,7 @@ uint8_t SilentModeMenu_MMU = 1; //activate mmu unit stealth mode int8_t FSensorStateMenu = 1; -#if IR_SENSOR_ANALOG +#ifdef IR_SENSOR_ANALOG bool bMenuFSDetect=false; #endif //IR_SENSOR_ANALOG @@ -239,7 +239,7 @@ static FanCheck lcd_selftest_fan_auto(int _fan); static bool lcd_selftest_fsensor(); #endif //PAT9125 static bool selftest_irsensor(); -#if IR_SENSOR_ANALOG +#ifdef IR_SENSOR_ANALOG static bool lcd_selftest_IRsensor(bool bStandalone=false); static void lcd_detect_IRsensor(); #endif //IR_SENSOR_ANALOG @@ -1945,7 +1945,7 @@ static void lcd_menu_temperatures() menu_back_if_clicked(); } -#if defined (VOLT_BED_PIN) || defined (VOLT_PWR_PIN) || IR_SENSOR_ANALOG +#if defined (VOLT_BED_PIN) || defined (VOLT_PWR_PIN) || defined(IR_SENSOR_ANALOG) #define VOLT_DIV_R1 10000 #define VOLT_DIV_R2 2370 #define VOLT_DIV_FAC ((float)VOLT_DIV_R2 / (VOLT_DIV_R2 + VOLT_DIV_R1)) @@ -1957,27 +1957,24 @@ static void lcd_menu_temperatures() //! | | //! | PWR: 00.0V | c=12 r=1 //! | Bed: 00.0V | c=12 r=1 -//! | | +//! | IR : 00.0V | c=12 r=1 optional //! ---------------------- //! @endcode //! @todo Positioning of the messages and values on LCD aren't fixed to their exact place. This causes issues with translations. static void lcd_menu_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_home(); -#if !IR_SENSOR_ANALOG - lcd_printf_P(PSTR("\n")); -#endif //!IR_SENSOR_ANALOG - lcd_printf_P(PSTR(" PWR: %4.1fV\n" " BED: %4.1fV"), volt_pwr, volt_bed); -#if IR_SENSOR_ANALOG - float volt_IR = VOLT_DIV_REF * ((float)current_voltage_raw_IR / (1023 * OVERSAMPLENR)); - lcd_printf_P(PSTR("\n IR : %3.1fV"),volt_IR); + lcd_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_home(); + lcd_printf_P(PSTR(" PWR: %4.1fV\n" " BED: %4.1fV"), volt_pwr, volt_bed); +#ifdef IR_SENSOR_ANALOG + float volt_IR = VOLT_DIV_REF * ((float)current_voltage_raw_IR / (1023 * OVERSAMPLENR)); + lcd_printf_P(PSTR("\n IR : %3.1fV"),volt_IR); #endif //IR_SENSOR_ANALOG - menu_back_if_clicked(); + menu_back_if_clicked(); } -#endif //defined (VOLT_BED_PIN) || defined (VOLT_PWR_PIN) || IR_SENSOR_ANALOG +#endif //defined (VOLT_BED_PIN) || defined (VOLT_PWR_PIN) || defined(IR_SENSOR_ANALOG) #ifdef TMC2130 //! @brief Show Belt Status @@ -2151,7 +2148,7 @@ static void lcd_support_menu() MENU_ITEM_BACK_P(_i("Date:"));////MSG_DATE c=17 r=1 MENU_ITEM_BACK_P(PSTR(__DATE__)); -#if IR_SENSOR_ANALOG +#ifdef IR_SENSOR_ANALOG MENU_ITEM_BACK_P(STR_SEPARATOR); MENU_ITEM_BACK_P(PSTR("Fil. sensor v.:")); switch(oFsensorPCB) @@ -5653,7 +5650,7 @@ SETTINGS_VERSION; MENU_END(); } -#if IR_SENSOR_ANALOG +#ifdef IR_SENSOR_ANALOG static void lcd_fsensor_actionNA_set(void) { switch(oFsensorActionNA) @@ -5719,7 +5716,7 @@ void lcd_hw_setup_menu(void) // can not be "static" SETTINGS_NOZZLE; MENU_ITEM_SUBMENU_P(_i("Checks"), lcd_checking_menu); -#if IR_SENSOR_ANALOG +#ifdef IR_SENSOR_ANALOG FSENSOR_ACTION_NA; MENU_ITEM_FUNCTION_P(PSTR("FS Detect"), lcd_detect_IRsensor); #endif //IR_SENSOR_ANALOG @@ -7140,7 +7137,7 @@ static void lcd_tune_menu() else { MENU_ITEM_TOGGLE_P(_T(MSG_FSENSOR), _T(MSG_ON), lcd_fsensor_state_set); } -#if IR_SENSOR_ANALOG +#ifdef IR_SENSOR_ANALOG FSENSOR_ACTION_NA; #endif //IR_SENSOR_ANALOG #endif //FILAMENT_SENSOR @@ -7520,7 +7517,7 @@ void lcd_belttest() } #endif //TMC2130 -#if IR_SENSOR_ANALOG +#ifdef IR_SENSOR_ANALOG static bool lcd_selftest_IRsensor(bool bStandalone) { bool bAction; @@ -7586,7 +7583,7 @@ bool lcd_selftest() int _progress = 0; bool _result = true; bool _swapped_fan = false; -//#if IR_SENSOR_ANALOG +//#ifdef IR_SENSOR_ANALOG #if (0) bool bAction; bAction=lcd_show_fullscreen_message_yes_no_and_wait_P(_i("Is the filament unloaded?"),false,true); @@ -7796,7 +7793,7 @@ bool lcd_selftest() _progress = lcd_selftest_screen(TestScreen::FsensorOk, _progress, 3, true, 2000); //fil sensor OK } #endif //PAT9125 -//#if IR_SENSOR_ANALOG +//#ifdef IR_SENSOR_ANALOG #if (0) _progress = lcd_selftest_screen(TestScreen::Fsensor, _progress, 3, true, 2000); //check filament sensor _result = lcd_selftest_IRsensor(); diff --git a/Firmware/ultralcd.h b/Firmware/ultralcd.h index ca64659a..d82d71d9 100755 --- a/Firmware/ultralcd.h +++ b/Firmware/ultralcd.h @@ -140,7 +140,7 @@ extern uint8_t farm_status; #define SILENT_MODE_OFF SILENT_MODE_POWER #endif -#if IR_SENSOR_ANALOG +#ifdef IR_SENSOR_ANALOG extern bool bMenuFSDetect; #endif //IR_SENSOR_ANALOG @@ -257,7 +257,7 @@ enum class WizState : uint8_t void lcd_wizard(WizState state); #define VOLT_DIV_REF 5 -#if IR_SENSOR_ANALOG +#ifdef IR_SENSOR_ANALOG #define IRsensor_Hmin_TRESHOLD (3.0*1023*OVERSAMPLENR/VOLT_DIV_REF) // ~3.0V (0.6*Vcc) #define IRsensor_Lmax_TRESHOLD (1.5*1023*OVERSAMPLENR/VOLT_DIV_REF) // ~1.5V (0.3*Vcc) #define IRsensor_Hopen_TRESHOLD (4.6*1023*OVERSAMPLENR/VOLT_DIV_REF) // ~4.6V (N.C. @ Ru~20-50k, Rd'=56k, Ru'=10k) From 818efb4fa203daa731923b0458f2b2800da4e42a Mon Sep 17 00:00:00 2001 From: "D.R.racer" Date: Thu, 26 Mar 2020 15:07:48 +0100 Subject: [PATCH 122/158] updated messages + slight refactoring to save some bytes --- Firmware/Marlin_main.cpp | 2 +- Firmware/ultralcd.cpp | 103 +++++++++++++++++++-------------------- Firmware/ultralcd.h | 1 + 3 files changed, 53 insertions(+), 53 deletions(-) diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index 95ea92e1..ed38dded 100755 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -9480,7 +9480,7 @@ static uint8_t nFSCheckCount=0; nFSCheckCount=0; // not necessary oFsensorPCB=ClFsensorPCB::_Rev03b; eeprom_update_byte((uint8_t*)EEPROM_FSENSOR_PCB,(uint8_t)oFsensorPCB); - printf_P(PSTR("Filament sensor board change detected: revision 03b or newer\n")); + printf_IRSensorAnalogBoardChange(true); lcd_setstatuspgm(_i("FS rev. 03b or newer")); } } diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index dc4fa56b..78f2df71 100755 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -2160,10 +2160,8 @@ static void lcd_support_menu() MENU_ITEM_BACK_P(PSTR(" 03b or newer")); break; case ClFsensorPCB::_Undef: - MENU_ITEM_BACK_P(PSTR(" N/A")); - break; default: - MENU_ITEM_BACK_P(PSTR(" unknown")); + MENU_ITEM_BACK_P(PSTR(" state unknown")); } #endif // IR_SENSOR_ANALOG @@ -5718,7 +5716,7 @@ void lcd_hw_setup_menu(void) // can not be "static" #ifdef IR_SENSOR_ANALOG FSENSOR_ACTION_NA; - MENU_ITEM_FUNCTION_P(PSTR("FS Detect"), lcd_detect_IRsensor); + MENU_ITEM_FUNCTION_P(PSTR("Fsensor Detection"), lcd_detect_IRsensor); #endif //IR_SENSOR_ANALOG MENU_END(); } @@ -7518,58 +7516,59 @@ void lcd_belttest() #endif //TMC2130 #ifdef IR_SENSOR_ANALOG -static bool lcd_selftest_IRsensor(bool bStandalone) -{ -bool bAction; -bool bPCBrev03b; -uint16_t volt_IR_int; -float volt_IR; - -volt_IR_int=current_voltage_raw_IR; -bPCBrev03b=(volt_IR_int<((int)IRsensor_Hopen_TRESHOLD)); -volt_IR=VOLT_DIV_REF*((float)volt_IR_int/(1023*OVERSAMPLENR)); -printf_P(PSTR("Measured filament sensor high level: %4.2fV\n"),volt_IR); -if(volt_IR_int<((int)IRsensor_Hmin_TRESHOLD)) - { - if(!bStandalone) - lcd_selftest_error(TestError::FsensorLevel,"HIGH",""); - return(false); - } -lcd_show_fullscreen_message_and_wait_P(_i("Please insert filament (but not load them!) into extruder and then press the knob.")); -volt_IR_int=current_voltage_raw_IR; -volt_IR=VOLT_DIV_REF*((float)volt_IR_int/(1023*OVERSAMPLENR)); -printf_P(PSTR("Measured filament sensor low level: %4.2fV\n"),volt_IR); -if(volt_IR_int>((int)IRsensor_Lmax_TRESHOLD)) - { - if(!bStandalone) - lcd_selftest_error(TestError::FsensorLevel,"LOW",""); - return(false); - } -if((bPCBrev03b?1:0)!=(uint8_t)oFsensorPCB) // safer then "(uint8_t)bPCBrev03b" - { - printf_P(PSTR("Filament sensor board change detected: revision %S\n"),bPCBrev03b?PSTR("03b or newer"):PSTR("03 or older")); - oFsensorPCB=bPCBrev03b?ClFsensorPCB::_Rev03b:ClFsensorPCB::_Old; - eeprom_update_byte((uint8_t*)EEPROM_FSENSOR_PCB,(uint8_t)oFsensorPCB); - } -return(true); +// called also from marlin_main.cpp +void printf_IRSensorAnalogBoardChange(bool bPCBrev03b){ + printf_P(PSTR("Filament sensor board change detected: revision %S\n"), bPCBrev03b ? PSTR("03b or newer") : PSTR("03 or older")); } -static void lcd_detect_IRsensor() +static bool lcd_selftest_IRsensor(bool bStandalone) { -bool bAction; + bool bAction; + bool bPCBrev03b; + uint16_t volt_IR_int; + float volt_IR; -bMenuFSDetect=true; // inhibits some code inside "manage_inactivity()" -bAction=lcd_show_fullscreen_message_yes_no_and_wait_P(_i("Is the filament unloaded?"),false,true); -if(!bAction) - { - lcd_show_fullscreen_message_and_wait_P(_i("... so unload the filament and repeat action!")); - return; - } -bAction=lcd_selftest_IRsensor(true); -if(bAction) - lcd_show_fullscreen_message_and_wait_P(_i("PCB check successful - withdraw the filament now!")); -else lcd_show_fullscreen_message_and_wait_P(_i("PCB check unsuccessful - withdraw the filament now!")); -bMenuFSDetect=false; // de-inhibits some code inside "manage_inactivity()" + volt_IR_int=current_voltage_raw_IR; + bPCBrev03b=(volt_IR_int<((int)IRsensor_Hopen_TRESHOLD)); + volt_IR=VOLT_DIV_REF*((float)volt_IR_int/(1023*OVERSAMPLENR)); + printf_P(PSTR("Measured filament sensor high level: %4.2fV\n"),volt_IR); + if(volt_IR_int < ((int)IRsensor_Hmin_TRESHOLD)){ + if(!bStandalone) + lcd_selftest_error(TestError::FsensorLevel,"HIGH",""); + return(false); + } + lcd_show_fullscreen_message_and_wait_P(_i("Please insert filament (but not load them!) into extruder and then press the knob.")); + volt_IR_int=current_voltage_raw_IR; + volt_IR=VOLT_DIV_REF*((float)volt_IR_int/(1023*OVERSAMPLENR)); + printf_P(PSTR("Measured filament sensor low level: %4.2fV\n"),volt_IR); + if(volt_IR_int > ((int)IRsensor_Lmax_TRESHOLD)){ + if(!bStandalone) + lcd_selftest_error(TestError::FsensorLevel,"LOW",""); + return(false); + } + if((bPCBrev03b?1:0)!=(uint8_t)oFsensorPCB){ // safer then "(uint8_t)bPCBrev03b" + printf_IRSensorAnalogBoardChange(bPCBrev03b); + oFsensorPCB=bPCBrev03b?ClFsensorPCB::_Rev03b:ClFsensorPCB::_Old; + eeprom_update_byte((uint8_t*)EEPROM_FSENSOR_PCB,(uint8_t)oFsensorPCB); + } + return(true); +} + +static void lcd_detect_IRsensor(){ + bool bAction; + + bMenuFSDetect = true; // inhibits some code inside "manage_inactivity()" + bAction = lcd_show_fullscreen_message_yes_no_and_wait_P(_i("Is the filament loaded?"), false, false); + if(!bAction){ + lcd_show_fullscreen_message_and_wait_P(_i("Please unload the filament first, then repeat this action.")); + return; + } + bAction = lcd_selftest_IRsensor(true); + if(bAction) + lcd_show_fullscreen_message_and_wait_P(_i("Sensor verified, remove the filament now.")); + else + lcd_show_fullscreen_message_and_wait_P(_i("Verification failed, remove the filament and try again.")); + bMenuFSDetect=false; // de-inhibits some code inside "manage_inactivity()" } #endif //IR_SENSOR_ANALOG diff --git a/Firmware/ultralcd.h b/Firmware/ultralcd.h index d82d71d9..c183e0a5 100755 --- a/Firmware/ultralcd.h +++ b/Firmware/ultralcd.h @@ -142,6 +142,7 @@ extern uint8_t farm_status; #ifdef IR_SENSOR_ANALOG extern bool bMenuFSDetect; +void printf_IRSensorAnalogBoardChange(bool bPCBrev03b); #endif //IR_SENSOR_ANALOG extern int8_t SilentModeMenu; From d0c51b9e73847d06c0b62aa5e0b451b005227878 Mon Sep 17 00:00:00 2001 From: Alex Voinea Date: Thu, 26 Mar 2020 19:06:35 +0200 Subject: [PATCH 123/158] int -> bool --- Firmware/Marlin.h | 4 ++-- Firmware/tmc2130.cpp | 2 +- Firmware/ultralcd.cpp | 2 +- 3 files changed, 4 insertions(+), 4 deletions(-) diff --git a/Firmware/Marlin.h b/Firmware/Marlin.h index d5462a6a..d04860b3 100755 --- a/Firmware/Marlin.h +++ b/Firmware/Marlin.h @@ -311,9 +311,9 @@ extern int8_t lcd_change_fil_state; extern float default_retraction; #ifdef TMC2130 -bool homeaxis(int axis, bool doError = 1, uint8_t cnt = 1, uint8_t* pstep = 0); +bool homeaxis(int axis, bool doError = true, uint8_t cnt = 1, uint8_t* pstep = 0); #else -bool homeaxis(int axis, bool doError = 1, uint8_t cnt = 1); +bool homeaxis(int axis, bool doError = true, uint8_t cnt = 1); #endif //TMC2130 diff --git a/Firmware/tmc2130.cpp b/Firmware/tmc2130.cpp index d0fcd2ee..3a4e5b51 100755 --- a/Firmware/tmc2130.cpp +++ b/Firmware/tmc2130.cpp @@ -994,7 +994,7 @@ bool tmc2130_home_calibrate(uint8_t axis) uint8_t step[16]; uint8_t cnt[16]; uint8_t val[16]; - homeaxis(axis, 1, 16, step); + homeaxis(axis, true, 16, step); bubblesort_uint8(step, 16, 0); printf_P(PSTR("sorted samples:\n")); for (uint8_t i = 0; i < 16; i++) diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index 2610d083..0fbdefc4 100755 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -7697,7 +7697,7 @@ bool lcd_selftest() set_destination_to_current(); _progress = lcd_selftest_screen(TestScreen::AxisZ, _progress, 3, true, 1500); #ifdef TMC2130 - _result = homeaxis(Z_AXIS, 0); + _result = homeaxis(Z_AXIS, false); #else _result = lcd_selfcheck_axis(Z_AXIS, Z_MAX_POS); #endif //TMC2130 From 159c1d68a6efb181adfff1998e856c8b02ee8886 Mon Sep 17 00:00:00 2001 From: 3d-gussner <3d.gussner@gmail.com> Date: Sat, 28 Mar 2020 10:40:50 +0100 Subject: [PATCH 124/158] Fix missing (hex) in D5 code --- Firmware/Dcodes.cpp | 2 +- Firmware/Marlin_main.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Firmware/Dcodes.cpp b/Firmware/Dcodes.cpp index 79695c9e..9b491a3c 100644 --- a/Firmware/Dcodes.cpp +++ b/Firmware/Dcodes.cpp @@ -372,7 +372,7 @@ void dcode_4() #### Parameters - `A` - Address (x00000-x3ffff) - `C` - Count (1-8192) - - `X` - Data + - `X` - Data (hex) - `E` - Erase #### Notes diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index e4e40cfb..d8b8957f 100755 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -8882,7 +8882,7 @@ Sigma_Exit: #### Parameters - `A` - Address (x00000-x3ffff) - `C` - Count (1-8192) - - `X` - Data + - `X` - Data (hex) - `E` - Erase #### Notes From 7179151d3f4a430c300fdcf21478fcdd2babe005 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?val=C3=A8re=20didon?= Date: Sun, 29 Mar 2020 17:26:56 +0200 Subject: [PATCH 125/158] feutre -> furtif Translation error of Stealth --- lang/lang_en_fr.txt | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/lang/lang_en_fr.txt b/lang/lang_en_fr.txt index f6add948..51ddf159 100755 --- a/lang/lang_en_fr.txt +++ b/lang/lang_en_fr.txt @@ -20,7 +20,7 @@ #MSG_CRASH_DET_STEALTH_FORCE_OFF c=20 r=4 "WARNING:\x0aCrash detection\x0adisabled in\x0aStealth mode" -"ATTENTION:\x0aDetection de crash\x0adesactivee en\x0amode feutre" +"ATTENTION:\x0aDetection de crash\x0adesactivee en\x0amode furtif" # ">Cancel" @@ -550,7 +550,7 @@ #MSG_SILENT "Silent" -"Feutre" +"Furtif" # "MMU needs user attention." From 0f9aa00eaf37a05c4ee8ff5639a29e7315892c04 Mon Sep 17 00:00:00 2001 From: 3d-gussner <3d.gussner@gmail.com> Date: Mon, 30 Mar 2020 10:36:13 +0200 Subject: [PATCH 126/158] Typo in some hex default values --- Firmware/eeprom.h | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/Firmware/eeprom.h b/Firmware/eeprom.h index 17fcf089..c1eb662e 100644 --- a/Firmware/eeprom.h +++ b/Firmware/eeprom.h @@ -225,10 +225,10 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP | ^ | ^ | ^ | fa 00h 250 | ^ | PRINTER_MK2.5 | ??? | ^ | ^ | ^ | ^ | 1a 4fh 20250 | ^ | PRINTER_MK2.5 with MMU2 | ??? | ^ | ^ | ^ | ^ | fc 00h 252 | ^ | PRINTER_MK2.5S | ??? | ^ -| ^ | ^ | ^ | 1c 4fh 20250 | ^ | PRINTER_MK2.5S with MMU2S | ??? | ^ -| ^ | ^ | ^ | 0c 12h 300 | ^ | PRINTER_MK3 | ??? | ^ +| ^ | ^ | ^ | 1c 4fh 20252 | ^ | PRINTER_MK2.5S with MMU2S | ??? | ^ +| ^ | ^ | ^ | 2c 01h 300 | ^ | PRINTER_MK3 | ??? | ^ | ^ | ^ | ^ | 4c 4fh 20300 | ^ | PRINTER_MK3 with MMU2 | ??? | ^ -| ^ | ^ | ^ | 0e 12h 302 | ^ | PRINTER_MK3S | ??? | ^ +| ^ | ^ | ^ | 2e 01h 302 | ^ | PRINTER_MK3S | ??? | ^ | ^ | ^ | ^ | 4e 4fh 20302 | ^ | PRINTER_MK3S with MMU2S | ??? | ^ | 0x0EEC 3820 | uint16 | EEPROM_BOARD_TYPE | ??? | ff ffh 65535 | Board Type | ??? | D3 Ax0eec C2 | ^ | ^ | ^ | c8 00h 200 | ^ | BOARD_RAMBO_MINI_1_0 | ??? | ^ @@ -355,7 +355,7 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP | 0x0D32 3378 | uint8 | EEPROM_BACKLIGHT_MODE | 02h 2 | ffh 255 | LCD backlight mode: __Auto__ | LCD menu | D3 Ax0d32 C1 | ^ | ^ | ^ | 01h 1 | ^ | LCD backlight mode: __Bright__ | ^ | ^ | ^ | ^ | ^ | 00h 0 | ^ | LCD backlight mode: __Dim__ | ^ | ^ -| 0x0D30 3376 | uint16 | EEPROM_BACKLIGHT_TIMEOUT | 01 00 - ff ff | ff ffh 65535 | LCD backlight timeout: __10__ seconds | LCD menu | D3 Ax0d30 C2 +| 0x0D30 3376 | uint16 | EEPROM_BACKLIGHT_TIMEOUT | 00 00 - ff ff | 0a 00h 65535 | LCD backlight timeout: __10__ seconds | LCD menu | D3 Ax0d30 C2 | 0x0D2C 3372 | float | EEPROM_UVLO_LA_K | ??? | ff ff ff ffh | Power panic saved Linear Advanced K value | ??? | D3 Ax0d2c C4 From 988ba6d8b080b9dea1892c5e8b612f037cceb368 Mon Sep 17 00:00:00 2001 From: Alex Voinea Date: Mon, 30 Mar 2020 15:37:05 +0300 Subject: [PATCH 127/158] Fix DEBUG_BUILD --- Firmware/Dcodes.cpp | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/Firmware/Dcodes.cpp b/Firmware/Dcodes.cpp index 79695c9e..cda53171 100644 --- a/Firmware/Dcodes.cpp +++ b/Firmware/Dcodes.cpp @@ -1,5 +1,6 @@ #include "Dcodes.h" //#include "Marlin.h" +#include "configuration.h" #include "language.h" #include "cmdqueue.h" #include @@ -185,7 +186,6 @@ void dcode_3() #define BOOT_APP_FLG_COPY 0x02 #define BOOT_APP_FLG_FLASH 0x04 -extern uint8_t fsensor_log; extern float current_temperature_pinda; extern float axis_steps_per_unit[NUM_AXIS]; @@ -194,6 +194,8 @@ extern float axis_steps_per_unit[NUM_AXIS]; #endif //0 #define LOG(args...) +extern uint8_t fsensor_log; + /*! * ### D-1 - Endless Loop D-1: Endless Loop From 104f81cd27feae620055a19f0f5a2f9ec8c9e8e2 Mon Sep 17 00:00:00 2001 From: Alex Voinea Date: Mon, 30 Mar 2020 15:42:30 +0300 Subject: [PATCH 128/158] Fix case sensitive include --- Firmware/Dcodes.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Firmware/Dcodes.cpp b/Firmware/Dcodes.cpp index cda53171..8a7e63e5 100644 --- a/Firmware/Dcodes.cpp +++ b/Firmware/Dcodes.cpp @@ -1,6 +1,6 @@ #include "Dcodes.h" //#include "Marlin.h" -#include "configuration.h" +#include "Configuration.h" #include "language.h" #include "cmdqueue.h" #include From f13269d8a9f9ac9eb4c4078e37f57f3eea86d838 Mon Sep 17 00:00:00 2001 From: Alex Voinea Date: Mon, 30 Mar 2020 16:50:50 +0300 Subject: [PATCH 129/158] Code cleanup --- Firmware/Dcodes.cpp | 4 ++-- Firmware/fsensor.cpp | 2 ++ Firmware/fsensor.h | 3 +++ 3 files changed, 7 insertions(+), 2 deletions(-) diff --git a/Firmware/Dcodes.cpp b/Firmware/Dcodes.cpp index 8a7e63e5..67cf1eb8 100644 --- a/Firmware/Dcodes.cpp +++ b/Firmware/Dcodes.cpp @@ -194,8 +194,6 @@ extern float axis_steps_per_unit[NUM_AXIS]; #endif //0 #define LOG(args...) -extern uint8_t fsensor_log; - /*! * ### D-1 - Endless Loop D-1: Endless Loop @@ -845,11 +843,13 @@ void dcode_9125() pat9125_y = (int)code_value(); LOG("pat9125_y=%d\n", pat9125_y); } +#ifdef DEBUG_FSENSOR_LOG if (code_seen('L')) { fsensor_log = (int)code_value(); LOG("fsensor_log=%d\n", fsensor_log); } +#endif //DEBUG_FSENSOR_LOG } #endif //PAT9125 diff --git a/Firmware/fsensor.cpp b/Firmware/fsensor.cpp index cfb378ed..219ab4f8 100755 --- a/Firmware/fsensor.cpp +++ b/Firmware/fsensor.cpp @@ -69,8 +69,10 @@ unsigned long fsensor_softfail_last = 0; uint8_t fsensor_softfail_ccnt = 0; #endif +#ifdef DEBUG_FSENSOR_LOG //! log flag: 0=log disabled, 1=log enabled uint8_t fsensor_log = 1; +#endif //DEBUG_FSENSOR_LOG //! @name filament autoload variables diff --git a/Firmware/fsensor.h b/Firmware/fsensor.h index 19f96812..4949381b 100755 --- a/Firmware/fsensor.h +++ b/Firmware/fsensor.h @@ -72,6 +72,9 @@ extern bool fsensor_oq_result(void); //! @{ extern void fsensor_st_block_chunk(int cnt); +// debugging +extern uint8_t fsensor_log; + // There's really nothing to do in block_begin: the stepper ISR likely has // called us already at the end of the last block, making this integration // redundant. LA1.5 might not always do that during a coasting move, so attempt From 9abc79d89cb9d0b7dd2adb044f44d9ef11828af3 Mon Sep 17 00:00:00 2001 From: 3d-gussner <3d.gussner@gmail.com> Date: Mon, 30 Mar 2020 16:16:07 +0200 Subject: [PATCH 130/158] EEPROM_BACKLIGHT_TIMEOUT min is 1 sec --- Firmware/eeprom.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Firmware/eeprom.h b/Firmware/eeprom.h index c1eb662e..5fdd9080 100644 --- a/Firmware/eeprom.h +++ b/Firmware/eeprom.h @@ -355,7 +355,7 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP | 0x0D32 3378 | uint8 | EEPROM_BACKLIGHT_MODE | 02h 2 | ffh 255 | LCD backlight mode: __Auto__ | LCD menu | D3 Ax0d32 C1 | ^ | ^ | ^ | 01h 1 | ^ | LCD backlight mode: __Bright__ | ^ | ^ | ^ | ^ | ^ | 00h 0 | ^ | LCD backlight mode: __Dim__ | ^ | ^ -| 0x0D30 3376 | uint16 | EEPROM_BACKLIGHT_TIMEOUT | 00 00 - ff ff | 0a 00h 65535 | LCD backlight timeout: __10__ seconds | LCD menu | D3 Ax0d30 C2 +| 0x0D30 3376 | uint16 | EEPROM_BACKLIGHT_TIMEOUT | 01 00 - ff ff | 0a 00h 65535 | LCD backlight timeout: __10__ seconds | LCD menu | D3 Ax0d30 C2 | 0x0D2C 3372 | float | EEPROM_UVLO_LA_K | ??? | ff ff ff ffh | Power panic saved Linear Advanced K value | ??? | D3 Ax0d2c C4 From aa9aa14472ae1a7b1ebacd4f356ece014761d074 Mon Sep 17 00:00:00 2001 From: 3d-gussner <3d.gussner@gmail.com> Date: Mon, 30 Mar 2020 16:24:20 +0200 Subject: [PATCH 131/158] Version to 1.0.1 --- Firmware/eeprom.h | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Firmware/eeprom.h b/Firmware/eeprom.h index 5fdd9080..3e97cac2 100644 --- a/Firmware/eeprom.h +++ b/Firmware/eeprom.h @@ -72,7 +72,7 @@ static_assert(sizeof(Sheets) == EEPROM_SHEETS_SIZEOF, "Sizeof(Sheets) is not EEP To convert hex to dec https://www.rapidtables.com/convert/number/hex-to-decimal.html - Version: 1.0 + Version: 1.0.1 --------------------------------------------------------------------------------- From 6da401be564b2621be8d4c49e3f07ec2e4b77321 Mon Sep 17 00:00:00 2001 From: 3d-gussner <3d.gussner@gmail.com> Date: Mon, 30 Mar 2020 16:53:58 +0200 Subject: [PATCH 132/158] Move few D-codes command from Marlin_main to Dcodes D80, D81 and D106 have been added to `Marlin_main.cpp` but all other D-codes moved to `Dcodes.cpp/.h` --- Firmware/Dcodes.cpp | 92 ++++++++++++++++++++++++++++++++++++++++ Firmware/Dcodes.h | 22 ++++++++-- Firmware/Marlin_main.cpp | 54 ++--------------------- 3 files changed, 113 insertions(+), 55 deletions(-) diff --git a/Firmware/Dcodes.cpp b/Firmware/Dcodes.cpp index 79695c9e..7506e7fc 100644 --- a/Firmware/Dcodes.cpp +++ b/Firmware/Dcodes.cpp @@ -635,6 +635,98 @@ void dcode_12() } +#ifdef HEATBED_ANALYSIS + /*! + ### D80 - Bed check D80: Bed check + This command will log data to SD card file "mesh.txt". + #### Usage + + D80 [ E | F | G | H | I | J ] + + #### Parameters + - `E` - Dimension X (default 40) + - `F` - Dimention Y (default 40) + - `G` - Points X (default 40) + - `H` - Points Y (default 40) + - `I` - Offset X (default 74) + - `J` - Offset Y (default 34) + */ +void dcode_80() +{ + float dimension_x = 40; + float dimension_y = 40; + int points_x = 40; + int points_y = 40; + float offset_x = 74; + float offset_y = 33; + + if (code_seen('E')) dimension_x = code_value(); + if (code_seen('F')) dimension_y = code_value(); + if (code_seen('G')) {points_x = code_value(); } + if (code_seen('H')) {points_y = code_value(); } + if (code_seen('I')) {offset_x = code_value(); } + if (code_seen('J')) {offset_y = code_value(); } + printf_P(PSTR("DIM X: %f\n"), dimension_x); + printf_P(PSTR("DIM Y: %f\n"), dimension_y); + printf_P(PSTR("POINTS X: %d\n"), points_x); + printf_P(PSTR("POINTS Y: %d\n"), points_y); + printf_P(PSTR("OFFSET X: %f\n"), offset_x); + printf_P(PSTR("OFFSET Y: %f\n"), offset_y); + bed_check(dimension_x,dimension_y,points_x,points_y,offset_x,offset_y); +} + + + /*! + ### D81 - Bed analysis D80: Bed analysis + This command will log data to SD card file "wldsd.txt". + #### Usage + + D81 [ E | F | G | H | I | J ] + + #### Parameters + - `E` - Dimension X (default 40) + - `F` - Dimention Y (default 40) + - `G` - Points X (default 40) + - `H` - Points Y (default 40) + - `I` - Offset X (default 74) + - `J` - Offset Y (default 34) + */ +void dcode_81() +{ + float dimension_x = 40; + float dimension_y = 40; + int points_x = 40; + int points_y = 40; + float offset_x = 74; + float offset_y = 33; + + if (code_seen('E')) dimension_x = code_value(); + if (code_seen('F')) dimension_y = code_value(); + if (code_seen("G")) { strchr_pointer+=1; points_x = code_value(); } + if (code_seen("H")) { strchr_pointer+=1; points_y = code_value(); } + if (code_seen("I")) { strchr_pointer+=1; offset_x = code_value(); } + if (code_seen("J")) { strchr_pointer+=1; offset_y = code_value(); } + + bed_analysis(dimension_x,dimension_y,points_x,points_y,offset_x,offset_y); + +} + +#endif //HEATBED_ANALYSIS + + /*! + ### D106 - Print measured fan speed for different pwm values D106: Print measured fan speed for different pwm values + */ +void dcode_106() +{ + for (int i = 255; i > 0; i = i - 5) { + fanSpeed = i; + //delay_keep_alive(2000); + for (int j = 0; j < 100; j++) { + delay_keep_alive(100); + } + printf_P(_N("%d: %d\n"), i, fan_speed[1]); + } +} #ifdef TMC2130 #include "planner.h" diff --git a/Firmware/Dcodes.h b/Firmware/Dcodes.h index eaf849ed..894cba52 100644 --- a/Firmware/Dcodes.h +++ b/Firmware/Dcodes.h @@ -2,26 +2,40 @@ #define DCODES_H extern void dcode__1(); //D-1 - Endless loop (to simulate deadlock) - extern void dcode_0(); //D0 - Reset extern void dcode_1(); //D1 - Clear EEPROM extern void dcode_2(); //D2 - Read/Write RAM + +#ifdef DEBUG_DCODE3 extern void dcode_3(); //D3 - Read/Write EEPROM +#endif //DEBUG_DCODE3 + extern void dcode_4(); //D4 - Read/Write PIN + +#ifdef DEBUG_DCODE5 extern void dcode_5(); //D5 - Read/Write FLASH +#endif //DEBUG_DCODE5 + extern void dcode_6(); //D6 - Read/Write external FLASH extern void dcode_7(); //D7 - Read/Write Bootloader extern void dcode_8(); //D8 - Read/Write PINDA extern void dcode_9(); //D9 - Read/Write ADC (Write=enable simulated, Read=disable simulated) - extern void dcode_10(); //D10 - XYZ calibration = OK +extern void dcode_12(); //D12 - Log time. Writes the current time in the log file. + +#ifdef HEATBED_ANALYSIS +extern void dcode_80(); //D80 - Bed check. This command will log data to SD card file "mesh.txt". +extern void dcode_81(); //D81 - Bed analysis. This command will log data to SD card file "wldsd.txt". +#endif //HEATBED_ANALYSIS + + extern void dcode_106(); //D106 - Print measured fan speed for different pwm values #ifdef TMC2130 -extern void dcode_2130(); //D2130 - TMC2130 + extern void dcode_2130(); //D2130 - TMC2130 #endif //TMC2130 #ifdef PAT9125 -extern void dcode_9125(); //D9125 - PAT9125 + extern void dcode_9125(); //D9125 - PAT9125 #endif //PAT9125 diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index e4e40cfb..c4948a20 100755 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -8976,28 +8976,7 @@ Sigma_Exit: - `J` - Offset Y (default 34) */ case 80: - { - float dimension_x = 40; - float dimension_y = 40; - int points_x = 40; - int points_y = 40; - float offset_x = 74; - float offset_y = 33; - - if (code_seen('E')) dimension_x = code_value(); - if (code_seen('F')) dimension_y = code_value(); - if (code_seen('G')) {points_x = code_value(); } - if (code_seen('H')) {points_y = code_value(); } - if (code_seen('I')) {offset_x = code_value(); } - if (code_seen('J')) {offset_y = code_value(); } - printf_P(PSTR("DIM X: %f\n"), dimension_x); - printf_P(PSTR("DIM Y: %f\n"), dimension_y); - printf_P(PSTR("POINTS X: %d\n"), points_x); - printf_P(PSTR("POINTS Y: %d\n"), points_y); - printf_P(PSTR("OFFSET X: %f\n"), offset_x); - printf_P(PSTR("OFFSET Y: %f\n"), offset_y); - bed_check(dimension_x,dimension_y,points_x,points_y,offset_x,offset_y); - }break; + dcode_80(); break; /*! ### D81 - Bed analysis D80: Bed analysis @@ -9015,24 +8994,7 @@ Sigma_Exit: - `J` - Offset Y (default 34) */ case 81: - { - float dimension_x = 40; - float dimension_y = 40; - int points_x = 40; - int points_y = 40; - float offset_x = 74; - float offset_y = 33; - - if (code_seen('E')) dimension_x = code_value(); - if (code_seen('F')) dimension_y = code_value(); - if (code_seen("G")) { strchr_pointer+=1; points_x = code_value(); } - if (code_seen("H")) { strchr_pointer+=1; points_y = code_value(); } - if (code_seen("I")) { strchr_pointer+=1; offset_x = code_value(); } - if (code_seen("J")) { strchr_pointer+=1; offset_y = code_value(); } - - bed_analysis(dimension_x,dimension_y,points_x,points_y,offset_x,offset_y); - - } break; + dcode_81(); break; #endif //HEATBED_ANALYSIS #ifdef DEBUG_DCODES @@ -9041,17 +9003,7 @@ Sigma_Exit: ### D106 - Print measured fan speed for different pwm values D106: Print measured fan speed for different pwm values */ case 106: - { - for (int i = 255; i > 0; i = i - 5) { - fanSpeed = i; - //delay_keep_alive(2000); - for (int j = 0; j < 100; j++) { - delay_keep_alive(100); - - } - printf_P(_N("%d: %d\n"), i, fan_speed[1]); - } - }break; + dcode_106(); break; #ifdef TMC2130 /*! From e48101312641776b43fe6426d7500c6a97ed04bd Mon Sep 17 00:00:00 2001 From: 3d-gussner <3d.gussner@gmail.com> Date: Mon, 30 Mar 2020 17:01:46 +0200 Subject: [PATCH 133/158] Reset all stats during Shipping prep (#2563) * Reset all stats during Shipping prep Last print stats were missing * keep old indentation Co-authored-by: D.R.racer --- Firmware/Marlin_main.cpp | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index e4e40cfb..ad5a1a85 100755 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -715,6 +715,12 @@ static void factory_reset(char level) eeprom_update_dword((uint32_t *)EEPROM_TOTALTIME, 0); eeprom_update_dword((uint32_t *)EEPROM_FILAMENTUSED, 0); + + eeprom_update_byte((uint8_t *)EEPROM_CRASH_COUNT_X, 0); + eeprom_update_byte((uint8_t *)EEPROM_CRASH_COUNT_Y, 0); + eeprom_update_byte((uint8_t *)EEPROM_FERROR_COUNT, 0); + eeprom_update_byte((uint8_t *)EEPROM_POWER_COUNT, 0); + eeprom_update_word((uint16_t *)EEPROM_CRASH_COUNT_X_TOT, 0); eeprom_update_word((uint16_t *)EEPROM_CRASH_COUNT_Y_TOT, 0); eeprom_update_word((uint16_t *)EEPROM_FERROR_COUNT_TOT, 0); From 0c383e20b3d159b02ed99e445fccc15a14f62344 Mon Sep 17 00:00:00 2001 From: vintagepc <53943260+vintagepc@users.noreply.github.com> Date: Tue, 31 Mar 2020 17:33:08 -0400 Subject: [PATCH 134/158] Pull in changes from #5 --- Firmware/ultralcd.cpp | 28 +++++++++++++++------------- 1 file changed, 15 insertions(+), 13 deletions(-) diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index c7c84d7f..9982061c 100755 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -7832,7 +7832,7 @@ bool lcd_selftest() static void reset_crash_det(unsigned char axis) { current_position[axis] += 10; - plan_buffer_line_curposXYZE(manual_feedrate[0] / 60, active_extruder); + plan_buffer_line_curposXYZE(homing_feedrate[axis] / 60, active_extruder); st_synchronize(); if (eeprom_read_byte((uint8_t*)EEPROM_CRASH_DET)) tmc2130_sg_stop_on_crash = true; } @@ -7853,17 +7853,15 @@ static bool lcd_selfcheck_axis_sg(unsigned char axis) { tmc2130_home_exit(); enable_endstops(true); - if (axis == X_AXIS) { //there is collision between cables and PSU cover in X axis if Z coordinate is too low - raise_z_above(17,true); - tmc2130_home_enter(Z_AXIS_MASK); - st_synchronize(); - tmc2130_home_exit(); - } + + raise_z_above(MESH_HOME_Z_SEARCH); + st_synchronize(); + tmc2130_home_enter(1 << axis); // first axis length measurement begin current_position[axis] -= (axis_length + margin); - plan_buffer_line_curposXYZE(manual_feedrate[0] / 60, active_extruder); + plan_buffer_line_curposXYZE(homing_feedrate[axis] / 60, active_extruder); st_synchronize(); @@ -7873,11 +7871,11 @@ static bool lcd_selfcheck_axis_sg(unsigned char axis) { current_position_init = st_get_position_mm(axis); current_position[axis] += 2 * margin; - plan_buffer_line_curposXYZE(manual_feedrate[0] / 60, active_extruder); + plan_buffer_line_curposXYZE(homing_feedrate[axis] / 60, active_extruder); st_synchronize(); current_position[axis] += axis_length; - plan_buffer_line_curposXYZE(manual_feedrate[0] / 60, active_extruder); + plan_buffer_line_curposXYZE(homing_feedrate[axis] / 60, active_extruder); st_synchronize(); @@ -7893,11 +7891,11 @@ static bool lcd_selfcheck_axis_sg(unsigned char axis) { current_position[axis] -= margin; - plan_buffer_line_curposXYZE(manual_feedrate[0] / 60, active_extruder); + plan_buffer_line_curposXYZE(homing_feedrate[axis] / 60, active_extruder); st_synchronize(); current_position[axis] -= (axis_length + margin); - plan_buffer_line_curposXYZE(manual_feedrate[0] / 60, active_extruder); + plan_buffer_line_curposXYZE(homing_feedrate[axis] / 60, active_extruder); st_synchronize(); @@ -7905,6 +7903,7 @@ static bool lcd_selfcheck_axis_sg(unsigned char axis) { measured_axis_length[1] = abs(current_position_final - current_position_init); + tmc2130_home_exit(); //end of second measurement, now check for possible errors: @@ -7923,6 +7922,8 @@ static bool lcd_selfcheck_axis_sg(unsigned char axis) { current_position[axis] = 0; plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]); reset_crash_det(axis); + enable_endstops(true); + endstops_hit_on_purpose(); return false; } } @@ -7941,12 +7942,13 @@ static bool lcd_selfcheck_axis_sg(unsigned char axis) { current_position[axis] = 0; plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]); reset_crash_det(axis); - + endstops_hit_on_purpose(); return false; } current_position[axis] = 0; plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]); reset_crash_det(axis); + endstops_hit_on_purpose(); return true; } #endif //TMC2130 From b449e248a15c07f7b790e062412209da404f0dea Mon Sep 17 00:00:00 2001 From: vintagepc <53943260+vintagepc@users.noreply.github.com> Date: Tue, 31 Mar 2020 17:48:56 -0400 Subject: [PATCH 135/158] Fix printf()s --- Firmware/ultralcd.cpp | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index 9982061c..ec67e415 100755 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -7476,21 +7476,21 @@ void lcd_belttest() uint16_t X = eeprom_read_word((uint16_t*)(EEPROM_BELTSTATUS_X)); uint16_t Y = eeprom_read_word((uint16_t*)(EEPROM_BELTSTATUS_Y)); - lcd_puts_at_P(0,0,_i("Checking X axis ")); // share message with selftest - lcd_set_cursor(0,1), lcd_printf_P(PSTR("X: %d -> ..."),X); + lcd_printf_P(_i("Checking X axis ")); // share message with selftest + lcd_set_cursor(0,1), lcd_printf_P(PSTR("X: %u -> ..."),X); KEEPALIVE_STATE(IN_HANDLER); // N.B: it doesn't make sense to handle !lcd_selfcheck...() because selftest_sg throws its own error screen // that clobbers ours, with more info than we could provide. So on fail we just fall through to take us back to status. if (lcd_selfcheck_axis_sg(X_AXIS)){ X = eeprom_read_word((uint16_t*)(EEPROM_BELTSTATUS_X)); - lcd_set_cursor(9,1), lcd_printf_P(PSTR("%d"),X); // Show new X value next to old one. + lcd_set_cursor(10,1), lcd_printf_P(PSTR("%u"),X); // Show new X value next to old one. lcd_puts_at_P(0,2,_i("Checking Y axis ")); - lcd_set_cursor(0,3), lcd_printf_P(PSTR("Y: %d -> ..."),Y); + lcd_set_cursor(0,3), lcd_printf_P(PSTR("Y: %u -> ..."),Y); if (lcd_selfcheck_axis_sg(Y_AXIS)) { Y = eeprom_read_word((uint16_t*)(EEPROM_BELTSTATUS_Y)); - lcd_set_cursor(9,3),lcd_printf_P(PSTR("%d"),Y); + lcd_set_cursor(10,3),lcd_printf_P(PSTR("%u"),Y); lcd_set_cursor(19, 3); lcd_print(LCD_STR_UPLEVEL); lcd_wait_for_click_delay(10); From b8896ad9c0dd53b8f2be5d2cf5ae80ab63511d88 Mon Sep 17 00:00:00 2001 From: Alex Voinea Date: Wed, 1 Apr 2020 12:28:39 +0300 Subject: [PATCH 136/158] First attempt for Z probe checking during selftest on the MK3/S --- Firmware/ultralcd.cpp | 26 ++++++++++++++++---------- 1 file changed, 16 insertions(+), 10 deletions(-) diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index daf9f017..08e8d567 100755 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -168,10 +168,10 @@ static void reset_crash_det(unsigned char axis); static bool lcd_selfcheck_axis_sg(unsigned char axis); static bool lcd_selfcheck_axis(int _axis, int _travel); #else -static bool lcd_selfcheck_endstops(); static bool lcd_selfcheck_axis(int _axis, int _travel); static bool lcd_selfcheck_pulleys(int axis); #endif //TMC2130 +static bool lcd_selfcheck_endstops(); static bool lcd_selfcheck_check_heater(bool _isbed); enum class TestScreen : uint_least8_t @@ -7667,11 +7667,7 @@ bool lcd_selftest() if (_result) { _progress = lcd_selftest_screen(TestScreen::FansOk, _progress, 3, true, 2000); -#ifndef TMC2130 - _result = lcd_selfcheck_endstops(); -#else - _result = true; -#endif + _result = lcd_selfcheck_endstops(); //With TMC2130, only the Z probe is tested. } if (_result) @@ -8137,31 +8133,42 @@ static bool lcd_selfcheck_pulleys(int axis) } return(true); } +#endif //not defined TMC2130 static bool lcd_selfcheck_endstops() { bool _result = true; - if (((READ(X_MIN_PIN) ^ X_MIN_ENDSTOP_INVERTING) == 1) || + if ( + #ifndef TMC2130 + ((READ(X_MIN_PIN) ^ X_MIN_ENDSTOP_INVERTING) == 1) || ((READ(Y_MIN_PIN) ^ Y_MIN_ENDSTOP_INVERTING) == 1) || + #endif //!TMC2130 ((READ(Z_MIN_PIN) ^ Z_MIN_ENDSTOP_INVERTING) == 1)) { + #ifndef TMC2130 if ((READ(X_MIN_PIN) ^ X_MIN_ENDSTOP_INVERTING) == 1) current_position[0] += 10; if ((READ(Y_MIN_PIN) ^ Y_MIN_ENDSTOP_INVERTING) == 1) current_position[1] += 10; + #endif //!TMC2130 if ((READ(Z_MIN_PIN) ^ Z_MIN_ENDSTOP_INVERTING) == 1) current_position[2] += 10; } plan_buffer_line_curposXYZE(manual_feedrate[0] / 60, active_extruder); - _delay(500); + st_synchronize(); - if (((READ(X_MIN_PIN) ^ X_MIN_ENDSTOP_INVERTING) == 1) || + if ( + #ifndef TMC2130 + ((READ(X_MIN_PIN) ^ X_MIN_ENDSTOP_INVERTING) == 1) || ((READ(Y_MIN_PIN) ^ Y_MIN_ENDSTOP_INVERTING) == 1) || + #endif //!TMC2130 ((READ(Z_MIN_PIN) ^ Z_MIN_ENDSTOP_INVERTING) == 1)) { _result = false; char _error[4] = ""; + #ifndef TMC2130 if ((READ(X_MIN_PIN) ^ X_MIN_ENDSTOP_INVERTING) == 1) strcat(_error, "X"); if ((READ(Y_MIN_PIN) ^ Y_MIN_ENDSTOP_INVERTING) == 1) strcat(_error, "Y"); + #endif //!TMC2130 if ((READ(Z_MIN_PIN) ^ Z_MIN_ENDSTOP_INVERTING) == 1) strcat(_error, "Z"); lcd_selftest_error(TestError::Endstops, _error, ""); } @@ -8169,7 +8176,6 @@ static bool lcd_selfcheck_endstops() manage_inactivity(true); return _result; } -#endif //not defined TMC2130 static bool lcd_selfcheck_check_heater(bool _isbed) { From 8b2b32c85bf04b8dc6b6333228ce069f66b761bb Mon Sep 17 00:00:00 2001 From: Alex Voinea Date: Wed, 1 Apr 2020 13:15:08 +0300 Subject: [PATCH 137/158] Raise on nozzle crash --- Firmware/Marlin_main.cpp | 24 ++++++++++++++++++------ 1 file changed, 18 insertions(+), 6 deletions(-) diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index ad5a1a85..0700514d 100755 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -2314,9 +2314,15 @@ bool homeaxis(int axis, bool doError, uint8_t cnt) #ifdef TMC2130 if (READ(Z_TMC2130_DIAG) != 0) { //Z crash FORCE_HIGH_POWER_END; - if (doError) kill(_T(MSG_BED_LEVELING_FAILED_POINT_LOW)); - current_position[axis] = -5; //assume that nozzle crashed into bed - plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]); + if (doError) + { + current_position[Z_AXIS] += MESH_HOME_Z_SEARCH; + plan_buffer_line_curposXYZE(max_feedrate[Z_AXIS], active_extruder); + st_synchronize(); + kill(_T(MSG_BED_LEVELING_FAILED_POINT_LOW)); + } + current_position[axis] = -MESH_HOME_Z_SEARCH; //assume that nozzle crashed into bed + plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]); return 0; } #endif //TMC2130 @@ -2332,9 +2338,15 @@ bool homeaxis(int axis, bool doError, uint8_t cnt) #ifdef TMC2130 if (READ(Z_TMC2130_DIAG) != 0) { //Z crash FORCE_HIGH_POWER_END; - if (doError) kill(_T(MSG_BED_LEVELING_FAILED_POINT_LOW)); - current_position[axis] = -5; //assume that nozzle crashed into bed - plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]); + if (doError) + { + current_position[Z_AXIS] += MESH_HOME_Z_SEARCH; + plan_buffer_line_curposXYZE(max_feedrate[Z_AXIS], active_extruder); + st_synchronize(); + kill(_T(MSG_BED_LEVELING_FAILED_POINT_LOW)); + } + current_position[axis] = -MESH_HOME_Z_SEARCH; //assume that nozzle crashed into bed + plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]); return 0; } #endif //TMC2130 From 792bab9bbb0ad21ab1bd36cb36c77df7e7333914 Mon Sep 17 00:00:00 2001 From: Alex Voinea Date: Wed, 1 Apr 2020 13:50:22 +0300 Subject: [PATCH 138/158] Fix go up --- Firmware/Marlin_main.cpp | 12 ++++++++---- 1 file changed, 8 insertions(+), 4 deletions(-) diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index 0700514d..0a621aab 100755 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -2316,14 +2316,16 @@ bool homeaxis(int axis, bool doError, uint8_t cnt) FORCE_HIGH_POWER_END; if (doError) { + current_position[Z_AXIS] = 0; + plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]); current_position[Z_AXIS] += MESH_HOME_Z_SEARCH; plan_buffer_line_curposXYZE(max_feedrate[Z_AXIS], active_extruder); st_synchronize(); kill(_T(MSG_BED_LEVELING_FAILED_POINT_LOW)); } - current_position[axis] = -MESH_HOME_Z_SEARCH; //assume that nozzle crashed into bed + current_position[Z_AXIS] = -MESH_HOME_Z_SEARCH; //assume that nozzle crashed into bed plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]); - return 0; + return 0; } #endif //TMC2130 current_position[axis] = 0; @@ -2340,14 +2342,16 @@ bool homeaxis(int axis, bool doError, uint8_t cnt) FORCE_HIGH_POWER_END; if (doError) { + current_position[Z_AXIS] = 0; + plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]); current_position[Z_AXIS] += MESH_HOME_Z_SEARCH; plan_buffer_line_curposXYZE(max_feedrate[Z_AXIS], active_extruder); st_synchronize(); kill(_T(MSG_BED_LEVELING_FAILED_POINT_LOW)); } - current_position[axis] = -MESH_HOME_Z_SEARCH; //assume that nozzle crashed into bed + current_position[Z_AXIS] = -MESH_HOME_Z_SEARCH; //assume that nozzle crashed into bed plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]); - return 0; + return 0; } #endif //TMC2130 axis_is_at_home(axis); From ecd409c44f37bb935c4918e7149a6fcb09ef271f Mon Sep 17 00:00:00 2001 From: 3d-gussner <3d.gussner@gmail.com> Date: Wed, 1 Apr 2020 16:24:20 +0200 Subject: [PATCH 139/158] Make ALL D-codes available for DEBUG mode until now D3 and D5 needed to be defined separately --- Firmware/Dcodes.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Firmware/Dcodes.cpp b/Firmware/Dcodes.cpp index 9b491a3c..7d3d6dce 100644 --- a/Firmware/Dcodes.cpp +++ b/Firmware/Dcodes.cpp @@ -97,7 +97,7 @@ void print_mem(uint32_t address, uint16_t count, uint8_t type, uint8_t countperl } } -#ifdef DEBUG_DCODE3 +#if defined DEBUG_DCODE3 || defined DEBUG_DCODES #define EEPROM_SIZE 0x1000 /*! ### D3 - Read/Write EEPROM D3: Read/Write EEPROM @@ -360,7 +360,7 @@ void dcode_4() } #endif //DEBUG_DCODES -#ifdef DEBUG_DCODE5 +#if defined DEBUG_DCODE5 || defined DEBUG_DCODES /*! ### D5 - Read/Write FLASH D5: Read/Write Flash From f32b6c2912d9647b9cda98c2ac859615b0ab608e Mon Sep 17 00:00:00 2001 From: 3d-gussner <3d.gussner@gmail.com> Date: Wed, 1 Apr 2020 18:56:34 +0200 Subject: [PATCH 140/158] Forgot to modify Marlin_main --- 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 0931ff57..a6becaa6 100755 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -8835,7 +8835,7 @@ Sigma_Exit: case 2: dcode_2(); break; #endif //DEBUG_DCODES -#ifdef DEBUG_DCODE3 +#if defined DEBUG_DCODE3 || defined DEBUG_DCODES /*! ### D3 - Read/Write EEPROM D3: Read/Write EEPROM @@ -8876,7 +8876,7 @@ Sigma_Exit: case 4: dcode_4(); break; #endif //DEBUG_DCODES -#ifdef DEBUG_DCODE5 +#if defined DEBUG_DCODE5 || defined DEBUG_DCODES /*! ### D5 - Read/Write FLASH D5: Read/Write Flash From fd1d05ab48c3885a0fbb5b613edaf8bbf3c05606 Mon Sep 17 00:00:00 2001 From: Alex Voinea Date: Thu, 2 Apr 2020 14:44:44 +0300 Subject: [PATCH 141/158] :recycle:Code optimization --- Firmware/Marlin.h | 4 ++-- Firmware/Marlin_main.cpp | 52 +++++++++++++++------------------------- Firmware/tmc2130.cpp | 2 +- Firmware/ultralcd.cpp | 2 +- 4 files changed, 23 insertions(+), 37 deletions(-) diff --git a/Firmware/Marlin.h b/Firmware/Marlin.h index fb70dfed..363407e2 100755 --- a/Firmware/Marlin.h +++ b/Firmware/Marlin.h @@ -310,9 +310,9 @@ extern int8_t lcd_change_fil_state; extern float default_retraction; #ifdef TMC2130 -bool homeaxis(int axis, bool doError = true, uint8_t cnt = 1, uint8_t* pstep = 0); +void homeaxis(int axis, uint8_t cnt = 1, uint8_t* pstep = 0); #else -bool homeaxis(int axis, bool doError = true, uint8_t cnt = 1); +void homeaxis(int axis, uint8_t cnt = 1); #endif //TMC2130 diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index 0a621aab..2ba941e1 100755 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -2197,9 +2197,24 @@ bool calibrate_z_auto() #endif //TMC2130 #ifdef TMC2130 -bool homeaxis(int axis, bool doError, uint8_t cnt, uint8_t* pstep) +static void check_Z_crash(void) +{ + if (READ(Z_TMC2130_DIAG) != 0) { //Z crash + FORCE_HIGH_POWER_END; + current_position[Z_AXIS] = 0; + plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]); + current_position[Z_AXIS] += MESH_HOME_Z_SEARCH; + plan_buffer_line_curposXYZE(max_feedrate[Z_AXIS], active_extruder); + st_synchronize(); + kill(_T(MSG_BED_LEVELING_FAILED_POINT_LOW)); + } +} +#endif //TMC2130 + +#ifdef TMC2130 +void homeaxis(int axis, uint8_t cnt, uint8_t* pstep) #else -bool homeaxis(int axis, bool doError, uint8_t cnt) +void homeaxis(int axis, uint8_t cnt) #endif //TMC2130 { bool endstops_enabled = enable_endstops(true); //RP: endstops should be allways enabled durring homing @@ -2312,21 +2327,7 @@ bool homeaxis(int axis, bool doError, uint8_t cnt) plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder); st_synchronize(); #ifdef TMC2130 - if (READ(Z_TMC2130_DIAG) != 0) { //Z crash - FORCE_HIGH_POWER_END; - if (doError) - { - current_position[Z_AXIS] = 0; - plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]); - current_position[Z_AXIS] += MESH_HOME_Z_SEARCH; - plan_buffer_line_curposXYZE(max_feedrate[Z_AXIS], active_extruder); - st_synchronize(); - kill(_T(MSG_BED_LEVELING_FAILED_POINT_LOW)); - } - current_position[Z_AXIS] = -MESH_HOME_Z_SEARCH; //assume that nozzle crashed into bed - plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]); - return 0; - } + check_Z_crash(); #endif //TMC2130 current_position[axis] = 0; plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]); @@ -2338,21 +2339,7 @@ bool homeaxis(int axis, bool doError, uint8_t cnt) plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder); st_synchronize(); #ifdef TMC2130 - if (READ(Z_TMC2130_DIAG) != 0) { //Z crash - FORCE_HIGH_POWER_END; - if (doError) - { - current_position[Z_AXIS] = 0; - plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]); - current_position[Z_AXIS] += MESH_HOME_Z_SEARCH; - plan_buffer_line_curposXYZE(max_feedrate[Z_AXIS], active_extruder); - st_synchronize(); - kill(_T(MSG_BED_LEVELING_FAILED_POINT_LOW)); - } - current_position[Z_AXIS] = -MESH_HOME_Z_SEARCH; //assume that nozzle crashed into bed - plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]); - return 0; - } + check_Z_crash(); #endif //TMC2130 axis_is_at_home(axis); destination[axis] = current_position[axis]; @@ -2364,7 +2351,6 @@ bool homeaxis(int axis, bool doError, uint8_t cnt) #endif } enable_endstops(endstops_enabled); - return 1; } /**/ diff --git a/Firmware/tmc2130.cpp b/Firmware/tmc2130.cpp index 3a4e5b51..108d00b1 100755 --- a/Firmware/tmc2130.cpp +++ b/Firmware/tmc2130.cpp @@ -994,7 +994,7 @@ bool tmc2130_home_calibrate(uint8_t axis) uint8_t step[16]; uint8_t cnt[16]; uint8_t val[16]; - homeaxis(axis, true, 16, step); + homeaxis(axis, 16, step); bubblesort_uint8(step, 16, 0); printf_P(PSTR("sorted samples:\n")); for (uint8_t i = 0; i < 16; i++) diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index 08e8d567..62c41072 100755 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -7734,7 +7734,7 @@ bool lcd_selftest() set_destination_to_current(); _progress = lcd_selftest_screen(TestScreen::AxisZ, _progress, 3, true, 1500); #ifdef TMC2130 - _result = homeaxis(Z_AXIS, false); + homeaxis(Z_AXIS); //In case of failure, the code gets stuck in this function. #else _result = lcd_selfcheck_axis(Z_AXIS, Z_MAX_POS); #endif //TMC2130 From a1b8ee67b32dafa74cca86dc8805606ed2522228 Mon Sep 17 00:00:00 2001 From: 3d-gussner <3d.gussner@gmail.com> Date: Thu, 2 Apr 2020 14:56:19 +0200 Subject: [PATCH 142/158] Fix missing (hex) in D5 code (#2560) * Fix missing (hex) in D5 code * Make ALL D-codes available for DEBUG mode until now D3 and D5 needed to be defined separately * Forgot to modify Marlin_main --- Firmware/Dcodes.cpp | 6 +++--- Firmware/Marlin_main.cpp | 6 +++--- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/Firmware/Dcodes.cpp b/Firmware/Dcodes.cpp index 67cf1eb8..f943b4a3 100644 --- a/Firmware/Dcodes.cpp +++ b/Firmware/Dcodes.cpp @@ -98,7 +98,7 @@ void print_mem(uint32_t address, uint16_t count, uint8_t type, uint8_t countperl } } -#ifdef DEBUG_DCODE3 +#if defined DEBUG_DCODE3 || defined DEBUG_DCODES #define EEPROM_SIZE 0x1000 /*! ### D3 - Read/Write EEPROM D3: Read/Write EEPROM @@ -360,7 +360,7 @@ void dcode_4() } #endif //DEBUG_DCODES -#ifdef DEBUG_DCODE5 +#if defined DEBUG_DCODE5 || defined DEBUG_DCODES /*! ### D5 - Read/Write FLASH D5: Read/Write Flash @@ -372,7 +372,7 @@ void dcode_4() #### Parameters - `A` - Address (x00000-x3ffff) - `C` - Count (1-8192) - - `X` - Data + - `X` - Data (hex) - `E` - Erase #### Notes diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index ad5a1a85..a6becaa6 100755 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -8835,7 +8835,7 @@ Sigma_Exit: case 2: dcode_2(); break; #endif //DEBUG_DCODES -#ifdef DEBUG_DCODE3 +#if defined DEBUG_DCODE3 || defined DEBUG_DCODES /*! ### D3 - Read/Write EEPROM D3: Read/Write EEPROM @@ -8876,7 +8876,7 @@ Sigma_Exit: case 4: dcode_4(); break; #endif //DEBUG_DCODES -#ifdef DEBUG_DCODE5 +#if defined DEBUG_DCODE5 || defined DEBUG_DCODES /*! ### D5 - Read/Write FLASH D5: Read/Write Flash @@ -8888,7 +8888,7 @@ Sigma_Exit: #### Parameters - `A` - Address (x00000-x3ffff) - `C` - Count (1-8192) - - `X` - Data + - `X` - Data (hex) - `E` - Erase #### Notes From 9b3f51008be76d86c25b3412f09fd91653a84ee3 Mon Sep 17 00:00:00 2001 From: Alex Voinea Date: Thu, 2 Apr 2020 19:32:13 +0300 Subject: [PATCH 143/158] :art:Change CRLF line ending to LF --- Firmware/heatbed_pwm.cpp | 380 +++++++++++++++++++-------------------- 1 file changed, 190 insertions(+), 190 deletions(-) diff --git a/Firmware/heatbed_pwm.cpp b/Firmware/heatbed_pwm.cpp index e8551501..4cd0bf5e 100755 --- a/Firmware/heatbed_pwm.cpp +++ b/Firmware/heatbed_pwm.cpp @@ -1,190 +1,190 @@ -#include -#include -#include "io_atmega2560.h" - -// All this is about silencing the heat bed, as it behaves like a loudspeaker. -// Basically, we want the PWM heating switched at 30Hz (or so) which is a well ballanced -// frequency for both power supply units (i.e. both PSUs are reasonably silent). -// The only trouble is the rising or falling edge of bed heating - that creates an audible click. -// This audible click may be suppressed by making the rising or falling edge NOT sharp. -// Of course, making non-sharp edges in digital technology is not easy, but there is a solution. -// It is possible to do a fast PWM sequence with duty starting from 0 to 255. -// Doing this at higher frequency than the bed "loudspeaker" can handle makes the click barely audible. -// Technically: -// timer0 is set to fast PWM mode at 62.5kHz (timer0 is linked to the bed heating pin) (zero prescaler) -// To keep the bed switching at 30Hz - we don't want the PWM running at 62kHz all the time -// since it would burn the heatbed's MOSFET: -// 16MHz/256 levels of PWM duty gives us 62.5kHz -// 62.5kHz/256 gives ~244Hz, that is still too fast - 244/8 gives ~30Hz, that's what we need -// So the automaton runs atop of inner 8 (or 16) cycles. -// The finite automaton is running in the ISR(TIMER0_OVF_vect) - -// 2019-08-14 update: the original algorithm worked very well, however there were 2 regressions: -// 1. 62kHz ISR requires considerable amount of processing power, -// USB transfer speed dropped by 20%, which was most notable when doing short G-code segments. -// 2. Some users reported TLed PSU started clicking when running at 120V/60Hz. -// This looks like the original algorithm didn't maintain base PWM 30Hz, but only 15Hz -// To address both issues, there is an improved approach based on the idea of leveraging -// different CLK prescalers in some automaton states - i.e. when holding LOW or HIGH on the output pin, -// we don't have to clock 62kHz, but we can increase the CLK prescaler for these states to 8 (or even 64). -// That shall result in the ISR not being called that much resulting in regained performance -// Theoretically this is relatively easy, however one must be very carefull handling the AVR's timer -// control registers correctly, especially setting them in a correct order. -// Some registers are double buffered, some changes are applied in next cycles etc. -// The biggest problem was with the CLK prescaler itself - this circuit is shared among almost all timers, -// we don't want to reset the prescaler counted value when transiting among automaton states. -// Resetting the prescaler would make the PWM more precise, right now there are temporal segments -// of variable period ranging from 0 to 7 62kHz ticks - that's logical, the timer must "sync" -// to the new slower CLK after setting the slower prescaler value. -// In our application, this isn't any significant problem and may be ignored. -// Doing changes in timer's registers non-correctly results in artefacts on the output pin -// - it can toggle unnoticed, which will result in bed clicking again. -// That's why there are special transition states ZERO_TO_RISE and ONE_TO_FALL, which enable the -// counter change its operation atomically and without artefacts on the output pin. -// The resulting signal on the output pin was checked with an osciloscope. -// If there are any change requirements in the future, the signal must be checked with an osciloscope again, -// ad-hoc changes may completely screw things up! - -// 2020-01-29 update: we are introducing a new option to the automaton that will allow us to force the output state -// to either full ON or OFF. This is so that interference during the MBL probing is minimal. -// To accomplish this goal we use bedPWMDisabled. It is only supposed to be used for brief periods of time as to -// not make the bed temperature too unstable. Also, careful consideration should be used when using this -// option as leaving this enabled will also keep the bed output in the state it stopped in. - -///! Definition off finite automaton states -enum class States : uint8_t { - ZERO_START = 0,///< entry point of the automaton - reads the soft_pwm_bed value for the next whole PWM cycle - ZERO, ///< steady 0 (OFF), no change for the whole period - ZERO_TO_RISE, ///< metastate allowing the timer change its state atomically without artefacts on the output pin - RISE, ///< 16 fast PWM cycles with increasing duty up to steady ON - RISE_TO_ONE, ///< metastate allowing the timer change its state atomically without artefacts on the output pin - ONE, ///< steady 1 (ON), no change for the whole period - ONE_TO_FALL, ///< metastate allowing the timer change its state atomically without artefacts on the output pin - FALL, ///< 16 fast PWM cycles with decreasing duty down to steady OFF - FALL_TO_ZERO ///< metastate allowing the timer change its state atomically without artefacts on the output pin -}; - -///! Inner states of the finite automaton -static States state = States::ZERO_START; - -bool bedPWMDisabled = 0; - -///! Fast PWM counter is used in the RISE and FALL states (62.5kHz) -static uint8_t slowCounter = 0; -///! Slow PWM counter is used in the ZERO and ONE states (62.5kHz/8 or 64) -static uint8_t fastCounter = 0; -///! PWM counter for the whole cycle - a cache for soft_pwm_bed -static uint8_t pwm = 0; - -///! The slow PWM duty for the next 30Hz cycle -///! Set in the whole firmware at various places -extern unsigned char soft_pwm_bed; - -/// fastMax - how many fast PWM steps to do in RISE and FALL states -/// 16 is a good compromise between silenced bed ("smooth" edges) -/// and not burning the switching MOSFET -static const uint8_t fastMax = 16; - -/// Scaler 16->256 for fast PWM -static const uint8_t fastShift = 4; - -/// Increment slow PWM counter by slowInc every ZERO or ONE state -/// This allows for fine-tuning the basic PWM switching frequency -/// A possible further optimization - use a 64 prescaler (instead of 8) -/// increment slowCounter by 1 -/// but use less bits of soft PWM - something like soft_pwm_bed >> 2 -/// that may further reduce the CPU cycles required by the bed heating automaton -/// Due to the nature of bed heating the reduced PID precision may not be a major issue, however doing 8x less ISR(timer0_ovf) may significantly improve the performance -static const uint8_t slowInc = 1; - -ISR(TIMER0_OVF_vect) // timer compare interrupt service routine -{ - switch(state){ - case States::ZERO_START: - if (bedPWMDisabled) return; // stay in the OFF state and do not change the output pin - pwm = soft_pwm_bed << 1;// expecting soft_pwm_bed to be 7bit! - if( pwm != 0 ){ - state = States::ZERO; // do nothing, let it tick once again after the 30Hz period - } - break; - case States::ZERO: // end of state ZERO - we'll either stay in ZERO or change to RISE - // In any case update our cache of pwm value for the next whole cycle from soft_pwm_bed - slowCounter += slowInc; // this does software timer_clk/256 or less (depends on slowInc) - if( slowCounter > pwm ){ - return; - } // otherwise moving towards RISE - state = States::ZERO_TO_RISE; // and finalize the change in a transitional state RISE0 - break; - // even though it may look like the ZERO state may be glued together with the ZERO_TO_RISE, don't do it - // the timer must tick once more in order to get rid of occasional output pin toggles. - case States::ZERO_TO_RISE: // special state for handling transition between prescalers and switching inverted->non-inverted fast-PWM without toggling the output pin. - // It must be done in consequent steps, otherwise the pin will get flipped up and down during one PWM cycle. - // Also beware of the correct sequence of the following timer control registers initialization - it really matters! - state = States::RISE; // prepare for standard RISE cycles - fastCounter = fastMax - 1;// we'll do 16-1 cycles of RISE - TCNT0 = 255; // force overflow on the next clock cycle - TCCR0B = (1 << CS00); // change prescaler to 1, i.e. 62.5kHz - TCCR0A &= ~(1 << COM0B0); // Clear OC0B on Compare Match, set OC0B at BOTTOM (non-inverting mode) - break; - case States::RISE: - OCR0B = (fastMax - fastCounter) << fastShift; - if( fastCounter ){ - --fastCounter; - } else { // end of RISE cycles, changing into state ONE - state = States::RISE_TO_ONE; - OCR0B = 255; // full duty - TCNT0 = 254; // make the timer overflow in the next cycle - // @@TODO these constants are still subject to investigation - } - break; - case States::RISE_TO_ONE: - state = States::ONE; - OCR0B = 255; // full duty - TCNT0 = 255; // make the timer overflow in the next cycle - TCCR0B = (1 << CS01); // change prescaler to 8, i.e. 7.8kHz - break; - case States::ONE: // state ONE - we'll either stay in ONE or change to FALL - OCR0B = 255; - if (bedPWMDisabled) return; // stay in the ON state and do not change the output pin - slowCounter += slowInc; // this does software timer_clk/256 or less - if( slowCounter < pwm ){ - return; - } - if( (soft_pwm_bed << 1) >= (255 - slowInc - 1) ){ //@@TODO simplify & explain - // if slowInc==2, soft_pwm == 251 will be the first to do short drops to zero. 252 will keep full heating - return; // want full duty for the next ONE cycle again - so keep on heating and just wait for the next timer ovf - } - // otherwise moving towards FALL - // @@TODO it looks like ONE_TO_FALL isn't necessary, there are no artefacts at all - state = States::ONE;//_TO_FALL; -// TCCR0B = (1 << CS00); // change prescaler to 1, i.e. 62.5kHz -// break; -// case States::ONE_TO_FALL: -// OCR0B = 255; // zero duty - state=States::FALL; - fastCounter = fastMax - 1;// we'll do 16-1 cycles of RISE - TCNT0 = 255; // force overflow on the next clock cycle - TCCR0B = (1 << CS00); // change prescaler to 1, i.e. 62.5kHz - // must switch to inverting mode already here, because it takes a whole PWM cycle and it would make a "1" at the end of this pwm cycle - // COM0B1 remains set both in inverting and non-inverting mode - TCCR0A |= (1 << COM0B0); // inverting mode - break; - case States::FALL: - OCR0B = (fastMax - fastCounter) << fastShift; // this is the same as in RISE, because now we are setting the zero part of duty due to inverting mode - //TCCR0A |= (1 << COM0B0); // already set in ONE_TO_FALL - if( fastCounter ){ - --fastCounter; - } else { // end of FALL cycles, changing into state ZERO - state = States::FALL_TO_ZERO; - TCNT0 = 128; //@@TODO again - need to wait long enough to propagate the timer state changes - OCR0B = 255; - } - break; - case States::FALL_TO_ZERO: - state = States::ZERO_START; // go to read new soft_pwm_bed value for the next cycle - TCNT0 = 128; - OCR0B = 255; - TCCR0B = (1 << CS01); // change prescaler to 8, i.e. 7.8kHz - break; - } -} +#include +#include +#include "io_atmega2560.h" + +// All this is about silencing the heat bed, as it behaves like a loudspeaker. +// Basically, we want the PWM heating switched at 30Hz (or so) which is a well ballanced +// frequency for both power supply units (i.e. both PSUs are reasonably silent). +// The only trouble is the rising or falling edge of bed heating - that creates an audible click. +// This audible click may be suppressed by making the rising or falling edge NOT sharp. +// Of course, making non-sharp edges in digital technology is not easy, but there is a solution. +// It is possible to do a fast PWM sequence with duty starting from 0 to 255. +// Doing this at higher frequency than the bed "loudspeaker" can handle makes the click barely audible. +// Technically: +// timer0 is set to fast PWM mode at 62.5kHz (timer0 is linked to the bed heating pin) (zero prescaler) +// To keep the bed switching at 30Hz - we don't want the PWM running at 62kHz all the time +// since it would burn the heatbed's MOSFET: +// 16MHz/256 levels of PWM duty gives us 62.5kHz +// 62.5kHz/256 gives ~244Hz, that is still too fast - 244/8 gives ~30Hz, that's what we need +// So the automaton runs atop of inner 8 (or 16) cycles. +// The finite automaton is running in the ISR(TIMER0_OVF_vect) + +// 2019-08-14 update: the original algorithm worked very well, however there were 2 regressions: +// 1. 62kHz ISR requires considerable amount of processing power, +// USB transfer speed dropped by 20%, which was most notable when doing short G-code segments. +// 2. Some users reported TLed PSU started clicking when running at 120V/60Hz. +// This looks like the original algorithm didn't maintain base PWM 30Hz, but only 15Hz +// To address both issues, there is an improved approach based on the idea of leveraging +// different CLK prescalers in some automaton states - i.e. when holding LOW or HIGH on the output pin, +// we don't have to clock 62kHz, but we can increase the CLK prescaler for these states to 8 (or even 64). +// That shall result in the ISR not being called that much resulting in regained performance +// Theoretically this is relatively easy, however one must be very carefull handling the AVR's timer +// control registers correctly, especially setting them in a correct order. +// Some registers are double buffered, some changes are applied in next cycles etc. +// The biggest problem was with the CLK prescaler itself - this circuit is shared among almost all timers, +// we don't want to reset the prescaler counted value when transiting among automaton states. +// Resetting the prescaler would make the PWM more precise, right now there are temporal segments +// of variable period ranging from 0 to 7 62kHz ticks - that's logical, the timer must "sync" +// to the new slower CLK after setting the slower prescaler value. +// In our application, this isn't any significant problem and may be ignored. +// Doing changes in timer's registers non-correctly results in artefacts on the output pin +// - it can toggle unnoticed, which will result in bed clicking again. +// That's why there are special transition states ZERO_TO_RISE and ONE_TO_FALL, which enable the +// counter change its operation atomically and without artefacts on the output pin. +// The resulting signal on the output pin was checked with an osciloscope. +// If there are any change requirements in the future, the signal must be checked with an osciloscope again, +// ad-hoc changes may completely screw things up! + +// 2020-01-29 update: we are introducing a new option to the automaton that will allow us to force the output state +// to either full ON or OFF. This is so that interference during the MBL probing is minimal. +// To accomplish this goal we use bedPWMDisabled. It is only supposed to be used for brief periods of time as to +// not make the bed temperature too unstable. Also, careful consideration should be used when using this +// option as leaving this enabled will also keep the bed output in the state it stopped in. + +///! Definition off finite automaton states +enum class States : uint8_t { + ZERO_START = 0,///< entry point of the automaton - reads the soft_pwm_bed value for the next whole PWM cycle + ZERO, ///< steady 0 (OFF), no change for the whole period + ZERO_TO_RISE, ///< metastate allowing the timer change its state atomically without artefacts on the output pin + RISE, ///< 16 fast PWM cycles with increasing duty up to steady ON + RISE_TO_ONE, ///< metastate allowing the timer change its state atomically without artefacts on the output pin + ONE, ///< steady 1 (ON), no change for the whole period + ONE_TO_FALL, ///< metastate allowing the timer change its state atomically without artefacts on the output pin + FALL, ///< 16 fast PWM cycles with decreasing duty down to steady OFF + FALL_TO_ZERO ///< metastate allowing the timer change its state atomically without artefacts on the output pin +}; + +///! Inner states of the finite automaton +static States state = States::ZERO_START; + +bool bedPWMDisabled = 0; + +///! Fast PWM counter is used in the RISE and FALL states (62.5kHz) +static uint8_t slowCounter = 0; +///! Slow PWM counter is used in the ZERO and ONE states (62.5kHz/8 or 64) +static uint8_t fastCounter = 0; +///! PWM counter for the whole cycle - a cache for soft_pwm_bed +static uint8_t pwm = 0; + +///! The slow PWM duty for the next 30Hz cycle +///! Set in the whole firmware at various places +extern unsigned char soft_pwm_bed; + +/// fastMax - how many fast PWM steps to do in RISE and FALL states +/// 16 is a good compromise between silenced bed ("smooth" edges) +/// and not burning the switching MOSFET +static const uint8_t fastMax = 16; + +/// Scaler 16->256 for fast PWM +static const uint8_t fastShift = 4; + +/// Increment slow PWM counter by slowInc every ZERO or ONE state +/// This allows for fine-tuning the basic PWM switching frequency +/// A possible further optimization - use a 64 prescaler (instead of 8) +/// increment slowCounter by 1 +/// but use less bits of soft PWM - something like soft_pwm_bed >> 2 +/// that may further reduce the CPU cycles required by the bed heating automaton +/// Due to the nature of bed heating the reduced PID precision may not be a major issue, however doing 8x less ISR(timer0_ovf) may significantly improve the performance +static const uint8_t slowInc = 1; + +ISR(TIMER0_OVF_vect) // timer compare interrupt service routine +{ + switch(state){ + case States::ZERO_START: + if (bedPWMDisabled) return; // stay in the OFF state and do not change the output pin + pwm = soft_pwm_bed << 1;// expecting soft_pwm_bed to be 7bit! + if( pwm != 0 ){ + state = States::ZERO; // do nothing, let it tick once again after the 30Hz period + } + break; + case States::ZERO: // end of state ZERO - we'll either stay in ZERO or change to RISE + // In any case update our cache of pwm value for the next whole cycle from soft_pwm_bed + slowCounter += slowInc; // this does software timer_clk/256 or less (depends on slowInc) + if( slowCounter > pwm ){ + return; + } // otherwise moving towards RISE + state = States::ZERO_TO_RISE; // and finalize the change in a transitional state RISE0 + break; + // even though it may look like the ZERO state may be glued together with the ZERO_TO_RISE, don't do it + // the timer must tick once more in order to get rid of occasional output pin toggles. + case States::ZERO_TO_RISE: // special state for handling transition between prescalers and switching inverted->non-inverted fast-PWM without toggling the output pin. + // It must be done in consequent steps, otherwise the pin will get flipped up and down during one PWM cycle. + // Also beware of the correct sequence of the following timer control registers initialization - it really matters! + state = States::RISE; // prepare for standard RISE cycles + fastCounter = fastMax - 1;// we'll do 16-1 cycles of RISE + TCNT0 = 255; // force overflow on the next clock cycle + TCCR0B = (1 << CS00); // change prescaler to 1, i.e. 62.5kHz + TCCR0A &= ~(1 << COM0B0); // Clear OC0B on Compare Match, set OC0B at BOTTOM (non-inverting mode) + break; + case States::RISE: + OCR0B = (fastMax - fastCounter) << fastShift; + if( fastCounter ){ + --fastCounter; + } else { // end of RISE cycles, changing into state ONE + state = States::RISE_TO_ONE; + OCR0B = 255; // full duty + TCNT0 = 254; // make the timer overflow in the next cycle + // @@TODO these constants are still subject to investigation + } + break; + case States::RISE_TO_ONE: + state = States::ONE; + OCR0B = 255; // full duty + TCNT0 = 255; // make the timer overflow in the next cycle + TCCR0B = (1 << CS01); // change prescaler to 8, i.e. 7.8kHz + break; + case States::ONE: // state ONE - we'll either stay in ONE or change to FALL + OCR0B = 255; + if (bedPWMDisabled) return; // stay in the ON state and do not change the output pin + slowCounter += slowInc; // this does software timer_clk/256 or less + if( slowCounter < pwm ){ + return; + } + if( (soft_pwm_bed << 1) >= (255 - slowInc - 1) ){ //@@TODO simplify & explain + // if slowInc==2, soft_pwm == 251 will be the first to do short drops to zero. 252 will keep full heating + return; // want full duty for the next ONE cycle again - so keep on heating and just wait for the next timer ovf + } + // otherwise moving towards FALL + // @@TODO it looks like ONE_TO_FALL isn't necessary, there are no artefacts at all + state = States::ONE;//_TO_FALL; +// TCCR0B = (1 << CS00); // change prescaler to 1, i.e. 62.5kHz +// break; +// case States::ONE_TO_FALL: +// OCR0B = 255; // zero duty + state=States::FALL; + fastCounter = fastMax - 1;// we'll do 16-1 cycles of RISE + TCNT0 = 255; // force overflow on the next clock cycle + TCCR0B = (1 << CS00); // change prescaler to 1, i.e. 62.5kHz + // must switch to inverting mode already here, because it takes a whole PWM cycle and it would make a "1" at the end of this pwm cycle + // COM0B1 remains set both in inverting and non-inverting mode + TCCR0A |= (1 << COM0B0); // inverting mode + break; + case States::FALL: + OCR0B = (fastMax - fastCounter) << fastShift; // this is the same as in RISE, because now we are setting the zero part of duty due to inverting mode + //TCCR0A |= (1 << COM0B0); // already set in ONE_TO_FALL + if( fastCounter ){ + --fastCounter; + } else { // end of FALL cycles, changing into state ZERO + state = States::FALL_TO_ZERO; + TCNT0 = 128; //@@TODO again - need to wait long enough to propagate the timer state changes + OCR0B = 255; + } + break; + case States::FALL_TO_ZERO: + state = States::ZERO_START; // go to read new soft_pwm_bed value for the next cycle + TCNT0 = 128; + OCR0B = 255; + TCCR0B = (1 << CS01); // change prescaler to 8, i.e. 7.8kHz + break; + } +} From 65a406a2f3f4131a029f385cf4e4af582a6d4396 Mon Sep 17 00:00:00 2001 From: 3d-gussner <3d.gussner@gmail.com> Date: Tue, 7 Apr 2020 11:22:48 +0200 Subject: [PATCH 144/158] Bugfix for last PR I forgot to change also the - `#ifdef DEBUG_DCODE_3` to `#if defined DEBUG_DCODE3 || defined DEBUG_DCODES` - `#ifdef DEBUG_DCODE_5` to `#if defined DEBUG_DCODE5 || defined DEBUG_DCODES` in the `Dcodes.h` file which I added to `Dcodes.cpp`. Due to this issue the "Debug" version fails during compiling. Sorry for that. --- Firmware/Dcodes.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Firmware/Dcodes.h b/Firmware/Dcodes.h index 894cba52..856d04ad 100644 --- a/Firmware/Dcodes.h +++ b/Firmware/Dcodes.h @@ -6,13 +6,13 @@ extern void dcode_0(); //D0 - Reset extern void dcode_1(); //D1 - Clear EEPROM extern void dcode_2(); //D2 - Read/Write RAM -#ifdef DEBUG_DCODE3 +#if defined DEBUG_DCODE3 || defined DEBUG_DCODES extern void dcode_3(); //D3 - Read/Write EEPROM #endif //DEBUG_DCODE3 extern void dcode_4(); //D4 - Read/Write PIN -#ifdef DEBUG_DCODE5 +#if defined DEBUG_DCODE5 || defined DEBUG_DCODES extern void dcode_5(); //D5 - Read/Write FLASH #endif //DEBUG_DCODE5 From c1d05210ff7f36b9b95df4bd947eed9f615c29cd Mon Sep 17 00:00:00 2001 From: 3d-gussner <3d.gussner@gmail.com> Date: Tue, 7 Apr 2020 11:42:09 +0200 Subject: [PATCH 145/158] Cleanup useless `break;` --- Firmware/Marlin_main.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index 8b3d4a73..95b2501c 100755 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -8901,7 +8901,6 @@ Sigma_Exit: */ case 5: dcode_5(); break; - break; #endif //DEBUG_DCODE5 #ifdef DEBUG_DCODES From 5d27f3362ae937b0ac9be520993323c116ec1991 Mon Sep 17 00:00:00 2001 From: Yuri D'Elia Date: Wed, 8 Apr 2020 22:27:57 +0200 Subject: [PATCH 146/158] Remove empty line --- Firmware/Marlin_main.cpp | 1 - 1 file changed, 1 deletion(-) diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index 8b3d4a73..6999db99 100755 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -7116,7 +7116,6 @@ Sigma_Exit: { float e = code_value(); #ifndef LA_NOCOMPAT - e = la10c_jerk(e); #endif cs.max_jerk[E_AXIS] = e; From 9ec0ac9c64324067fa220886d3d8e5a0ceb9ce27 Mon Sep 17 00:00:00 2001 From: Yuri D'Elia Date: Wed, 8 Apr 2020 22:30:39 +0200 Subject: [PATCH 147/158] Always reset e_steps between blocks If e_steps are scheduled, but not ticked, they're just lost. Only carry over the pressure state. --- Firmware/stepper.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Firmware/stepper.cpp b/Firmware/stepper.cpp index 6e0937cf..c7105da7 100644 --- a/Firmware/stepper.cpp +++ b/Firmware/stepper.cpp @@ -354,10 +354,10 @@ FORCE_INLINE void stepper_next_block() max_adv_steps = current_block->max_adv_steps; e_step_loops = current_block->advance_step_loops; } else { - e_steps = 0; e_step_loops = 1; current_adv_steps = 0; } + e_steps = 0; nextAdvanceISR = ADV_NEVER; LA_phase = -1; #endif From 919386c957eaf35ff0cca442c9e3000ccf36f2ae Mon Sep 17 00:00:00 2001 From: Yuri D'Elia Date: Wed, 8 Apr 2020 22:36:27 +0200 Subject: [PATCH 148/158] Remove several globals by using a single target pressure In the current code we initialize the LA state on-demand already at the right step, which makes keeping track of the tick position no longer necessary. Make the advance ISR almost stateless by removing the last vestiges of the original implementation and introduce a single target pressure. This will be needed later in order to trigger the LA isr inside the cruising phase. --- Firmware/stepper.cpp | 20 ++++++++------------ 1 file changed, 8 insertions(+), 12 deletions(-) diff --git a/Firmware/stepper.cpp b/Firmware/stepper.cpp index c7105da7..bc860b14 100644 --- a/Firmware/stepper.cpp +++ b/Firmware/stepper.cpp @@ -128,9 +128,7 @@ volatile signed char count_direction[NUM_AXIS] = { 1, 1, 1, 1}; static uint16_t eISR_Err; static uint16_t current_adv_steps; - static uint16_t final_adv_steps; - static uint16_t max_adv_steps; - static uint32_t LA_decelerate_after; + static uint16_t target_adv_steps; static int8_t e_steps; static uint8_t e_step_loops; @@ -349,10 +347,8 @@ FORCE_INLINE void stepper_next_block() #ifdef LIN_ADVANCE if (current_block->use_advance_lead) { - LA_decelerate_after = current_block->decelerate_after; - final_adv_steps = current_block->final_adv_steps; - max_adv_steps = current_block->max_adv_steps; e_step_loops = current_block->advance_step_loops; + target_adv_steps = current_block->max_adv_steps; } else { e_step_loops = 1; current_adv_steps = 0; @@ -827,11 +823,14 @@ FORCE_INLINE void isr() { uint16_t timer = calc_timer(step_rate, step_loops); _NEXT_ISR(timer); deceleration_time += timer; + #ifdef LIN_ADVANCE if (current_block->use_advance_lead) { la_state = ADV_DECELERATE; - if (step_events_completed.wide <= (unsigned long int)current_block->decelerate_after + step_loops) + if (step_events_completed.wide <= (unsigned long int)current_block->decelerate_after + step_loops) { + target_adv_steps = current_block->final_adv_steps; la_state |= ADV_INIT; + } } #endif } @@ -898,7 +897,7 @@ FORCE_INLINE void isr() { // Timer interrupt for E. e_steps is set in the main routine. FORCE_INLINE void advance_isr() { - if (step_events_completed.wide > LA_decelerate_after && current_adv_steps > final_adv_steps) { + if (current_adv_steps > target_adv_steps) { // decompression e_steps -= e_step_loops; if (e_steps) WRITE_NC(E0_DIR_PIN, e_steps < 0? INVERT_E0_DIR: !INVERT_E0_DIR); @@ -908,7 +907,7 @@ FORCE_INLINE void advance_isr() { current_adv_steps = 0; nextAdvanceISR = eISR_Rate; } - else if (step_events_completed.wide < LA_decelerate_after && current_adv_steps < max_adv_steps) { + else if (current_adv_steps < target_adv_steps) { // compression e_steps += e_step_loops; if (e_steps) WRITE_NC(E0_DIR_PIN, e_steps < 0? INVERT_E0_DIR: !INVERT_E0_DIR); @@ -1233,9 +1232,6 @@ void st_init() nextMainISR = 0; nextAdvanceISR = ADV_NEVER; main_Rate = ADV_NEVER; - e_steps = 0; - e_step_loops = 1; - LA_phase = -1; current_adv_steps = 0; #endif From 02a36c498cfb087fc4d1e470a7490d08a10484a5 Mon Sep 17 00:00:00 2001 From: Yuri D'Elia Date: Wed, 8 Apr 2020 22:49:48 +0200 Subject: [PATCH 149/158] Release excess pressure within cruising blocks LA assumes all the nozzle pressure is released at the end of each extrusion, which makes calculating the required pressure advance during travels and retracts not normally necessary. This is not always true in our planner, since the E axis is explicitly ignored when not in use, but also due to E-jerk allowing a non-linear jump in speed. And since the compression factor is currently tied by XYZ axes and not independently calculated, this can result in a wrong estimation of final pressure in several conditions. To avoid overburdening the planner, change the underlying assumptions about backpressure: 1) Pressure is no longer lost when LA is disabled: if a retract is followed by an unretract of the same length, the pressure will be likely maintained entirely. This also holds true during travels, as long as the retract length can overcome all the backpressure (which is the case in all but the most noodly materials) 2) Pressure is released as soon as possible during travels: we now enable LA also during travels, but under the sole condition of undoing excess pressure. We do that by checking for backpressure at the start of any segment without an acceleration phase that doesn't have any E-steps (a result which can happen due to the above). If pressure is not nominal, we run the extruder in reverse at maximum jerk as long as the segment allows us, since proper acceleration would be prohibitive at this stage. As the pressure difference resulting by the above is still _very_ low, any wipe or short travel will be able to equalize the nozzle pressure *before* extrusion is resumed, avoiding ooze. --- Firmware/planner.cpp | 17 ++++++++++------- Firmware/stepper.cpp | 19 ++++++++++++++++++- 2 files changed, 28 insertions(+), 8 deletions(-) diff --git a/Firmware/planner.cpp b/Firmware/planner.cpp index 57d7b89b..35031ab2 100644 --- a/Firmware/planner.cpp +++ b/Firmware/planner.cpp @@ -1061,14 +1061,12 @@ Having the real displacement of the head, we can calculate the total movement le /** * Use LIN_ADVANCE within this block if all these are true: * - * block->steps_e : This is a print move, because we checked for X, Y, Z steps before. * extruder_advance_K : There is an advance factor set. - * delta_mm[E_AXIS] > 0 : Extruder is running forward (e.g., for "Wipe while retracting" (Slic3r) or "Combing" (Cura) moves) + * delta_mm[E_AXIS] >= 0 : Extruding or traveling, but _not_ retracting. * |delta_mm[Z_AXIS]| < 0.5 : Z is only moved for leveling (_not_ for priming) */ - block->use_advance_lead = block->steps_e.wide - && extruder_advance_K - && delta_mm[E_AXIS] > 0 + block->use_advance_lead = extruder_advance_K + && delta_mm[E_AXIS] >= 0 && abs(delta_mm[Z_AXIS]) < 0.5; if (block->use_advance_lead) { e_D_ratio = (e - position_float[E_AXIS]) / @@ -1082,7 +1080,7 @@ Having the real displacement of the head, we can calculate the total movement le // 100mm wide lines using 3mm filament or 35mm wide lines using 1.75mm filament. if (e_D_ratio > 3.0) block->use_advance_lead = false; - else { + else if (e_D_ratio > 0) { const uint32_t max_accel_steps_per_s2 = cs.max_jerk[E_AXIS] / (extruder_advance_K * e_D_ratio) * steps_per_mm; if (block->acceleration_st > max_accel_steps_per_s2) { block->acceleration_st = max_accel_steps_per_s2; @@ -1133,9 +1131,14 @@ Having the real displacement of the head, we can calculate the total movement le block->adv_comp = extruder_advance_K * e_D_ratio * cs.axis_steps_per_unit[E_AXIS]; block->max_adv_steps = block->nominal_speed * block->adv_comp; + float advance_speed; + if (e_D_ratio > 0) + advance_speed = (extruder_advance_K * e_D_ratio * block->acceleration * cs.axis_steps_per_unit[E_AXIS]); + else + advance_speed = cs.max_jerk[E_AXIS] * cs.axis_steps_per_unit[E_AXIS]; + // to save more space we avoid another copy of calc_timer and go through slow division, but we // still need to replicate the *exact* same step grouping policy (see below) - float advance_speed = (extruder_advance_K * e_D_ratio * block->acceleration * cs.axis_steps_per_unit[E_AXIS]); if (advance_speed > MAX_STEP_FREQUENCY) advance_speed = MAX_STEP_FREQUENCY; float advance_rate = (F_CPU / 8.0) / advance_speed; if (advance_speed > 20000) { diff --git a/Firmware/stepper.cpp b/Firmware/stepper.cpp index bc860b14..de068166 100644 --- a/Firmware/stepper.cpp +++ b/Firmware/stepper.cpp @@ -351,7 +351,6 @@ FORCE_INLINE void stepper_next_block() target_adv_steps = current_block->max_adv_steps; } else { e_step_loops = 1; - current_adv_steps = 0; } e_steps = 0; nextAdvanceISR = ADV_NEVER; @@ -840,6 +839,24 @@ FORCE_INLINE void isr() { // the initial interrupt blocking. OCR1A_nominal = calc_timer(uint16_t(current_block->nominal_rate), step_loops); step_loops_nominal = step_loops; + +#ifdef LIN_ADVANCE + if(current_block->use_advance_lead) { + if(current_adv_steps < target_adv_steps) { + // after reaching cruising speed, halt compression. if we couldn't accumulate the + // required pressure in the acceleration phase due to lost ticks it's unlikely we + // could undo all of it during deceleration either + target_adv_steps = current_adv_steps; + } + else if (!nextAdvanceISR && current_adv_steps > target_adv_steps) { + // we're cruising in a block with excess backpressure and without a previous + // acceleration phase - this *cannot* happen during a regular block, but it's + // likely in result of chained a wipe move. release the pressure earlier by + // forcedly enabling LA while cruising! + la_state = ADV_INIT; + } + } +#endif } _NEXT_ISR(OCR1A_nominal); } From 207f0f27a69a00f6b3b8bdf3d3d69918d15fce6d Mon Sep 17 00:00:00 2001 From: Alex Voinea Date: Thu, 9 Apr 2020 16:33:51 +0300 Subject: [PATCH 150/158] :bug:Flip lcd_detect_IRsensor logic --- Firmware/ultralcd.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index 62c41072..8fab599f 100755 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -7563,7 +7563,7 @@ static void lcd_detect_IRsensor(){ bMenuFSDetect = true; // inhibits some code inside "manage_inactivity()" bAction = lcd_show_fullscreen_message_yes_no_and_wait_P(_i("Is the filament loaded?"), false, false); - if(!bAction){ + if(bAction){ lcd_show_fullscreen_message_and_wait_P(_i("Please unload the filament first, then repeat this action.")); return; } From 13b0e27cd76e014c7856ce8037f618242dad7e37 Mon Sep 17 00:00:00 2001 From: Yuri D'Elia Date: Thu, 9 Apr 2020 22:34:30 +0200 Subject: [PATCH 151/158] Do not overflow during LA acceleration limiting Perform the check one step earlier, avoiding 32bit overflow for very low compression factors. Fixes #2566 (although for K15 to have effect the conversion probably needs to be adjusted on the low end) --- Firmware/planner.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/Firmware/planner.cpp b/Firmware/planner.cpp index 35031ab2..1bc97de6 100644 --- a/Firmware/planner.cpp +++ b/Firmware/planner.cpp @@ -1081,9 +1081,9 @@ Having the real displacement of the head, we can calculate the total movement le if (e_D_ratio > 3.0) block->use_advance_lead = false; else if (e_D_ratio > 0) { - const uint32_t max_accel_steps_per_s2 = cs.max_jerk[E_AXIS] / (extruder_advance_K * e_D_ratio) * steps_per_mm; - if (block->acceleration_st > max_accel_steps_per_s2) { - block->acceleration_st = max_accel_steps_per_s2; + const float max_accel_per_s2 = cs.max_jerk[E_AXIS] / (extruder_advance_K * e_D_ratio); + if (cs.acceleration > max_accel_per_s2) { + block->acceleration_st = ceil(max_accel_per_s2 * steps_per_mm); #ifdef LA_DEBUG SERIAL_ECHOLNPGM("LA: Block acceleration limited due to max E-jerk"); #endif From ae4abdf11f5ae57478333f8b08e10255ecdd03d4 Mon Sep 17 00:00:00 2001 From: Yuri D'Elia Date: Sun, 12 Apr 2020 01:17:45 +0200 Subject: [PATCH 152/158] Unify LA for all trapezoid steps Handle uniformly compression & decompression at any stage of the trapezoid. Compared to before, this now enables LA compression also in the cruising step (handling the converse of a chained wipe), as well as decompression during acceleration. Both of these can happen as a result of jerk moves, but are incredibly rare. This is mostly needed to allow rapid decompression directly at the acceleration step during travels between a retraction&deretraction. We also check for the pressure level in a single place, reducing code size as well as disabling LA earlier when not needed for the rest of the block. --- Firmware/planner.cpp | 4 +++- Firmware/stepper.cpp | 54 +++++++++++++++++++++++++++----------------- 2 files changed, 36 insertions(+), 22 deletions(-) diff --git a/Firmware/planner.cpp b/Firmware/planner.cpp index 1bc97de6..0d77900e 100644 --- a/Firmware/planner.cpp +++ b/Firmware/planner.cpp @@ -1065,10 +1065,12 @@ Having the real displacement of the head, we can calculate the total movement le * delta_mm[E_AXIS] >= 0 : Extruding or traveling, but _not_ retracting. * |delta_mm[Z_AXIS]| < 0.5 : Z is only moved for leveling (_not_ for priming) */ - block->use_advance_lead = extruder_advance_K + block->use_advance_lead = extruder_advance_K > 0 && delta_mm[E_AXIS] >= 0 && abs(delta_mm[Z_AXIS]) < 0.5; if (block->use_advance_lead) { + // all extrusion moves with LA require a compression which is proportional to the + // extrusion_length to distance ratio (e/D) e_D_ratio = (e - position_float[E_AXIS]) / sqrt(sq(x - position_float[X_AXIS]) + sq(y - position_float[Y_AXIS]) diff --git a/Firmware/stepper.cpp b/Firmware/stepper.cpp index de068166..1b4c3b9a 100644 --- a/Firmware/stepper.cpp +++ b/Firmware/stepper.cpp @@ -117,8 +117,8 @@ volatile signed char count_direction[NUM_AXIS] = { 1, 1, 1, 1}; void advance_isr(); static const uint16_t ADV_NEVER = 0xFFFF; - static const uint8_t ADV_INIT = 0b01; - static const uint8_t ADV_DECELERATE = 0b10; + static const uint8_t ADV_INIT = 0b01; // initialize LA + static const uint8_t ADV_ACC_VARY = 0b10; // varying acceleration phase static uint16_t nextMainISR; static uint16_t nextAdvanceISR; @@ -130,9 +130,10 @@ volatile signed char count_direction[NUM_AXIS] = { 1, 1, 1, 1}; static uint16_t current_adv_steps; static uint16_t target_adv_steps; - static int8_t e_steps; - static uint8_t e_step_loops; - static int8_t LA_phase; + static int8_t e_steps; // scheduled e-steps during each isr loop + static uint8_t e_step_loops; // e-steps to execute at most in each isr loop + static uint8_t e_extruding; // current move is an extrusion move + static int8_t LA_phase; // LA compensation phase #define _NEXT_ISR(T) main_Rate = nextMainISR = T #else @@ -366,11 +367,17 @@ FORCE_INLINE void stepper_next_block() counter_y.lo = counter_x.lo; counter_z.lo = counter_x.lo; counter_e.lo = counter_x.lo; +#ifdef LIN_ADVANCE + e_extruding = current_block->steps_e.lo != 0; +#endif } else { counter_x.wide = -(current_block->step_event_count.wide >> 1); counter_y.wide = counter_x.wide; counter_z.wide = counter_x.wide; counter_e.wide = counter_x.wide; +#ifdef LIN_ADVANCE + e_extruding = current_block->steps_e.wide != 0; +#endif } step_events_completed.wide = 0; // Set directions. @@ -806,7 +813,7 @@ FORCE_INLINE void isr() { #ifdef LIN_ADVANCE if (current_block->use_advance_lead) { if (step_events_completed.wide <= (unsigned long int)step_loops) - la_state = ADV_INIT; + la_state = ADV_INIT | ADV_ACC_VARY; } #endif } @@ -825,10 +832,9 @@ FORCE_INLINE void isr() { #ifdef LIN_ADVANCE if (current_block->use_advance_lead) { - la_state = ADV_DECELERATE; if (step_events_completed.wide <= (unsigned long int)current_block->decelerate_after + step_loops) { target_adv_steps = current_block->final_adv_steps; - la_state |= ADV_INIT; + la_state = ADV_INIT | ADV_ACC_VARY; } } #endif @@ -842,17 +848,10 @@ FORCE_INLINE void isr() { #ifdef LIN_ADVANCE if(current_block->use_advance_lead) { - if(current_adv_steps < target_adv_steps) { - // after reaching cruising speed, halt compression. if we couldn't accumulate the - // required pressure in the acceleration phase due to lost ticks it's unlikely we - // could undo all of it during deceleration either - target_adv_steps = current_adv_steps; - } - else if (!nextAdvanceISR && current_adv_steps > target_adv_steps) { - // we're cruising in a block with excess backpressure and without a previous - // acceleration phase - this *cannot* happen during a regular block, but it's - // likely in result of chained a wipe move. release the pressure earlier by - // forcedly enabling LA while cruising! + if (!nextAdvanceISR) { + // Due to E-jerk, there can be discontinuities in pressure state where an + // acceleration or deceleration can be skipped or joined with the previous block. + // If LA was not previously active, re-check the pressure level la_state = ADV_INIT; } } @@ -865,10 +864,23 @@ FORCE_INLINE void isr() { #ifdef LIN_ADVANCE // avoid multiple instances or function calls to advance_spread - if (la_state & ADV_INIT) eISR_Err = current_block->advance_rate / 4; + if (la_state & ADV_INIT) { + if (current_adv_steps == target_adv_steps) { + // nothing to be done in this phase + la_state = 0; + } + else { + eISR_Err = current_block->advance_rate / 4; + if ((la_state & ADV_ACC_VARY) && e_extruding && (current_adv_steps > target_adv_steps)) { + // LA could reverse the direction of extrusion in this phase + LA_phase = 0; + } + } + } if (la_state & ADV_INIT || nextAdvanceISR != ADV_NEVER) { + // update timers & phase for the next iteration advance_spread(main_Rate); - if (la_state & ADV_DECELERATE) { + if (LA_phase >= 0) { if (step_loops == e_step_loops) LA_phase = (eISR_Rate > main_Rate); else { From 48c459e208ce733e95f2bfc8d99e288a8abe9d74 Mon Sep 17 00:00:00 2001 From: Yuri D'Elia Date: Sun, 12 Apr 2020 02:58:44 +0200 Subject: [PATCH 153/158] Increase the LA10->15 response --- Firmware/la10compat.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Firmware/la10compat.cpp b/Firmware/la10compat.cpp index 5b851bc3..9f0d5e5f 100644 --- a/Firmware/la10compat.cpp +++ b/Firmware/la10compat.cpp @@ -37,7 +37,7 @@ void la10c_mode_change(LA10C_MODE mode) // Approximate a LA10 value to a LA15 equivalent. static float la10c_convert(float k) { - float new_K = k * 0.004 - 0.06; + float new_K = k * 0.004 - 0.05; return (new_K < 0? 0: new_K); } From 85a4c44d83bff1253e86e2bd62be578ceabffd56 Mon Sep 17 00:00:00 2001 From: vintagepc <53943260+vintagepc@users.noreply.github.com> Date: Thu, 16 Apr 2020 07:29:59 -0400 Subject: [PATCH 154/158] revert feedrates --- Firmware/ultralcd.cpp | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index ec67e415..07c19ad5 100755 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -7832,7 +7832,7 @@ bool lcd_selftest() static void reset_crash_det(unsigned char axis) { current_position[axis] += 10; - plan_buffer_line_curposXYZE(homing_feedrate[axis] / 60, active_extruder); + plan_buffer_line_curposXYZE(manual_feedrate[0] / 60, active_extruder); st_synchronize(); if (eeprom_read_byte((uint8_t*)EEPROM_CRASH_DET)) tmc2130_sg_stop_on_crash = true; } @@ -7861,7 +7861,7 @@ static bool lcd_selfcheck_axis_sg(unsigned char axis) { // first axis length measurement begin current_position[axis] -= (axis_length + margin); - plan_buffer_line_curposXYZE(homing_feedrate[axis] / 60, active_extruder); + plan_buffer_line_curposXYZE(manual_feedrate[0] / 60, active_extruder); st_synchronize(); @@ -7871,11 +7871,11 @@ static bool lcd_selfcheck_axis_sg(unsigned char axis) { current_position_init = st_get_position_mm(axis); current_position[axis] += 2 * margin; - plan_buffer_line_curposXYZE(homing_feedrate[axis] / 60, active_extruder); + plan_buffer_line_curposXYZE(manual_feedrate[0] / 60, active_extruder); st_synchronize(); current_position[axis] += axis_length; - plan_buffer_line_curposXYZE(homing_feedrate[axis] / 60, active_extruder); + plan_buffer_line_curposXYZE(hmanual_feedrate[0] / 60, active_extruder); st_synchronize(); @@ -7891,11 +7891,11 @@ static bool lcd_selfcheck_axis_sg(unsigned char axis) { current_position[axis] -= margin; - plan_buffer_line_curposXYZE(homing_feedrate[axis] / 60, active_extruder); + plan_buffer_line_curposXYZE(manual_feedrate[0] / 60, active_extruder); st_synchronize(); current_position[axis] -= (axis_length + margin); - plan_buffer_line_curposXYZE(homing_feedrate[axis] / 60, active_extruder); + plan_buffer_line_curposXYZE(manual_feedrate[0] / 60, active_extruder); st_synchronize(); From dce453fd4a9f41c097e15cabebf1a65aba495837 Mon Sep 17 00:00:00 2001 From: vintagepc <53943260+vintagepc@users.noreply.github.com> Date: Thu, 16 Apr 2020 07:31:54 -0400 Subject: [PATCH 155/158] typo --- Firmware/ultralcd.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index 07c19ad5..ad19c66b 100755 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -7875,7 +7875,7 @@ static bool lcd_selfcheck_axis_sg(unsigned char axis) { st_synchronize(); current_position[axis] += axis_length; - plan_buffer_line_curposXYZE(hmanual_feedrate[0] / 60, active_extruder); + plan_buffer_line_curposXYZE(manual_feedrate[0] / 60, active_extruder); st_synchronize(); @@ -7891,11 +7891,11 @@ static bool lcd_selfcheck_axis_sg(unsigned char axis) { current_position[axis] -= margin; - plan_buffer_line_curposXYZE(manual_feedrate[0] / 60, active_extruder); + plan_buffer_line_curposXYZE(manual_feedrate[0] / 60, active_extruder); st_synchronize(); current_position[axis] -= (axis_length + margin); - plan_buffer_line_curposXYZE(manual_feedrate[0] / 60, active_extruder); + plan_buffer_line_curposXYZE(manual_feedrate[0] / 60, active_extruder); st_synchronize(); From 8ef87d76ef46379586f8248b1e61b0232f02d346 Mon Sep 17 00:00:00 2001 From: Alex Voinea Date: Mon, 20 Apr 2020 10:55:14 +0300 Subject: [PATCH 156/158] MK2.x: move away from endstops after lcd_selfcheck_pulleys() (#2617) * Removed duplicate #defines cleaned up display routine * Change to raise_z_above() * Better display handling * Ditch charswitch, show ... for measuring * Pull in changes from #5 * Fix printf()s * revert feedrates * typo * MK2.x: move away from endstops after lcd_selfcheck_pulleys() amend * Use absolute coordinates Co-authored-by: vintagepc <53943260+vintagepc@users.noreply.github.com> --- Firmware/ultralcd.cpp | 7 +++++-- 1 file changed, 5 insertions(+), 2 deletions(-) diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index c44e3c37..469a9ce1 100755 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -7705,8 +7705,8 @@ bool lcd_selftest() //homeaxis(X_AXIS); //homeaxis(Y_AXIS); - current_position[X_AXIS] += pgm_read_float(bed_ref_points_4); - current_position[Y_AXIS] += pgm_read_float(bed_ref_points_4+1); + current_position[X_AXIS] = pgm_read_float(bed_ref_points_4); + current_position[Y_AXIS] = pgm_read_float(bed_ref_points_4+1); #ifdef TMC2130 //current_position[X_AXIS] += 0; current_position[Y_AXIS] += 4; @@ -8099,6 +8099,9 @@ static bool lcd_selfcheck_pulleys(int axis) ((READ(Y_MIN_PIN) ^ Y_MIN_ENDSTOP_INVERTING) == 1)) { endstop_triggered = true; if (current_position_init - 1 <= current_position[axis] && current_position_init + 1 >= current_position[axis]) { + current_position[axis] += 10; + plan_buffer_line_curposXYZE(manual_feedrate[0] / 60, active_extruder); + st_synchronize(); return(true); } else { From baaa372a56c8deece078087c6e309e8507aaccd2 Mon Sep 17 00:00:00 2001 From: DRracer Date: Fri, 24 Apr 2020 19:46:54 +0200 Subject: [PATCH 157/158] Rephrase texts for fsensor detection and cleanup (#2630) * Rephrase texts for fsensor detection and cleanup * fsensor msgs only for MK3S --- Firmware/Marlin_main.cpp | 4 ++-- Firmware/fsensor.cpp | 6 +++--- Firmware/fsensor.h | 2 +- Firmware/messages.c | 6 ++++++ Firmware/messages.h | 4 ++++ Firmware/ultralcd.cpp | 26 +++++++++++++------------- Firmware/ultralcd.h | 2 +- 7 files changed, 30 insertions(+), 20 deletions(-) diff --git a/Firmware/Marlin_main.cpp b/Firmware/Marlin_main.cpp index e4e1e0b2..731ac380 100755 --- a/Firmware/Marlin_main.cpp +++ b/Firmware/Marlin_main.cpp @@ -9484,10 +9484,10 @@ static uint8_t nFSCheckCount=0; if(nFSCheckCount>FS_CHECK_COUNT) { nFSCheckCount=0; // not necessary - oFsensorPCB=ClFsensorPCB::_Rev03b; + oFsensorPCB=ClFsensorPCB::_Rev04; eeprom_update_byte((uint8_t*)EEPROM_FSENSOR_PCB,(uint8_t)oFsensorPCB); printf_IRSensorAnalogBoardChange(true); - lcd_setstatuspgm(_i("FS rev. 03b or newer")); + lcd_setstatuspgm(_i("FS v0.4 or newer")); } } else nFSCheckCount=0; diff --git a/Firmware/fsensor.cpp b/Firmware/fsensor.cpp index 219ab4f8..0acb9e28 100755 --- a/Firmware/fsensor.cpp +++ b/Firmware/fsensor.cpp @@ -201,7 +201,7 @@ void fsensor_init(void) fsensor_disable(false); // (in this case) EEPROM update is not necessary printf_P(PSTR("FSensor %S"), (fsensor_enabled?PSTR("ENABLED"):PSTR("DISABLED"))); #ifdef IR_SENSOR_ANALOG - printf_P(PSTR(" (sensor board revision: %S)\n"),(oFsensorPCB==ClFsensorPCB::_Rev03b)?PSTR("03b or newer"):PSTR("03 or older")); + printf_P(PSTR(" (sensor board revision: %S)\n"),(oFsensorPCB==ClFsensorPCB::_Rev04) ? MSG_04_OR_NEWER : MSG_03_OR_OLDER); #else //IR_SENSOR_ANALOG printf_P(PSTR("\n")); #endif //IR_SENSOR_ANALOG @@ -691,7 +691,7 @@ void fsensor_update(void) ADCSRB=nMUX2; ENABLE_TEMPERATURE_INTERRUPT(); // end of sequence for ... - if((oFsensorPCB==ClFsensorPCB::_Rev03b)&&((nADC*OVERSAMPLENR)>((int)IRsensor_Hopen_TRESHOLD))) + if((oFsensorPCB==ClFsensorPCB::_Rev04)&&((nADC*OVERSAMPLENR)>((int)IRsensor_Hopen_TRESHOLD))) { fsensor_disable(); fsensor_not_responding = true; @@ -727,7 +727,7 @@ bool bCheckResult; volt_IR_int=current_voltage_raw_IR; bCheckResult=(volt_IR_int<((int)IRsensor_Lmax_TRESHOLD))||(volt_IR_int>((int)IRsensor_Hmin_TRESHOLD)); -bCheckResult=bCheckResult&&(!((oFsensorPCB==ClFsensorPCB::_Rev03b)&&(volt_IR_int>((int)IRsensor_Hopen_TRESHOLD)))); +bCheckResult=bCheckResult&&(!((oFsensorPCB==ClFsensorPCB::_Rev04)&&(volt_IR_int>((int)IRsensor_Hopen_TRESHOLD)))); return(bCheckResult); } #endif //IR_SENSOR_ANALOG diff --git a/Firmware/fsensor.h b/Firmware/fsensor.h index 4949381b..4038d6b6 100755 --- a/Firmware/fsensor.h +++ b/Firmware/fsensor.h @@ -90,7 +90,7 @@ extern uint8_t fsensor_log; enum class ClFsensorPCB:uint_least8_t { _Old=0, - _Rev03b=1, + _Rev04=1, _Undef=EEPROM_EMPTY_VALUE }; diff --git a/Firmware/messages.c b/Firmware/messages.c index 4e229ba7..c18b7a91 100644 --- a/Firmware/messages.c +++ b/Firmware/messages.c @@ -138,6 +138,11 @@ const char MSG_TIMEOUT[] PROGMEM_I1 = ISTR("Timeout"); //// const char MSG_BRIGHT[] PROGMEM_I1 = ISTR("Bright"); //// const char MSG_DIM[] PROGMEM_I1 = ISTR("Dim"); //// const char MSG_AUTO[] PROGMEM_I1 = ISTR("Auto"); //// +#ifdef IR_SENSOR_ANALOG +// Beware - the space at the beginning is necessary since it is reused in LCD menu items which are to be with a space +const char MSG_04_OR_NEWER[] PROGMEM_I1 = ISTR(" 0.4 or newer"); +const char MSG_03_OR_OLDER[] PROGMEM_I1 = ISTR(" 0.3 or older"); +#endif //not internationalized messages const char MSG_SD_WORKDIR_FAIL[] PROGMEM_N1 = "workDir open failed"; //// @@ -170,3 +175,4 @@ const char MSG_FANCHECK_PRINT[] PROGMEM_N1 = "Err: PRINT FAN ERROR"; ////c=20 const char MSG_M112_KILL[] PROGMEM_N1 = "M112 called. Emergency Stop."; ////c=20 const char MSG_ADVANCE_K[] PROGMEM_N1 = "Advance K:"; ////c=13 const char MSG_POWERPANIC_DETECTED[] PROGMEM_N1 = "POWER PANIC DETECTED"; ////c=20 + diff --git a/Firmware/messages.h b/Firmware/messages.h index 7cc240d3..599f1d1f 100644 --- a/Firmware/messages.h +++ b/Firmware/messages.h @@ -138,6 +138,10 @@ extern const char MSG_TIMEOUT[]; extern const char MSG_BRIGHT[]; extern const char MSG_DIM[]; extern const char MSG_AUTO[]; +#ifdef IR_SENSOR_ANALOG +extern const char MSG_04_OR_NEWER[]; +extern const char MSG_03_OR_OLDER[]; +#endif //not internationalized messages extern const char MSG_BROWNOUT_RESET[]; diff --git a/Firmware/ultralcd.cpp b/Firmware/ultralcd.cpp index 469a9ce1..eeda00d1 100755 --- a/Firmware/ultralcd.cpp +++ b/Firmware/ultralcd.cpp @@ -2166,14 +2166,14 @@ static void lcd_support_menu() switch(oFsensorPCB) { case ClFsensorPCB::_Old: - MENU_ITEM_BACK_P(PSTR(" 03 or older")); + MENU_ITEM_BACK_P(MSG_03_OR_OLDER); break; - case ClFsensorPCB::_Rev03b: - MENU_ITEM_BACK_P(PSTR(" 03b or newer")); + case ClFsensorPCB::_Rev04: + MENU_ITEM_BACK_P(MSG_04_OR_NEWER); break; case ClFsensorPCB::_Undef: default: - MENU_ITEM_BACK_P(PSTR(" state unknown")); + MENU_ITEM_BACK_P(PSTR(" unknown state")); } #endif // IR_SENSOR_ANALOG @@ -7504,19 +7504,19 @@ void lcd_belttest() #ifdef IR_SENSOR_ANALOG // called also from marlin_main.cpp -void printf_IRSensorAnalogBoardChange(bool bPCBrev03b){ - printf_P(PSTR("Filament sensor board change detected: revision %S\n"), bPCBrev03b ? PSTR("03b or newer") : PSTR("03 or older")); +void printf_IRSensorAnalogBoardChange(bool bPCBrev04){ + printf_P(PSTR("Filament sensor board change detected: revision %S\n"), bPCBrev04 ? MSG_04_OR_NEWER : MSG_03_OR_OLDER); } static bool lcd_selftest_IRsensor(bool bStandalone) { bool bAction; - bool bPCBrev03b; + bool bPCBrev04; uint16_t volt_IR_int; float volt_IR; volt_IR_int=current_voltage_raw_IR; - bPCBrev03b=(volt_IR_int<((int)IRsensor_Hopen_TRESHOLD)); + bPCBrev04=(volt_IR_int<((int)IRsensor_Hopen_TRESHOLD)); volt_IR=VOLT_DIV_REF*((float)volt_IR_int/(1023*OVERSAMPLENR)); printf_P(PSTR("Measured filament sensor high level: %4.2fV\n"),volt_IR); if(volt_IR_int < ((int)IRsensor_Hmin_TRESHOLD)){ @@ -7524,7 +7524,7 @@ static bool lcd_selftest_IRsensor(bool bStandalone) lcd_selftest_error(TestError::FsensorLevel,"HIGH",""); return(false); } - lcd_show_fullscreen_message_and_wait_P(_i("Please insert filament (but not load them!) into extruder and then press the knob.")); + lcd_show_fullscreen_message_and_wait_P(_i("Insert the filament (do not load it) into the extruder and then press the knob.")); volt_IR_int=current_voltage_raw_IR; volt_IR=VOLT_DIV_REF*((float)volt_IR_int/(1023*OVERSAMPLENR)); printf_P(PSTR("Measured filament sensor low level: %4.2fV\n"),volt_IR); @@ -7533,9 +7533,9 @@ static bool lcd_selftest_IRsensor(bool bStandalone) lcd_selftest_error(TestError::FsensorLevel,"LOW",""); return(false); } - if((bPCBrev03b?1:0)!=(uint8_t)oFsensorPCB){ // safer then "(uint8_t)bPCBrev03b" - printf_IRSensorAnalogBoardChange(bPCBrev03b); - oFsensorPCB=bPCBrev03b?ClFsensorPCB::_Rev03b:ClFsensorPCB::_Old; + if((bPCBrev04?1:0)!=(uint8_t)oFsensorPCB){ // safer then "(uint8_t)bPCBrev04" + printf_IRSensorAnalogBoardChange(bPCBrev04); + oFsensorPCB=bPCBrev04?ClFsensorPCB::_Rev04:ClFsensorPCB::_Old; eeprom_update_byte((uint8_t*)EEPROM_FSENSOR_PCB,(uint8_t)oFsensorPCB); } return(true); @@ -7545,7 +7545,7 @@ static void lcd_detect_IRsensor(){ bool bAction; bMenuFSDetect = true; // inhibits some code inside "manage_inactivity()" - bAction = lcd_show_fullscreen_message_yes_no_and_wait_P(_i("Is the filament loaded?"), false, false); + bAction = lcd_show_fullscreen_message_yes_no_and_wait_P(_i("Is filament loaded?"), false, false); if(bAction){ lcd_show_fullscreen_message_and_wait_P(_i("Please unload the filament first, then repeat this action.")); return; diff --git a/Firmware/ultralcd.h b/Firmware/ultralcd.h index c183e0a5..70584d6e 100755 --- a/Firmware/ultralcd.h +++ b/Firmware/ultralcd.h @@ -142,7 +142,7 @@ extern uint8_t farm_status; #ifdef IR_SENSOR_ANALOG extern bool bMenuFSDetect; -void printf_IRSensorAnalogBoardChange(bool bPCBrev03b); +void printf_IRSensorAnalogBoardChange(bool bPCBrev04); #endif //IR_SENSOR_ANALOG extern int8_t SilentModeMenu; From 40c052f48285c5ab563dad5ff2d65c6eced28fd1 Mon Sep 17 00:00:00 2001 From: DRracer Date: Fri, 24 Apr 2020 20:02:13 +0200 Subject: [PATCH 158/158] Version changed (3.9.0-RC2 build 3398) --- Firmware/Configuration.h | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Firmware/Configuration.h b/Firmware/Configuration.h index 98923ef4..8d241bb0 100644 --- a/Firmware/Configuration.h +++ b/Firmware/Configuration.h @@ -16,8 +16,8 @@ extern uint16_t nPrinterType; extern PGM_P sPrinterName; // Firmware version -#define FW_VERSION "3.9.0-RC1" -#define FW_COMMIT_NR 3272 +#define FW_VERSION "3.9.0-RC2" +#define FW_COMMIT_NR 3398 // 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