From 900e0c9bf23f7df6a2057af4b2c1f166e55e9163 Mon Sep 17 00:00:00 2001 From: Bernhard Kubicek Date: Sun, 6 Nov 2011 17:33:09 +0100 Subject: [PATCH] overworked the serial responses. Quite difficult, since many texts are Pronterface protocol. --- Marlin/EEPROMwrite.h | 32 ++++++------- Marlin/Makefile | 1 + Marlin/Marlin.h | 10 ++-- Marlin/Marlin.pde | 97 +++++++++++++++++++++------------------ Marlin/motion_control.cpp | 2 +- Marlin/stepper.cpp | 2 +- Marlin/temperature.cpp | 27 ++++------- Marlin/ultralcd.pde | 4 +- Marlin/watchdog.pde | 2 +- 9 files changed, 90 insertions(+), 87 deletions(-) diff --git a/Marlin/EEPROMwrite.h b/Marlin/EEPROMwrite.h index ea843344f4..dba2d443e5 100644 --- a/Marlin/EEPROMwrite.h +++ b/Marlin/EEPROMwrite.h @@ -59,7 +59,7 @@ void StoreSettings() { char ver2[4]=EEPROM_VERSION; i=EEPROM_OFFSET; EEPROM_writeAnything(i,ver2); // validate data - ECHOLN("Settings Stored"); + SERIAL_ECHOLN("Settings Stored"); } @@ -68,7 +68,7 @@ void RetrieveSettings(bool def=false){ // if def=true, the default values will char stored_ver[4]; char ver[4]=EEPROM_VERSION; EEPROM_readAnything(i,stored_ver); //read stored version -// ECHOLN("Version: [" << ver << "] Stored version: [" << stored_ver << "]"); +// 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); @@ -87,7 +87,7 @@ void RetrieveSettings(bool def=false){ // if def=true, the default values will EEPROM_readAnything(i,Ki); EEPROM_readAnything(i,Kd); - ECHOLN("Stored settings retreived:"); + SERIAL_ECHOLN("Stored settings retreived:"); } else { float tmp1[]=DEFAULT_AXIS_STEPS_PER_UNIT; @@ -105,21 +105,21 @@ void RetrieveSettings(bool def=false){ // if def=true, the default values will mintravelfeedrate=DEFAULT_MINTRAVELFEEDRATE; max_xy_jerk=DEFAULT_XYJERK; max_z_jerk=DEFAULT_ZJERK; - ECHOLN("Using Default settings:"); + SERIAL_ECHOLN("Using Default settings:"); } - ECHOLN("Steps per unit:"); - 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)); - ECHOLN("Maximum feedrates (mm/s):"); - 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)); - ECHOLN("Maximum Acceleration (mm/s2):"); - 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)); - ECHOLN("Acceleration: S=acceleration, T=retract acceleration"); - ECHOLN(" M204 S" <<_FLOAT(acceleration,2) << " T" << _FLOAT(retract_acceleration,2)); - 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)"); - 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)); + SERIAL_ECHOLN("Steps per unit:"); + 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)); + SERIAL_ECHOLN("Maximum feedrates (mm/s):"); + 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)); + SERIAL_ECHOLN("Maximum Acceleration (mm/s2):"); + 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)); + SERIAL_ECHOLN("Acceleration: S=acceleration, T=retract acceleration"); + SERIAL_ECHOLN(" M204 S" <<_FLOAT(acceleration,2) << " T" << _FLOAT(retract_acceleration,2)); + 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)"); + 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)); #ifdef PIDTEMP - ECHOLN("PID settings:"); - ECHOLN(" M301 P" << _FLOAT(Kp,3) << " I" << _FLOAT(Ki,3) << " D" << _FLOAT(Kd,3)); + SERIAL_ECHOLN("PID settings:"); + SERIAL_ECHOLN(" M301 P" << _FLOAT(Kp,3) << " I" << _FLOAT(Ki,3) << " D" << _FLOAT(Kd,3)); #endif } diff --git a/Marlin/Makefile b/Marlin/Makefile index f456e3cbd4..0504319f72 100644 --- a/Marlin/Makefile +++ b/Marlin/Makefile @@ -14,6 +14,7 @@ UPLOAD_SPEED = 115200 UPLOAD_PROTOCOL = stk500v2 BUILD_MCU = atmega2560 BUILD_F_CPU = 16000000L +TERM=bash # getting undefined reference to `__cxa_pure_virtual' #~ [http://www.arduino.cc/cgi-bin/yabb2/YaBB.pl?num=1254180518 Arduino Forum - Makefile] diff --git a/Marlin/Marlin.h b/Marlin/Marlin.h index e56b67128e..06f701d034 100644 --- a/Marlin/Marlin.h +++ b/Marlin/Marlin.h @@ -6,9 +6,11 @@ #include #include "fastio.h" - -#define ECHO(x) Serial << "echo: " << x; -#define ECHOLN(x) Serial << "echo: "<- 1 if(root.isOpen()) root.close(); - if (!card.init(SPI_FULL_SPEED,SDSS)){ + if (!card.init(SPI_FULL_SPEED,SDSS)) + { //if (!card.init(SPI_HALF_SPEED,SDSS)) - Serial.println("SD init fail"); + SERIAL_ECHOLN("SD init fail"); } else if (!volume.init(&card)) - Serial.println("volume.init failed"); + { + SERIAL_ERRORLN("volume.init failed"); + } else if (!root.openRoot(&volume)) - Serial.println("openRoot failed"); + { + SERIAL_ERRORLN("openRoot failed"); + } else - { + { sdactive = true; - Serial.println("SD card ok"); - } + SERIAL_ECHOLN("SD card ok"); + } #endif //SDSS } @@ -214,7 +221,7 @@ inline void write_command(char *buf){ //Serial.println(begin); file.write(begin); if (file.writeError){ - Serial.println("error writing to file"); + SERIAL_ERRORLN("error writing to file"); } } #endif //SDSUPPORT @@ -227,7 +234,7 @@ void enquecommand(const char *cmd) { //this is dangerous if a mixing of serial and this happsens strcpy(&(cmdbuffer[bufindw][0]),cmd); - Serial.print("en:");Serial.println(cmdbuffer[bufindw]); + SERIAL_ECHOLN("enqueing \""<= filesize){ sdmode = false; - Serial.println("Done printing file"); - stoptime=millis(); - char time[30]; - unsigned long t=(stoptime-starttime)/1000; - int sec,min; - min=t/60; - sec=t%60; - sprintf(time,"%i min, %i sec",min,sec); - Serial.println(time); - LCD_MESSAGE(time); - checkautostart(true); + Serial.println("echo: Done printing file"); + stoptime=millis(); + char time[30]; + unsigned long t=(stoptime-starttime)/1000; + int sec,min; + min=t/60; + sec=t%60; + sprintf(time,"echo: %i min, %i sec",min,sec); + Serial.println(time); + LCD_MESSAGE(time); + checkautostart(true); } if(!serial_count) return; //if empty line cmdbuffer[bufindw][serial_count] = 0; //terminate string @@ -721,7 +728,7 @@ inline void process_commands() case 24: //M24 - Start SD print if(sdactive){ sdmode = true; - starttime=millis(); + starttime=millis(); } break; case 25: //M25 - Pause SD print @@ -774,19 +781,19 @@ inline void process_commands() //processed in write to file routine above //savetosd = false; break; - case 30: - { - stoptime=millis(); - char time[30]; - unsigned long t=(stoptime-starttime)/1000; - int sec,min; - min=t/60; - sec=t%60; - sprintf(time,"%i min, %i sec",min,sec); - Serial.println(time); - LCD_MESSAGE(time); - } - break; + case 30: //M30 take time since the start of the SD print or an M109 command + { + stoptime=millis(); + char time[30]; + unsigned long t=(stoptime-starttime)/1000; + int sec,min; + min=t/60; + sec=t%60; + sprintf(time,"echo: time needed %i min, %i sec",min,sec); + Serial.println(time); + LCD_MESSAGE(time); + } + break; #endif //SDSUPPORT case 42: //M42 -Change pin status via gcode if (code_seen('S')) @@ -847,7 +854,7 @@ inline void process_commands() Serial.println(); #endif #else - Serial.println("No thermistors - no temp"); + Serial.println("echo: No thermistors - no temp"); #endif return; //break; @@ -888,7 +895,8 @@ inline void process_commands() } #endif //TEMP_RESIDENCY_TIME } - LCD_MESSAGE("Marlin ready."); + LCD_MESSAGE("Heating done."); + starttime=millis(); } break; case 190: // M190 - Wait bed for heater to reach target. @@ -1063,9 +1071,9 @@ inline void process_commands() if(code_seen('P')) Kp = code_value(); if(code_seen('I')) Ki = code_value()*PID_dT; if(code_seen('D')) Kd = code_value()/PID_dT; -// ECHOLN("Kp "<<_FLOAT(Kp,2)); -// ECHOLN("Ki "<<_FLOAT(Ki/PID_dT,2)); -// ECHOLN("Kd "<<_FLOAT(Kd*PID_dT,2)); +// SERIAL_ECHOLN("Kp "<<_FLOAT(Kp,2)); +// SERIAL_ECHOLN("Ki "<<_FLOAT(Ki/PID_dT,2)); +// SERIAL_ECHOLN("Kd "<<_FLOAT(Kd*PID_dT,2)); // temp_iState_min = 0.0; // if (Ki!=0) { @@ -1093,8 +1101,9 @@ inline void process_commands() } } else{ - Serial.println("Unknown command:"); - Serial.println(cmdbuffer[bufindr]); + Serial.print("echo: Unknown command:\""); + Serial.print(cmdbuffer[bufindr]); + Serial.println("\""); } ClearToSend(); @@ -1288,7 +1297,7 @@ void kill() disable_e(); if(PS_ON_PIN > -1) pinMode(PS_ON_PIN,INPUT); - Serial.println("!! Printer halted. kill() called !!"); + SERIAL_ERRORLN("Printer halted. kill() called !!"); while(1); // Wait for reset } diff --git a/Marlin/motion_control.cpp b/Marlin/motion_control.cpp index 875531fb78..0b734de4ab 100644 --- a/Marlin/motion_control.cpp +++ b/Marlin/motion_control.cpp @@ -35,7 +35,7 @@ void mc_arc(float *position, float *target, float *offset, uint8_t axis_0, uint8 { // int acceleration_manager_was_enabled = plan_is_acceleration_manager_enabled(); // plan_set_acceleration_manager_enabled(false); // disable acceleration management for the duration of the arc - Serial.println("mc_arc"); + SERIAL_ECHOLN("mc_arc."); float center_axis0 = position[axis_0] + offset[axis_0]; float center_axis1 = position[axis_1] + offset[axis_1]; float linear_travel = target[axis_linear] - position[axis_linear]; diff --git a/Marlin/stepper.cpp b/Marlin/stepper.cpp index f4bd1289e0..9e5db44a82 100644 --- a/Marlin/stepper.cpp +++ b/Marlin/stepper.cpp @@ -211,7 +211,7 @@ inline void trapezoid_generator_reset() { // It pops blocks from the block_buffer and executes them by pulsing the stepper pins appropriately. ISR(TIMER1_COMPA_vect) { - if(busy){ Serial.print(*(unsigned short *)OCR1A); Serial.println(" BUSY"); + if(busy){ SERIAL_ERRORLN(*(unsigned short *)OCR1A<< " ISR overtaking itself."); return; } // The busy-flag is used to avoid reentering this interrupt diff --git a/Marlin/temperature.cpp b/Marlin/temperature.cpp index 14530ca3f6..6971739242 100644 --- a/Marlin/temperature.cpp +++ b/Marlin/temperature.cpp @@ -142,17 +142,8 @@ CRITICAL_SECTION_END; } #endif //PID_OPENLOOP #ifdef PID_DEBUG - Serial.print(" Input "); - Serial.print(pid_input); - Serial.print(" Output "); - Serial.print(pid_output); - Serial.print(" pTerm "); - Serial.print(pTerm); - Serial.print(" iTerm "); - Serial.print(iTerm); - Serial.print(" dTerm "); - Serial.print(dTerm); - Serial.println(); + SERIAL_ECHOLN(" PIDDEBUG Input "<= maxttemp_0) { target_raw[TEMPSENSOR_HOTEND_0] = 0; analogWrite(HEATER_0_PIN, 0); - Serial.println("!! Temperature extruder 0 switched off. MAXTEMP triggered !!"); + SERIAL_ERRORLN("Temperature extruder 0 switched off. MAXTEMP triggered !!"); kill(); } #endif @@ -497,7 +488,7 @@ ISR(TIMER0_COMPB_vect) target_raw[TEMPSENSOR_HOTEND_1] = 0; if(current_raw[2] >= maxttemp_1) { analogWrite(HEATER_2_PIN, 0); - Serial.println("!! Temperature extruder 1 switched off. MAXTEMP triggered !!"); + SERIAL_ERRORLN("Temperature extruder 1 switched off. MAXTEMP triggered !!"); kill() } #endif @@ -507,7 +498,7 @@ ISR(TIMER0_COMPB_vect) if(current_raw[TEMPSENSOR_HOTEND_0] <= minttemp_0) { target_raw[TEMPSENSOR_HOTEND_0] = 0; analogWrite(HEATER_0_PIN, 0); - Serial.println("!! Temperature extruder 0 switched off. MINTEMP triggered !!"); + SERIAL_ERRORLN("Temperature extruder 0 switched off. MINTEMP triggered !!"); kill(); } #endif @@ -517,7 +508,7 @@ ISR(TIMER0_COMPB_vect) if(current_raw[TEMPSENSOR_HOTEND_1] <= minttemp_1) { target_raw[TEMPSENSOR_HOTEND_1] = 0; analogWrite(HEATER_2_PIN, 0); - Serial.println("!! Temperature extruder 1 switched off. MINTEMP triggered !!"); + SERIAL_ERRORLN("Temperature extruder 1 switched off. MINTEMP triggered !!"); kill(); } #endif @@ -527,7 +518,7 @@ ISR(TIMER0_COMPB_vect) if(current_raw[1] <= bed_minttemp) { target_raw[1] = 0; WRITE(HEATER_1_PIN, 0); - Serial.println("!! Temperatur heated bed switched off. MINTEMP triggered !!"); + SERIAL_ERRORLN("Temperatur heated bed switched off. MINTEMP triggered !!"); kill(); } #endif @@ -537,7 +528,7 @@ ISR(TIMER0_COMPB_vect) if(current_raw[1] >= bed_maxttemp) { target_raw[1] = 0; WRITE(HEATER_1_PIN, 0); - Serial.println("!! Temperature heated bed switched off. MAXTEMP triggered !!"); + SERIAL_ERRORLN("Temperature heated bed switched off. MAXTEMP triggered !!"); kill(); } #endif diff --git a/Marlin/ultralcd.pde b/Marlin/ultralcd.pde index 444020c228..bd256100ab 100644 --- a/Marlin/ultralcd.pde +++ b/Marlin/ultralcd.pde @@ -1382,7 +1382,7 @@ void MainMenu::showMainMenu() }break; #endif default: - Serial.println('NEVER say never'); + SERIAL_ERRORLN("Something is wrong in the MenuStructure."); break; } } @@ -1414,7 +1414,7 @@ void MainMenu::update() { force_lcd_update=true; oldcardstatus=CARDINSERTED; - //Serial.println("SD CHANGE"); + //Serial.println("echo: SD CHANGE"); if(CARDINSERTED) { initsd(); diff --git a/Marlin/watchdog.pde b/Marlin/watchdog.pde index 4c677e79e3..09d881d1d0 100644 --- a/Marlin/watchdog.pde +++ b/Marlin/watchdog.pde @@ -15,7 +15,7 @@ ISR(WDT_vect) #ifdef RESET_MANUAL LCD_MESSAGE("Please Reset!"); - ECHOLN("echo_: Something is wrong, please turn off the printer."); + SERIAL_ERRORLN("Something is wrong, please turn off the printer."); #else LCD_MESSAGE("Timeout, resetting!"); #endif