Browse Source

made progmem mainly, found one bug in cardreader, added a empty class for cardreader in case no sd support.

Bernhard Kubicek 13 years ago
parent
commit
7b70caab7c
7 changed files with 944 additions and 851 deletions
  1. 64
    15
      Marlin/EEPROMwrite.h
  2. 4
    2
      Marlin/Marlin.h
  3. 78
    69
      Marlin/Marlin.pde
  4. 30
    1
      Marlin/cardreader.h
  5. 7
    16
      Marlin/cardreader.pde
  6. 693
    693
      Marlin/pins.h
  7. 68
    55
      Marlin/ultralcd.pde

+ 64
- 15
Marlin/EEPROMwrite.h View File

25
 }
25
 }
26
 //======================================================================================
26
 //======================================================================================
27
 
27
 
28
+#include <avr/pgmspace.h>
29
+
30
+void serialprintPGM(const char *str)
31
+{
32
+  char ch=pgm_read_byte(str);
33
+  while(ch)
34
+  {
35
+    Serial.print(ch);
36
+    ch=pgm_read_byte(++str);
37
+  }
38
+}
39
+#define SerialprintPGM(x) serialprintPGM(PSTR(x))
40
+
28
 #define EEPROM_OFFSET 100
41
 #define EEPROM_OFFSET 100
29
 
42
 
30
 
43
 
62
   char ver2[4]=EEPROM_VERSION;
75
   char ver2[4]=EEPROM_VERSION;
63
   i=EEPROM_OFFSET;
76
   i=EEPROM_OFFSET;
64
   EEPROM_writeAnything(i,ver2); // validate data
77
   EEPROM_writeAnything(i,ver2); // validate data
65
-  SERIAL_ECHOLN("Settings Stored");
78
+  SerialprintPGM("echo: Settings Stored\n");
66
 }
79
 }
67
 
80
 
68
 void RetrieveSettings(bool def=false)
81
 void RetrieveSettings(bool def=false)
91
     EEPROM_readAnything(i,Ki);
104
     EEPROM_readAnything(i,Ki);
92
     EEPROM_readAnything(i,Kd);
105
     EEPROM_readAnything(i,Kd);
93
 
106
 
94
-    SERIAL_ECHOLN("Stored settings retreived:");
107
+    SerialprintPGM("echo: Stored settings retreived:\n");
95
   }
108
   }
96
   else 
109
   else 
97
   {
110
   {
111
     mintravelfeedrate=DEFAULT_MINTRAVELFEEDRATE;
124
     mintravelfeedrate=DEFAULT_MINTRAVELFEEDRATE;
112
     max_xy_jerk=DEFAULT_XYJERK;
125
     max_xy_jerk=DEFAULT_XYJERK;
113
     max_z_jerk=DEFAULT_ZJERK;
126
     max_z_jerk=DEFAULT_ZJERK;
114
-    SERIAL_ECHOLN("Using Default settings:");
127
+    SerialprintPGM("echo: Using Default settings:\n");
115
   }
128
   }
116
-  SERIAL_ECHOLN("Steps per unit:");
117
-  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));
118
-  SERIAL_ECHOLN("Maximum feedrates (mm/s):");
119
-  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));
120
-  SERIAL_ECHOLN("Maximum Acceleration (mm/s2):");
121
-  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));
122
-  SERIAL_ECHOLN("Acceleration: S=acceleration, T=retract acceleration");
123
-  SERIAL_ECHOLN("   M204 S"  <<_FLOAT(acceleration,2) << " T" << _FLOAT(retract_acceleration,2));
124
-  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)");
125
-  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));
129
+  SerialprintPGM("echo: Steps per unit:\n   M92 X");
130
+    Serial.print(axis_steps_per_unit[0]);
131
+    SerialprintPGM(" Y"); 
132
+    Serial.print(axis_steps_per_unit[1]);
133
+    SerialprintPGM(" Z");
134
+    Serial.print(axis_steps_per_unit[2]);
135
+    SerialprintPGM(" E");
136
+    Serial.print(axis_steps_per_unit[3]);
137
+    
138
+  SerialprintPGM("\nMaximum feedrates (mm/s):\n   M203 X"  );
139
+    Serial.print(max_feedrate[0]/60);
140
+    SerialprintPGM(" Y" ); 
141
+    Serial.print(max_feedrate[1]/60 ); 
142
+    SerialprintPGM(" Z" ); 
143
+    Serial.print(max_feedrate[2]/60 ); 
144
+    SerialprintPGM(" E" ); 
145
+    Serial.print(max_feedrate[3]/60);
146
+  SerialprintPGM("\nMaximum Acceleration (mm/s2):\n   M201 X"  );
147
+    Serial.print(max_acceleration_units_per_sq_second[0] ); 
148
+    SerialprintPGM(" Y" ); 
149
+    Serial.print(max_acceleration_units_per_sq_second[1] ); 
150
+    SerialprintPGM(" Z" ); 
151
+    Serial.print(max_acceleration_units_per_sq_second[2] );
152
+    SerialprintPGM(" E" ); 
153
+    Serial.print(max_acceleration_units_per_sq_second[3]);
154
+  SerialprintPGM("\necho: Acceleration: S=acceleration, T=retract acceleration\n   M204 S"  );
155
+    Serial.print(acceleration ); 
156
+    SerialprintPGM(" T" ); 
157
+    Serial.print(retract_acceleration);
158
+  SerialprintPGM("\necho: 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)");
159
+  SerialprintPGM("   M205 S"  );
160
+    Serial.print(minimumfeedrate/60 ); 
161
+    SerialprintPGM(" T" ); 
162
+    Serial.print(mintravelfeedrate/60 ); 
163
+    SerialprintPGM(" B" ); 
164
+    Serial.print(minsegmenttime ); 
165
+    SerialprintPGM(" X" ); 
166
+    Serial.print(max_xy_jerk/60 ); 
167
+    SerialprintPGM(" Z" ); 
168
+    Serial.print(max_z_jerk/60);
169
+    SerialprintPGM("\n" ); 
126
   #ifdef PIDTEMP
170
   #ifdef PIDTEMP
127
-    SERIAL_ECHOLN("PID settings:");
128
-    SERIAL_ECHOLN("   M301 P"  << _FLOAT(Kp,3) << " I" << _FLOAT(Ki,3) << " D" << _FLOAT(Kd,3));  
171
+    SerialprintPGM("PID settings:");
172
+    SerialprintPGM("   M301 P"  ); 
173
+    Serial.print(Kp ); 
174
+    SerialprintPGM(" I" ); 
175
+    Serial.print(Ki ); 
176
+    SerialprintPGM(" D" ); 
177
+    Serial.print(Kd);  
129
   #endif
178
   #endif
130
 }  
179
 }  
131
 
180
 

+ 4
- 2
Marlin/Marlin.h View File

9
 #include "streaming.h"
