Browse Source

overworked the serial responses. Quite difficult, since many texts are Pronterface protocol.

Bernhard Kubicek 13 years ago
parent
commit
900e0c9bf2

+ 16
- 16
Marlin/EEPROMwrite.h View File

59
   char ver2[4]=EEPROM_VERSION;
59
   char ver2[4]=EEPROM_VERSION;
60
   i=EEPROM_OFFSET;
60
   i=EEPROM_OFFSET;
61
   EEPROM_writeAnything(i,ver2); // validate data
61
   EEPROM_writeAnything(i,ver2); // validate data
62
-   ECHOLN("Settings Stored");
62
+   SERIAL_ECHOLN("Settings Stored");
63
 
63
 
64
 }
64
 }
65
 
65
 
68
   char stored_ver[4];
68
   char stored_ver[4];
69
   char ver[4]=EEPROM_VERSION;
69
   char ver[4]=EEPROM_VERSION;
70
   EEPROM_readAnything(i,stored_ver); //read stored version
70
   EEPROM_readAnything(i,stored_ver); //read stored version
71
-//  ECHOLN("Version: [" << ver << "] Stored version: [" << stored_ver << "]");
71
+//  SERIAL_ECHOLN("Version: [" << ver << "] Stored version: [" << stored_ver << "]");
72
   if ((!def)&&(strncmp(ver,stored_ver,3)==0)) {   // version number match
72
   if ((!def)&&(strncmp(ver,stored_ver,3)==0)) {   // version number match
73
       EEPROM_readAnything(i,axis_steps_per_unit);  
73
       EEPROM_readAnything(i,axis_steps_per_unit);  
74
       EEPROM_readAnything(i,max_feedrate);  
74
       EEPROM_readAnything(i,max_feedrate);  
87
       EEPROM_readAnything(i,Ki);
87
       EEPROM_readAnything(i,Ki);
88
       EEPROM_readAnything(i,Kd);
88
       EEPROM_readAnything(i,Kd);
89
 
89
 
90
-      ECHOLN("Stored settings retreived:");
90
+      SERIAL_ECHOLN("Stored settings retreived:");
91
   }
91
   }
92
   else {
92
   else {
93
     float tmp1[]=DEFAULT_AXIS_STEPS_PER_UNIT;
93
     float tmp1[]=DEFAULT_AXIS_STEPS_PER_UNIT;
105
     mintravelfeedrate=DEFAULT_MINTRAVELFEEDRATE;
105
     mintravelfeedrate=DEFAULT_MINTRAVELFEEDRATE;
106
     max_xy_jerk=DEFAULT_XYJERK;
106
     max_xy_jerk=DEFAULT_XYJERK;
107
     max_z_jerk=DEFAULT_ZJERK;
107
     max_z_jerk=DEFAULT_ZJERK;
108
-    ECHOLN("Using Default settings:");
108
+    SERIAL_ECHOLN("Using Default settings:");
109
   }
109
   }
