static void abortPrint()
{
    postMenuCheck = NULL;
    lifetime_stats_print_end();
    doCooldown();

    clear_command_queue();
    char buffer[32];
    if (card.sdprinting)
    {
    	// we're not printing any more
        card.sdprinting = false;
    }

    if (primed)
    	{
    	// set up the end of print retraction
    	sprintf_P(buffer, PSTR("G92 E%i"), int(((float)END_OF_PRINT_RETRACTION) / volume_to_filament_length[active_extruder]));
    	enquecommand(buffer);
    	// perform the retraction at the standard retract speed
    	sprintf_P(buffer, PSTR("G1 F%i E0"), int(retract_feedrate));
    	enquecommand(buffer);

    	// no longer primed
    	primed = false;
    	}
// joris dont home Z with z-unlimited after print
    enquecommand_P(PSTR("G28 X0 Y0"));
//    enquecommand_P(PSTR("G28"));
// joris dont release stepper Z with z-unlimited after print
    enquecommand_P(PSTR("M84 X Y"));
//    enquecommand_P(PSTR("M84"));
}
static void parkHeadForCenterAdjustment()
{
    char buffer[32];
    sprintf_P(buffer, PSTR("G1 F%i Z5"), int(homing_feedrate[Z_AXIS]));
    enquecommand(buffer);
    sprintf_P(buffer, PSTR("G1 F%i X%i Y%i"), int(homing_feedrate[X_AXIS]), X_MAX_LENGTH / 2, Y_MAX_LENGTH - 10);
    enquecommand(buffer);
    sprintf_P(buffer, PSTR("G1 F%i Z0"), int(homing_feedrate[Z_AXIS]));
    enquecommand(buffer);
}
Пример #3
0
static void mma_ClickAxis(uint8_t line, volatile long &pos, bool &adjustValue, uint8_t axis)
{
    adjustValue = !adjustValue;
    if(adjustValue) {
	enquecommand("G91");
	pos = 0;
    } else {
      enquecommand("G90");
    }
}
static void parkHeadForRightAdjustment()
{
    char buffer[32];
    sprintf_P(buffer, PSTR("G1 F%i Z5"), int(homing_feedrate[Z_AXIS]));
    enquecommand(buffer);
    sprintf_P(buffer, PSTR("G1 F%i X%i Y%i"), int(homing_feedrate[X_AXIS]), BED_RIGHT_ADJUST_X, BED_RIGHT_ADJUST_Y);
    enquecommand(buffer);
    sprintf_P(buffer, PSTR("G1 F%i Z0"), int(homing_feedrate[Z_AXIS]));
    enquecommand(buffer);
}
static void parkHeadForRightAdjustment()
{
    char buffer[32];
    sprintf_P(buffer, PSTR("G1 F%i Z5"), int(homing_feedrate[Z_AXIS]));
    enquecommand(buffer);
    sprintf_P(buffer, PSTR("G1 F%i X%i Y%i"), int(homing_feedrate[X_AXIS]), X_MAX_POS - 5, 10);
    enquecommand(buffer);
    sprintf_P(buffer, PSTR("G1 F%i Z0"), int(homing_feedrate[Z_AXIS]));
    enquecommand(buffer);
}
Пример #6
0
static void mma_ClickExtruder(uint8_t line, volatile long &pos, bool &adjustValue, uint8_t direction)
{
    if (direction == MMA_EXTRUDE) {
	enquecommand("G92 E0");
	enquecommand("G1 F70 E1");
	beepshort();
    } else {
	enquecommand("G92 E0");
	enquecommand("G1 F700 E-1");
	beepshort();
    }
}
static void parkHeadForLeftAdjustment()
{
    add_homeing[Z_AXIS] -= current_position[Z_AXIS];
    current_position[Z_AXIS] = 0;
    plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);

    char buffer[32];
    sprintf_P(buffer, PSTR("G1 F%i Z5"), int(homing_feedrate[Z_AXIS]));
    enquecommand(buffer);
    sprintf_P(buffer, PSTR("G1 F%i X%i Y%i"), int(homing_feedrate[X_AXIS]), BED_LEFT_ADJUST_X, BED_LEFT_ADJUST_Y);
    enquecommand(buffer);
    sprintf_P(buffer, PSTR("G1 F%i Z0"), int(homing_feedrate[Z_AXIS]));
    enquecommand(buffer);
}
Пример #8
0
void CardReader::checkautostart(bool force)
{
  if(!force)
  {
    if(!autostart_stilltocheck)
      return;
    if(autostart_atmillis<millis())
      return;
  }
  autostart_stilltocheck=false;
  if(!cardOK)
  {
    initsd();
    if(!cardOK) //fail
      return;
  }
  
  char autoname[30];
  sprintf(autoname,"auto%i.g",lastnr);
  for(int8_t i=0;i<(int8_t)strlen(autoname);i++)
    autoname[i]=tolower(autoname[i]);
  dir_t p;

  root.rewind();
  
  bool found=false;
  while (root.readDir(p, NULL) > 0) 
  {
    for(int8_t i=0;i<(int8_t)strlen((char*)p.name);i++)
    p.name[i]=tolower(p.name[i]);
    //Serial.print((char*)p.name);
    //Serial.print(" ");
    //Serial.println(autoname);
    if(p.name[9]!='~') //skip safety copies
    if(strncmp((char*)p.name,autoname,5)==0)
    {
      char cmd[30];

      sprintf(cmd,"M23 %s",autoname);
      enquecommand(cmd);
      enquecommand("M24");
      found=true;
    }
  }
  if(!found)
    lastnr=-1;
  else
    lastnr++;
}
static void storeHomingZ_parkHeadForLeftAdjustment()
{
    add_homeing[Z_AXIS] -= current_position[Z_AXIS];
    Config_StoreSettings();
    current_position[Z_AXIS] = 0;
    plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);

    char buffer[32];
    sprintf_P(buffer, PSTR("G1 F%i Z5"), int(homing_feedrate[Z_AXIS]));
    enquecommand(buffer);
    sprintf_P(buffer, PSTR("G1 F%i X%i Y%i"), int(homing_feedrate[X_AXIS]), 35, 10);
    enquecommand(buffer);
    sprintf_P(buffer, PSTR("G1 F%i Z0"), int(homing_feedrate[Z_AXIS]));
    enquecommand(buffer);
}
static void homeAndParkHeadForCenterAdjustment()
{
    enquecommand_P(PSTR("G28 X0 Y0"));
    char buffer[32];
    sprintf_P(buffer, PSTR("G1 F%i Z%i X%i Y%i"), int(homing_feedrate[0]), 35, X_MAX_LENGTH/2, Y_MAX_LENGTH - 10);
    enquecommand(buffer);
}
static void homeAndRaiseBed()
{
    enquecommand_P(PSTR("G28 Z0"));
    char buffer[32];
    sprintf_P(buffer, PSTR("G1 F%i Z%i"), int(homing_feedrate[0]), 35);
    enquecommand(buffer);
}
Пример #12
0
void CardReader::checkautostart(bool force) {
  if (!force && (!autostart_stilltocheck || autostart_atmillis < millis()))
    return;

  autostart_stilltocheck = false;

  if (!cardOK) {
    initsd();
    if (!cardOK) return; // fail
  }

  char autoname[30];
  sprintf_P(autoname, PSTR("auto%i.g"), autostart_index);
  for (int8_t i = 0; i < (int8_t)strlen(autoname); i++) autoname[i] = tolower(autoname[i]);

  dir_t p;

  root.rewind();

  bool found = false;
  while (root.readDir(p, NULL) > 0) {
    for (int8_t i = 0; i < (int8_t)strlen((char*)p.name); i++) p.name[i] = tolower(p.name[i]);
    if (p.name[9] != '~' && strncmp((char*)p.name, autoname, 5) == 0) {
      char cmd[30];
      sprintf_P(cmd, PSTR("M23 %s"), autoname);
      enquecommand(cmd);
      enquecommands_P(PSTR("M24"));
      found = true;
    }
  }
  if (!found)
    autostart_index = -1;
  else
    autostart_index++;
}
static void homeAndParkHeadForCenterAdjustment()
{
    enquecommand_P(PSTR("G28 X0 Y0"));
    char buffer[32];
    sprintf_P(buffer, PSTR("G1 F%i Z%i X%i Y%i"), int(homing_feedrate[0]), 35, BED_CENTER_ADJUST_X, BED_CENTER_ADJUST_Y);
    enquecommand(buffer);
}
void lcd_menu_insert_material()
{
    char buffer[32];
    enquecommand_P(PSTR("G28 X0 Y0"));
    sprintf_P(buffer, PSTR("G1 F%i X%i Y%i"), int(homing_feedrate[0]), X_MAX_LENGTH/2, 10);
    enquecommand(buffer);
    
    currentMenu = lcd_menu_insert_material_preheat;
}
Пример #15
0
static void laser_set_focus(float f_length) {
	if (!has_axis_homed[Z_AXIS]) {
		enquecommand_P(PSTR("G28 Z F150"));
	}
	focalLength = f_length;
	float focus = LASER_FOCAL_HEIGHT - f_length;
	char cmd[20];

	sprintf_P(cmd, PSTR("G0 Z%s F150"), ftostr52(focus));
	enquecommand(cmd);
}
Пример #16
0
static void menu_action_sdfile(const char* filename, char* longFilename)
{
    char cmd[30];
    char* c;
    sprintf_P(cmd, PSTR("M23 %s"), filename);
    for(c = &cmd[4]; *c; c++)
        *c = tolower(*c);
    enquecommand(cmd);
    enquecommand_P(PSTR("M24"));
    lcd_return_to_status();
}
static void lcd_menu_change_material_remove_wait_user_ready()
{
    current_position[E_AXIS] = 0;
    plan_set_e_position(current_position[E_AXIS]);
    lcd_change_to_menu(lcd_menu_change_material_insert_wait_user, MAIN_MENU_ITEM_POS(0));
    
    char buffer[32];
    enquecommand_P(PSTR("G28 X0 Y0"));
    sprintf_P(buffer, PSTR("G1 F%i X%i Y%i"), int(homing_feedrate[0]), X_MAX_LENGTH/2, 10);
    enquecommand(buffer);
}
Пример #18
0
void CardReader::printingHasFinished()
{
 st_synchronize();
 quickStop();
 sdprinting = false;
 if(SD_FINISHED_STEPPERRELEASE)
 {
   //finishAndDisableSteppers();
   enquecommand(SD_FINISHED_RELEASECOMMAND);
 }
 autotempShutdown();
}
static void abortPrint()
{
    postMenuCheck = NULL;
    doCooldown();

    clear_command_queue();
    char buffer[32];
    if (card.sdprinting)
    {
        card.sdprinting = false;
        sprintf_P(buffer, PSTR("G92 E%i"), int(20.0 / volume_to_filament_length[active_extruder]));
        enquecommand(buffer);
        enquecommand_P(PSTR("G1 F1500 E0"));
    }
    enquecommand_P(PSTR("G28"));
    enquecommand_P(PSTR("M84"));
}
static void lcd_menu_material_main()
{
    lcd_tripple_menu(PSTR("CHANGE"), PSTR("SETTINGS"), PSTR("RETURN"));

    if (lcd_lib_button_pressed)
    {
        if (IS_SELECTED_MAIN(0) && !is_command_queued())
        {
            minProgress = 0;
            char buffer[32];
            enquecommand_P(PSTR("G28 X0 Y0"));
            sprintf_P(buffer, PSTR("G1 F%i X%i Y%i"), int(homing_feedrate[0]), X_MAX_LENGTH/2, 10);
            enquecommand(buffer);
            lcd_change_to_menu_change_material(lcd_menu_material_main_return);
        }
        else if (IS_SELECTED_MAIN(1))
            lcd_change_to_menu(lcd_menu_material_select, SCROLL_MENU_ITEM_POS(0));
        else if (IS_SELECTED_MAIN(2))
            lcd_change_to_menu(lcd_menu_main);
    }

    lcd_lib_update_screen();
}
Пример #21
0
void mma_AdjustAxis(uint8_t line, volatile long &pos, uint8_t axis)
{
    if (pos > 0) {
	switch (axis) {
	case X_AXIS: enquecommand("G1 F700 X0.1"); break;
	case Y_AXIS: enquecommand("G1 F700 Y0.1"); break;
	case Z_AXIS: enquecommand("G1 F70 Z0.1"); break;
	default: break;
	}
    } else if (pos < 0) {
	switch (axis) {
	case X_AXIS: enquecommand("G1 F700 X-0.1"); break;
	case Y_AXIS: enquecommand("G1 F700 Y-0.1"); break;
	case Z_AXIS: enquecommand("G1 F70 Z-0.1"); break;
	default: break;
	}
    }
    pos = 0;

    mma_ShowAxis(line, axis);
}
Пример #22
0
void process()
{
    switch (buff_obj[0]) {
        case 'V':
            writeString((char *)"{VER:008}");
            return;

        case 'S':
            if (buff_value[0]=='E') writeString((char *)"{SYS:echo}");
/*            else if (buff_value[0]=='H')
            {
                uint8_t i,itemCount;
                
                itemCount=countFiles(false);
                //if (file_from_wifi!=0)
                {
                    writeString((char *)"{WIFI:");
                    writeInt(file_from_wifi,3);
                    put('/');
                    writeInt(itemCount,3);
                    put('}');
                }
            }*/
            else if (buff_value[0]=='L')
            {
                uint8_t i;
                uint8_t itemCount;
                
                if ( card.isFileOpen() ) {
                    writeString((char *)"{SYS:BUSY}");
                    return;
                }
				
				//card.initsd();
				//card.getWorkDirName();

                itemCount = countFiles(true);
				
				if (itemCount==0)
				{
					card.initsd();
					card.setroot();
					itemCount = countFiles(true);
				}
				
                for (i=0;i<itemCount;i++)
                {
                    ListFile(i,itemCount);
                }

                if (itemCount==0)
                {
                    if (card.cardOK) i=101;
					else i=102;
                    writeString((char *)"{ERR:");
                    writeInt(i,3);
                    put('}');
                }
                else writeString((char *)"{SYS:OK}");
            }
            else if (buff_value[0]=='I')
            {
                int16_t t;
                                
				writeString((char *)"{T0:");
				t=degHotend(0);
				if (t>999) t=999;
				writeInt(t,3);
				put('/');
				t=degTargetHotend(0);
				writeInt(t,3);
				put('}');
				
				writeString((char *)"{T1:");
				t=degHotend(1);
				if (t>999) t=999;
				writeInt(t,3);
				put('/');
				t=degTargetHotend(1);
				writeInt(t,3);
				put('}');
				
				writeString((char *)"{TP:");
				t=degBed();
				if (t>999) t=999;
				writeInt(t,3);
				put('/');
				t=degTargetBed();
				writeInt(t,3);
				put('}');
            }
            else if (buff_value[0]=='F')
            {
                /*if (buff_value[1]=='X')
                {
                    eeprom::setEepromInt64(eeprom_offsets::FILAMENT_TRIP, eeprom::getEepromInt64(eeprom_offsets::FILAMENT_LIFETIME, 0));
                    eeprom::setEepromInt64(eeprom_offsets::FILAMENT_TRIP + sizeof(int64_t), eeprom::getEepromInt64(eeprom_offsets::FILAMENT_LIFETIME + sizeof(int64_t), 0));
                }*/
                
                writeString((char *)"{TU:");
                
                uint16_t total_hours;
                uint8_t total_minutes;
                //eeprom::getBuildTime(&total_hours, &total_minutes);
				total_hours=0;
				total_minutes=0;
                writeInt(total_hours,5);
                put('.');
                writeInt(total_minutes,2);
                put('/');
                
                uint8_t build_hours;
                uint8_t build_minutes;
                //host::getPrintTime(build_hours, build_minutes);
				build_hours=0;
				build_minutes=0;
                writeInt(build_hours,3);
                put('.');
                writeInt(build_minutes,2);
                put('/');
                
                uint32_t filamentUsedA,filamentUsedB,filamentUsed;
                char str[11];
                //filamentUsedA=stepperAxisStepsToMM(eeprom::getEepromInt64(eeprom_offsets::FILAMENT_LIFETIME, 0),                  A_AXIS);
                //filamentUsedB=stepperAxisStepsToMM(eeprom::getEepromInt64(eeprom_offsets::FILAMENT_LIFETIME + sizeof(int64_t),0), B_AXIS);
                //filamentUsed=filamentUsedA+filamentUsedB;
				filamentUsed=0;
                itoa(filamentUsed,str,10);
                writeString((char *)str);
                put('/');
                
                //filamentUsedA -= stepperAxisStepsToMM(eeprom::getEepromInt64(eeprom_offsets::FILAMENT_TRIP, 0),                  A_AXIS);
                //filamentUsedB -= stepperAxisStepsToMM(eeprom::getEepromInt64(eeprom_offsets::FILAMENT_TRIP + sizeof(int64_t),0), B_AXIS);
                //filamentUsed=filamentUsedA+filamentUsedB;
				filamentUsed=0;
                itoa(filamentUsed,str,10);
                writeString((char *)str);
                put('}');
            }
            else if (buff_value[0]=='R' && 
                buff_value[1]=='E' &&
                buff_value[2]=='S' &&
                buff_value[3]=='E' &&
                buff_value[4]=='T')
            {
                //Motherboard::getBoard().reset(true);
				
            }
/*
            else if (buff_value[0]=='S')
            {
                writeString((char *)"{SYS:P");
                uint8_t i = command::pauseState();
                writeInt(i,3);
                put('/');
                put('H');
                i=host::getHostState();
                writeInt(i,3);
                put('}');
            }
            break;
            */
		
        case 'C':
            if (buff_value[0]=='P')
            {
                uint16_t t;
                
                t=atoi((const char*)buff_value+1);
                
                if (t<0 || t>150) return;
                setTargetBed(t);
            }
            else if (buff_value[0]=='T')
            {
                int16_t t;
                
                t=atoi((const char*)buff_value+2);
                if (t<0 || t>280) return;
                
                if (buff_value[1] == '0')
                {
                    setTargetHotend(t,0);
                }
                else
                {
                    setTargetHotend(t,1);
                }
            }
            else if (buff_value[0]=='S')
            {
                int16_t t;
                uint8_t i;
                
                t=atoi((const char*)buff_value+1);
                
                if (t<1) t=1;
                else if (t>50) t=50;
                
                feedmultiply=t*10;
            }
            break;
            
        case 'P':
            uint8_t i;
            if (buff_value[0]=='H')
            {
            	enquecommand_P(PSTR("G28"));
            }
            else if (buff_value[0]=='C')
            {
                //host::startOnboardBuild(utility::TOOLHEAD_CALIBRATE);
            }
            else if (buff_value[0]=='X')
            {
				extern bool cancel_heatup;
                writeString((char *)"{SYS:CANCELING}");
				//card.pauseSDPrint();
				//disable_heater();
				card.sdprinting = false;
				card.closefile();
				quickStop();
				if(SD_FINISHED_STEPPERRELEASE)
				{
					enquecommand_P(PSTR(SD_FINISHED_RELEASECOMMAND));
				}
				autotempShutdown();
				cancel_heatup = true;
				writeString((char *)"{SYS:STARTED}");
				writeString((char *)"{U:RG1R180180120P0L1S0D0O1E1H0C0X1Y1Z1A2B2N3M0}");
				
            }
            else if (buff_value[0]=='P')
            {
                writeString((char *)"{SYS:PAUSE}");
                card.pauseSDPrint();
                writeString((char *)"{SYS:PAUSED}");
            }
            else if (buff_value[0]=='R')
            {
                writeString((char *)"{SYS:RESUME}");
                card.startFileprint();
                writeString((char *)"{SYS:RESUMED}");
            }
            else if (buff_value[0]=='Z')
            {
                /*i=(buff_value[1]-'0')*100 + (buff_value[2]-'0')*10 + (buff_value[3]-'0');
                float pauseAtZPos = i;
                command::pauseAtZPos(stepperAxisMMToSteps(pauseAtZPos, Z_AXIS));*/
            }
            else
            {
                i=(buff_value[0]-'0')*100 + (buff_value[1]-'0')*10 + (buff_value[2]-'0');
                card.getfilename(i);
				if (card.filenameIsDir)
				{
					writeString((char *)"{SYS:DIR}");
					card.chdir(card.filename);
				}
				else 
				{
					char cmd[30];
					char* c;
					
					writeString((char *)"{PRINTFILE:");
					if (card.longFilename[0]!=0) writeString(card.longFilename);
					else writeString(card.filename);
					put('}');
					
					sprintf_P(cmd, PSTR("M23 %s"), card.filename);
					for(c = &cmd[4]; *c; c++)
					*c = tolower(*c);
					enquecommand(cmd);
					enquecommand_P(PSTR("M24"));
				}
            }
            break;

        case 'B':
            PrintingStatus();
            break;

/*
        case 'J':
            switch (buff_value[0])
            {
                case 'S':
                    BOARD_STATUS_SET(Motherboard::STATUS_MANUAL_MODE);
                    jog_speed=atoi((const char*)buff_value+1);
                    break;
                    
                case 'E':
                    steppers::enableAxes(0xff, false);
                    BOARD_STATUS_CLEAR(Motherboard::STATUS_MANUAL_MODE);
                    break;
                    
                case 'X':
                case 'Y':
                case 'Z':
                case 'A':
                case 'B':
                    steppers::abort();
                    uint8_t dummy;
                    Point position = steppers::getStepperPosition(&dummy);
                    
                    int32_t t;
                    t=atoi((const char*)buff_value+1);

                    if (buff_value[0]<='B') position[buff_value[0]-'A'+3] += (t<<4);
                    else position[buff_value[0]-'X'] += (t<<4);
                    
                    steppers::setTargetNew(position, jog_speed, 0, 0);
                    break;
            }
            break;
*/
/*
        case 'H':
        	if (buff_value[0]=='R')
        	{
        		extern uint32_t homePosition[PROFILES_HOME_POSITIONS_STORED];

        		writeString((char *)"{H:R");
        		eeprom_read_block(homePosition, (void *)eeprom_offsets::AXIS_HOME_POSITIONS_STEPS, PROFILES_HOME_POSITIONS_STORED * sizeof(uint32_t));
        		writeInt(homePosition[0],5);
        		put('/');
        		writeInt(homePosition[1],5);
        		put('/');
        		writeInt(homePosition[2],5);
        		put('/');
        		writeInt((int32_t)(eeprom::getEeprom32(eeprom_offsets::TOOLHEAD_OFFSET_SETTINGS, 0)),5);
        		put('/');
        		writeInt((int32_t)(eeprom::getEeprom32(eeprom_offsets::TOOLHEAD_OFFSET_SETTINGS + sizeof(int32_t), 0)),5);
        		put('}');
        	}
        	else if (buff_value[0]=='W')
        	{
        		extern uint32_t homePosition[PROFILES_HOME_POSITIONS_STORED];
        		int32_t offset[2],t;
        		uint8_t axis;
        		axis=buff_value[1]-'X';
        		if (axis>=0 && axis<=2)
        		{
        			homePosition[axis]=atoi((const char*)buff_value+2);
        			cli();
					eeprom_write_block((void *)&homePosition[axis],
					   (void*)(eeprom_offsets::AXIS_HOME_POSITIONS_STEPS + sizeof(uint32_t) * axis) ,
					   sizeof(uint32_t));
					sei();
        		}

        		axis=buff_value[1]-'x';
        		if (axis>=0 && axis<=1)
        		{
        			t=atoi((const char*)buff_value+2);

                    int32_t offset[2];
                    bool    smallOffsets;

                    offset[0]  = (int32_t)(eeprom::getEeprom32(eeprom_offsets::TOOLHEAD_OFFSET_SETTINGS, 0));
                    offset[1]  = (int32_t)(eeprom::getEeprom32(eeprom_offsets::TOOLHEAD_OFFSET_SETTINGS + sizeof(int32_t), 0));
                    smallOffsets = abs(offset[0]) < ((int32_t)stepperAxisStepsPerMM(0) << 2);

                    int32_t delta = stepperAxisMMToSteps((float)(t - 7) * 0.1f, axis);
                    if ( !smallOffsets ) delta = -delta;

                    int32_t new_offset = offset[axis] + delta;
                    eeprom_write_block((uint8_t *)&new_offset,
                           (uint8_t *)eeprom_offsets::TOOLHEAD_OFFSET_SETTINGS + axis * sizeof(int32_t),
                           sizeof(int32_t));
        		}
        	}
        	break;
*/
/*
        case 'U':
            if (buff_value[0]=='R')
            {
            	int temp;

                writeString((char *)"{U:RG");
                if (eeprom::getEeprom8(eeprom_offsets::OVERRIDE_GCODE_TEMP, 0) != 0) put('1');
                else put('0');

                put('R');
                temp=eeprom::getEeprom16(eeprom_offsets::PREHEAT_SETTINGS + preheat_eeprom_offsets::PREHEAT_LEFT_OFFSET, DEFAULT_PREHEAT_TEMP);
                writeInt(temp,3);
                //put('/');
                temp=eeprom::getEeprom16(eeprom_offsets::PREHEAT_SETTINGS + preheat_eeprom_offsets::PREHEAT_RIGHT_OFFSET, DEFAULT_PREHEAT_TEMP);
                writeInt(temp,3);
                //put('/');
                temp=eeprom::getEeprom16(eeprom_offsets::PREHEAT_SETTINGS + preheat_eeprom_offsets::PREHEAT_PLATFORM_OFFSET, DEFAULT_PREHEAT_TEMP);
                writeInt(temp,3);

                put('P');
                if (eeprom::hasHBP() != 0) put('1');
                else put('0');
                
                put('L');
                if (eeprom::getEeprom8(eeprom_offsets::ACCELERATION_SETTINGS + acceleration_eeprom_offsets::ACCELERATION_ACTIVE, 0x01) != 0) put('1');
                else put('0');
                
                put('S');
                if (eeprom::getEeprom8(eeprom_offsets::COOL_PLAT, 0) != 0) put('1');
                else put('0');
                
                put('D');
                if (eeprom::getEeprom8(eeprom_offsets::DITTO_PRINT_ENABLED, 0) != 0) put('1');
                else put('0');
                
                put('O');
                if (eeprom::getEeprom8(eeprom_offsets::TOOLHEAD_OFFSET_SYSTEM,
                                       DEFAULT_TOOLHEAD_OFFSET_SYSTEM) != 0) put('1');
                else put('0');
                
                put('E');
                if (eeprom::getEeprom8(eeprom_offsets::EXTRUDER_HOLD,
                                       DEFAULT_EXTRUDER_HOLD) != 0) put('1');
                else put('0');
                
                put('H');
                if (eeprom::getEeprom8(eeprom_offsets::HEAT_DURING_PAUSE, DEFAULT_HEAT_DURING_PAUSE) != 0) put('1');
                else put('0');
                
                put('C');
                if (eeprom::getEeprom8(eeprom_offsets::SD_USE_CRC, DEFAULT_SD_USE_CRC) != 0) put('1');
                else put('0');
                
                put('X');
                put ('0' + eeprom::getEeprom8(eeprom_offsets::STEPPER_X_CURRENT, 0));
                
                put('Y');
                put ('0' + eeprom::getEeprom8(eeprom_offsets::STEPPER_Y_CURRENT, 0));
                
                put('Z');
                put ('0' + eeprom::getEeprom8(eeprom_offsets::STEPPER_Z_CURRENT, 0));
                
                put('A');
                put ('0' + eeprom::getEeprom8(eeprom_offsets::STEPPER_A_CURRENT, 0));
                
                put('B');
                put ('0' + eeprom::getEeprom8(eeprom_offsets::STEPPER_B_CURRENT, 0));

                put('N');
                put ('0' + eeprom::getEeprom8(eeprom_offsets::LANGUAGE, 0));

                put('M');
                put ('0' + eeprom::getEeprom8(eeprom_offsets::WIFI_SD, 0));
                
                put('}');
            }
            else if (buff_value[0]=='W')
            {
                uint8_t *c;
                uint8_t cmd=0;
                
                c=buff_value;
                while (*++c!=0)
                {
                    if (*c<='9' && *c>='0')
                    {
                        uint8_t value;
                        value = *c - '0';
                        
                        switch (cmd)
                        {
                            case 'G':
                                eeprom_write_byte((uint8_t *)eeprom_offsets::OVERRIDE_GCODE_TEMP,value);
                                break;
                                
                            case 'P':
                                eeprom_write_byte((uint8_t*)eeprom_offsets::HBP_PRESENT, value);
                                break;
                                
                            case 'L':
                                eeprom_write_byte((uint8_t*)eeprom_offsets::ACCELERATION_SETTINGS +
                                                  acceleration_eeprom_offsets::ACCELERATION_ACTIVE,
                                                  value);
                                break;
                                
                            case 'S':
                                eeprom_write_byte((uint8_t*)eeprom_offsets::COOL_PLAT, value);
                                break;
                                
                            case 'D':
                                eeprom_write_byte((uint8_t*)eeprom_offsets::DITTO_PRINT_ENABLED, value);
                                break;
                                
                            case 'O':
                                eeprom_write_byte((uint8_t*)eeprom_offsets::TOOLHEAD_OFFSET_SYSTEM, value);
                                break;
                                
                            case 'E':
                                eeprom_write_byte((uint8_t*)eeprom_offsets::EXTRUDER_HOLD, value);
                                break;
                                
                            case 'H':
                                eeprom_write_byte((uint8_t*)eeprom_offsets::HEAT_DURING_PAUSE, value);
                                break;
                                
                            case 'C':
                                eeprom_write_byte((uint8_t*)eeprom_offsets::SD_USE_CRC, value);
                                break;
                                
                            case 'T':
                                eeprom_write_byte((uint8_t*)eeprom_offsets::PSTOP_ENABLE, value);
                                break;
                                
                            case 'X':
                                eeprom_write_byte((uint8_t*)eeprom_offsets::STEPPER_X_CURRENT, value);
                                break;
                                
                            case 'Y':
                                eeprom_write_byte((uint8_t*)eeprom_offsets::STEPPER_Y_CURRENT, value);
                                break;
                                
                            case 'Z':
                                eeprom_write_byte((uint8_t*)eeprom_offsets::STEPPER_Z_CURRENT, value);
                                break;
                                
                            case 'A':
                                eeprom_write_byte((uint8_t*)eeprom_offsets::STEPPER_A_CURRENT, value);
                                break;
                                
                            case 'B':
                                eeprom_write_byte((uint8_t*)eeprom_offsets::STEPPER_B_CURRENT, value);
                                break;

                            case 'N':
                                eeprom_write_byte((uint8_t*)eeprom_offsets::LANGUAGE, value);
                                break;

                            case 'M':
                                eeprom_write_byte((uint8_t*)eeprom_offsets::WIFI_SD, value);
                                break;
                                
                            default:
                                break;
                        }
                    }
                    else if (*c<='Z' && *c>='A') cmd = *c;
                }
            }
            else if (buff_value[0] == 'U' &&
                    buff_value[1] == 'P' &&
                    buff_value[2] == 'D' &&
                    buff_value[3] == 'A' &&
                    buff_value[4] == 'T' &&
                    buff_value[5] == 'E')
            {
                char r;
                cli();
                wdt_disable();

                while (1)
                {
                    if (UCSR0A & (1<<RXC0))
                    {
                        r = UDR0;
                        UDR3 = r;
                    }

                    if (UCSR3A & (1<<RXC3))
                    {
                        r = UDR3;
                        UDR0 = r;
                    }
                }
            }
            else {
                if (buff_value[0]=='E' && buff_value[1]=='R' && buff_value[2]=='A' && buff_value[3]=='S' && buff_value[4]=='E')
                {
                    eeprom::factoryResetEEPROM();
                    Motherboard::getBoard().reset(true);
                }
                
                else if (buff_value[0]=='F' && buff_value[1]=='U' && buff_value[2]=='L' && buff_value[3]=='L' && buff_value[4]=='E' && buff_value[5]=='R' && buff_value[6]=='A' && buff_value[7]=='S' && buff_value[8]=='E')
                {
                    eeprom::erase();
                    host::stopBuildNow();
                }
            }
            break;
*/
        default:
            break;
    }
}