瀏覽代碼

Fan kick improvement - long pulse (800ms) when starting, short pulse (50ms) every 4s when speed < 25.
Debug macros, debug codes (D0 - reset, D1 - clear eeprom, D2 - get/set pin).

Robert Pelnar 7 年之前
父節點
當前提交
ba636f175c

+ 9 - 1
Firmware/Configuration.h

@@ -171,6 +171,10 @@
 //if PREVENT_DANGEROUS_EXTRUDE is on, you can still disable (uncomment) very long bits of extrusion separately.
 #define PREVENT_LENGTHY_EXTRUDE
 
+#ifdef DEBUG_DISABLE_PREVENT_EXTRUDER
+#undef PREVENT_DANGEROUS_EXTRUDE
+#undef PREVENT_LENGTHY_EXTRUDE
+#endif //DEBUG_DISABLE_PREVENT_EXTRUDER
 
 #define EXTRUDE_MAXLENGTH (X_MAX_LENGTH+Y_MAX_LENGTH) //prevent extrusion of very large distances.
 
@@ -280,9 +284,13 @@ const bool Z_MAX_ENDSTOP_INVERTING = true; // set to true to invert the logic of
 #define Y_HOME_DIR -1
 #define Z_HOME_DIR -1
 
+#ifdef DEBUG_DISABLE_SWLIMITS
+#define min_software_endstops false
+#define max_software_endstops false
+#else
 #define min_software_endstops true // If true, axis won't move to coordinates less than HOME_POS.
 #define max_software_endstops true  // If true, axis won't move to coordinates greater than the defined lengths below.
-
+#endif //DEBUG_DISABLE_SWLIMITS
 
 
 #define X_MAX_LENGTH (X_MAX_POS - X_MIN_POS)

+ 5 - 1
Firmware/Configuration_adv.h

@@ -68,7 +68,11 @@
 // When first starting the main fan, run it at full speed for the
 // given number of milliseconds.  This gets the fan spinning reliably
 // before setting a PWM value. (Does not work with software PWM for fan on Sanguinololu)
-#define FAN_KICKSTART_TIME 1000
+// RP: new implementation - long pulse at 100% when starting, short pulse  
+#define FAN_KICK_START_TIME 800  //when starting from zero (long kick time)
+#define FAN_KICK_RUN_MINPWM 25   //PWM treshold for short kicks
+#define FAN_KICK_IDLE_TIME  4000 //delay between short kicks
+#define FAN_KICK_RUN_TIME   50   //short kick time
 
 
 

+ 61 - 1
Firmware/Marlin_main.cpp

@@ -55,6 +55,7 @@
 #include "math.h"
 #include "util.h"
 
+#include <avr/wdt.h>
 
 #ifdef BLINKM
 #include "BlinkM.h"
@@ -1190,6 +1191,7 @@ void setup()
 		eeprom_write_byte((uint8_t*)EEPROM_CALIBRATION_STATUS_PINDA, 0);
 	}
 
+#ifndef DEBUG_DISABLE_STARTMSGS
 	check_babystep(); //checking if Z babystep is in allowed range
 	
   if (calibration_status() == CALIBRATION_STATUS_ASSEMBLED ||
@@ -1216,6 +1218,7 @@ void setup()
 	  lcd_show_fullscreen_message_and_wait_P(MSG_DEFAULT_SETTINGS_LOADED);
   }
   
+#endif //DEBUG_DISABLE_STARTMSGS
   lcd_update_enable(true);
 
   // Store the currently running firmware into an eeprom,
@@ -5652,6 +5655,60 @@ case 404:  //M404 Enter the nominal filament width (3mm, 1.75mm ) N<3.0> or disp
 	  }
   } // end if(code_seen('T')) (end of T codes)
 