110
-  ECHOLN("Steps per unit:");
111
-  ECHOLN("   M92 X"   <<_FLOAT(axis_steps_per_unit[0],3) << " Y" <<  _FLOAT(axis_steps_per_unit[1],3) << " Z" << _FLOAT(axis_steps_per_unit[2],3) << " E" << _FLOAT(axis_steps_per_unit[3],3));
112
-  ECHOLN("Maximum feedrates (mm/s):");
113
-  ECHOLN("   M203 X"  <<_FLOAT(max_feedrate[0]/60,2)<<" Y" << _FLOAT(max_feedrate[1]/60,2) << " Z" << _FLOAT(max_feedrate[2]/60,2) << " E" << _FLOAT(max_feedrate[3]/60,2));
114
-  ECHOLN("Maximum Acceleration (mm/s2):");
115
-  ECHOLN("   M201 X"  <<_FLOAT(max_acceleration_units_per_sq_second[0],0) << " Y" << _FLOAT(max_acceleration_units_per_sq_second[1],0) << " Z" << _FLOAT(max_acceleration_units_per_sq_second[2],0) << " E" << _FLOAT(max_acceleration_units_per_sq_second[3],0));
116
-  ECHOLN("Acceleration: S=acceleration, T=retract acceleration");
117
-  ECHOLN("   M204 S"  <<_FLOAT(acceleration,2) << " T" << _FLOAT(retract_acceleration,2));
118
-  ECHOLN("Advanced variables: S=Min feedrate (mm/s), T=Min travel feedrate (mm/s), B=minimum segment time (ms), X=maximum xY jerk (mm/s),  Z=maximum Z jerk (mm/s)");
119
-  ECHOLN("   M205 S"  <<_FLOAT(minimumfeedrate/60,2) << " T" << _FLOAT(mintravelfeedrate/60,2) << " B" << _FLOAT(minsegmenttime,2) << " X" << _FLOAT(max_xy_jerk/60,2) << " Z" << _FLOAT(max_z_jerk/60,2));
110
+  SERIAL_ECHOLN("Steps per unit:");
111
+  SERIAL_ECHOLN("   M92 X"   <<_FLOAT(axis_steps_per_unit[0],3) << " Y" <<  _FLOAT(axis_steps_per_unit[1],3) << " Z" << _FLOAT(axis_steps_per_unit[2],3) << " E" << _FLOAT(axis_steps_per_unit[3],3));
112
+  SERIAL_ECHOLN("Maximum feedrates (mm/s):");
113
+  SERIAL_ECHOLN("   M203 X"  <<_FLOAT(max_feedrate[0]/60,2)<<" Y" << _FLOAT(max_feedrate[1]/60,2) << " Z" << _FLOAT(max_feedrate[2]/60,2) << " E" << _FLOAT(max_feedrate[3]/60,2));
114
+  SERIAL_ECHOLN("Maximum Acceleration (mm/s2):");
115
+  SERIAL_ECHOLN("   M201 X"  <<_FLOAT(max_acceleration_units_per_sq_second[0],0) << " Y" << _FLOAT(max_acceleration_units_per_sq_second[1],0) << " Z" << _FLOAT(max_acceleration_units_per_sq_second[2],0) << " E" << _FLOAT(max_acceleration_units_per_sq_second[3],0));
116
+  SERIAL_ECHOLN("Acceleration: S=acceleration, T=retract acceleration");
117
+  SERIAL_ECHOLN("   M204 S"  <<_FLOAT(acceleration,2) << " T" << _FLOAT(retract_acceleration,2));
118
+  SERIAL_ECHOLN("Advanced variables: S=Min feedrate (mm/s), T=Min travel feedrate (mm/s), B=minimum segment time (ms), X=maximum xY jerk (mm/s),  Z=maximum Z jerk (mm/s)");
119
+  SERIAL_ECHOLN("   M205 S"  <<_FLOAT(minimumfeedrate/60,2) << " T" << _FLOAT(mintravelfeedrate/60,2) << " B" << _FLOAT(minsegmenttime,2) << " X" << _FLOAT(max_xy_jerk/60,2) << " Z" << _FLOAT(max_z_jerk/60,2));
120
 #ifdef PIDTEMP
120
 #ifdef PIDTEMP
121
-  ECHOLN("PID settings:");
122
-  ECHOLN("   M301 P"  << _FLOAT(Kp,3) << " I" << _FLOAT(Ki,3) << " D" << _FLOAT(Kd,3));  
121
+  SERIAL_ECHOLN("PID settings:");
122
+  SERIAL_ECHOLN("   M301 P"  << _FLOAT(Kp,3) << " I" << _FLOAT(Ki,3) << " D" << _FLOAT(Kd,3));  
123
 #endif
123
 #endif
124
   
124
   
125
 }  
125
 }  

+ 1
- 0
Marlin/Makefile View File

14
 UPLOAD_PROTOCOL = stk500v2
14
 UPLOAD_PROTOCOL = stk500v2
15
 BUILD_MCU = atmega2560
15
 BUILD_MCU = atmega2560
16
 BUILD_F_CPU = 16000000L
16
 BUILD_F_CPU = 16000000L
17
+TERM=bash
17
 
18
 
18
 # getting undefined reference to `__cxa_pure_virtual'
19
 # getting undefined reference to `__cxa_pure_virtual'
19
 #~ [http://www.arduino.cc/cgi-bin/yabb2/YaBB.pl?num=1254180518 Arduino Forum - Makefile]