9
 #include "streaming.h"
10
 #define SERIAL_ECHO(x) Serial << "echo: " << x;
10
 #define SERIAL_ECHO(x) Serial << "echo: " << x;
11
 #define SERIAL_ECHOLN(x) Serial << "echo: "<<x<<endl;
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
+#define SERIAL_ERROR(x) Serial << "Error: " << x;
13
+#define SERIAL_ERRORLN(x) Serial << "Error: " << x<<endl;
14
+#define SERIAL_PROTOCOL(x) Serial << x;
15
+#define SERIAL_PROTOCOLLN(x) Serial << x<<endl;
14
 
16
 
15
 void get_command();
17
 void get_command();
16
 void process_commands();
18
 void process_commands();

+ 78
- 69
Marlin/Marlin.pde View File

44
 
44
 
45
 
45
 
46
 
46
 
47
+
47
 // look here for descriptions of gcodes: http://linuxcnc.org/handbook/gcode/g-code.html
48
 // look here for descriptions of gcodes: http://linuxcnc.org/handbook/gcode/g-code.html
48
 // http://objects.reprap.org/wiki/Mendel_User_Manual:_RepRapGCodes
49
 // http://objects.reprap.org/wiki/Mendel_User_Manual:_RepRapGCodes
49
 
50
 
171
 //===========================================================================
172
 //===========================================================================
172
 
173
 
173
 
174
 
175
+extern "C"{
176
+  extern unsigned int __bss_end;
177
+  extern unsigned int __heap_start;
178
+  extern void *__brkval;
179
+
180
+  int freeMemory() {
181
+    int free_memory;
182
+
183
+    if((int)__brkval == 0)
184
+      free_memory = ((int)&free_memory) - ((int)&__bss_end);
185
+    else
186
+      free_memory = ((int)&free_memory) - ((int)__brkval);
187
+
188
+    return free_memory;
189
+  }
190
+}
191
+
174
 
192
 
175
 //adds an command to the main command buffer
193
 //adds an command to the main command buffer
176
 //thats really done in a non-safe way.
194
 //thats really done in a non-safe way.