+#ifdef DEBUG_DCODES
+  else if (code_seen('D')) // D codes (debug)
+  {
+    switch((int)code_value_uint8())
+    {
+	case 0: // D0 - Reset
+		if (*(strchr_pointer + 1) == 0) break;
+		MYSERIAL.println("D0 - Reset");
+		asm volatile("jmp 0x00000");
+		break;
+	case 1: // D1 - Clear EEPROM
+		{
+			MYSERIAL.println("D1 - Clear EEPROM");
+			cli();
+			for (int i = 0; i < 4096; i++)
+				eeprom_write_byte((unsigned char*)i, (unsigned char)0);
+			sei();
+		}
+		break;
+	case 2: // D2 - Read/Write PIN
+		{
+			if (code_seen('P')) // Pin (0-255)
+			{
+				int pin = (int)code_value();
+				if ((pin >= 0) && (pin <= 255))
+				{
+					if (code_seen('F')) // Function in/out (0/1)
+					{
+						int fnc = (int)code_value();
+						if (fnc == 0) pinMode(pin, INPUT);
+						else if (fnc == 1) pinMode(pin, OUTPUT);
+					}
+					if (code_seen('V')) // Value (0/1)
+					{
+						int val = (int)code_value();
+						if (val == 0) digitalWrite(pin, LOW);
+						else if (val == 1) digitalWrite(pin, HIGH);
+					}
+					else
+					{
+						int val = (digitalRead(pin) != LOW)?1:0;
+						MYSERIAL.print("PIN");
+						MYSERIAL.print(pin);
+						MYSERIAL.print("=");
+						MYSERIAL.println(val);
+					}
+				}
+			}
+		}
+		break;
+	}
+  }
+#endif //DEBUG_DCODES
+
   else
   {
     SERIAL_ECHO_START;
@@ -5725,6 +5782,9 @@ void get_arc_coordinates()
 
 void clamp_to_software_endstops(float target[3])
 {
+#ifdef DEBUG_DISABLE_SWLIMITS
+	return;
+#endif //DEBUG_DISABLE_SWLIMITS
     world2machine_clamp(target[0], target[1]);
 
     // Clamp the Z coordinate.
@@ -6664,4 +6724,4 @@ void serialecho_temperatures() {
 	SERIAL_PROTOCOLPGM(" B:");
 	SERIAL_PROTOCOL_F(degBed(), 1);
 	SERIAL_PROTOCOLLN("");
-}
+}

+ 47 - 19
Firmware/planner.cpp

@@ -506,25 +506,53 @@ void check_axes_activity()
     disable_e2(); 
   }
 #if defined(FAN_PIN) && FAN_PIN > -1
-  #ifdef FAN_KICKSTART_TIME
-    static unsigned long fan_kick_end;
-    if (tail_fan_speed) {
-      if (fan_kick_end == 0) {
-        // Just starting up fan - run at full power.
-        fan_kick_end = millis() + FAN_KICKSTART_TIME;
-        tail_fan_speed = 255;
-      } else if (fan_kick_end > millis())
-        // Fan still spinning up.
-        tail_fan_speed = 255;
-    } else {
-      fan_kick_end = 0;
-    }
-  #endif//FAN_KICKSTART_TIME
-  #ifdef FAN_SOFT_PWM
-  fanSpeedSoftPwm = tail_fan_speed;
-  #else
-  analogWrite(FAN_PIN,tail_fan_speed);
-  #endif//!FAN_SOFT_PWM
+#ifdef FAN_KICK_START_TIME
+	static bool fan_kick = false;
+	static unsigned long fan_kick_timer = 0;
+	static unsigned char prev_fan_speed = 0;
+	if (tail_fan_speed)
+	{
+		if (prev_fan_speed != tail_fan_speed)
+		{ //speed changed
+			if (prev_fan_speed == 0) //prev speed == 0 (starting - long kick)
+				fan_kick_timer = millis() + FAN_KICK_START_TIME;
+			else if (tail_fan_speed <= FAN_KICK_RUN_MINPWM) //speed <= max kick speed (short kick)
+				fan_kick_timer = millis() + FAN_KICK_RUN_TIME;
+			else //speed > max kick speed (no kick)
+				fan_kick_timer = 0;
+			prev_fan_speed = tail_fan_speed; //store previous value
+			if (fan_kick_timer)
+				fan_kick = true;
+		}
+		else
+		{
+			if (fan_kick)
+			{
+				if (fan_kick_timer < millis())
+				{
+					fan_kick = false;
+					if (tail_fan_speed <= FAN_KICK_RUN_MINPWM)
+						fan_kick_timer = millis() + FAN_KICK_IDLE_TIME;
+				}
+			}
+			else if (tail_fan_speed <= FAN_KICK_RUN_MINPWM)
+			{
+				if (fan_kick_timer < millis())
+				{
+					fan_kick_timer = millis() + FAN_KICK_RUN_TIME;
+					fan_kick = true;
+				}
+			}
+		}
+		if (fan_kick)
+			tail_fan_speed = 255;
+	}
+#endif//FAN_KICKSTART_TIME
+#ifdef FAN_SOFT_PWM
+	fanSpeedSoftPwm = tail_fan_speed;
+#else
+	analogWrite(FAN_PIN,tail_fan_speed);
+#endif//!FAN_SOFT_PWM
 #endif//FAN_PIN > -1
 #ifdef AUTOTEMP
   getHighESpeed();