20
 #~ [http://www.arduino.cc/cgi-bin/yabb2/YaBB.pl?num=1254180518 Arduino Forum - Makefile]

+ 6
- 4
Marlin/Marlin.h View File

6
 #include <WProgram.h>
6
 #include <WProgram.h>
7
 #include "fastio.h"
7
 #include "fastio.h"
8
 
8
 
9
-
10
-#define ECHO(x) Serial << "echo: " << x;
11
-#define ECHOLN(x) Serial << "echo: "<<x<<endl;
9
+#include "streaming.h"
10
+#define SERIAL_ECHO(x) Serial << "echo: " << x;
11
+#define SERIAL_ECHOLN(x) Serial << "echo: "<<x<<endl;
12
+#define SERIAL_ERROR(x) Serial << "echo: ERROR: " << x;
13
+#define SERIAL_ERRORLN(x) Serial << "echo: ERROR: " << x<<endl;
12
 
14
 
13
 void get_command();
15
 void get_command();
14
 void process_commands();
16
 void process_commands();
67
 //void plan_set_position(float x, float y, float z, float e);
69
 //void plan_set_position(float x, float y, float z, float e);
68
 //void st_wake_up();
70
 //void st_wake_up();
69
 //void st_synchronize();
71
 //void st_synchronize();
70
-void enquecommand(const char *cmd);
72
+void enquecommand(const char *cmd); //put an ascii command at the end of the current buffer.
71
 
73
 
72
 
74
 
73
 #ifndef CRITICAL_SECTION_START
75
 #ifndef CRITICAL_SECTION_START

+ 53
- 44
Marlin/Marlin.pde View File

82
 // M27  - Report SD print status
82
 // M27  - Report SD print status
83
 // M28  - Start SD write (M28 filename.g)
83
 // M28  - Start SD write (M28 filename.g)
84
 // M29  - Stop SD write
84
 // M29  - Stop SD write
85
+// M30  - Output time since last M109 or SD card start to serial
85
 // M42  - Change pin status via gcode
86
 // M42  - Change pin status via gcode
86
 // M80  - Turn on Power Supply
87
 // M80  - Turn on Power Supply
87
 // M81  - Turn off Power Supply
88
 // M81  - Turn off Power Supply
172
 int16_t n;
173
 int16_t n;
173
 unsigned long autostart_atmillis=0;
174
 unsigned long autostart_atmillis=0;
174
 
175
 
175
-void initsd(){
176
+void initsd()
177
+{
176
   sdactive = false;
178
   sdactive = false;
177
 #if SDSS >- 1
179
 #if SDSS >- 1
178
   if(root.isOpen())
180
   if(root.isOpen())
179
     root.close();
181
     root.close();
180
-  if (!card.init(SPI_FULL_SPEED,SDSS)){
182
+  if (!card.init(SPI_FULL_SPEED,SDSS))
183
+  {
181
     //if (!card.init(SPI_HALF_SPEED,SDSS))
184
     //if (!card.init(SPI_HALF_SPEED,SDSS))
182
-    Serial.println("SD init fail");
185
+    SERIAL_ECHOLN("SD init fail");
183
   }
186
   }
184
   else if (!volume.init(&card))
187
   else if (!volume.init(&card))
185
-    Serial.println("volume.init failed");
188
+  {
189
+    SERIAL_ERRORLN("volume.init failed");
190
+  }
186
   else if (!root.openRoot(&volume)) 
191
   else if (!root.openRoot(&volume)) 
187
-    Serial.println("openRoot failed");
192
+  {
193
+    SERIAL_ERRORLN("openRoot failed");
194
+  }
188
   else 
195
   else 
189
-	{
196
+  {
190
     sdactive = true;
197
     sdactive = true;
191
-		Serial.println("SD card ok");
192
-	}
198
+    SERIAL_ECHOLN("SD card ok");
199
+  }
193
 #endif //SDSS
200
 #endif //SDSS
194
 }
201
 }
195
 
202
 
214
   //Serial.println(begin);
221
   //Serial.println(begin);
215
   file.write(begin);
222
   file.write(begin);
216
   if (file.writeError){
223
   if (file.writeError){
217
-    Serial.println("error writing to file");
224
+    SERIAL_ERRORLN("error writing to file");
218
   }
225
   }