191
 { 
209
 { 
192
   Serial.begin(BAUDRATE);
210
   Serial.begin(BAUDRATE);
193
   SERIAL_ECHOLN("Marlin "<<version_string);
211
   SERIAL_ECHOLN("Marlin "<<version_string);
194
-  Serial.println("start");
212
+  SERIAL_PROTOCOLLN("start");
213
+  Serial.print("echo: Free Memory:");
214
+  serial.println(freeMemory());
195
   for(int8_t i = 0; i < BUFSIZE; i++)
215
   for(int8_t i = 0; i < BUFSIZE; i++)
196
   {
216
   {
197
     fromsd[i] = false;
217
     fromsd[i] = false;
224
 	if(strstr(cmdbuffer[bufindr],"M29") == NULL)
244
 	if(strstr(cmdbuffer[bufindr],"M29") == NULL)
225
 	{
245
 	{
226
 	  card.write_command(cmdbuffer[bufindr]);
246
 	  card.write_command(cmdbuffer[bufindr]);
227
-	  Serial.println("ok");
247
+	  SERIAL_PROTOCOLLN("ok");
228
 	}
248
 	}
229
 	else
249
 	else
230
 	{
250
 	{
231
 	  card.closefile();
251
 	  card.closefile();
232
-	  Serial.println("Done saving file.");
252
+	  SERIAL_PROTOCOLLN("Done saving file.");
233
 	}
253
 	}
234
       }
254
       }
235
       else
255
       else
264
           strchr_pointer = strchr(cmdbuffer[bufindw], 'N');
284
           strchr_pointer = strchr(cmdbuffer[bufindw], 'N');
265
           gcode_N = (strtol(&cmdbuffer[bufindw][strchr_pointer - cmdbuffer[bufindw] + 1], NULL, 10));
285
           gcode_N = (strtol(&cmdbuffer[bufindw][strchr_pointer - cmdbuffer[bufindw] + 1], NULL, 10));
266
           if(gcode_N != gcode_LastN+1 && (strstr(cmdbuffer[bufindw], "M110") == NULL) ) {
286
           if(gcode_N != gcode_LastN+1 && (strstr(cmdbuffer[bufindw], "M110") == NULL) ) {
267
-            Serial.print("Serial Error: Line Number is not Last Line Number+1, Last Line:");
268
-            Serial.println(gcode_LastN);
287
+            SERIAL_ERRORLN("Line Number is not Last Line Number+1, Last Line:"<<gcode_LastN);
269
             //Serial.println(gcode_N);
288
             //Serial.println(gcode_N);
270
             FlushSerialRequestResend();
289
             FlushSerialRequestResend();
271
             serial_count = 0;
290
             serial_count = 0;
280
             strchr_pointer = strchr(cmdbuffer[bufindw], '*');
299
             strchr_pointer = strchr(cmdbuffer[bufindw], '*');
281
 
300
 
282
             if( (int)(strtod(&cmdbuffer[bufindw][strchr_pointer - cmdbuffer[bufindw] + 1], NULL)) != checksum) {
301
             if( (int)(strtod(&cmdbuffer[bufindw][strchr_pointer - cmdbuffer[bufindw] + 1], NULL)) != checksum) {
283
-              Serial.print("Error: checksum mismatch, Last Line:");
284
-              Serial.println(gcode_LastN);
302
+              SERIAL_ERRORLN("checksum mismatch, Last Line:"<<gcode_LastN);
285
               FlushSerialRequestResend();
303
               FlushSerialRequestResend();
286
               serial_count = 0;
304
               serial_count = 0;
287
               return;
305
               return;
290
           }
308
           }
291
           else 
309
           else 
292
           {
310
           {
293
-            Serial.print("Error: No Checksum with line number, Last Line:");
294
-            Serial.println(gcode_LastN);
311
+            SERIAL_ERRORLN("No Checksum with line number, Last Line:"<<gcode_LastN);
295
             FlushSerialRequestResend();
312
             FlushSerialRequestResend();
296
             serial_count = 0;
313
             serial_count = 0;
297
             return;
314
             return;
304
         {
321
         {
305
           if((strstr(cmdbuffer[bufindw], "*") != NULL))
322
           if((strstr(cmdbuffer[bufindw], "*") != NULL))
306
           {
323
           {
307
-            Serial.print("Error: No Line Number with checksum, Last Line:");
308
-            Serial.println(gcode_LastN);
324
+            SERIAL_ERRORLN("No Line Number with checksum, Last Line:"<<gcode_LastN);
309
             serial_count = 0;
325
             serial_count = 0;
310
             return;
326
             return;
311
           }
327
           }
321
             if(card.saving)
337
             if(card.saving)
322
               break;
338
               break;
323
 	    #endif //SDSUPPORT
339
 	    #endif //SDSUPPORT
324
-            Serial.println("ok"); 
340
+            SERIAL_PROTOCOLLN("ok"); 
325
             break;
341
             break;
326
           default:
342
           default:
327
             break;
343
             break;
353
      
369
      
354
       if(card.eof()){
370
       if(card.eof()){
355
         card.sdprinting = false;
371
         card.sdprinting = false;
356
-        Serial.println("echo: Done printing file");
372
+        SERIAL_PROTOCOL("Done printing file");
357
         stoptime=millis();
373
         stoptime=millis();
358
         char time[30];
374
         char time[30];
359
         unsigned long t=(stoptime-starttime)/1000;
375
         unsigned long t=(stoptime-starttime)/1000;
360
         int sec,min;
376
         int sec,min;
361
         min=t/60;
377
         min=t/60;
362
         sec=t%60;
378
         sec=t%60;
363
-        sprintf(time,"echo: %i min, %i sec",min,sec);
364
-        Serial.println(time);
379
+        sprintf(time,"%i min, %i sec",min,sec);
380
+        SERIAL_ECHOLN(time);
365
         LCD_MESSAGE(time);
381
         LCD_MESSAGE(time);
366
         card.checkautostart(true);
382
         card.checkautostart(true);
367
       }
383
       }
517
     #ifdef SDSUPPORT
533
     #ifdef SDSUPPORT
518
 
534
 
519
     case 20: // M20 - list SD card
535
     case 20: // M20 - list SD card
520
-      Serial.println("Begin file list");
536
+      SERIAL_PROTOCOLLN("Begin file list");
521
       card.ls();
537
       card.ls();
522
-      Serial.println("End file list");
538
+      SERIAL_PROTOCOLLN("End file list");
523
       break;
539
       break;
524
     case 21: // M21 - init SD card
540
     case 21: // M21 - init SD card
525
       
541
       
575
       int sec,min;
591
       int sec,min;
576
       min=t/60;
592
       min=t/60;
577
       sec=t%60;
593
       sec=t%60;
578
-      sprintf(time,"echo: time needed %i min, %i sec",min,sec);
579
-      Serial.println(time);
594
+      sprintf(time,"%i min, %i sec",min,sec);
595
+      SERIAL_ERRORLN(time);
580
       LCD_MESSAGE(time);
596
       LCD_MESSAGE(time);
581
     }
597
     }
582
     break;
598
     break;
613
       if (code_seen('S')) setTargetBed(code_value());
629
       if (code_seen('S')) setTargetBed(code_value());
614
       break;
630
       break;
615
     case 105: // M105
631
     case 105: // M105
632
+      //SERIAL_ECHOLN(freeMemory());
616
       #if (TEMP_0_PIN > -1) || defined (HEATER_USES_AD595)
633
       #if (TEMP_0_PIN > -1) || defined (HEATER_USES_AD595)
617
         tt = degHotend0();
634
         tt = degHotend0();
618
       #endif
635
       #endif
620
           bt = degBed();
637
           bt = degBed();
621
       #endif
638
       #endif
622
       #if (TEMP_0_PIN > -1) || defined (HEATER_USES_AD595)
639
       #if (TEMP_0_PIN > -1) || defined (HEATER_USES_AD595)
623
-        Serial.print("ok T:");
624
-        Serial.print(tt); 
640
+        SERIAL_PROTOCOL("ok T:");
641
+        SERIAL_PROTOCOL(tt); 
625
         #if TEMP_1_PIN > -1 
642
         #if TEMP_1_PIN > -1 
626
           #ifdef PIDTEMP
643
           #ifdef PIDTEMP
627
-            Serial.print(" B:");
644
+            SERIAL_PROTOCOL(" B:");
628
             #if TEMP_1_PIN > -1
645
             #if TEMP_1_PIN > -1
629
-              Serial.println(bt); 
646
+              SERIAL_PROTOCOLLN(bt); 
630
             #else
647
             #else
631
-              Serial.println(HeaterPower); 
648
+              SERIAL_PROTOCOLLN(HeaterPower); 
632
             #endif
649
             #endif
633
           #else //not PIDTEMP
650
           #else //not PIDTEMP
634
-            Serial.println();
651
+            SERIAL_PROTOCOLLN("");
635
            #endif //PIDTEMP
652
            #endif //PIDTEMP
636
          #else
653
          #else
637
-            Serial.println();
654
+            SERIAL_PROTOCOLLN("");
638
           #endif //TEMP_1_PIN
655
           #endif //TEMP_1_PIN
639
         #else
656
         #else
640
           SERIAL_ERRORLN("No thermistors - no temp");
657
           SERIAL_ERRORLN("No thermistors - no temp");
664
         #endif //TEMP_RESIDENCY_TIME
681
         #endif //TEMP_RESIDENCY_TIME
665
         if( (millis() - codenum) > 1000 ) 
682
         if( (millis() - codenum) > 1000 ) 
666
         { //Print Temp Reading every 1 second while heating up/cooling down
683
         { //Print Temp Reading every 1 second while heating up/cooling down
667
-          Serial.print("T:");
668
-        Serial.println( degHotend0() ); 
684
+          SERIAL_PROTOCOLLN("T:"<< degHotend0() ); 
669
           codenum = millis();
685
           codenum = millis();
670
         }
686
         }
671
         manage_heater();
687
         manage_heater();
694
           if( (millis()-codenum) > 1000 ) //Print Temp Reading every 1 second while heating up.
710
           if( (millis()-codenum) > 1000 ) //Print Temp Reading every 1 second while heating up.
695
           {
711
           {
696
             float tt=degHotend0();
712
             float tt=degHotend0();
697
-            Serial.print("T:");
698
-            Serial.println( tt );
699
-            Serial.print("ok T:");
700
-            Serial.print( tt ); 
701
-            Serial.print(" B:");
702
-            Serial.println( degBed() ); 
713
+            SERIAL_PROTOCOLLN("T:"<<tt );
714
+            SERIAL_PROTOCOLLN("ok T:"<<tt <<" B:"<<degBed() ); 
703
             codenum = millis(); 
715
             codenum = millis(); 
704
           }
716
           }
705
           manage_heater();
717
           manage_heater();
766
       }
778
       }
767
       break;
779
       break;
768
     case 115: // M115
780
     case 115: // M115
769
-      Serial.println("FIRMWARE_NAME:Marlin; Sprinter/grbl mashup for gen6 FIRMWARE_URL:http://www.mendel-parts.com PROTOCOL_VERSION:1.0 MACHINE_TYPE:Mendel EXTRUDER_COUNT:1");
781
+      SERIAL_PROTOCOLLN("FIRMWARE_NAME:Marlin; Sprinter/grbl mashup for gen6 FIRMWARE_URL:http://www.mendel-parts.com PROTOCOL_VERSION:1.0 MACHINE_TYPE:Mendel EXTRUDER_COUNT:1");
770
       break;
782
       break;
771
     case 114: // M114
783
     case 114: // M114
772
-      Serial.print("X:");
773
-      Serial.print(current_position[X_AXIS]);
774
-      Serial.print("Y:");
775
-      Serial.print(current_position[Y_AXIS]);
776
-      Serial.print("Z:");
777
-      Serial.print(current_position[Z_AXIS]);
778
-      Serial.print("E:");      
779
-      Serial.print(current_position[E_AXIS]);
784
+      SERIAL_PROTOCOL("X:");
785
+      SERIAL_PROTOCOL(current_position[X_AXIS]);
786
+      SERIAL_PROTOCOL("Y:");
787
+      SERIAL_PROTOCOL(current_position[Y_AXIS]);
788
+      SERIAL_PROTOCOL("Z:");
789
+      SERIAL_PROTOCOL(current_position[Z_AXIS]);
790
+      SERIAL_PROTOCOL("E:");      
791
+      SERIAL_PROTOCOL(current_position[E_AXIS]);
780
       #ifdef DEBUG_STEPS
792
       #ifdef DEBUG_STEPS
781
-        Serial.print(" Count X:");
782
-        Serial.print(float(count_position[X_AXIS])/axis_steps_per_unit[X_AXIS]);
783
-        Serial.print("Y:");
784
-        Serial.print(float(count_position[Y_AXIS])/axis_steps_per_unit[Y_AXIS]);
785
-        Serial.print("Z:");
786
-        Serial.println(float(count_position[Z_AXIS])/axis_steps_per_unit[Z_AXIS]);
793
+        SERIAL_PROTOCOL(" Count X:");
794
+        SERIAL_PROTOCOL(float(count_position[X_AXIS])/axis_steps_per_unit[X_AXIS]);
795
+        SERIAL_PROTOCOL("Y:");
796
+        SERIAL_PROTOCOL(float(count_position[Y_AXIS])/axis_steps_per_unit[Y_AXIS]);
797
+        SERIAL_PROTOCOL("Z:");
798
+        SERIAL_PROTOCOL(float(count_position[Z_AXIS])/axis_steps_per_unit[Z_AXIS]);
787
       #endif
799
       #endif
788
-      Serial.println("");
800
+      SERIAL_PROTOCOLLN("");
789
       break;
801
       break;
790
     case 119: // M119
802
     case 119: // M119
791
       #if (X_MIN_PIN > -1)
803
       #if (X_MIN_PIN > -1)
792
-        Serial.print("x_min:");
793
-        Serial.print((READ(X_MIN_PIN)^ENDSTOPS_INVERTING)?"H ":"L ");
804
+        SERIAL_PROTOCOL("x_min:");
805
+        SERIAL_PROTOCOL(((READ(X_MIN_PIN)^ENDSTOPS_INVERTING)?"H ":"L "));
794
       #endif
806
       #endif
795
       #if (X_MAX_PIN > -1)
807
       #if (X_MAX_PIN > -1)
796
-        Serial.print("x_max:");
797
-        Serial.print((READ(X_MAX_PIN)^ENDSTOPS_INVERTING)?"H ":"L ");
808
+        SERIAL_PROTOCOL("x_max:");
809
+        SERIAL_PROTOCOL(((READ(X_MAX_PIN)^ENDSTOPS_INVERTING)?"H ":"L "));
798
       #endif
810
       #endif
799
       #if (Y_MIN_PIN > -1)
811
       #if (Y_MIN_PIN > -1)
800
-        Serial.print("y_min:");
801
-        Serial.print((READ(Y_MIN_PIN)^ENDSTOPS_INVERTING)?"H ":"L ");
812
+        SERIAL_PROTOCOL("y_min:");
813
+        SERIAL_PROTOCOL(((READ(Y_MIN_PIN)^ENDSTOPS_INVERTING)?"H ":"L "));
802
       #endif
814
       #endif
803
       #if (Y_MAX_PIN > -1)
815
       #if (Y_MAX_PIN > -1)
804
-        Serial.print("y_max:");
805
-        Serial.print((READ(Y_MAX_PIN)^ENDSTOPS_INVERTING)?"H ":"L ");
816
+        SERIAL_PROTOCOL("y_max:");
817
+        SERIAL_PROTOCOL(((READ(Y_MAX_PIN)^ENDSTOPS_INVERTING)?"H ":"L "));
806
       #endif
818
       #endif
807
       #if (Z_MIN_PIN > -1)
819
       #if (Z_MIN_PIN > -1)
808
-        Serial.print("z_min:");
809
-        Serial.print((READ(Z_MIN_PIN)^ENDSTOPS_INVERTING)?"H ":"L ");
820
+        SERIAL_PROTOCOL("z_min:");
821
+        SERIAL_PROTOCOL(((READ(Z_MIN_PIN)^ENDSTOPS_INVERTING)?"H ":"L "));
810
       #endif
822
       #endif
811
       #if (Z_MAX_PIN > -1)
823
       #if (Z_MAX_PIN > -1)
812
-        Serial.print("z_max:");
813
-        Serial.print((READ(Z_MAX_PIN)^ENDSTOPS_INVERTING)?"H ":"L ");
824
+        SERIAL_PROTOCOL("z_max:");
825
+        SERIAL_PROTOCOL(((READ(Z_MAX_PIN)^ENDSTOPS_INVERTING)?"H ":"L "));
814
       #endif
826
       #endif
815
-      Serial.println("");
827
+      SERIAL_PROTOCOLLN("");
816
       break;
828
       break;
817
       //TODO: update for all axis, use for loop
829
       //TODO: update for all axis, use for loop
818
     case 201: // M201
830
     case 201: // M201
885
   }
897
   }
886
   else
898
   else
887
   {
899
   {
888
-    Serial.print("echo: Unknown command:\"");
889
-    Serial.print(cmdbuffer[bufindr]);
890
-    Serial.println("\"");
900
+    SERIAL_ECHOLN("Unknown command:\""<<cmdbuffer[bufindr]<<"\"");
891
   }
901
   }
892
 
902
 
893
   ClearToSend();
903
   ClearToSend();
897
 {
907
 {
898
   //char cmdbuffer[bufindr][100]="Resend:";
908
   //char cmdbuffer[bufindr][100]="Resend:";
899
   Serial.flush();
909
   Serial.flush();
900
-  Serial.print("Resend:");
901
-  Serial.println(gcode_LastN + 1);
910
+  SERIAL_PROTOCOLLN("Resend:"<<gcode_LastN + 1);
902
   ClearToSend();
911
   ClearToSend();
903
 }
912
 }
904
 
913
 
909
   if(fromsd[bufindr])
918
   if(fromsd[bufindr])
910
     return;
919
     return;
911
   #endif //SDSUPPORT
920
   #endif //SDSUPPORT
912
-  Serial.println("ok"); 
921
+  SERIAL_PROTOCOLLN("ok"); 
913
 }
922
 }