+ 7 - 7
Firmware/stepper.cpp

@@ -418,7 +418,7 @@ void isr() {
       CHECK_ENDSTOPS
       {
         {
-          #if defined(X_MIN_PIN) && X_MIN_PIN > -1
+          #if defined(X_MIN_PIN) && (X_MIN_PIN > -1) && !defined(DEBUG_DISABLE_XMINLIMIT)
             bool x_min_endstop=(READ(X_MIN_PIN) != X_MIN_ENDSTOP_INVERTING);
             if(x_min_endstop && old_x_min_endstop && (current_block->steps_x > 0)) {
               endstops_trigsteps[X_AXIS] = count_position[X_AXIS];
@@ -434,7 +434,7 @@ void isr() {
       CHECK_ENDSTOPS
       {
         {
-          #if defined(X_MAX_PIN) && X_MAX_PIN > -1
+          #if defined(X_MAX_PIN) && (X_MAX_PIN > -1) && !defined(DEBUG_DISABLE_XMAXLIMIT)
             bool x_max_endstop=(READ(X_MAX_PIN) != X_MAX_ENDSTOP_INVERTING);
             if(x_max_endstop && old_x_max_endstop && (current_block->steps_x > 0)){
               endstops_trigsteps[X_AXIS] = count_position[X_AXIS];
@@ -454,7 +454,7 @@ void isr() {
     #endif
       CHECK_ENDSTOPS
       {
-        #if defined(Y_MIN_PIN) && Y_MIN_PIN > -1
+        #if defined(Y_MIN_PIN) && (Y_MIN_PIN > -1) && !defined(DEBUG_DISABLE_YMINLIMIT)
           bool y_min_endstop=(READ(Y_MIN_PIN) != Y_MIN_ENDSTOP_INVERTING);
           if(y_min_endstop && old_y_min_endstop && (current_block->steps_y > 0)) {
             endstops_trigsteps[Y_AXIS] = count_position[Y_AXIS];
@@ -468,7 +468,7 @@ void isr() {
     else { // +direction
       CHECK_ENDSTOPS
       {
-        #if defined(Y_MAX_PIN) && Y_MAX_PIN > -1
+        #if defined(Y_MAX_PIN) && (Y_MAX_PIN > -1) && !defined(DEBUG_DISABLE_YMAXLIMIT)
           bool y_max_endstop=(READ(Y_MAX_PIN) != Y_MAX_ENDSTOP_INVERTING);
           if(y_max_endstop && old_y_max_endstop && (current_block->steps_y > 0)){
             endstops_trigsteps[Y_AXIS] = count_position[Y_AXIS];
@@ -490,7 +490,7 @@ void isr() {
       count_direction[Z_AXIS]=-1;
       if(check_endstops && ! check_z_endstop)
       {
-        #if defined(Z_MIN_PIN) && Z_MIN_PIN > -1
+        #if defined(Z_MIN_PIN) && (Z_MIN_PIN > -1) && !defined(DEBUG_DISABLE_ZMINLIMIT)
           bool z_min_endstop=(READ(Z_MIN_PIN) != Z_MIN_ENDSTOP_INVERTING);
           if(z_min_endstop && old_z_min_endstop && (current_block->steps_z > 0)) {
             endstops_trigsteps[Z_AXIS] = count_position[Z_AXIS];
@@ -511,7 +511,7 @@ void isr() {
       count_direction[Z_AXIS]=1;
       CHECK_ENDSTOPS
       {
-        #if defined(Z_MAX_PIN) && Z_MAX_PIN > -1
+        #if defined(Z_MAX_PIN) && (Z_MAX_PIN > -1) && !defined(DEBUG_DISABLE_ZMAXLIMIT)
           bool z_max_endstop=(READ(Z_MAX_PIN) != Z_MAX_ENDSTOP_INVERTING);
           if(z_max_endstop && old_z_max_endstop && (current_block->steps_z > 0)) {
             endstops_trigsteps[Z_AXIS] = count_position[Z_AXIS];
@@ -524,7 +524,7 @@ void isr() {
     }
 
     // Supporting stopping on a trigger of the Z-stop induction sensor, not only for the Z-minus movements.
-    #if defined(Z_MIN_PIN) && Z_MIN_PIN > -1
+    #if defined(Z_MIN_PIN) && (Z_MIN_PIN > -1) && !defined(DEBUG_DISABLE_ZMINLIMIT)
     if(check_z_endstop) {
         // Check the Z min end-stop no matter what.
         // Good for searching for the center of an induction target.

+ 6 - 0
Firmware/temperature.cpp

@@ -1303,6 +1303,9 @@ void max_temp_error(uint8_t e) {
 }
 
 void min_temp_error(uint8_t e) {
+#ifdef DEBUG_DISABLE_MINTEMP
+	return;
+#endif
   disable_heater();
   if(IsStopped() == false) {
     SERIAL_ERROR_START;
@@ -1333,6 +1336,9 @@ void bed_max_temp_error(void) {
 }
 
 void bed_min_temp_error(void) {
+#ifdef DEBUG_DISABLE_MINTEMP
+	return;
+#endif
 #if HEATER_BED_PIN > -1
     WRITE(HEATER_BED_PIN, 0);
 #endif

+ 8 - 7
Firmware/ultralcd.cpp

@@ -2043,8 +2043,9 @@ void lcd_diag_show_end_stops()
 
 
 void prusa_statistics(int _message, uint8_t _fil_nr) {
-	
-
+#ifdef DEBUG_DISABLE_PRUSA_STATISTICS
+	return;
+#endif //DEBUG_DISABLE_PRUSA_STATISTICS
 	switch (_message)
 	{
 
@@ -2630,7 +2631,7 @@ static void lcd_calibration_menu()
   if (!isPrintPaused)
   {
     MENU_ITEM(function, MSG_SELFTEST, lcd_selftest);
-#ifdef MK1BP
+#ifdef MK1BP
     // MK1
     // "Calibrate Z"
     MENU_ITEM(gcode, MSG_HOMEYZ, PSTR("G28 Z"));
@@ -2648,14 +2649,14 @@ MENU_ITEM(function, MSG_CALIBRATE_BED, lcd_mesh_calibration);
 #endif //MK1BP
     MENU_ITEM(gcode, MSG_AUTO_HOME, PSTR("G28 W"));
     MENU_ITEM(submenu, MSG_BED_CORRECTION_MENU, lcd_adjust_bed);
-#ifndef MK1BP
+#ifndef MK1BP
 	MENU_ITEM(submenu, MSG_CALIBRATION_PINDA_MENU, lcd_pinda_calibration_menu);
-#endif //MK1BP
+#endif //MK1BP
 	MENU_ITEM(submenu, MSG_PID_EXTRUDER, pid_extruder);
     MENU_ITEM(submenu, MSG_SHOW_END_STOPS, menu_show_end_stops);
-#ifndef MK1BP
+#ifndef MK1BP
     MENU_ITEM(gcode, MSG_CALIBRATE_BED_RESET, PSTR("M44"));
-#endif //MK1BP
+#endif //MK1BP
 #ifndef SNMM
 	//MENU_ITEM(function, MSG_RESET_CALIBRATE_E, lcd_extr_cal_reset);
 #endif

+ 5 - 1
Firmware/ultralcd_implementation_hitachi_HD44780.h

@@ -804,7 +804,11 @@ static void lcd_implementation_status_screen()
     lcd_printPGM(PSTR("  "));
 
 
-    //Print status line
+#ifdef DEBUG_DISABLE_LCD_STATUS_LINE
+	return;
+#endif //DEBUG_DISABLE_LCD_STATUS_LINE
+
+	//Print status line
     lcd.setCursor(0, 3);
 
     // If heating in progress, set flag