overworked the serial responses. Quite difficult, since many texts are Pronterface protocol.
This commit is contained in:
parent
1740a83e11
commit
900e0c9bf2
@ -59,7 +59,7 @@ void StoreSettings() {
|
|||||||
char ver2[4]=EEPROM_VERSION;
|
char ver2[4]=EEPROM_VERSION;
|
||||||
i=EEPROM_OFFSET;
|
i=EEPROM_OFFSET;
|
||||||
EEPROM_writeAnything(i,ver2); // validate data
|
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 stored_ver[4];
|
||||||
char ver[4]=EEPROM_VERSION;
|
char ver[4]=EEPROM_VERSION;
|
||||||
EEPROM_readAnything(i,stored_ver); //read stored 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
|
if ((!def)&&(strncmp(ver,stored_ver,3)==0)) { // version number match
|
||||||
EEPROM_readAnything(i,axis_steps_per_unit);
|
EEPROM_readAnything(i,axis_steps_per_unit);
|
||||||
EEPROM_readAnything(i,max_feedrate);
|
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,Ki);
|
||||||
EEPROM_readAnything(i,Kd);
|
EEPROM_readAnything(i,Kd);
|
||||||
|
|
||||||
ECHOLN("Stored settings retreived:");
|
SERIAL_ECHOLN("Stored settings retreived:");
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
float tmp1[]=DEFAULT_AXIS_STEPS_PER_UNIT;
|
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;
|
mintravelfeedrate=DEFAULT_MINTRAVELFEEDRATE;
|
||||||
max_xy_jerk=DEFAULT_XYJERK;
|
max_xy_jerk=DEFAULT_XYJERK;
|
||||||
max_z_jerk=DEFAULT_ZJERK;
|
max_z_jerk=DEFAULT_ZJERK;
|
||||||
ECHOLN("Using Default settings:");
|
SERIAL_ECHOLN("Using Default settings:");
|
||||||
}
|
}
|
||||||
ECHOLN("Steps per unit:");
|
SERIAL_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));
|
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));
|
||||||
ECHOLN("Maximum feedrates (mm/s):");
|
SERIAL_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));
|
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));
|
||||||
ECHOLN("Maximum Acceleration (mm/s2):");
|
SERIAL_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));
|
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));
|
||||||
ECHOLN("Acceleration: S=acceleration, T=retract acceleration");
|
SERIAL_ECHOLN("Acceleration: S=acceleration, T=retract acceleration");
|
||||||
ECHOLN(" M204 S" <<_FLOAT(acceleration,2) << " T" << _FLOAT(retract_acceleration,2));
|
SERIAL_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)");
|
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)");
|
||||||
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(" 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
|
#ifdef PIDTEMP
|
||||||
ECHOLN("PID settings:");
|
SERIAL_ECHOLN("PID settings:");
|
||||||
ECHOLN(" M301 P" << _FLOAT(Kp,3) << " I" << _FLOAT(Ki,3) << " D" << _FLOAT(Kd,3));
|
SERIAL_ECHOLN(" M301 P" << _FLOAT(Kp,3) << " I" << _FLOAT(Ki,3) << " D" << _FLOAT(Kd,3));
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
}
|
}
|
||||||
|
@ -14,6 +14,7 @@ UPLOAD_SPEED = 115200
|
|||||||
UPLOAD_PROTOCOL = stk500v2
|
UPLOAD_PROTOCOL = stk500v2
|
||||||
BUILD_MCU = atmega2560
|
BUILD_MCU = atmega2560
|
||||||
BUILD_F_CPU = 16000000L
|
BUILD_F_CPU = 16000000L
|
||||||
|
TERM=bash
|
||||||
|
|
||||||
# getting undefined reference to `__cxa_pure_virtual'
|
# getting undefined reference to `__cxa_pure_virtual'
|
||||||
#~ [http://www.arduino.cc/cgi-bin/yabb2/YaBB.pl?num=1254180518 Arduino Forum - Makefile]
|
#~ [http://www.arduino.cc/cgi-bin/yabb2/YaBB.pl?num=1254180518 Arduino Forum - Makefile]
|
||||||
|
@ -6,9 +6,11 @@
|
|||||||
#include <WProgram.h>
|
#include <WProgram.h>
|
||||||
#include "fastio.h"
|
#include "fastio.h"
|
||||||
|
|
||||||
|
#include "streaming.h"
|
||||||
#define ECHO(x) Serial << "echo: " << x;
|
#define SERIAL_ECHO(x) Serial << "echo: " << x;
|
||||||
#define ECHOLN(x) Serial << "echo: "<<x<<endl;
|
#define SERIAL_ECHOLN(x) Serial << "echo: "<<x<<endl;
|
||||||
|
#define SERIAL_ERROR(x) Serial << "echo: ERROR: " << x;
|
||||||
|
#define SERIAL_ERRORLN(x) Serial << "echo: ERROR: " << x<<endl;
|
||||||
|
|
||||||
void get_command();
|
void get_command();
|
||||||
void process_commands();
|
void process_commands();
|
||||||
@ -67,7 +69,7 @@ void kill();
|
|||||||
//void plan_set_position(float x, float y, float z, float e);
|
//void plan_set_position(float x, float y, float z, float e);
|
||||||
//void st_wake_up();
|
//void st_wake_up();
|
||||||
//void st_synchronize();
|
//void st_synchronize();
|
||||||
void enquecommand(const char *cmd);
|
void enquecommand(const char *cmd); //put an ascii command at the end of the current buffer.
|
||||||
|
|
||||||
|
|
||||||
#ifndef CRITICAL_SECTION_START
|
#ifndef CRITICAL_SECTION_START
|
||||||
|
@ -82,6 +82,7 @@ char version_string[] = "1.0.0 Alpha 1";
|
|||||||
// M27 - Report SD print status
|
// M27 - Report SD print status
|
||||||
// M28 - Start SD write (M28 filename.g)
|
// M28 - Start SD write (M28 filename.g)
|
||||||
// M29 - Stop SD write
|
// M29 - Stop SD write
|
||||||
|
// M30 - Output time since last M109 or SD card start to serial
|
||||||
// M42 - Change pin status via gcode
|
// M42 - Change pin status via gcode
|
||||||
// M80 - Turn on Power Supply
|
// M80 - Turn on Power Supply
|
||||||
// M81 - Turn off Power Supply
|
// M81 - Turn off Power Supply
|
||||||
@ -172,24 +173,30 @@ bool savetosd = false;
|
|||||||
int16_t n;
|
int16_t n;
|
||||||
unsigned long autostart_atmillis=0;
|
unsigned long autostart_atmillis=0;
|
||||||
|
|
||||||
void initsd(){
|
void initsd()
|
||||||
|
{
|
||||||
sdactive = false;
|
sdactive = false;
|
||||||
#if SDSS >- 1
|
#if SDSS >- 1
|
||||||
if(root.isOpen())
|
if(root.isOpen())
|
||||||
root.close();
|
root.close();
|
||||||
if (!card.init(SPI_FULL_SPEED,SDSS)){
|
if (!card.init(SPI_FULL_SPEED,SDSS))
|
||||||
|
{
|
||||||
//if (!card.init(SPI_HALF_SPEED,SDSS))
|
//if (!card.init(SPI_HALF_SPEED,SDSS))
|
||||||
Serial.println("SD init fail");
|
SERIAL_ECHOLN("SD init fail");
|
||||||
}
|
}
|
||||||
else if (!volume.init(&card))
|
else if (!volume.init(&card))
|
||||||
Serial.println("volume.init failed");
|
{
|
||||||
|
SERIAL_ERRORLN("volume.init failed");
|
||||||
|
}
|
||||||
else if (!root.openRoot(&volume))
|
else if (!root.openRoot(&volume))
|
||||||
Serial.println("openRoot failed");
|
{
|
||||||
|
SERIAL_ERRORLN("openRoot failed");
|
||||||
|
}
|
||||||
else
|
else
|
||||||
{
|
{
|
||||||
sdactive = true;
|
sdactive = true;
|
||||||
Serial.println("SD card ok");
|
SERIAL_ECHOLN("SD card ok");
|
||||||
}
|
}
|
||||||
#endif //SDSS
|
#endif //SDSS
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -214,7 +221,7 @@ inline void write_command(char *buf){
|
|||||||
//Serial.println(begin);
|
//Serial.println(begin);
|
||||||
file.write(begin);
|
file.write(begin);
|
||||||
if (file.writeError){
|
if (file.writeError){
|
||||||
Serial.println("error writing to file");
|
SERIAL_ERRORLN("error writing to file");
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif //SDSUPPORT
|
#endif //SDSUPPORT
|
||||||
@ -227,7 +234,7 @@ void enquecommand(const char *cmd)
|
|||||||
{
|
{
|
||||||
//this is dangerous if a mixing of serial and this happsens
|
//this is dangerous if a mixing of serial and this happsens
|
||||||
strcpy(&(cmdbuffer[bufindw][0]),cmd);
|
strcpy(&(cmdbuffer[bufindw][0]),cmd);
|
||||||
Serial.print("en:");Serial.println(cmdbuffer[bufindw]);
|
SERIAL_ECHOLN("enqueing \""<<cmdbuffer[bufindw]<<"\"");
|
||||||
bufindw= (bufindw + 1)%BUFSIZE;
|
bufindw= (bufindw + 1)%BUFSIZE;
|
||||||
buflen += 1;
|
buflen += 1;
|
||||||
}
|
}
|
||||||
@ -237,7 +244,7 @@ void setup()
|
|||||||
{
|
{
|
||||||
|
|
||||||
Serial.begin(BAUDRATE);
|
Serial.begin(BAUDRATE);
|
||||||
ECHOLN("Marlin "<<version_string);
|
SERIAL_ECHOLN("Marlin "<<version_string);
|
||||||
Serial.println("start");
|
Serial.println("start");
|
||||||
#if defined FANCY_LCD || defined SIMPLE_LCD
|
#if defined FANCY_LCD || defined SIMPLE_LCD
|
||||||
lcd_init();
|
lcd_init();
|
||||||
@ -478,17 +485,17 @@ inline void get_command()
|
|||||||
sdpos = file.curPosition();
|
sdpos = file.curPosition();
|
||||||
if(sdpos >= filesize){
|
if(sdpos >= filesize){
|
||||||
sdmode = false;
|
sdmode = false;
|
||||||
Serial.println("Done printing file");
|
Serial.println("echo: Done printing file");
|
||||||
stoptime=millis();
|
stoptime=millis();
|
||||||
char time[30];
|
char time[30];
|
||||||
unsigned long t=(stoptime-starttime)/1000;
|
unsigned long t=(stoptime-starttime)/1000;
|
||||||
int sec,min;
|
int sec,min;
|
||||||
min=t/60;
|
min=t/60;
|
||||||
sec=t%60;
|
sec=t%60;
|
||||||
sprintf(time,"%i min, %i sec",min,sec);
|
sprintf(time,"echo: %i min, %i sec",min,sec);
|
||||||
Serial.println(time);
|
Serial.println(time);
|
||||||
LCD_MESSAGE(time);
|
LCD_MESSAGE(time);
|
||||||
checkautostart(true);
|
checkautostart(true);
|
||||||
}
|
}
|
||||||
if(!serial_count) return; //if empty line
|
if(!serial_count) return; //if empty line
|
||||||
cmdbuffer[bufindw][serial_count] = 0; //terminate string
|
cmdbuffer[bufindw][serial_count] = 0; //terminate string
|
||||||
@ -721,7 +728,7 @@ inline void process_commands()
|
|||||||
case 24: //M24 - Start SD print
|
case 24: //M24 - Start SD print
|
||||||
if(sdactive){
|
if(sdactive){
|
||||||
sdmode = true;
|
sdmode = true;
|
||||||
starttime=millis();
|
starttime=millis();
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case 25: //M25 - Pause SD print
|
case 25: //M25 - Pause SD print
|
||||||
@ -774,19 +781,19 @@ inline void process_commands()
|
|||||||
//processed in write to file routine above
|
//processed in write to file routine above
|
||||||
//savetosd = false;
|
//savetosd = false;
|
||||||
break;
|
break;
|
||||||
case 30:
|
case 30: //M30 take time since the start of the SD print or an M109 command
|
||||||
{
|
{
|
||||||
stoptime=millis();
|
stoptime=millis();
|
||||||
char time[30];
|
char time[30];
|
||||||
unsigned long t=(stoptime-starttime)/1000;
|
unsigned long t=(stoptime-starttime)/1000;
|
||||||
int sec,min;
|
int sec,min;
|
||||||
min=t/60;
|
min=t/60;
|
||||||
sec=t%60;
|
sec=t%60;
|
||||||
sprintf(time,"%i min, %i sec",min,sec);
|
sprintf(time,"echo: time needed %i min, %i sec",min,sec);
|
||||||
Serial.println(time);
|
Serial.println(time);
|
||||||
LCD_MESSAGE(time);
|
LCD_MESSAGE(time);
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
#endif //SDSUPPORT
|
#endif //SDSUPPORT
|
||||||
case 42: //M42 -Change pin status via gcode
|
case 42: //M42 -Change pin status via gcode
|
||||||
if (code_seen('S'))
|
if (code_seen('S'))
|
||||||
@ -847,7 +854,7 @@ inline void process_commands()
|
|||||||
Serial.println();
|
Serial.println();
|
||||||
#endif
|
#endif
|
||||||
#else
|
#else
|
||||||
Serial.println("No thermistors - no temp");
|
Serial.println("echo: No thermistors - no temp");
|
||||||
#endif
|
#endif
|
||||||
return;
|
return;
|
||||||
//break;
|
//break;
|
||||||
@ -888,7 +895,8 @@ inline void process_commands()
|
|||||||
}
|
}
|
||||||
#endif //TEMP_RESIDENCY_TIME
|
#endif //TEMP_RESIDENCY_TIME
|
||||||
}
|
}
|
||||||
LCD_MESSAGE("Marlin ready.");
|
LCD_MESSAGE("Heating done.");
|
||||||
|
starttime=millis();
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
case 190: // M190 - Wait bed for heater to reach target.
|
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('P')) Kp = code_value();
|
||||||
if(code_seen('I')) Ki = code_value()*PID_dT;
|
if(code_seen('I')) Ki = code_value()*PID_dT;
|
||||||
if(code_seen('D')) Kd = code_value()/PID_dT;
|
if(code_seen('D')) Kd = code_value()/PID_dT;
|
||||||
// ECHOLN("Kp "<<_FLOAT(Kp,2));
|
// SERIAL_ECHOLN("Kp "<<_FLOAT(Kp,2));
|
||||||
// ECHOLN("Ki "<<_FLOAT(Ki/PID_dT,2));
|
// SERIAL_ECHOLN("Ki "<<_FLOAT(Ki/PID_dT,2));
|
||||||
// ECHOLN("Kd "<<_FLOAT(Kd*PID_dT,2));
|
// SERIAL_ECHOLN("Kd "<<_FLOAT(Kd*PID_dT,2));
|
||||||
|
|
||||||
// temp_iState_min = 0.0;
|
// temp_iState_min = 0.0;
|
||||||
// if (Ki!=0) {
|
// if (Ki!=0) {
|
||||||
@ -1093,8 +1101,9 @@ inline void process_commands()
|
|||||||
}
|
}
|
||||||
}
|
}
|
||||||
else{
|
else{
|
||||||
Serial.println("Unknown command:");
|
Serial.print("echo: Unknown command:\"");
|
||||||
Serial.println(cmdbuffer[bufindr]);
|
Serial.print(cmdbuffer[bufindr]);
|
||||||
|
Serial.println("\"");
|
||||||
}
|
}
|
||||||
|
|
||||||
ClearToSend();
|
ClearToSend();
|
||||||
@ -1288,7 +1297,7 @@ void kill()
|
|||||||
disable_e();
|
disable_e();
|
||||||
|
|
||||||
if(PS_ON_PIN > -1) pinMode(PS_ON_PIN,INPUT);
|
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
|
while(1); // Wait for reset
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -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();
|
// 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
|
// 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_axis0 = position[axis_0] + offset[axis_0];
|
||||||
float center_axis1 = position[axis_1] + offset[axis_1];
|
float center_axis1 = position[axis_1] + offset[axis_1];
|
||||||
float linear_travel = target[axis_linear] - position[axis_linear];
|
float linear_travel = target[axis_linear] - position[axis_linear];
|
||||||
|
@ -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.
|
// It pops blocks from the block_buffer and executes them by pulsing the stepper pins appropriately.
|
||||||
ISR(TIMER1_COMPA_vect)
|
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;
|
return;
|
||||||
} // The busy-flag is used to avoid reentering this interrupt
|
} // The busy-flag is used to avoid reentering this interrupt
|
||||||
|
|
||||||
|
@ -142,17 +142,8 @@ CRITICAL_SECTION_END;
|
|||||||
}
|
}
|
||||||
#endif //PID_OPENLOOP
|
#endif //PID_OPENLOOP
|
||||||
#ifdef PID_DEBUG
|
#ifdef PID_DEBUG
|
||||||
Serial.print(" Input ");
|
SERIAL_ECHOLN(" PIDDEBUG Input "<<pid_input<<" Output "<<pid_output" pTerm "<<pTerm<<" iTerm "<<iTerm<<" dTerm "<<dTerm);
|
||||||
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();
|
|
||||||
#endif //PID_DEBUG
|
#endif //PID_DEBUG
|
||||||
analogWrite(HEATER_0_PIN, pid_output);
|
analogWrite(HEATER_0_PIN, pid_output);
|
||||||
#endif //PIDTEMP
|
#endif //PIDTEMP
|
||||||
@ -452,7 +443,7 @@ ISR(TIMER0_COMPB_vect)
|
|||||||
temp_count++;
|
temp_count++;
|
||||||
break;
|
break;
|
||||||
default:
|
default:
|
||||||
Serial.println("!! Temp measurement error !!");
|
SERIAL_ERRORLN("Temp measurement error!");
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -486,7 +477,7 @@ ISR(TIMER0_COMPB_vect)
|
|||||||
if(current_raw[TEMPSENSOR_HOTEND_0] >= maxttemp_0) {
|
if(current_raw[TEMPSENSOR_HOTEND_0] >= maxttemp_0) {
|
||||||
target_raw[TEMPSENSOR_HOTEND_0] = 0;
|
target_raw[TEMPSENSOR_HOTEND_0] = 0;
|
||||||
analogWrite(HEATER_0_PIN, 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();
|
kill();
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
@ -497,7 +488,7 @@ ISR(TIMER0_COMPB_vect)
|
|||||||
target_raw[TEMPSENSOR_HOTEND_1] = 0;
|
target_raw[TEMPSENSOR_HOTEND_1] = 0;
|
||||||
if(current_raw[2] >= maxttemp_1) {
|
if(current_raw[2] >= maxttemp_1) {
|
||||||
analogWrite(HEATER_2_PIN, 0);
|
analogWrite(HEATER_2_PIN, 0);
|
||||||
Serial.println("!! Temperature extruder 1 switched off. MAXTEMP triggered !!");
|
SERIAL_ERRORLN("Temperature extruder 1 switched off. MAXTEMP triggered !!");
|
||||||
kill()
|
kill()
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
@ -507,7 +498,7 @@ ISR(TIMER0_COMPB_vect)
|
|||||||
if(current_raw[TEMPSENSOR_HOTEND_0] <= minttemp_0) {
|
if(current_raw[TEMPSENSOR_HOTEND_0] <= minttemp_0) {
|
||||||
target_raw[TEMPSENSOR_HOTEND_0] = 0;
|
target_raw[TEMPSENSOR_HOTEND_0] = 0;
|
||||||
analogWrite(HEATER_0_PIN, 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();
|
kill();
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
@ -517,7 +508,7 @@ ISR(TIMER0_COMPB_vect)
|
|||||||
if(current_raw[TEMPSENSOR_HOTEND_1] <= minttemp_1) {
|
if(current_raw[TEMPSENSOR_HOTEND_1] <= minttemp_1) {
|
||||||
target_raw[TEMPSENSOR_HOTEND_1] = 0;
|
target_raw[TEMPSENSOR_HOTEND_1] = 0;
|
||||||
analogWrite(HEATER_2_PIN, 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();
|
kill();
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
@ -527,7 +518,7 @@ ISR(TIMER0_COMPB_vect)
|
|||||||
if(current_raw[1] <= bed_minttemp) {
|
if(current_raw[1] <= bed_minttemp) {
|
||||||
target_raw[1] = 0;
|
target_raw[1] = 0;
|
||||||
WRITE(HEATER_1_PIN, 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();
|
kill();
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
@ -537,7 +528,7 @@ ISR(TIMER0_COMPB_vect)
|
|||||||
if(current_raw[1] >= bed_maxttemp) {
|
if(current_raw[1] >= bed_maxttemp) {
|
||||||
target_raw[1] = 0;
|
target_raw[1] = 0;
|
||||||
WRITE(HEATER_1_PIN, 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();
|
kill();
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
@ -1382,7 +1382,7 @@ void MainMenu::showMainMenu()
|
|||||||
}break;
|
}break;
|
||||||
#endif
|
#endif
|
||||||
default:
|
default:
|
||||||
Serial.println('NEVER say never');
|
SERIAL_ERRORLN("Something is wrong in the MenuStructure.");
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -1414,7 +1414,7 @@ void MainMenu::update()
|
|||||||
{
|
{
|
||||||
force_lcd_update=true;
|
force_lcd_update=true;
|
||||||
oldcardstatus=CARDINSERTED;
|
oldcardstatus=CARDINSERTED;
|
||||||
//Serial.println("SD CHANGE");
|
//Serial.println("echo: SD CHANGE");
|
||||||
if(CARDINSERTED)
|
if(CARDINSERTED)
|
||||||
{
|
{
|
||||||
initsd();
|
initsd();
|
||||||
|
@ -15,7 +15,7 @@ ISR(WDT_vect)
|
|||||||
|
|
||||||
#ifdef RESET_MANUAL
|
#ifdef RESET_MANUAL
|
||||||
LCD_MESSAGE("Please Reset!");
|
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
|
#else
|
||||||
LCD_MESSAGE("Timeout, resetting!");
|
LCD_MESSAGE("Timeout, resetting!");
|
||||||
#endif
|
#endif
|
||||||
|
Loading…
Reference in New Issue
Block a user