914
 
923
 
915
 inline void get_coordinates()
924
 inline void get_coordinates()

+ 30
- 1
Marlin/cardreader.h View File

31
 
31
 
32
   inline void ls() {root.ls();};
32
   inline void ls() {root.ls();};
33
   inline bool eof() { sdpos = file.curPosition();return sdpos>=filesize ;};
33
   inline bool eof() { sdpos = file.curPosition();return sdpos>=filesize ;};
34
-  inline char get() {  int16_t n = file.read(); return (n!=-1)?(char)n:'\n';};
34
+  inline char get() {  int16_t n = file.read(); return (n==-1)?'\n':(char)n;};
35
   inline void setIndex(long index) {sdpos = index;file.seekSet(index);};
35
   inline void setIndex(long index) {sdpos = index;file.seekSet(index);};
36
 
36
 
37
 public:
37
 public:
52
   bool autostart_stilltocheck; //the sd start is delayed, because otherwise the serial cannot answer fast enought to make contact with the hostsoftware.
52
   bool autostart_stilltocheck; //the sd start is delayed, because otherwise the serial cannot answer fast enought to make contact with the hostsoftware.
53
 };
53
 };
54
   
54
   
55
+
56
+#else
57
+class CardReader
58
+{
59
+public:
60
+  inline CardReader(){};
61
+  
62
+  inline static void initsd(){};
63
+  inline static void write_command(char *buf){};
64
+  
65
+  inline static void checkautostart(bool x) {}; 
66
+  
67
+  inline static void closefile() {};
68
+  inline static void release(){};
69
+  inline static void startFileprint(){};
70
+  inline static void startFilewrite(char *name){};
71
+  inline static void pauseSDPrint(){};
72
+  inline static void getStatus(){};
73
+  
74
+  inline static void selectFile(char* name){};
75
+  inline static void getfilename(const uint8_t nr){};
76
+  inline static uint8_t getnrfilenames(){return 0;};
77
+  
78
+
79
+  inline static void ls() {};
80
+  inline static bool eof() {return true;};
81
+  inline static char get() {return 0;};
82
+  inline static void setIndex(){};
83
+};
55
 #endif //SDSUPPORT