219
 }
226
 }
220
 #endif //SDSUPPORT
227
 #endif //SDSUPPORT
227
   {
234
   {
228
     //this is dangerous if a mixing of serial and this happsens
235
     //this is dangerous if a mixing of serial and this happsens
229
     strcpy(&(cmdbuffer[bufindw][0]),cmd);
236
     strcpy(&(cmdbuffer[bufindw][0]),cmd);
230
-    Serial.print("en:");Serial.println(cmdbuffer[bufindw]);
237
+    SERIAL_ECHOLN("enqueing \""<<cmdbuffer[bufindw]<<"\"");
231
     bufindw= (bufindw + 1)%BUFSIZE;
238
     bufindw= (bufindw + 1)%BUFSIZE;
232
     buflen += 1;
239
     buflen += 1;
233
   }
240
   }
237
 { 
244
 { 
238
 	
245
 	
239
   Serial.begin(BAUDRATE);
246
   Serial.begin(BAUDRATE);
240
-  ECHOLN("Marlin "<<version_string);
247
+  SERIAL_ECHOLN("Marlin "<<version_string);
241
   Serial.println("start");
248
   Serial.println("start");
242
 #if defined FANCY_LCD || defined SIMPLE_LCD
249
 #if defined FANCY_LCD || defined SIMPLE_LCD
243
   lcd_init();
250
   lcd_init();
478
       sdpos = file.curPosition();
485
       sdpos = file.curPosition();
479
       if(sdpos >= filesize){
486
       if(sdpos >= filesize){
480
         sdmode = false;
487
         sdmode = false;
481
-        Serial.println("Done printing file");
482
-				stoptime=millis();
483
-				char time[30];
484
-				unsigned long t=(stoptime-starttime)/1000;
485
-				int sec,min;
486
-				min=t/60;
487
-				sec=t%60;
488
-				sprintf(time,"%i min, %i sec",min,sec);
489
-				Serial.println(time);
490
-				LCD_MESSAGE(time);
491
-				checkautostart(true);
488
+        Serial.println("echo: Done printing file");
489
+	stoptime=millis();
490
+	char time[30];
491
+	unsigned long t=(stoptime-starttime)/1000;
492
+	int sec,min;
493
+	min=t/60;
494
+	sec=t%60;
495
+	sprintf(time,"echo: %i min, %i sec",min,sec);
496
+	Serial.println(time);
497
+	LCD_MESSAGE(time);
498
+	checkautostart(true);
492
       }
499
       }
493
       if(!serial_count) return; //if empty line
500
       if(!serial_count) return; //if empty line
494
       cmdbuffer[bufindw][serial_count] = 0; //terminate string
501
       cmdbuffer[bufindw][serial_count] = 0; //terminate string
721
     case 24: //M24 - Start SD print
728
     case 24: //M24 - Start SD print
722
       if(sdactive){
729
       if(sdactive){
723
         sdmode = true;
730
         sdmode = true;
724
-				starttime=millis();
731
+	starttime=millis();
725
       }
732
       }
726
       break;
733
       break;
727
     case 25: //M25 - Pause SD print
734
     case 25: //M25 - Pause SD print
774
       //processed in write to file routine above
781
       //processed in write to file routine above
775
       //savetosd = false;
782
       //savetosd = false;
776
       break;
783
       break;
777
-		case 30:
778
-		{
779
-			stoptime=millis();
780
-				char time[30];
781
-				unsigned long t=(stoptime-starttime)/1000;
782
-				int sec,min;
783
-				min=t/60;
784
-				sec=t%60;
785
-				sprintf(time,"%i min, %i sec",min,sec);
786
-				Serial.println(time);
787
-				LCD_MESSAGE(time);
788
-                }
789
-                                break;
784
+    case 30: //M30 take time since the start of the SD print or an M109 command
785
+    {
786
+      stoptime=millis();
787
+      char time[30];
788
+      unsigned long t=(stoptime-starttime)/1000;
789
+      int sec,min;
790
+      min=t/60;
791
+      sec=t%60;
792
+      sprintf(time,"echo: time needed %i min, %i sec",min,sec);
793
+      Serial.println(time);
794
+      LCD_MESSAGE(time);
795
+    }
796
+    break;
790
 #endif //SDSUPPORT
797
 #endif //SDSUPPORT
791
       case 42: //M42 -Change pin status via gcode
798
       case 42: //M42 -Change pin status via gcode
792
         if (code_seen('S'))
799
         if (code_seen('S'))
847
             Serial.println();
854
             Serial.println();
848
           #endif
855
           #endif
849
         #else
856
         #else
850
-          Serial.println("No thermistors - no temp");
857
+          Serial.println("echo: No thermistors - no temp");
851
         #endif
858
         #endif
852
         return;
859
         return;
853
         //break;
860
         //break;
888
               }
895
               }
