Browse Source

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

Bernhard Kubicek 13 years ago
parent
commit
900e0c9bf2
9 changed files with 90 additions and 87 deletions
  1. 16
    16
      Marlin/EEPROMwrite.h
  2. 1
    0
      Marlin/Makefile
  3. 6
    4
      Marlin/Marlin.h
  4. 53
    44
      Marlin/Marlin.pde
  5. 1
    1
      Marlin/motion_control.cpp
  6. 1
    1
      Marlin/stepper.cpp
  7. 9
    18
      Marlin/temperature.cpp
  8. 2
    2
      Marlin/ultralcd.pde
  9. 1
    1
      Marlin/watchdog.pde

+ 16
- 16
Marlin/EEPROMwrite.h View File

@@ -59,7 +59,7 @@ void StoreSettings() {
59 59
   char ver2[4]=EEPROM_VERSION;
60 60
   i=EEPROM_OFFSET;
61 61
   EEPROM_writeAnything(i,ver2); // validate data
62
-   ECHOLN("Settings Stored");
62
+   SERIAL_ECHOLN("Settings Stored");
63 63
 
64 64
 }
65 65
 
@@ -68,7 +68,7 @@ void RetrieveSettings(bool def=false){  // if def=true, the default values will
68 68
   char stored_ver[4];
69 69
   char ver[4]=EEPROM_VERSION;
70 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 72
   if ((!def)&&(strncmp(ver,stored_ver,3)==0)) {   // version number match
73 73
       EEPROM_readAnything(i,axis_steps_per_unit);  
74 74
       EEPROM_readAnything(i,max_feedrate);  
@@ -87,7 +87,7 @@ void RetrieveSettings(bool def=false){  // if def=true, the default values will
87 87
       EEPROM_readAnything(i,Ki);
88 88
       EEPROM_readAnything(i,Kd);
89 89
 
90
-      ECHOLN("Stored settings retreived:");
90
+      SERIAL_ECHOLN("Stored settings retreived:");
91 91
   }
92 92
   else {
93 93
     float tmp1[]=DEFAULT_AXIS_STEPS_PER_UNIT;
@@ -105,21 +105,21 @@ void RetrieveSettings(bool def=false){  // if def=true, the default values will
105 105
     mintravelfeedrate=DEFAULT_MINTRAVELFEEDRATE;
106 106
     max_xy_jerk=DEFAULT_XYJERK;
107 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 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 123
 #endif
124 124
   
125 125
 }  

+ 1
- 0
Marlin/Makefile View File

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

+ 6
- 4
Marlin/Marlin.h View File

@@ -6,9 +6,11 @@
6 6
 #include <WProgram.h>
7 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 15
 void get_command();
14 16
 void process_commands();
@@ -67,7 +69,7 @@ void kill();
67 69
 //void plan_set_position(float x, float y, float z, float e);
68 70
 //void st_wake_up();
69 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 75
 #ifndef CRITICAL_SECTION_START

+ 53
- 44
Marlin/Marlin.pde View File

@@ -82,6 +82,7 @@ char version_string[] = "1.0.0 Alpha 1";
82 82
 // M27  - Report SD print status
83 83
 // M28  - Start SD write (M28 filename.g)
84 84
 // M29  - Stop SD write
85
+// M30  - Output time since last M109 or SD card start to serial
85 86
 // M42  - Change pin status via gcode
86 87
 // M80  - Turn on Power Supply
87 88
 // M81  - Turn off Power Supply
@@ -172,24 +173,30 @@ bool savetosd = false;
172 173
 int16_t n;
173 174
 unsigned long autostart_atmillis=0;
174 175
 
175
-void initsd(){
176
+void initsd()
177
+{
176 178
   sdactive = false;
177 179
 #if SDSS >- 1
178 180
   if(root.isOpen())
179 181
     root.close();
180
-  if (!card.init(SPI_FULL_SPEED,SDSS)){
182
+  if (!card.init(SPI_FULL_SPEED,SDSS))
183
+  {
181 184
     //if (!card.init(SPI_HALF_SPEED,SDSS))
182
-    Serial.println("SD init fail");
185
+    SERIAL_ECHOLN("SD init fail");
183 186
   }
184 187
   else if (!volume.init(&card))
185
-    Serial.println("volume.init failed");
188
+  {
189
+    SERIAL_ERRORLN("volume.init failed");
190
+  }
186 191
   else if (!root.openRoot(&volume)) 
187
-    Serial.println("openRoot failed");
192
+  {
193
+    SERIAL_ERRORLN("openRoot failed");
194
+  }
188 195
   else 
189
-	{
196
+  {
190 197
     sdactive = true;
191
-		Serial.println("SD card ok");
192
-	}
198
+    SERIAL_ECHOLN("SD card ok");
199
+  }
193 200
 #endif //SDSS
194 201
 }
195 202
 
@@ -214,7 +221,7 @@ inline void write_command(char *buf){
214 221
   //Serial.println(begin);
215 222
   file.write(begin);
216 223
   if (file.writeError){
217
-    Serial.println("error writing to file");
224
+    SERIAL_ERRORLN("error writing to file");
218 225
   }
219 226
 }
220 227
 #endif //SDSUPPORT
@@ -227,7 +234,7 @@ void enquecommand(const char *cmd)
227 234
   {
228 235
     //this is dangerous if a mixing of serial and this happsens
229 236
     strcpy(&(cmdbuffer[bufindw][0]),cmd);
230
-    Serial.print("en:");Serial.println(cmdbuffer[bufindw]);
237
+    SERIAL_ECHOLN("enqueing \""<<cmdbuffer[bufindw]<<"\"");
231 238
     bufindw= (bufindw + 1)%BUFSIZE;
232 239
     buflen += 1;
233 240
   }
@@ -237,7 +244,7 @@ void setup()
237 244
 { 
238 245
 	
239 246
   Serial.begin(BAUDRATE);
240
-  ECHOLN("Marlin "<<version_string);
247
+  SERIAL_ECHOLN("Marlin "<<version_string);
241 248
   Serial.println("start");
242 249
 #if defined FANCY_LCD || defined SIMPLE_LCD
243 250
   lcd_init();
@@ -478,17 +485,17 @@ inline void get_command()
478 485
       sdpos = file.curPosition();
479 486
       if(sdpos >= filesize){
480 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 500
       if(!serial_count) return; //if empty line
494 501
       cmdbuffer[bufindw][serial_count] = 0; //terminate string
@@ -721,7 +728,7 @@ inline void process_commands()
721 728
     case 24: //M24 - Start SD print
722 729
       if(sdactive){
723 730
         sdmode = true;
724
-				starttime=millis();
731
+	starttime=millis();
725 732
       }
726 733
       break;
727 734
     case 25: //M25 - Pause SD print
@@ -774,19 +781,19 @@ inline void process_commands()
774 781
       //processed in write to file routine above
775 782
       //savetosd = false;
776 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 797
 #endif //SDSUPPORT
791 798
       case 42: //M42 -Change pin status via gcode
792 799
         if (code_seen('S'))
@@ -847,7 +854,7 @@ inline void process_commands()
847 854
             Serial.println();
848 855
           #endif
849 856
         #else
850
-          Serial.println("No thermistors - no temp");
857
+          Serial.println("echo: No thermistors - no temp");
851 858
         #endif
852 859
         return;
853 860
         //break;
@@ -888,7 +895,8 @@ inline void process_commands()
888 895
               }
889 896
               #endif //TEMP_RESIDENCY_TIME
890 897
             }
891
-            LCD_MESSAGE("Marlin ready.");
898
+            LCD_MESSAGE("Heating done.");
899
+	    starttime=millis();
892 900
           }
893 901
           break;
894 902
       case 190: // M190 - Wait bed for heater to reach target.
@@ -1063,9 +1071,9 @@ inline void process_commands()
1063 1071
       if(code_seen('P')) Kp = code_value();
1064 1072
       if(code_seen('I')) Ki = code_value()*PID_dT;
1065 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 1078
 //      temp_iState_min = 0.0;
1071 1079
 //      if (Ki!=0) {
@@ -1093,8 +1101,9 @@ inline void process_commands()
1093 1101
     }
1094 1102
   }
1095 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 1109
   ClearToSend();
@@ -1288,7 +1297,7 @@ void kill()
1288 1297
   disable_e();
1289 1298
   
1290 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 1301
   while(1); // Wait for reset
1293 1302
 }
1294 1303
 

+ 1
- 1
Marlin/motion_control.cpp View File

@@ -35,7 +35,7 @@ void mc_arc(float *position, float *target, float *offset, uint8_t axis_0, uint8
35 35
 {      
36 36
 //   int acceleration_manager_was_enabled = plan_is_acceleration_manager_enabled();
37 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 39
   float center_axis0 = position[axis_0] + offset[axis_0];
40 40
   float center_axis1 = position[axis_1] + offset[axis_1];
41 41
   float linear_travel = target[axis_linear] - position[axis_linear];

+ 1
- 1
Marlin/stepper.cpp View File

@@ -211,7 +211,7 @@ inline void trapezoid_generator_reset() {
211 211
 // It pops blocks from the block_buffer and executes them by pulsing the stepper pins appropriately. 
212 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 215
     return; 
216 216
   } // The busy-flag is used to avoid reentering this interrupt
217 217
 

+ 9
- 18
Marlin/temperature.cpp View File

@@ -142,17 +142,8 @@ CRITICAL_SECTION_END;
142 142
     }
143 143
 #endif //PID_OPENLOOP
144 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 147
 #endif //PID_DEBUG
157 148
     analogWrite(HEATER_0_PIN, pid_output);
158 149
 #endif //PIDTEMP
@@ -452,7 +443,7 @@ ISR(TIMER0_COMPB_vect)
452 443
             temp_count++;
453 444
             break;
454 445
     default:
455
-            Serial.println("!! Temp measurement error !!");
446
+            SERIAL_ERRORLN("Temp measurement error!");
456 447
             break;
457 448
   }
458 449
     
@@ -486,7 +477,7 @@ ISR(TIMER0_COMPB_vect)
486 477
     if(current_raw[TEMPSENSOR_HOTEND_0] >= maxttemp_0) {
487 478
       target_raw[TEMPSENSOR_HOTEND_0] = 0;
488 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 481
       kill();
491 482
     }
492 483
   #endif
@@ -497,7 +488,7 @@ ISR(TIMER0_COMPB_vect)
497 488
       target_raw[TEMPSENSOR_HOTEND_1] = 0;
498 489
     if(current_raw[2] >= maxttemp_1) {
499 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 492
       kill()
502 493
     }
503 494
   #endif
@@ -507,7 +498,7 @@ ISR(TIMER0_COMPB_vect)
507 498
     if(current_raw[TEMPSENSOR_HOTEND_0] <= minttemp_0) {
508 499
       target_raw[TEMPSENSOR_HOTEND_0] = 0;
509 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 502
       kill();
512 503
     }
513 504
   #endif
@@ -517,7 +508,7 @@ ISR(TIMER0_COMPB_vect)
517 508
     if(current_raw[TEMPSENSOR_HOTEND_1] <= minttemp_1) {
518 509
       target_raw[TEMPSENSOR_HOTEND_1] = 0;
519 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 512
       kill();
522 513
     }
523 514
   #endif
@@ -527,7 +518,7 @@ ISR(TIMER0_COMPB_vect)
527 518
     if(current_raw[1] <= bed_minttemp) {
528 519
       target_raw[1] = 0;
529 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 522
       kill();
532 523
     }
533 524
   #endif
@@ -537,7 +528,7 @@ ISR(TIMER0_COMPB_vect)
537 528
     if(current_raw[1] >= bed_maxttemp) {
538 529
       target_raw[1] = 0;
539 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 532
       kill();
542 533
     }
543 534
   #endif

+ 2
- 2
Marlin/ultralcd.pde View File

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

+ 1
- 1
Marlin/watchdog.pde View File

@@ -15,7 +15,7 @@ ISR(WDT_vect)
15 15
  
16 16
     #ifdef RESET_MANUAL
17 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 19
     #else
20 20
       LCD_MESSAGE("Timeout, resetting!");
21 21
     #endif 

Loading…
Cancel
Save