84
 #endif //SDSUPPORT
56
   
85
   
57
   
86
   

+ 7
- 16
Marlin/cardreader.pde View File

76
     file.close();
76
     file.close();
77
    
77
    
78
     if (file.open(&root, name, O_READ)) {
78
     if (file.open(&root, name, O_READ)) {
79
-      Serial.print("File opened:");
80
-      Serial.print(name);
81
-      Serial.print(" Size:");
82
       filesize = file.fileSize();
79
       filesize = file.fileSize();
83
-      Serial.println(filesize);
80
+      SERIAL_PROTOCOLLN("File opened:"<<name<<" Size:"<<filesize);
84
       sdpos = 0;
81
       sdpos = 0;
85
       
82
       
86
-      Serial.println("File selected");
83
+      SERIAL_PROTOCOLLN("File selected");
87
     }
84
     }
88
     else{
85
     else{
89
-      Serial.println("file.open failed");
86
+      SERIAL_PROTOCOLLN("file.open failed");
90
     }
87
     }
91
   }
88
   }
92
 }
89
 }
101
     
98
     
102
     if (!file.open(&root, name, O_CREAT | O_APPEND | O_WRITE | O_TRUNC))
99
     if (!file.open(&root, name, O_CREAT | O_APPEND | O_WRITE | O_TRUNC))
103
     {
100
     {
104
-      Serial.print("open failed, File: ");
105
-      Serial.print(name);
106
-      Serial.print(".");
101
+      SERIAL_PROTOCOLLN("open failed, File: "<<name<<".");
107
     }
102
     }
108
     else{
103
     else{
109
       saving = true;
104
       saving = true;
110
-      Serial.print("Writing to file: ");
111
-      Serial.println(name);
105
+      SERIAL_PROTOCOLLN("Writing to file: "<<name);
112
     }
106
     }
113
   }
107
   }
114
 }
108
 }
116
 void CardReader::getStatus()
110
 void CardReader::getStatus()
117
 {
111
 {
118
   if(cardOK){
112
   if(cardOK){
119
-    Serial.print("SD printing byte ");
120
-    Serial.print(sdpos);
121
-    Serial.print("/");
122
-    Serial.println(filesize);
113
+    SERIAL_PROTOCOLLN("SD printing byte "<<sdpos<<"/"<<filesize);
123
   }
114
   }
124
   else{
115
   else{
125
-    Serial.println("Not SD printing");
116
+    SERIAL_PROTOCOLLN("Not SD printing");
126
   }
117
   }
127
 }
118
 }
128
 void CardReader::write_command(char *buf)
119
 void CardReader::write_command(char *buf)

+ 693
- 693
Marlin/pins.h
File diff suppressed because it is too large
View File


+ 68
- 55
Marlin/ultralcd.pde View File

42
  
42
  
43
 static MainMenu menu;
43
 static MainMenu menu;
44
 
44
 
45
+#include <avr/pgmspace.h>
46
+
47
+void lcdProgMemprint(const char *str)
48
+{
49
+  char ch=pgm_read_byte(str);
50
+  while(ch)
51
+  {
52
+    lcd.print(ch);
53
+    ch=pgm_read_byte(++str);
54
+  }
55
+}
56
+#define lcdprintPGM(x) lcdProgMemprint(PSTR(x))
57
+
45
 
58
 
46
 //===========================================================================
59
 //===========================================================================
47
 //=============================functions         ============================
60
 //=============================functions         ============================
264
     feedmultiplychanged=false;
277
     feedmultiplychanged=false;
265
     encoderpos=feedmultiply;
278
     encoderpos=feedmultiply;
266
     clear();
279
     clear();
267
-    lcd.setCursor(0,0);lcd.print("\002123/567\001 ");
280
+    lcd.setCursor(0,0);lcdprintPGM("\002123/567\001 ");
268
     #if defined BED_USES_THERMISTOR || defined BED_USES_AD595 
281
     #if defined BED_USES_THERMISTOR || defined BED_USES_AD595 
269
-      lcd.setCursor(10,0);lcd.print("B123/567\001 ");
282
+      lcd.setCursor(10,0);lcdprintPGM("B123/567\001 ");
270
     #endif
283
     #endif
271
   }
284
   }
272
     
285
     
311
     
324
     
312
     if(starttime!=oldtime)
325
     if(starttime!=oldtime)
313
     {
326
     {
314
-      lcd.print(itostr2(time/60));lcd.print("h ");lcd.print(itostr2(time%60));lcd.print("m");
327
+      lcd.print(itostr2(time/60));lcdprintPGM("h ");lcd.print(itostr2(time%60));lcdprintPGM("m");
315
       oldtime=time;
328
       oldtime=time;
316
     }
329
     }
317
   }
330
   }
320
   if((currentz!=oldzpos)||force_lcd_update)