889
               #endif //TEMP_RESIDENCY_TIME
896
               #endif //TEMP_RESIDENCY_TIME
890
             }
897
             }
891
-            LCD_MESSAGE("Marlin ready.");
898
+            LCD_MESSAGE("Heating done.");
899
+	    starttime=millis();
892
           }
900
           }
893
           break;
901
           break;
894
       case 190: // M190 - Wait bed for heater to reach target.
902
       case 190: // M190 - Wait bed for heater to reach target.
1063
       if(code_seen('P')) Kp = code_value();
1071
       if(code_seen('P')) Kp = code_value();
1064
       if(code_seen('I')) Ki = code_value()*PID_dT;
1072
       if(code_seen('I')) Ki = code_value()*PID_dT;
1065
       if(code_seen('D')) Kd = code_value()/PID_dT;
1073
       if(code_seen('D')) Kd = code_value()/PID_dT;
1066
-//      ECHOLN("Kp "<<_FLOAT(Kp,2));
1067
-//      ECHOLN("Ki "<<_FLOAT(Ki/PID_dT,2));
1068
-//      ECHOLN("Kd "<<_FLOAT(Kd*PID_dT,2));
1074
+//      SERIAL_ECHOLN("Kp "<<_FLOAT(Kp,2));
1075
+//      SERIAL_ECHOLN("Ki "<<_FLOAT(Ki/PID_dT,2));
1076
+//      SERIAL_ECHOLN("Kd "<<_FLOAT(Kd*PID_dT,2));
1069
 
1077
 
1070
 //      temp_iState_min = 0.0;
1078
 //      temp_iState_min = 0.0;
1071
 //      if (Ki!=0) {
1079
 //      if (Ki!=0) {
1093
     }
1101
     }
1094
   }
1102
   }
1095
   else{
1103
   else{
1096
-    Serial.println("Unknown command:");
1097
-    Serial.println(cmdbuffer[bufindr]);
1104
+    Serial.print("echo: Unknown command:\"");
1105
+    Serial.print(cmdbuffer[bufindr]);
1106
+    Serial.println("\"");
1098
   }
1107
   }
1099
 
1108
 
1100
   ClearToSend();
1109
   ClearToSend();
1288
   disable_e();
1297
   disable_e();
1289
   
1298
   
1290
   if(PS_ON_PIN > -1) pinMode(PS_ON_PIN,INPUT);
1299
   if(PS_ON_PIN > -1) pinMode(PS_ON_PIN,INPUT);
1291
-  Serial.println("!! Printer halted. kill() called !!");
1300
+  SERIAL_ERRORLN("Printer halted. kill() called !!");
1292
   while(1); // Wait for reset
1301
   while(1); // Wait for reset
1293
 }
1302
 }
1294
 
1303
 

+ 1
- 1
Marlin/motion_control.cpp View File

