From ab154d55927776add58c878f7de94e82b07bee1c Mon Sep 17 00:00:00 2001 From: Bernhard Kubicek Date: Wed, 9 Nov 2011 20:27:15 +0100 Subject: [PATCH] project progmem finished: total change with ultipanel: 2456 byte free ram initial. now: 4374 ram. --- Marlin/EEPROMwrite.h | 214 ++++++++++++++++++++--------------------- Marlin/Marlin.h | 49 ++++++++-- Marlin/Marlin.pde | 124 +++++++++++++++--------- Marlin/cardreader.h | 4 +- Marlin/cardreader.pde | 38 +++++--- Marlin/stepper.cpp | 4 +- Marlin/temperature.cpp | 23 +++-- Marlin/ultralcd.h | 1 + Marlin/ultralcd.pde | 17 +++- Marlin/watchdog.pde | 7 +- 10 files changed, 294 insertions(+), 187 deletions(-) diff --git a/Marlin/EEPROMwrite.h b/Marlin/EEPROMwrite.h index ae31bc9ec..fcb3d8d39 100644 --- a/Marlin/EEPROMwrite.h +++ b/Marlin/EEPROMwrite.h @@ -25,18 +25,9 @@ template int EEPROM_readAnything(int &ee, T& value) } //====================================================================================== -#include +#define SERIAL_ECHOPAIR(name,value) {SERIAL_ECHOPGM(name);SERIAL_ECHO(value);} + -void serialprintPGM(const char *str) -{ - char ch=pgm_read_byte(str); - while(ch) - { - Serial.print(ch); - ch=pgm_read_byte(++str); - } -} -#define SerialprintPGM(x) serialprintPGM(PSTR(x)) #define EEPROM_OFFSET 100 @@ -48,8 +39,9 @@ void serialprintPGM(const char *str) // ALSO: always make sure the variables in the Store and retrieve sections are in the same order. #define EEPROM_VERSION "V04" -void StoreSettings() +inline void StoreSettings() { +#ifdef EEPROM_SETTINGS char ver[4]= "000"; int i=EEPROM_OFFSET; EEPROM_writeAnything(i,ver); // invalidate data first @@ -75,107 +67,115 @@ void StoreSettings() char ver2[4]=EEPROM_VERSION; i=EEPROM_OFFSET; EEPROM_writeAnything(i,ver2); // validate data - SerialprintPGM("echo: Settings Stored\n"); + SERIAL_ECHO_START; + SERIAL_ECHOLNPGM("Settings Stored"); +#endif //EEPROM_SETTINGS } -void RetrieveSettings(bool def=false) +inline void RetrieveSettings(bool def=false) { // if def=true, the default values will be used - int i=EEPROM_OFFSET; - char stored_ver[4]; - char ver[4]=EEPROM_VERSION; - EEPROM_readAnything(i,stored_ver); //read stored version - // SERIAL_ECHOLN("Version: [" << ver << "] Stored version: [" << stored_ver << "]"); - if ((!def)&&(strncmp(ver,stored_ver,3)==0)) - { // version number match - EEPROM_readAnything(i,axis_steps_per_unit); - EEPROM_readAnything(i,max_feedrate); - EEPROM_readAnything(i,max_acceleration_units_per_sq_second); - EEPROM_readAnything(i,acceleration); - EEPROM_readAnything(i,retract_acceleration); - EEPROM_readAnything(i,minimumfeedrate); - EEPROM_readAnything(i,mintravelfeedrate); - EEPROM_readAnything(i,minsegmenttime); - EEPROM_readAnything(i,max_xy_jerk); - EEPROM_readAnything(i,max_z_jerk); - #ifndef PIDTEMP - float Kp,Ki,Kd; - #endif - EEPROM_readAnything(i,Kp); - EEPROM_readAnything(i,Ki); - EEPROM_readAnything(i,Kd); + #ifdef EEPROM_SETTINGS + int i=EEPROM_OFFSET; + char stored_ver[4]; + char ver[4]=EEPROM_VERSION; + EEPROM_readAnything(i,stored_ver); //read stored version + // SERIAL_ECHOLN("Version: [" << ver << "] Stored version: [" << stored_ver << "]"); + if ((!def)&&(strncmp(ver,stored_ver,3)==0)) + { // version number match + EEPROM_readAnything(i,axis_steps_per_unit); + EEPROM_readAnything(i,max_feedrate); + EEPROM_readAnything(i,max_acceleration_units_per_sq_second); + EEPROM_readAnything(i,acceleration); + EEPROM_readAnything(i,retract_acceleration); + EEPROM_readAnything(i,minimumfeedrate); + EEPROM_readAnything(i,mintravelfeedrate); + EEPROM_readAnything(i,minsegmenttime); + EEPROM_readAnything(i,max_xy_jerk); + EEPROM_readAnything(i,max_z_jerk); + #ifndef PIDTEMP + float Kp,Ki,Kd; + #endif + EEPROM_readAnything(i,Kp); + EEPROM_readAnything(i,Ki); + EEPROM_readAnything(i,Kd); - SerialprintPGM("echo: Stored settings retreived:\n"); - } - else - { - float tmp1[]=DEFAULT_AXIS_STEPS_PER_UNIT; - float tmp2[]=DEFAULT_MAX_FEEDRATE; - long tmp3[]=DEFAULT_MAX_ACCELERATION; - for (short i=0;i<4;i++) - { - axis_steps_per_unit[i]=tmp1[i]; - max_feedrate[i]=tmp2[i]; - max_acceleration_units_per_sq_second[i]=tmp3[i]; + SERIAL_ECHO_START; + SERIAL_ECHOLNPGM("Stored settings retreived:"); } - acceleration=DEFAULT_ACCELERATION; - retract_acceleration=DEFAULT_RETRACT_ACCELERATION; - minimumfeedrate=DEFAULT_MINIMUMFEEDRATE; - minsegmenttime=DEFAULT_MINSEGMENTTIME; - mintravelfeedrate=DEFAULT_MINTRAVELFEEDRATE; - max_xy_jerk=DEFAULT_XYJERK; - max_z_jerk=DEFAULT_ZJERK; - SerialprintPGM("echo: Using Default settings:\n"); - } - SerialprintPGM("echo: Steps per unit:\n M92 X"); - Serial.print(axis_steps_per_unit[0]); - SerialprintPGM(" Y"); - Serial.print(axis_steps_per_unit[1]); - SerialprintPGM(" Z"); - Serial.print(axis_steps_per_unit[2]); - SerialprintPGM(" E"); - Serial.print(axis_steps_per_unit[3]); - - SerialprintPGM("\nMaximum feedrates (mm/s):\n M203 X" ); - Serial.print(max_feedrate[0]/60); - SerialprintPGM(" Y" ); - Serial.print(max_feedrate[1]/60 ); - SerialprintPGM(" Z" ); - Serial.print(max_feedrate[2]/60 ); - SerialprintPGM(" E" ); - Serial.print(max_feedrate[3]/60); - SerialprintPGM("\nMaximum Acceleration (mm/s2):\n M201 X" ); - Serial.print(max_acceleration_units_per_sq_second[0] ); - SerialprintPGM(" Y" ); - Serial.print(max_acceleration_units_per_sq_second[1] ); - SerialprintPGM(" Z" ); - Serial.print(max_acceleration_units_per_sq_second[2] ); - SerialprintPGM(" E" ); - Serial.print(max_acceleration_units_per_sq_second[3]); - SerialprintPGM("\necho: Acceleration: S=acceleration, T=retract acceleration\n M204 S" ); - Serial.print(acceleration ); - SerialprintPGM(" T" ); - Serial.print(retract_acceleration); - 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)"); - SerialprintPGM(" M205 S" ); - Serial.print(minimumfeedrate/60 ); - SerialprintPGM(" T" ); - Serial.print(mintravelfeedrate/60 ); - SerialprintPGM(" B" ); - Serial.print(minsegmenttime ); - SerialprintPGM(" X" ); - Serial.print(max_xy_jerk/60 ); - SerialprintPGM(" Z" ); - Serial.print(max_z_jerk/60); - SerialprintPGM("\n" ); - #ifdef PIDTEMP - SerialprintPGM("PID settings:"); - SerialprintPGM(" M301 P" ); - Serial.print(Kp ); - SerialprintPGM(" I" ); - Serial.print(Ki ); - SerialprintPGM(" D" ); - Serial.print(Kd); + else + { + float tmp1[]=DEFAULT_AXIS_STEPS_PER_UNIT; + float tmp2[]=DEFAULT_MAX_FEEDRATE; + long tmp3[]=DEFAULT_MAX_ACCELERATION; + for (short i=0;i<4;i++) + { + axis_steps_per_unit[i]=tmp1[i]; + max_feedrate[i]=tmp2[i]; + max_acceleration_units_per_sq_second[i]=tmp3[i]; + } + acceleration=DEFAULT_ACCELERATION; + retract_acceleration=DEFAULT_RETRACT_ACCELERATION; + minimumfeedrate=DEFAULT_MINIMUMFEEDRATE; + minsegmenttime=DEFAULT_MINSEGMENTTIME; + mintravelfeedrate=DEFAULT_MINTRAVELFEEDRATE; + max_xy_jerk=DEFAULT_XYJERK; + max_z_jerk=DEFAULT_ZJERK; + SERIAL_ECHO_START; + SERIAL_ECHOLN("Using Default settings:"); + } + #ifdef EEPROM_CHITCHAT + SERIAL_ECHO_START; + SERIAL_ECHOLNPGM("Steps per unit:"); + SERIAL_ECHO_START; + SERIAL_ECHOPAIR(" M92 X",axis_steps_per_unit[0]); + SERIAL_ECHOPAIR(" Y",axis_steps_per_unit[1]); + SERIAL_ECHOPAIR(" Z",axis_steps_per_unit[2]); + SERIAL_ECHOPAIR(" E",axis_steps_per_unit[3]); + SERIAL_ECHOLN(""); + + SERIAL_ECHO_START; + SERIAL_ECHOLNPGM("Maximum feedrates (mm/s):"); + SERIAL_ECHO_START; + SERIAL_ECHOPAIR(" M203 X",max_feedrate[0]/60); + SERIAL_ECHOPAIR(" Y",max_feedrate[1]/60 ); + SERIAL_ECHOPAIR(" Z", max_feedrate[2]/60 ); + SERIAL_ECHOPAIR(" E", max_feedrate[3]/60); + SERIAL_ECHOLN(""); + SERIAL_ECHO_START; + SERIAL_ECHOLNPGM("Maximum Acceleration (mm/s2):"); + SERIAL_ECHO_START; + SERIAL_ECHOPAIR(" M201 X" ,max_acceleration_units_per_sq_second[0] ); + SERIAL_ECHOPAIR(" Y" , max_acceleration_units_per_sq_second[1] ); + SERIAL_ECHOPAIR(" Z" ,max_acceleration_units_per_sq_second[2] ); + SERIAL_ECHOPAIR(" E" ,max_acceleration_units_per_sq_second[3]); + SERIAL_ECHOLN(""); + SERIAL_ECHO_START; + SERIAL_ECHOLNPGM("Acceleration: S=acceleration, T=retract acceleration"); + SERIAL_ECHO_START; + SERIAL_ECHOPAIR(" M204 S",acceleration ); + SERIAL_ECHOPAIR(" T" ,retract_acceleration); + SERIAL_ECHOLN(""); + SERIAL_ECHO_START; + SERIAL_ECHOLNPGM("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)"); + SERIAL_ECHO_START; + SERIAL_ECHOPAIR(" M205 S",minimumfeedrate/60 ); + SERIAL_ECHOPAIR(" T" ,mintravelfeedrate/60 ); + SERIAL_ECHOPAIR(" B" ,minsegmenttime ); + SERIAL_ECHOPAIR(" X" ,max_xy_jerk/60 ); + SERIAL_ECHOPAIR(" Z" ,max_z_jerk/60); + SERIAL_ECHOLN(""); + #ifdef PIDTEMP + SERIAL_ECHO_START; + SERIAL_ECHOLNPGM("PID settings:"); + SERIAL_ECHO_START; + SERIAL_ECHOPAIR(" M301 P",Kp ); + SERIAL_ECHOPAIR(" I" ,Ki ); + SERIAL_ECHOPAIR(" D" ,Kd); + SERIAL_ECHOLN(""); + #endif #endif + + #endif //EEPROM_SETTINGS } #endif diff --git a/Marlin/Marlin.h b/Marlin/Marlin.h index 61b56fb97..99cd8021b 100644 --- a/Marlin/Marlin.h +++ b/Marlin/Marlin.h @@ -5,14 +5,49 @@ // Licence: GPL #include #include "fastio.h" - #include "streaming.h" -#define SERIAL_ECHO(x) Serial << "echo: " << x; -#define SERIAL_ECHOLN(x) Serial << "echo: "< + +//#define SERIAL_ECHO(x) Serial << "echo: " << x; +//#define SERIAL_ECHOLN(x) Serial << "echo: "<= (MAX_CMD_SIZE - 1)) + int16_t n=card.get(); + serial_char = (char)n; + if(serial_char == '\n' || serial_char == '\r' || serial_char == ':' || serial_count >= (MAX_CMD_SIZE - 1)||n==-1) { if(card.eof()){ card.sdprinting = false; - SERIAL_PROTOCOL("Done printing file"); + SERIAL_PROTOCOLLNPGM("Done printing file"); stoptime=millis(); char time[30]; unsigned long t=(stoptime-starttime)/1000; @@ -377,6 +391,7 @@ inline void get_command() min=t/60; sec=t%60; sprintf(time,"%i min, %i sec",min,sec); + SERIAL_ECHO_START; SERIAL_ECHOLN(time); LCD_MESSAGE(time); card.checkautostart(true); @@ -398,6 +413,7 @@ inline void get_command() if(!comment_mode) cmdbuffer[bufindw][serial_count++] = serial_char; } } + #endif //SDSUPPORT } @@ -473,6 +489,7 @@ inline void process_commands() previous_millis_cmd = millis(); return; case 4: // G4 dwell + LCD_MESSAGEPGM("DWELL..."); codenum = 0; if(code_seen('P')) codenum = code_value(); // milliseconds to wait if(code_seen('S')) codenum = code_value() * 1000; // seconds to wait @@ -533,13 +550,14 @@ inline void process_commands() #ifdef SDSUPPORT case 20: // M20 - list SD card - SERIAL_PROTOCOLLN("Begin file list"); + SERIAL_PROTOCOLLNPGM("Begin file list"); card.ls(); - SERIAL_PROTOCOLLN("End file list"); + SERIAL_PROTOCOLLNPGM("End file list"); break; case 21: // M21 - init SD card card.initsd(); + break; case 22: //M22 - release SD card card.release(); @@ -592,7 +610,8 @@ inline void process_commands() min=t/60; sec=t%60; sprintf(time,"%i min, %i sec",min,sec); - SERIAL_ERRORLN(time); + SERIAL_ECHO_START; + SERIAL_ECHOLN(time); LCD_MESSAGE(time); } break; @@ -637,7 +656,7 @@ inline void process_commands() bt = degBed(); #endif #if (TEMP_0_PIN > -1) || defined (HEATER_USES_AD595) - SERIAL_PROTOCOL("ok T:"); + SERIAL_PROTOCOLPGM("ok T:"); SERIAL_PROTOCOL(tt); #if TEMP_1_PIN > -1 #ifdef PIDTEMP @@ -654,13 +673,14 @@ inline void process_commands() SERIAL_PROTOCOLLN(""); #endif //TEMP_1_PIN #else - SERIAL_ERRORLN("No thermistors - no temp"); + SERIAL_ERROR_START; + SERIAL_ERRORLNPGM("No thermistors - no temp"); #endif return; break; case 109: {// M109 - Wait for extruder heater to reach target. - LCD_MESSAGE("Heating..."); + LCD_MESSAGEPGM("Heating..."); if (code_seen('S')) setTargetHotend0(code_value()); setWatch(); @@ -681,7 +701,8 @@ inline void process_commands() #endif //TEMP_RESIDENCY_TIME if( (millis() - codenum) > 1000 ) { //Print Temp Reading every 1 second while heating up/cooling down - SERIAL_PROTOCOLLN("T:"<< degHotend0() ); + SERIAL_PROTOCOLPGM("T:"); + SERIAL_PROTOCOLLN( degHotend0() ); codenum = millis(); } manage_heater(); @@ -697,12 +718,13 @@ inline void process_commands() } #endif //TEMP_RESIDENCY_TIME } - LCD_MESSAGE("Heating done."); + LCD_MESSAGEPGM("Heating done."); starttime=millis(); } break; case 190: // M190 - Wait bed for heater to reach target. #if TEMP_1_PIN > -1 + LCD_MESSAGEPGM("Bed Heating."); if (code_seen('S')) setTargetBed(code_value()); codenum = millis(); while(isHeatingBed()) @@ -710,12 +732,17 @@ inline void process_commands() if( (millis()-codenum) > 1000 ) //Print Temp Reading every 1 second while heating up. { float tt=degHotend0(); - SERIAL_PROTOCOLLN("T:"< -1) - SERIAL_PROTOCOL("x_min:"); + SERIAL_PROTOCOLPGM("x_min:"); SERIAL_PROTOCOL(((READ(X_MIN_PIN)^ENDSTOPS_INVERTING)?"H ":"L ")); #endif #if (X_MAX_PIN > -1) - SERIAL_PROTOCOL("x_max:"); + SERIAL_PROTOCOLPGM("x_max:"); SERIAL_PROTOCOL(((READ(X_MAX_PIN)^ENDSTOPS_INVERTING)?"H ":"L ")); #endif #if (Y_MIN_PIN > -1) - SERIAL_PROTOCOL("y_min:"); + SERIAL_PROTOCOLPGM("y_min:"); SERIAL_PROTOCOL(((READ(Y_MIN_PIN)^ENDSTOPS_INVERTING)?"H ":"L ")); #endif #if (Y_MAX_PIN > -1) - SERIAL_PROTOCOL("y_max:"); + SERIAL_PROTOCOLPGM("y_max:"); SERIAL_PROTOCOL(((READ(Y_MAX_PIN)^ENDSTOPS_INVERTING)?"H ":"L ")); #endif #if (Z_MIN_PIN > -1) - SERIAL_PROTOCOL("z_min:"); + SERIAL_PROTOCOLPGM("z_min:"); SERIAL_PROTOCOL(((READ(Z_MIN_PIN)^ENDSTOPS_INVERTING)?"H ":"L ")); #endif #if (Z_MAX_PIN > -1) - SERIAL_PROTOCOL("z_max:"); + SERIAL_PROTOCOLPGM("z_max:"); SERIAL_PROTOCOL(((READ(Z_MAX_PIN)^ENDSTOPS_INVERTING)?"H ":"L ")); #endif SERIAL_PROTOCOLLN(""); @@ -897,7 +925,10 @@ inline void process_commands() } else { - SERIAL_ECHOLN("Unknown command:\""< -1) pinMode(PS_ON_PIN,INPUT); - SERIAL_ERRORLN("Printer halted. kill() called !!"); + SERIAL_ERROR_START; + SERIAL_ERRORLNPGM("Printer halted. kill() called !!"); + LCD_MESSAGEPGM("KILLED. "); while(1); // Wait for reset } diff --git a/Marlin/cardreader.h b/Marlin/cardreader.h index 03696fa61..b3f514f61 100644 --- a/Marlin/cardreader.h +++ b/Marlin/cardreader.h @@ -30,8 +30,8 @@ public: inline void ls() {root.ls();}; - inline bool eof() { sdpos = file.curPosition();return sdpos>=filesize ;}; - inline char get() { int16_t n = file.read(); return (n==-1)?'\n':(char)n;}; + inline bool eof() { return sdpos>=filesize ;}; + inline int16_t get() { sdpos = file.curPosition();return (int16_t)file.read();}; inline void setIndex(long index) {sdpos = index;file.seekSet(index);}; public: diff --git a/Marlin/cardreader.pde b/Marlin/cardreader.pde index cd4bfeb7a..605af11bf 100644 --- a/Marlin/cardreader.pde +++ b/Marlin/cardreader.pde @@ -29,20 +29,24 @@ void CardReader::initsd() if (!card.init(SPI_FULL_SPEED,SDSS)) { //if (!card.init(SPI_HALF_SPEED,SDSS)) - SERIAL_ECHOLN("SD init fail"); + SERIAL_ECHO_START; + SERIAL_ECHOLNPGM("SD init fail"); } else if (!volume.init(&card)) { - SERIAL_ERRORLN("volume.init failed"); + SERIAL_ERROR_START; + SERIAL_ERRORLNPGM("volume.init failed"); } else if (!root.openRoot(&volume)) { - SERIAL_ERRORLN("openRoot failed"); + SERIAL_ERROR_START; + SERIAL_ERRORLNPGM("openRoot failed"); } else { cardOK = true; - SERIAL_ECHOLN("SD card ok"); + SERIAL_ECHO_START; + SERIAL_ECHOLNPGM("SD card ok"); } #endif //SDSS } @@ -77,13 +81,16 @@ void CardReader::selectFile(char* name) if (file.open(&root, name, O_READ)) { filesize = file.fileSize(); - SERIAL_PROTOCOLLN("File opened:"<= maxttemp_0) { target_raw[TEMPSENSOR_HOTEND_0] = 0; analogWrite(HEATER_0_PIN, 0); - SERIAL_ERRORLN("Temperature extruder 0 switched off. MAXTEMP triggered !!"); + SERIAL_ERROR_START; + SERIAL_ERRORLNPGM("Temperature extruder 0 switched off. MAXTEMP triggered !!"); kill(); } #endif @@ -507,7 +509,8 @@ ISR(TIMER0_COMPB_vect) target_raw[TEMPSENSOR_HOTEND_1] = 0; if(current_raw[2] >= maxttemp_1) { analogWrite(HEATER_2_PIN, 0); - SERIAL_ERRORLN("Temperature extruder 1 switched off. MAXTEMP triggered !!"); + SERIAL_ERROR_START; + SERIAL_ERRORLNPGM("Temperature extruder 1 switched off. MAXTEMP triggered !!"); kill() } #endif @@ -518,7 +521,8 @@ ISR(TIMER0_COMPB_vect) if(current_raw[TEMPSENSOR_HOTEND_0] <= minttemp_0) { target_raw[TEMPSENSOR_HOTEND_0] = 0; analogWrite(HEATER_0_PIN, 0); - SERIAL_ERRORLN("Temperature extruder 0 switched off. MINTEMP triggered !!"); + SERIAL_ERROR_START; + SERIAL_ERRORLNPGM("Temperature extruder 0 switched off. MINTEMP triggered !!"); kill(); } #endif @@ -529,7 +533,8 @@ ISR(TIMER0_COMPB_vect) if(current_raw[TEMPSENSOR_HOTEND_1] <= minttemp_1) { target_raw[TEMPSENSOR_HOTEND_1] = 0; analogWrite(HEATER_2_PIN, 0); - SERIAL_ERRORLN("Temperature extruder 1 switched off. MINTEMP triggered !!"); + SERIAL_ERROR_START; + SERIAL_ERRORLNPGM("Temperature extruder 1 switched off. MINTEMP triggered !!"); kill(); } #endif @@ -540,7 +545,8 @@ ISR(TIMER0_COMPB_vect) if(current_raw[1] <= bed_minttemp) { target_raw[1] = 0; WRITE(HEATER_1_PIN, 0); - SERIAL_ERRORLN("Temperatur heated bed switched off. MINTEMP triggered !!"); + SERIAL_ERROR_START; + SERIAL_ERRORLNPGM("Temperatur heated bed switched off. MINTEMP triggered !!"); kill(); } #endif @@ -551,7 +557,8 @@ ISR(TIMER0_COMPB_vect) if(current_raw[1] >= bed_maxttemp) { target_raw[1] = 0; WRITE(HEATER_1_PIN, 0); - SERIAL_ERRORLN("Temperature heated bed switched off. MAXTEMP triggered !!"); + SERIAL_ERROR_START; + SERIAL_ERRORLNPGM("Temperature heated bed switched off. MAXTEMP triggered !!"); kill(); } #endif diff --git a/Marlin/ultralcd.h b/Marlin/ultralcd.h index 0822e502b..4c725329d 100644 --- a/Marlin/ultralcd.h +++ b/Marlin/ultralcd.h @@ -83,6 +83,7 @@ #define LCD_MESSAGE(x) lcd_status(x); + #define LCD_MESSAGEPGM(x) lcd_statuspgm(PSTR(x)); #define LCD_STATUS lcd_status() #else //no lcd #define LCD_STATUS diff --git a/Marlin/ultralcd.pde b/Marlin/ultralcd.pde index 91d1a54a8..59edb3470 100644 --- a/Marlin/ultralcd.pde +++ b/Marlin/ultralcd.pde @@ -67,6 +67,18 @@ void lcd_status(const char* message) strncpy(messagetext,message,LCD_WIDTH); } +void lcd_statuspgm(const char* message) +{ + char ch=pgm_read_byte(message); + char *target=messagetext; + while(ch) + { + *target=ch; + target++; + ch=pgm_read_byte(++message); + } +} + inline void clear() { lcd.clear(); @@ -105,7 +117,7 @@ void lcd_init() lcd.createChar(2,Thermometer); lcd.createChar(3,uplevel); lcd.createChar(4,refresh); - LCD_MESSAGE(fillto(LCD_WIDTH,"UltiMarlin ready.")); + LCD_MESSAGEPGM("UltiMarlin ready."); } @@ -1369,7 +1381,8 @@ void MainMenu::showMainMenu() }break; #endif default: - SERIAL_ERRORLN("Something is wrong in the MenuStructure."); + SERIAL_ERROR_START; + SERIAL_ERRORLNPGM("Something is wrong in the MenuStructure."); break; } } diff --git a/Marlin/watchdog.pde b/Marlin/watchdog.pde index 167bc633d..9cf710a0c 100644 --- a/Marlin/watchdog.pde +++ b/Marlin/watchdog.pde @@ -41,10 +41,11 @@ ISR(WDT_vect) { #ifdef RESET_MANUAL - LCD_MESSAGE("Please Reset!"); - SERIAL_ERRORLN("Something is wrong, please turn off the printer."); + LCD_MESSAGEPGM("Please Reset!"); + SERIAL_ERROR_START; + SERIAL_ERRORLNPGM("Something is wrong, please turn off the printer."); #else - LCD_MESSAGE("Timeout, resetting!"); + LCD_MESSAGEPGM("Timeout, resetting!"); #endif //disable watchdog, it will survife reboot. WDTCSR |= (1<