333
   if((currentz!=oldzpos)||force_lcd_update)
321
   {
334
   {
322
     lcd.setCursor(10,1);
335
     lcd.setCursor(10,1);
323
-    lcd.print("Z:");lcd.print(itostr31(currentz));
336
+    lcdprintPGM("Z:");lcd.print(itostr31(currentz));
324
     oldzpos=currentz;
337
     oldzpos=currentz;
325
   }
338
   }
326
   static int oldfeedmultiply=0;
339
   static int oldfeedmultiply=0;
339
   {
352
   {
340
    oldfeedmultiply=curfeedmultiply;
353
    oldfeedmultiply=curfeedmultiply;
341
    lcd.setCursor(0,2);
354
    lcd.setCursor(0,2);
342
-   lcd.print(itostr3(curfeedmultiply));lcd.print("% ");
355
+   lcd.print(itostr3(curfeedmultiply));lcdprintPGM("% ");
343
   }
356
   }
344
   if(messagetext[0]!='\0')
357
   if(messagetext[0]!='\0')
345
   {
358
   {
353
   if(force_lcd_update)  //initial display of content
366
   if(force_lcd_update)  //initial display of content
354
   {
367
   {
355
     encoderpos=feedmultiply;
368
     encoderpos=feedmultiply;
356
-    lcd.setCursor(0,0);lcd.print("\002123/567\001 ");
369
+    lcd.setCursor(0,0);lcdprintPGM("\002123/567\001 ");
357
     #if defined BED_USES_THERMISTOR || defined BED_USES_AD595 
370
     #if defined BED_USES_THERMISTOR || defined BED_USES_AD595 
358
-    lcd.setCursor(10,0);lcd.print("B123/567\001 ");
371
+    lcd.setCursor(10,0);lcdprintPGM("B123/567\001 ");
359
     #endif
372
     #endif
360
   }
373
   }
361
     
374
     
405
       {
418
       {
406
         if(force_lcd_update)
419
         if(force_lcd_update)
407
         {
420
         {
408
-          lcd.setCursor(0,line);lcd.print(" Prepare");
421
+          lcd.setCursor(0,line);lcdprintPGM(" Prepare");
409
         }
422
         }
410
         if((activeline==line) && CLICKED)
423
         if((activeline==line) && CLICKED)
411
         {
424
         {
418
       {
431
       {
419
         if(force_lcd_update)
432
         if(force_lcd_update)
420
         {
433
         {
421
-          lcd.setCursor(0,line);lcd.print(" Auto Home");
434
+          lcd.setCursor(0,line);lcdprintPGM(" Auto Home");
422
         }
435
         }
423
         if((activeline==line) && CLICKED)
436
         if((activeline==line) && CLICKED)
424
         {
437
         {
431
       {
444
       {
432
         if(force_lcd_update)
445
         if(force_lcd_update)
433
         {
446
         {
434
-          lcd.setCursor(0,line);lcd.print(" Set Origin");
447
+          lcd.setCursor(0,line);lcdprintPGM(" Set Origin");
435
           
448
           
436
         }
449
         }
437
         if((activeline==line) && CLICKED)
450
         if((activeline==line) && CLICKED)
445
       {
458
       {
446
         if(force_lcd_update)
459
         if(force_lcd_update)
447
         {
460
         {
448
-          lcd.setCursor(0,line);lcd.print(" Preheat"); 
461
+          lcd.setCursor(0,line);lcdprintPGM(" Preheat"); 
449
         }
462
         }
450
         if((activeline==line) && CLICKED)
463
         if((activeline==line) && CLICKED)
451
         {
464
         {
458
       {
471
       {
459
         if(force_lcd_update)
472
         if(force_lcd_update)
460
         {
473
         {
461
-          lcd.setCursor(0,line);lcd.print(" Extrude");
474
+          lcd.setCursor(0,line);lcdprintPGM(" Extrude");
462
         }
475
         }
463
         if((activeline==line) && CLICKED)
476
         if((activeline==line) && CLICKED)
464
         {
477
         {
472
       {
485
       {
473
         if(force_lcd_update)
486
         if(force_lcd_update)
474
         {
487
         {
475
-          lcd.setCursor(0,line);lcd.print(" Disable Steppers");
488
+          lcd.setCursor(0,line);lcdprintPGM(" Disable Steppers");
476
         }
489
         }
477
         if((activeline==line) && CLICKED)
490
         if((activeline==line) && CLICKED)
478
         {
491
         {
541
       {
554
       {
542
         if(force_lcd_update)
555
         if(force_lcd_update)
543
         {
556
         {
544
-          lcd.setCursor(0,line);lcd.print(" Control");
557
+          lcd.setCursor(0,line);lcdprintPGM(" Control");
545
         }
558
         }
546
         if((activeline==line) && CLICKED)
559
         if((activeline==line) && CLICKED)
547
         {
560
         {
554
       {
567
       {
555
         if(force_lcd_update)
568
         if(force_lcd_update)
556
         {
569
         {
557
-          lcd.setCursor(0,line);lcd.print(" \002Nozzle:");
570
+          lcd.setCursor(0,line);lcdprintPGM(" \002Nozzle:");
558
           lcd.setCursor(13,line);lcd.print(ftostr3(intround(degHotend0())));
571
           lcd.setCursor(13,line);lcd.print(ftostr3(intround(degHotend0())));
559
         }
572
         }
560
         
573
         
588
       {
601
       {
589
         if(force_lcd_update)
602
         if(force_lcd_update)
590
         {
603
         {
591
-          lcd.setCursor(0,line);lcd.print(" Fan speed:");
604
+          lcd.setCursor(0,line);lcdprintPGM(" Fan speed:");
592
           lcd.setCursor(13,line);lcd.print(ftostr3(fanpwm));
605
           lcd.setCursor(13,line);lcd.print(ftostr3(fanpwm));
593
         }
606
         }
594
         
607
         
625
     {
638
     {
626
       if(force_lcd_update)
639
       if(force_lcd_update)
627
         {
640
         {
628
-          lcd.setCursor(0,line);lcd.print(" Acc:");
629
-          lcd.setCursor(13,line);lcd.print(itostr3(acceleration/100));lcd.print("00");
641
+          lcd.setCursor(0,line);lcdprintPGM(" Acc:");
642
+          lcd.setCursor(13,line);lcd.print(itostr3(acceleration/100));lcdprintPGM("00");
630
         }
643
         }
631
         
644
         
632
         if((activeline==line) )
645
         if((activeline==line) )
650
           {
663
           {
651
             if(encoderpos<5) encoderpos=5;
664
             if(encoderpos<5) encoderpos=5;
652
             if(encoderpos>990) encoderpos=990;
665
             if(encoderpos>990) encoderpos=990;
653
-            lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));lcd.print("00");
666
+            lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));lcdprintPGM("00");
654
           }
667
           }
655
         }
668
         }
656
       }break;
669
       }break;
658
       {
671
       {
659
       if(force_lcd_update)
672
       if(force_lcd_update)
660
         {
673
         {
661
-          lcd.setCursor(0,line);lcd.print(" Vxy-jerk: ");
674
+          lcd.setCursor(0,line);lcdprintPGM(" Vxy-jerk: ");
662
           lcd.setCursor(13,line);lcd.print(itostr3(max_xy_jerk/60));
675
           lcd.setCursor(13,line);lcd.print(itostr3(max_xy_jerk/60));
663
         }
676
         }
664
         
677
         
692
       {
705
       {
693
       if(force_lcd_update)
706
       if(force_lcd_update)
694
         {
707
         {
695
-          lcd.setCursor(0,line);lcd.print(" PID-P: ");
708
+          lcd.setCursor(0,line);lcdprintPGM(" PID-P: ");
696
           lcd.setCursor(13,line);lcd.print(itostr4(Kp));
709
           lcd.setCursor(13,line);lcd.print(itostr4(Kp));
697
         }
710
         }
698
         
711
         
726
       {
739
       {
727
       if(force_lcd_update)
740
       if(force_lcd_update)
728
         {
741
         {
729
-          lcd.setCursor(0,line);lcd.print(" PID-I: ");
742
+          lcd.setCursor(0,line);lcdprintPGM(" PID-I: ");
730
           lcd.setCursor(13,line);lcd.print(ftostr51(Ki));
743
           lcd.setCursor(13,line);lcd.print(ftostr51(Ki));
731
         }
744
         }
732
         
745
         
760
       {
773
       {
761
       if(force_lcd_update)
774
       if(force_lcd_update)
762
         {
775
         {
763
-          lcd.setCursor(0,line);lcd.print(" PID-D: ");
776
+          lcd.setCursor(0,line);lcdprintPGM(" PID-D: ");
764
           lcd.setCursor(13,line);lcd.print(itostr4(Kd));
777
           lcd.setCursor(13,line);lcd.print(itostr4(Kd));
765
         }
778
         }
766
         
779
         
797
       {
810
       {
798
       if(force_lcd_update)
811
       if(force_lcd_update)
799
         {
812
         {
800
-          lcd.setCursor(0,line);lcd.print(" PID-C: ");
813
+          lcd.setCursor(0,line);lcdprintPGM(" PID-C: ");
801
           lcd.setCursor(13,line);lcd.print(itostr3(Kc));
814
           lcd.setCursor(13,line);lcd.print(itostr3(Kc));
802
         }
815
         }
803
         
816
         
834
       {
847
       {
835
       if(force_lcd_update)
848
       if(force_lcd_update)
836
         {
849
         {
837
-          lcd.setCursor(0,line);lcd.print(" Vmax ");
838
-          if(i==ItemC_vmaxx)lcd.print("x:");
839
-          if(i==ItemC_vmaxy)lcd.print("y:");
840
-          if(i==ItemC_vmaxz)lcd.print("z:");
841
-          if(i==ItemC_vmaxe)lcd.print("e:");
850
+          lcd.setCursor(0,line);lcdprintPGM(" Vmax ");
851
+          if(i==ItemC_vmaxx)lcdprintPGM("x:");
852
+          if(i==ItemC_vmaxy)lcdprintPGM("y:");
853
+          if(i==ItemC_vmaxz)lcdprintPGM("z:");
854
+          if(i==ItemC_vmaxe)lcdprintPGM("e:");
842
           lcd.setCursor(13,line);lcd.print(itostr3(max_feedrate[i-ItemC_vmaxx]/60));
855
           lcd.setCursor(13,line);lcd.print(itostr3(max_feedrate[i-ItemC_vmaxx]/60));
843
         }
856
         }
844
         
857
         
873
     {
886
     {
874
       if(force_lcd_update)
887
       if(force_lcd_update)
875
         {
888
         {
876
-          lcd.setCursor(0,line);lcd.print(" Vmin:");
889
+          lcd.setCursor(0,line);lcdprintPGM(" Vmin:");
877
           lcd.setCursor(13,line);lcd.print(itostr3(minimumfeedrate/60));
890
           lcd.setCursor(13,line);lcd.print(itostr3(minimumfeedrate/60));
878
         }
891
         }
879
         
892
         
907
     {
920
     {
908
       if(force_lcd_update)
921
       if(force_lcd_update)
909
         {
922
         {
910
-          lcd.setCursor(0,line);lcd.print(" VTrav min:");
923
+          lcd.setCursor(0,line);lcdprintPGM(" VTrav min:");
911
           lcd.setCursor(13,line);lcd.print(itostr3(mintravelfeedrate/60));
924
           lcd.setCursor(13,line);lcd.print(itostr3(mintravelfeedrate/60));
912
         }
925
         }
913
         
926
         
945
     {
958
     {
946
       if(force_lcd_update)
959
       if(force_lcd_update)
947
         {
960
         {
948
-          lcd.setCursor(0,line);lcd.print(" Amax ");
949
-          if(i==ItemC_amaxx)lcd.print("x:");
950
-          if(i==ItemC_amaxy)lcd.print("y:");
951
-          if(i==ItemC_amaxz)lcd.print("z:");
952
-          if(i==ItemC_amaxe)lcd.print("e:");
953
-          lcd.setCursor(13,line);lcd.print(itostr3(max_acceleration_units_per_sq_second[i-ItemC_amaxx]/100));lcd.print("00");
961
+          lcd.setCursor(0,line);lcdprintPGM(" Amax ");
962
+          if(i==ItemC_amaxx)lcdprintPGM("x:");
963
+          if(i==ItemC_amaxy)lcdprintPGM("y:");
964
+          if(i==ItemC_amaxz)lcdprintPGM("z:");
965
+          if(i==ItemC_amaxe)lcdprintPGM("e:");
966
+          lcd.setCursor(13,line);lcd.print(itostr3(max_acceleration_units_per_sq_second[i-ItemC_amaxx]/100));lcdprintPGM("00");
954
         }
967
         }
955
         
968
         
956
         if((activeline==line) )
969
         if((activeline==line) )
974
           {
987
           {
975
             if(encoderpos<1) encoderpos=1;
988
             if(encoderpos<1) encoderpos=1;
976
             if(encoderpos>990) encoderpos=990;
989
             if(encoderpos>990) encoderpos=990;
977
-            lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));lcd.print("00");
990
+            lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));lcdprintPGM("00");
978
           }
991
           }
979
         }
992
         }
980
       }break;
993
       }break;
982
     {
995
     {
983
         if(force_lcd_update)
996
         if(force_lcd_update)
984
         {
997
         {
985
-          lcd.setCursor(0,line);lcd.print(" A-retract:");
986
-          lcd.setCursor(13,line);lcd.print(ftostr3(retract_acceleration/100));lcd.print("00");
998
+          lcd.setCursor(0,line);lcdprintPGM(" A-retract:");
999
+          lcd.setCursor(13,line);lcd.print(ftostr3(retract_acceleration/100));lcdprintPGM("00");
987
         }
1000
         }
988
         
1001
         
989
         if((activeline==line) )
1002
         if((activeline==line) )
1008
           {
1021
           {
1009
             if(encoderpos<10) encoderpos=10;
1022
             if(encoderpos<10) encoderpos=10;
1010
             if(encoderpos>990) encoderpos=990;
1023
             if(encoderpos>990) encoderpos=990;
1011
-            lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));lcd.print("00");
1024
+            lcd.setCursor(13,line);lcd.print(itostr3(encoderpos));lcdprintPGM("00");
1012
           }
1025
           }
1013
         }
1026
         }
1014
       }break;
1027
       }break;
1016
          {
1029
          {
1017
       if(force_lcd_update)
1030
       if(force_lcd_update)
1018
         {
1031
         {
1019
-          lcd.setCursor(0,line);lcd.print(" Esteps/mm:");
1032
+          lcd.setCursor(0,line);lcdprintPGM(" Esteps/mm:");
1020
           lcd.setCursor(13,line);lcd.print(itostr4(axis_steps_per_unit[3]));
1033
           lcd.setCursor(13,line);lcd.print(itostr4(axis_steps_per_unit[3]));
1021
         }
1034
         }
1022
         
1035
         
1053
     {
1066
     {
1054
       if(force_lcd_update)
1067
       if(force_lcd_update)
1055
       {
1068
       {
1056
-        lcd.setCursor(0,line);lcd.print(" Store EPROM");
1069
+        lcd.setCursor(0,line);lcdprintPGM(" Store EPROM");
1057
       }
1070
       }
1058
       if((activeline==line) && CLICKED)
1071
       if((activeline==line) && CLICKED)
1059
       {
1072
       {
1067
     {
1080
     {
1068
       if(force_lcd_update)
1081
       if(force_lcd_update)
1069
       {
1082
       {
1070
-        lcd.setCursor(0,line);lcd.print(" Load EPROM");
1083
+        lcd.setCursor(0,line);lcdprintPGM(" Load EPROM");
1071
       }
1084
       }
1072
       if((activeline==line) && CLICKED)
1085
       if((activeline==line) && CLICKED)
1073
       {
1086
       {
1081
     {
1094
     {
1082
       if(force_lcd_update)
1095
       if(force_lcd_update)
1083
       {
1096
       {
1084
-        lcd.setCursor(0,line);lcd.print(" Restore Failsafe");
1097
+        lcd.setCursor(0,line);lcdprintPGM(" Restore Failsafe");
1085
       }
1098
       }
1086
       if((activeline==line) && CLICKED)
1099
       if((activeline==line) && CLICKED)
1087
       {
1100
       {
1165
       {
1178
       {
1166
         if(force_lcd_update)
1179
         if(force_lcd_update)
1167
         {
1180
         {
1168
-          lcd.setCursor(0,line);lcd.print(" File");
1181
+          lcd.setCursor(0,line);lcdprintPGM(" File");
1169
         }
1182
         }
1170
         if((activeline==line) && CLICKED)
1183
         if((activeline==line) && CLICKED)
1171
         {
1184
         {
1185
           if(true)
1198
           if(true)
1186
           #endif
1199
           #endif
1187
           {
1200
           {
1188
-            lcd.print(" \004Refresh");
1201
+            lcdprintPGM(" \004Refresh");
1189
           }
1202
           }
1190
           else
1203
           else
1191
           {
1204
           {
1192
-            lcd.print(" \004Insert Card");
1205
+            lcdprintPGM(" \004Insert Card");
1193
           }
1206
           }
1194
           
1207
           
1195
         }
1208
         }
1210
         {
1223
         {
1211
           card.getfilename(i-2);
1224
           card.getfilename(i-2);
1212
           //Serial.print("Filenr:");Serial.println(i-2);
1225
           //Serial.print("Filenr:");Serial.println(i-2);
1213
-          lcd.setCursor(0,line);lcd.print(" ");lcd.print(card.filename);
1226
+          lcd.setCursor(0,line);lcdprintPGM(" ");lcd.print(card.filename);
1214
         }
1227
         }
1215
         if((activeline==line) && CLICKED)
1228
         if((activeline==line) && CLICKED)
1216
         {
1229
         {
1292
     { 
1305
     { 
1293
       case ItemM_watch:
1306
       case ItemM_watch:
1294
       {
1307
       {
1295
-        if(force_lcd_update) {lcd.setCursor(0,line);lcd.print(" Watch   \x7E");}
1308
+        if(force_lcd_update) {lcd.setCursor(0,line);lcdprintPGM(" Watch   \x7E");}
1296
         if((activeline==line)&&CLICKED)
1309
         if((activeline==line)&&CLICKED)
1297
         {
1310
         {
1298
           BLOCK;
1311
           BLOCK;
1302
       } break;
1315
       } break;
1303
       case ItemM_prepare:
1316
       case ItemM_prepare:
1304
       {
1317
       {
1305
-        if(force_lcd_update) {lcd.setCursor(0,line);lcd.print(" Prepare \x7E");}
1318
+        if(force_lcd_update) {lcd.setCursor(0,line);lcdprintPGM(" Prepare \x7E");}
1306
         if((activeline==line)&&CLICKED)
1319
         if((activeline==line)&&CLICKED)
1307
         {
1320
         {
1308
           BLOCK;
1321
           BLOCK;
1313
        
1326
        
1314
       case ItemM_control:
1327
       case ItemM_control:
1315
       {
1328
       {
1316
-        if(force_lcd_update) {lcd.setCursor(0,line);lcd.print(" Control \x7E");}
1329
+        if(force_lcd_update) {lcd.setCursor(0,line);lcdprintPGM(" Control \x7E");}
1317
         if((activeline==line)&&CLICKED)
1330
         if((activeline==line)&&CLICKED)
1318
         {
1331
         {
1319
           BLOCK;
1332
           BLOCK;
1334
           #endif
1347
           #endif
1335
           {
1348
           {
1336
             if(card.sdprinting)
1349
             if(card.sdprinting)
1337
-              lcd.print(" Stop Print   \x7E");
1350
+              lcdprintPGM(" Stop Print   \x7E");
1338
             else
1351
             else
1339
-              lcd.print(" Card Menu    \x7E");
1352
+              lcdprintPGM(" Card Menu    \x7E");
1340
           }
1353
           }
1341
           else
1354
           else
1342
           {
1355
           {
1343
-           lcd.print(" No Card"); 
1356
+           lcdprintPGM(" No Card"); 
1344
           }
1357
           }
1345
         }
1358
         }
1346
         #ifdef CARDINSERTED
1359
         #ifdef CARDINSERTED

Loading…
Cancel
Save