35
 {      
35
 {      
36
 //   int acceleration_manager_was_enabled = plan_is_acceleration_manager_enabled();
36
 //   int acceleration_manager_was_enabled = plan_is_acceleration_manager_enabled();
37
 //   plan_set_acceleration_manager_enabled(false); // disable acceleration management for the duration of the arc
37
 //   plan_set_acceleration_manager_enabled(false); // disable acceleration management for the duration of the arc
38
-  Serial.println("mc_arc");
38
+  SERIAL_ECHOLN("mc_arc.");
39
   float center_axis0 = position[axis_0] + offset[axis_0];
39
   float center_axis0 = position[axis_0] + offset[axis_0];
40
   float center_axis1 = position[axis_1] + offset[axis_1];
40
   float center_axis1 = position[axis_1] + offset[axis_1];
41
   float linear_travel = target[axis_linear] - position[axis_linear];
41
   float linear_travel = target[axis_linear] - position[axis_linear];

+ 1
- 1
Marlin/stepper.cpp View File

211
 // It pops blocks from the block_buffer and executes them by pulsing the stepper pins appropriately. 
211
 // It pops blocks from the block_buffer and executes them by pulsing the stepper pins appropriately. 
212
 ISR(TIMER1_COMPA_vect)
212
 ISR(TIMER1_COMPA_vect)
213
 {        
213
 {        
214
-  if(busy){ Serial.print(*(unsigned short *)OCR1A); Serial.println(" BUSY");
214
+  if(busy){ SERIAL_ERRORLN(*(unsigned short *)OCR1A<< " ISR overtaking itself.");
215
     return; 
215
     return; 
216
   } // The busy-flag is used to avoid reentering this interrupt
216
   } // The busy-flag is used to avoid reentering this interrupt
217
 
217
 

+ 9
- 18
Marlin/temperature.cpp View File

142
     }
142
     }
143
 #endif //PID_OPENLOOP
143
 #endif //PID_OPENLOOP
144
 #ifdef PID_DEBUG
144
 #ifdef PID_DEBUG
145
-     Serial.print(" Input ");
146
-     Serial.print(pid_input);
147
-     Serial.print(" Output ");
148
-     Serial.print(pid_output);    
149
-     Serial.print(" pTerm ");
150
-     Serial.print(pTerm); 
151
-     Serial.print(" iTerm ");
152
-     Serial.print(iTerm); 
153
-     Serial.print(" dTerm ");
154
-     Serial.print(dTerm); 
155
-     Serial.println();
145
+     SERIAL_ECHOLN(" PIDDEBUG Input "<<pid_input<<" Output "<<pid_output" pTerm "<<pTerm<<" iTerm "<<iTerm<<" dTerm "<<dTerm); 
146
+     
156
 #endif //PID_DEBUG
147
 #endif //PID_DEBUG
157
     analogWrite(HEATER_0_PIN, pid_output);
148
     analogWrite(HEATER_0_PIN, pid_output);
158
 #endif //PIDTEMP
149
 #endif //PIDTEMP
452
             temp_count++;
443
             temp_count++;
453
             break;
444
             break;
454
     default:
445
     default:
455
-            Serial.println("!! Temp measurement error !!");
446
+            SERIAL_ERRORLN("Temp measurement error!");
456
             break;
447
             break;
457
   }
448
   }
458
     
449
     
486
     if(current_raw[TEMPSENSOR_HOTEND_0] >= maxttemp_0) {
477
     if(current_raw[TEMPSENSOR_HOTEND_0] >= maxttemp_0) {
487
       target_raw[TEMPSENSOR_HOTEND_0] = 0;
478
       target_raw[TEMPSENSOR_HOTEND_0] = 0;
488
       analogWrite(HEATER_0_PIN, 0);
479
       analogWrite(HEATER_0_PIN, 0);
489
-      Serial.println("!! Temperature extruder 0 switched off. MAXTEMP triggered !!");
480
+      SERIAL_ERRORLN("Temperature extruder 0 switched off. MAXTEMP triggered !!");
490
       kill();
481
       kill();
491
     }
482
     }
492
   #endif
483
   #endif
497
       target_raw[TEMPSENSOR_HOTEND_1] = 0;
488
       target_raw[TEMPSENSOR_HOTEND_1] = 0;
498
     if(current_raw[2] >= maxttemp_1) {
489
     if(current_raw[2] >= maxttemp_1) {
499
       analogWrite(HEATER_2_PIN, 0);
490
       analogWrite(HEATER_2_PIN, 0);
500
-      Serial.println("!! Temperature extruder 1 switched off. MAXTEMP triggered !!");
491
+      SERIAL_ERRORLN("Temperature extruder 1 switched off. MAXTEMP triggered !!");
501
       kill()
492
       kill()
502
     }
493
     }
503
   #endif
494
   #endif
507
     if(current_raw[TEMPSENSOR_HOTEND_0] <= minttemp_0) {
498
     if(current_raw[TEMPSENSOR_HOTEND_0] <= minttemp_0) {
508
       target_raw[TEMPSENSOR_HOTEND_0] = 0;
499
       target_raw[TEMPSENSOR_HOTEND_0] = 0;
509
       analogWrite(HEATER_0_PIN, 0);
500
       analogWrite(HEATER_0_PIN, 0);
510
-      Serial.println("!! Temperature extruder 0 switched off. MINTEMP triggered !!");
501
+      SERIAL_ERRORLN("Temperature extruder 0 switched off. MINTEMP triggered !!");
511
       kill();
502
       kill();
512
     }
503
     }
513
   #endif
504
   #endif
517
     if(current_raw[TEMPSENSOR_HOTEND_1] <= minttemp_1) {
508
     if(current_raw[TEMPSENSOR_HOTEND_1] <= minttemp_1) {
518
       target_raw[TEMPSENSOR_HOTEND_1] = 0;
509
       target_raw[TEMPSENSOR_HOTEND_1] = 0;
519
       analogWrite(HEATER_2_PIN, 0);
510
       analogWrite(HEATER_2_PIN, 0);
520
-      Serial.println("!! Temperature extruder 1 switched off. MINTEMP triggered !!");
511
+      SERIAL_ERRORLN("Temperature extruder 1 switched off. MINTEMP triggered !!");
521
       kill();
512
       kill();
522
     }
513
     }
523
   #endif
514
   #endif
527
     if(current_raw[1] <= bed_minttemp) {
518
     if(current_raw[1] <= bed_minttemp) {
528
       target_raw[1] = 0;
519
       target_raw[1] = 0;
529
       WRITE(HEATER_1_PIN, 0);
520
       WRITE(HEATER_1_PIN, 0);
530
-      Serial.println("!! Temperatur heated bed switched off. MINTEMP triggered !!");
521
+      SERIAL_ERRORLN("Temperatur heated bed switched off. MINTEMP triggered !!");
531
       kill();
522
       kill();
532
     }
523
     }
533
   #endif
524
   #endif
537
     if(current_raw[1] >= bed_maxttemp) {
528
     if(current_raw[1] >= bed_maxttemp) {
538
       target_raw[1] = 0;
529
       target_raw[1] = 0;
539
       WRITE(HEATER_1_PIN, 0);
530
       WRITE(HEATER_1_PIN, 0);
540
-      Serial.println("!! Temperature heated bed switched off. MAXTEMP triggered !!");
531
+      SERIAL_ERRORLN("Temperature heated bed switched off. MAXTEMP triggered !!");
541
       kill();
532
       kill();
542
     }
533
     }
543
   #endif
534
   #endif

+ 2
- 2
Marlin/ultralcd.pde View File

1382
       }break;
1382
       }break;
1383
 #endif
1383
 #endif
1384
       default: 
1384
       default: 
1385
-        Serial.println('NEVER say never');
1385
+        SERIAL_ERRORLN("Something is wrong in the MenuStructure.");
1386
       break;
1386
       break;
1387
     }
1387
     }
1388
   }
1388
   }
1414
   {
1414
   {
1415
     force_lcd_update=true;
1415
     force_lcd_update=true;
1416
     oldcardstatus=CARDINSERTED;
1416
     oldcardstatus=CARDINSERTED;
1417
-    //Serial.println("SD CHANGE");
1417
+    //Serial.println("echo: SD CHANGE");
1418
     if(CARDINSERTED)
1418
     if(CARDINSERTED)
1419
     {
1419
     {
1420
       initsd();
1420
       initsd();

+ 1
- 1
Marlin/watchdog.pde View File

15
  
15
  
16
     #ifdef RESET_MANUAL
16
     #ifdef RESET_MANUAL
17
       LCD_MESSAGE("Please Reset!");
17
       LCD_MESSAGE("Please Reset!");
18
-      ECHOLN("echo_: Something is wrong, please turn off the printer.");
18
+      SERIAL_ERRORLN("Something is wrong, please turn off the printer.");
19
     #else
19
     #else
20
       LCD_MESSAGE("Timeout, resetting!");
20
       LCD_MESSAGE("Timeout, resetting!");
21
     #endif 
21
     #endif 

Loading…
Cancel
Save