Merge remote-tracking branch 'upstream/Marlin_v1' into Marlin_v1
This commit is contained in:
		| @@ -26,17 +26,19 @@ | ||||
| // 12 = Gen7 v1.3 | ||||
| // 13 = Gen7 v1.4 | ||||
| // 3  = MEGA/RAMPS up to 1.2 = 3 | ||||
| // 33 = RAMPS 1.3 (Power outputs: Extruder, Bed, Fan) | ||||
| // 34 = RAMPS 1.3 (Power outputs: Extruder0, Extruder1, Bed) | ||||
| // 33 = RAMPS 1.3 / 1.4 (Power outputs: Extruder, Bed, Fan) | ||||
| // 34 = RAMPS 1.3 / 1.4 (Power outputs: Extruder0, Extruder1, Bed) | ||||
| // 4  = Duemilanove w/ ATMega328P pin assignment | ||||
| // 5  = Gen6 | ||||
| // 51 = Gen6 deluxe | ||||
| // 6  = Sanguinololu < 1.2 | ||||
| // 62 = Sanguinololu 1.2 and above | ||||
| // 63 = Melzi | ||||
| // 64 = STB V1.1 | ||||
| // 7  = Ultimaker | ||||
| // 71 = Ultimaker (Older electronics. Pre 1.5.4. This is rare) | ||||
| // 8  = Teensylu | ||||
| // 80 = Rumba | ||||
| // 81 = Printrboard (AT90USB1286) | ||||
| // 82 = Brainwave (AT90USB646) | ||||
| // 9  = Gen3+ | ||||
| @@ -119,7 +121,8 @@ | ||||
| // PID settings: | ||||
| // Comment the following line to disable PID and enable bang-bang. | ||||
| #define PIDTEMP | ||||
| #define PID_MAX 256 // limits current to nozzle; 256=full current | ||||
| #define BANG_MAX 256 // limits current to nozzle while in bang-bang mode; 256=full current | ||||
| #define PID_MAX 256 // limits current to nozzle while PID is active (see PID_FUNCTIONAL_RANGE below); 256=full current | ||||
| #ifdef PIDTEMP | ||||
|   //#define PID_DEBUG // Sends debug data to the serial port.  | ||||
|   //#define PID_OPENLOOP 1 // Puts PID in open loop. M104/M140 sets the output power from 0 to PID_MAX | ||||
| @@ -283,7 +286,7 @@ const bool Z_ENDSTOPS_INVERTING = true; // set to true to invert the logic of th | ||||
| // default settings  | ||||
|  | ||||
| #define DEFAULT_AXIS_STEPS_PER_UNIT   {78.7402,78.7402,200*8/3,760*1.1}  // default steps per unit for ultimaker  | ||||
| #define DEFAULT_MAX_FEEDRATE          {500, 500, 5, 45}    // (mm/sec)     | ||||
| #define DEFAULT_MAX_FEEDRATE          {500, 500, 5, 25}    // (mm/sec)     | ||||
| #define DEFAULT_MAX_ACCELERATION      {9000,9000,100,10000}    // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for skeinforge 40+, for older versions raise them a lot. | ||||
|  | ||||
| #define DEFAULT_ACCELERATION          3000    // X, Y, Z and E max acceleration in mm/s^2 for printing moves  | ||||
| @@ -317,7 +320,9 @@ const bool Z_ENDSTOPS_INVERTING = true; // set to true to invert the logic of th | ||||
|  | ||||
| //LCD and SD support | ||||
| //#define ULTRA_LCD  //general lcd support, also 16x2 | ||||
| //#define DOGLCD	// Support for SPI LCD 128x64 (Controller ST7565R graphic Display Family) | ||||
| //#define SDSUPPORT // Enable SD Card Support in Hardware Console | ||||
| //#define SDSLOW // Use slower SD transfer mode (not normally needed - uncomment if you're getting volume init error) | ||||
|  | ||||
| //#define ULTIMAKERCONTROLLER //as available from the ultimaker online store. | ||||
| //#define ULTIPANEL  //the ultipanel as on thingiverse | ||||
| @@ -330,7 +335,19 @@ const bool Z_ENDSTOPS_INVERTING = true; // set to true to invert the logic of th | ||||
| // http://reprap.org/wiki/RAMPS_1.3/1.4_GADGETS3D_Shield_with_Panel | ||||
| //#define G3D_PANEL | ||||
|  | ||||
| // The RepRapDiscount FULL GRAPHIC Smart Controller (quadratic white PCB) | ||||
| // http://reprap.org/wiki/RepRapDiscount_Full_Graphic_Smart_Controller | ||||
| // | ||||
| // ==> REMEMBER TO INSTALL U8glib to your ARDUINO library folder: http://code.google.com/p/u8glib/wiki/u8glib | ||||
| //#define REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER | ||||
|  | ||||
| //automatic expansion | ||||
| #if defined (REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) | ||||
|  #define DOGLCD | ||||
|  #define U8GLIB_ST7920 | ||||
|  #define REPRAP_DISCOUNT_SMART_CONTROLLER | ||||
| #endif | ||||
|  | ||||
| #if defined(ULTIMAKERCONTROLLER) || defined(REPRAP_DISCOUNT_SMART_CONTROLLER) || defined(G3D_PANEL) | ||||
|  #define ULTIPANEL | ||||
|  #define NEWPANEL | ||||
| @@ -350,13 +367,22 @@ const bool Z_ENDSTOPS_INVERTING = true; // set to true to invert the logic of th | ||||
| //  #define NEWPANEL  //enable this if you have a click-encoder panel | ||||
|   #define SDSUPPORT | ||||
|   #define ULTRA_LCD | ||||
|   #define LCD_WIDTH 20 | ||||
|   #define LCD_HEIGHT 4 | ||||
|    | ||||
| 	#ifdef DOGLCD	// Change number of lines to match the DOG graphic display | ||||
| 		#define LCD_WIDTH 20 | ||||
| 		#define LCD_HEIGHT 5 | ||||
| 	#else | ||||
| 		#define LCD_WIDTH 20 | ||||
| 		#define LCD_HEIGHT 4 | ||||
| 	#endif | ||||
| #else //no panel but just lcd  | ||||
|   #ifdef ULTRA_LCD | ||||
|     #define LCD_WIDTH 16 | ||||
|     #define LCD_HEIGHT 2     | ||||
| 	#ifdef DOGLCD	// Change number of lines to match the 128x64 graphics display | ||||
| 		#define LCD_WIDTH 20 | ||||
| 		#define LCD_HEIGHT 5 | ||||
| 	#else | ||||
| 		#define LCD_WIDTH 16 | ||||
| 		#define LCD_HEIGHT 2 | ||||
| 	#endif     | ||||
|   #endif | ||||
| #endif | ||||
|  | ||||
|   | ||||
| @@ -3,26 +3,26 @@ | ||||
| #include "temperature.h" | ||||
| #include "ultralcd.h" | ||||
| #include "ConfigurationStore.h" | ||||
|  | ||||
| void _EEPROM_writeData(int &pos, uint8_t* value, uint8_t size) | ||||
| { | ||||
|     do | ||||
|     { | ||||
|         eeprom_write_byte((unsigned char*)pos, *value); | ||||
|         pos++; | ||||
|         value++; | ||||
|  | ||||
| void _EEPROM_writeData(int &pos, uint8_t* value, uint8_t size) | ||||
| { | ||||
|     do | ||||
|     { | ||||
|         eeprom_write_byte((unsigned char*)pos, *value); | ||||
|         pos++; | ||||
|         value++; | ||||
|     }while(--size); | ||||
| } | ||||
| } | ||||
| #define EEPROM_WRITE_VAR(pos, value) _EEPROM_writeData(pos, (uint8_t*)&value, sizeof(value)) | ||||
| void _EEPROM_readData(int &pos, uint8_t* value, uint8_t size) | ||||
| { | ||||
|     do | ||||
|     { | ||||
|         *value = eeprom_read_byte((unsigned char*)pos); | ||||
|         pos++; | ||||
|         value++; | ||||
| void _EEPROM_readData(int &pos, uint8_t* value, uint8_t size) | ||||
| { | ||||
|     do | ||||
|     { | ||||
|         *value = eeprom_read_byte((unsigned char*)pos); | ||||
|         pos++; | ||||
|         value++; | ||||
|     }while(--size); | ||||
| } | ||||
| } | ||||
| #define EEPROM_READ_VAR(pos, value) _EEPROM_readData(pos, (uint8_t*)&value, sizeof(value)) | ||||
| //====================================================================================== | ||||
|  | ||||
| @@ -43,7 +43,7 @@ void _EEPROM_readData(int &pos, uint8_t* value, uint8_t size) | ||||
| void Config_StoreSettings()  | ||||
| { | ||||
|   char ver[4]= "000"; | ||||
|   int i=EEPROM_OFFSET; | ||||
|   int i=EEPROM_OFFSET; | ||||
|   EEPROM_WRITE_VAR(i,ver); // invalidate data first  | ||||
|   EEPROM_WRITE_VAR(i,axis_steps_per_unit);   | ||||
|   EEPROM_WRITE_VAR(i,max_feedrate);   | ||||
| @@ -58,8 +58,8 @@ void Config_StoreSettings() | ||||
|   EEPROM_WRITE_VAR(i,max_e_jerk); | ||||
|   EEPROM_WRITE_VAR(i,add_homeing); | ||||
|   #ifndef ULTIPANEL | ||||
|   int plaPreheatHotendTemp = PLA_PREHEAT_HOTEND_TEMP, plaPreheatHPBTemp = PLA_PREHEAT_HPB_TEMP, plaPreheatFanSpeed = PLA_PREHEAT_FAN_SPEED; | ||||
|   int absPreheatHotendTemp = ABS_PREHEAT_HOTEND_TEMP, absPreheatHPBTemp = ABS_PREHEAT_HPB_TEMP, absPreheatFanSpeed = ABS_PREHEAT_FAN_SPEED; | ||||
|   int plaPreheatHotendTemp = PLA_PREHEAT_HOTEND_TEMP, plaPreheatHPBTemp = PLA_PREHEAT_HPB_TEMP, plaPreheatFanSpeed = PLA_PREHEAT_FAN_SPEED; | ||||
|   int absPreheatHotendTemp = ABS_PREHEAT_HOTEND_TEMP, absPreheatHPBTemp = ABS_PREHEAT_HPB_TEMP, absPreheatFanSpeed = ABS_PREHEAT_FAN_SPEED; | ||||
|   #endif | ||||
|   EEPROM_WRITE_VAR(i,plaPreheatHotendTemp); | ||||
|   EEPROM_WRITE_VAR(i,plaPreheatHPBTemp); | ||||
| @@ -72,10 +72,12 @@ void Config_StoreSettings() | ||||
|     EEPROM_WRITE_VAR(i,Ki); | ||||
|     EEPROM_WRITE_VAR(i,Kd); | ||||
|   #else | ||||
|     EEPROM_WRITE_VAR(i,3000); | ||||
|     EEPROM_WRITE_VAR(i,0); | ||||
|     EEPROM_WRITE_VAR(i,0); | ||||
|   #endif | ||||
| 		float dummy = 3000.0f; | ||||
|     EEPROM_WRITE_VAR(i,dummy); | ||||
| 		dummy = 0.0f; | ||||
|     EEPROM_WRITE_VAR(i,dummy); | ||||
|     EEPROM_WRITE_VAR(i,dummy); | ||||
|   #endif | ||||
|   char ver2[4]=EEPROM_VERSION; | ||||
|   i=EEPROM_OFFSET; | ||||
|   EEPROM_WRITE_VAR(i,ver2); // validate data | ||||
| @@ -105,7 +107,7 @@ void Config_PrintSettings() | ||||
|     SERIAL_ECHOPAIR(" Z", max_feedrate[2] );  | ||||
|     SERIAL_ECHOPAIR(" E", max_feedrate[3]); | ||||
|     SERIAL_ECHOLN(""); | ||||
|  | ||||
|  | ||||
|     SERIAL_ECHO_START; | ||||
|     SERIAL_ECHOLNPGM("Maximum Acceleration (mm/s2):"); | ||||
|     SERIAL_ECHO_START; | ||||
| @@ -120,9 +122,9 @@ void Config_PrintSettings() | ||||
|     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_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),  E=maximum E jerk (mm/s)"); | ||||
|     SERIAL_ECHO_START; | ||||
|     SERIAL_ECHOPAIR("  M205 S",minimumfeedrate );  | ||||
|     SERIAL_ECHOPAIR(" T" ,mintravelfeedrate );  | ||||
| @@ -131,7 +133,7 @@ void Config_PrintSettings() | ||||
|     SERIAL_ECHOPAIR(" Z" ,max_z_jerk); | ||||
|     SERIAL_ECHOPAIR(" E" ,max_e_jerk); | ||||
|     SERIAL_ECHOLN("");  | ||||
|  | ||||
|  | ||||
|     SERIAL_ECHO_START; | ||||
|     SERIAL_ECHOLNPGM("Home offset (mm):"); | ||||
|     SERIAL_ECHO_START; | ||||
| @@ -144,8 +146,8 @@ void Config_PrintSettings() | ||||
|     SERIAL_ECHOLNPGM("PID settings:"); | ||||
|     SERIAL_ECHO_START; | ||||
|     SERIAL_ECHOPAIR("   M301 P",Kp);  | ||||
|     SERIAL_ECHOPAIR(" I" ,Ki/PID_dT);  | ||||
|     SERIAL_ECHOPAIR(" D" ,Kd*PID_dT); | ||||
|     SERIAL_ECHOPAIR(" I" ,unscalePID_i(Ki));  | ||||
|     SERIAL_ECHOPAIR(" D" ,unscalePID_d(Kd)); | ||||
|     SERIAL_ECHOLN("");  | ||||
| #endif | ||||
| }  | ||||
| @@ -161,11 +163,15 @@ void Config_RetrieveSettings() | ||||
|     EEPROM_READ_VAR(i,stored_ver); //read stored version | ||||
|     //  SERIAL_ECHOLN("Version: [" << ver << "] Stored version: [" << stored_ver << "]"); | ||||
|     if (strncmp(ver,stored_ver,3) == 0) | ||||
|     { | ||||
|     { | ||||
|         // version number match | ||||
|         EEPROM_READ_VAR(i,axis_steps_per_unit);   | ||||
|         EEPROM_READ_VAR(i,max_feedrate);   | ||||
|         EEPROM_READ_VAR(i,max_acceleration_units_per_sq_second); | ||||
|          | ||||
|         // steps per sq second need to be updated to agree with the units per sq second (as they are what is used in the planner) | ||||
| 		reset_acceleration_rates(); | ||||
|          | ||||
|         EEPROM_READ_VAR(i,acceleration); | ||||
|         EEPROM_READ_VAR(i,retract_acceleration); | ||||
|         EEPROM_READ_VAR(i,minimumfeedrate); | ||||
| @@ -176,36 +182,37 @@ void Config_RetrieveSettings() | ||||
|         EEPROM_READ_VAR(i,max_e_jerk); | ||||
|         EEPROM_READ_VAR(i,add_homeing); | ||||
|         #ifndef ULTIPANEL | ||||
|         int plaPreheatHotendTemp, plaPreheatHPBTemp, plaPreheatFanSpeed; | ||||
|         int absPreheatHotendTemp, absPreheatHPBTemp, absPreheatFanSpeed; | ||||
|         int plaPreheatHotendTemp, plaPreheatHPBTemp, plaPreheatFanSpeed; | ||||
|         int absPreheatHotendTemp, absPreheatHPBTemp, absPreheatFanSpeed; | ||||
|         #endif | ||||
|         EEPROM_READ_VAR(i,plaPreheatHotendTemp); | ||||
|         EEPROM_READ_VAR(i,plaPreheatHPBTemp); | ||||
|         EEPROM_READ_VAR(i,plaPreheatFanSpeed); | ||||
|         EEPROM_READ_VAR(i,absPreheatHotendTemp); | ||||
|         EEPROM_READ_VAR(i,absPreheatHPBTemp); | ||||
|         EEPROM_READ_VAR(i,absPreheatFanSpeed); | ||||
|         EEPROM_READ_VAR(i,absPreheatFanSpeed); | ||||
|         #ifndef PIDTEMP | ||||
|         float Kp,Ki,Kd; | ||||
|         #endif | ||||
|         // do not need to scale PID values as the values in EEPROM are already scaled		 | ||||
|         EEPROM_READ_VAR(i,Kp); | ||||
|         EEPROM_READ_VAR(i,Ki); | ||||
|         EEPROM_READ_VAR(i,Kd); | ||||
|  | ||||
| 		// Call updatePID (similar to when we have processed M301) | ||||
| 		updatePID(); | ||||
|         SERIAL_ECHO_START; | ||||
|         SERIAL_ECHOLNPGM("Stored settings retreived:"); | ||||
|         SERIAL_ECHOLNPGM("Stored settings retrieved"); | ||||
|     } | ||||
|     else | ||||
|     { | ||||
|         Config_ResetDefault(); | ||||
|     } | ||||
|     else | ||||
|     { | ||||
|         Config_ResetDefault(); | ||||
|         SERIAL_ECHO_START; | ||||
|         SERIAL_ECHOLN("Using Default settings:"); | ||||
|     } | ||||
|     Config_PrintSettings(); | ||||
| } | ||||
| #endif | ||||
|  | ||||
| void Config_ResetDefault() | ||||
| #endif | ||||
|  | ||||
| void Config_ResetDefault() | ||||
| { | ||||
|     float tmp1[]=DEFAULT_AXIS_STEPS_PER_UNIT; | ||||
|     float tmp2[]=DEFAULT_MAX_FEEDRATE; | ||||
| @@ -216,6 +223,10 @@ void Config_ResetDefault() | ||||
|         max_feedrate[i]=tmp2[i];   | ||||
|         max_acceleration_units_per_sq_second[i]=tmp3[i]; | ||||
|     } | ||||
|      | ||||
|     // steps per sq second need to be updated to agree with the units per sq second | ||||
|     reset_acceleration_rates(); | ||||
|      | ||||
|     acceleration=DEFAULT_ACCELERATION; | ||||
|     retract_acceleration=DEFAULT_RETRACT_ACCELERATION; | ||||
|     minimumfeedrate=DEFAULT_MINIMUMFEEDRATE; | ||||
| @@ -234,11 +245,19 @@ void Config_ResetDefault() | ||||
|     absPreheatFanSpeed = ABS_PREHEAT_FAN_SPEED; | ||||
| #endif | ||||
| #ifdef PIDTEMP | ||||
|     Kp = DEFAULT_Kp; | ||||
|     Ki = (DEFAULT_Ki*PID_dT); | ||||
|     Kd = (DEFAULT_Kd/PID_dT); | ||||
|     Kp = DEFAULT_Kp; | ||||
|     Ki = scalePID_i(DEFAULT_Ki); | ||||
|     Kd = scalePID_d(DEFAULT_Kd); | ||||
|      | ||||
|     // call updatePID (similar to when we have processed M301) | ||||
|     updatePID(); | ||||
|      | ||||
| #ifdef PID_ADD_EXTRUSION_RATE | ||||
|     Kc = DEFAULT_Kc; | ||||
| #endif//PID_ADD_EXTRUSION_RATE | ||||
| #endif//PIDTEMP | ||||
|  | ||||
| SERIAL_ECHO_START; | ||||
| SERIAL_ECHOLNPGM("Hardcoded Default Settings Loaded"); | ||||
|  | ||||
| } | ||||
|   | ||||
							
								
								
									
										121
									
								
								Marlin/DOGMbitmaps.h
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										121
									
								
								Marlin/DOGMbitmaps.h
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,121 @@ | ||||
| #define START_BMPWIDTH 	60	//Width in pixels | ||||
| #define START_BMPHEIGHT 	64	//Height in pixels | ||||
| #define START_BMPBYTEWIDTH 	8	//Width in bytes | ||||
| unsigned char start_bmp[574] PROGMEM = { //AVR-GCC, WinAVR | ||||
| 0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xF0, | ||||
| 0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xF0, | ||||
| 0xFF,0xFF,0xFF,0xF9,0xFF,0xFF,0xFF,0xF0, | ||||
| 0xFF,0xFF,0xFF,0xF0,0xFF,0xFF,0xFF,0xF0, | ||||
| 0xFF,0xFF,0xFF,0xE0,0x7F,0xFF,0xFF,0xF0, | ||||
| 0xFF,0xFF,0xFF,0xC0,0x3F,0xFF,0xFF,0xF0, | ||||
| 0xFF,0xFF,0xFF,0x80,0x1F,0xFF,0xFF,0xF0, | ||||
| 0xFF,0xFF,0xFF,0x00,0x0F,0xFF,0xFF,0xF0, | ||||
| 0xFF,0xFF,0xFE,0x00,0x07,0xFF,0xFF,0xF0, | ||||
| 0xFF,0xFF,0xFC,0x00,0x03,0xFF,0xFF,0xF0, | ||||
| 0xFF,0xFF,0xF8,0x00,0x01,0xFF,0xFF,0xF0, | ||||
| 0xFF,0xFF,0xF0,0x00,0x00,0xFF,0xFF,0xF0, | ||||
| 0xFF,0xFF,0xE0,0x00,0x00,0x7F,0xFF,0xF0, | ||||
| 0xFF,0xFF,0xC0,0x00,0x00,0x3F,0xFF,0xF0, | ||||
| 0xFF,0xFF,0x80,0x00,0x00,0x3F,0xFF,0xF0, | ||||
| 0xFF,0xFF,0x00,0x00,0x00,0x1F,0xFF,0xF0, | ||||
| 0xFF,0xFE,0x00,0x00,0x00,0x0F,0xFF,0xF0, | ||||
| 0xFF,0xFE,0x00,0x00,0x00,0x07,0xFF,0xF0, | ||||
| 0xFF,0xFC,0x00,0x00,0x00,0x07,0xFF,0xF0, | ||||
| 0xFF,0xFC,0x00,0x00,0x00,0x03,0xFF,0xF0, | ||||
| 0xFF,0xF8,0x00,0x00,0x00,0x03,0xFF,0xF0, | ||||
| 0xFF,0xF8,0x00,0x00,0x00,0x03,0xFF,0xF0, | ||||
| 0xFF,0xF8,0x00,0x00,0x00,0x01,0xFF,0xF0, | ||||
| 0xFF,0xF8,0x00,0x00,0x00,0x01,0xFF,0xF0, | ||||
| 0xFF,0xF8,0x00,0x00,0x00,0x01,0xFF,0xF0, | ||||
| 0xFF,0xF8,0x00,0x00,0x00,0x01,0xFF,0xF0, | ||||
| 0xFF,0xF8,0x00,0x00,0x00,0x01,0xFF,0xF0, | ||||
| 0xFF,0xF8,0x00,0x00,0x00,0x01,0xFF,0xF0, | ||||
| 0xFF,0xF8,0x00,0x00,0x00,0x01,0xFF,0xF0, | ||||
| 0xFF,0xF8,0x00,0x00,0x00,0x01,0xFF,0xF0, | ||||
| 0xFF,0xF8,0x00,0x00,0x00,0x03,0xFF,0xF0, | ||||
| 0xFF,0xF8,0x00,0x00,0x00,0x03,0xFF,0xF0, | ||||
| 0xFF,0xFC,0x00,0x00,0x00,0x03,0xFF,0xF0, | ||||
| 0xFF,0xFC,0x00,0x00,0x00,0x07,0xFF,0xF0, | ||||
| 0xFF,0xFE,0x00,0x00,0x00,0x07,0xFF,0xF0, | ||||
| 0xFF,0xFE,0x00,0x00,0x00,0x0F,0xFF,0xF0, | ||||
| 0xFF,0xFF,0x00,0x00,0x00,0x1F,0xFF,0xF0, | ||||
| 0xFF,0xFF,0x80,0x00,0x00,0x1F,0xFF,0xF0, | ||||
| 0xFF,0xFF,0xC0,0x00,0x00,0x3F,0xFF,0xF0, | ||||
| 0xFF,0xFF,0xE0,0x00,0x00,0x7F,0xFF,0xF0, | ||||
| 0xFF,0xFF,0xF0,0x00,0x01,0xFF,0xFF,0xF0, | ||||
| 0xFF,0xFF,0xFC,0x00,0x03,0xFF,0xFF,0xF0, | ||||
| 0xFF,0xFF,0xFF,0x00,0x1F,0xFF,0xFF,0xF0, | ||||
| 0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xF0, | ||||
| 0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xF0, | ||||
| 0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xF0, | ||||
| 0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xF0, | ||||
| 0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xF0, | ||||
| 0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xF0, | ||||
| 0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xF0, | ||||
| 0x83,0xFF,0xFF,0xFE,0x0F,0xFF,0xFF,0xF0, | ||||
| 0x80,0xFF,0xFF,0xFE,0x03,0xFF,0xFF,0xF0, | ||||
| 0x88,0x7F,0xFF,0xFE,0x23,0xFF,0xFF,0xF0, | ||||
| 0x8C,0x70,0x38,0x0E,0x71,0x81,0xC0,0x70, | ||||
| 0x8C,0x60,0x38,0x0E,0x63,0x80,0xC0,0x30, | ||||
| 0x80,0xE3,0x19,0xC6,0x07,0xF8,0xC7,0x30, | ||||
| 0x80,0xE0,0x19,0xC6,0x03,0x80,0xC7,0x10, | ||||
| 0x8C,0x62,0x79,0xC6,0x63,0x9C,0xC7,0x30, | ||||
| 0x8C,0x63,0xF8,0xC6,0x71,0x18,0xC6,0x30, | ||||
| 0x8E,0x30,0x18,0x0E,0x71,0x80,0xC0,0x30, | ||||
| 0x9E,0x38,0x39,0x1E,0x79,0xC4,0xC4,0xF0, | ||||
| 0xFF,0xFF,0xF9,0xFF,0xFF,0xFF,0xC7,0xF0, | ||||
| 0xFF,0xFF,0xF9,0xFF,0xFF,0xFF,0xC7,0xF0, | ||||
| 0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xFF,0xF0 | ||||
| }; | ||||
|  | ||||
| #define STATUS_SCREENWIDTH 		115	//Width in pixels | ||||
| #define STATUS_SCREENHEIGHT 	19	//Height in pixels | ||||
| #define STATUS_SCREENBYTEWIDTH 	15	//Width in bytes | ||||
| unsigned char status_screen0_bmp[] PROGMEM = { //AVR-GCC, WinAVR | ||||
| 0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x7F,0xFF,0xE0, | ||||
| 0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x70,0x00,0xE0, | ||||
| 0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x63,0x0C,0x60, | ||||
| 0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x47,0x0E,0x20, | ||||
| 0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x4F,0x0F,0x20, | ||||
| 0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x5F,0x0F,0xA0, | ||||
| 0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x5E,0x07,0xA0, | ||||
| 0x7F,0x80,0x00,0x3F,0xC0,0x00,0x3F,0xC0,0x00,0x41,0x04,0x00,0x40,0x60,0x20, | ||||
| 0xFB,0xC0,0x00,0x79,0xE0,0x00,0x79,0xE0,0x00,0x20,0x82,0x00,0x40,0xF0,0x20, | ||||
| 0xF3,0xC0,0x00,0x76,0xE0,0x00,0x76,0xE0,0x00,0x20,0x82,0x00,0x40,0xF0,0x20, | ||||
| 0xEB,0xC0,0x00,0x7E,0xE0,0x00,0x7E,0xE0,0x00,0x41,0x04,0x00,0x40,0x60,0x20, | ||||
| 0x7B,0x80,0x00,0x3D,0xC0,0x00,0x39,0xC0,0x00,0x82,0x08,0x00,0x5E,0x07,0xA0, | ||||
| 0x7B,0x80,0x00,0x3B,0xC0,0x00,0x3E,0xC0,0x01,0x04,0x10,0x00,0x5F,0x0F,0xA0, | ||||
| 0xFB,0xC0,0x00,0x77,0xE0,0x00,0x76,0xE0,0x01,0x04,0x10,0x00,0x4F,0x0F,0x20, | ||||
| 0xFB,0xC0,0x00,0x70,0xE0,0x00,0x79,0xE0,0x00,0x82,0x08,0x00,0x47,0x0E,0x20, | ||||
| 0xFF,0xC0,0x00,0x7F,0xE0,0x00,0x7F,0xE0,0x00,0x41,0x04,0x00,0x63,0x0C,0x60, | ||||
| 0x3F,0x00,0x00,0x1F,0x80,0x00,0x1F,0x80,0x00,0x00,0x00,0x00,0x70,0x00,0xE0, | ||||
| 0x1E,0x00,0x00,0x0F,0x00,0x00,0x0F,0x00,0x01,0xFF,0xFF,0x80,0x7F,0xFF,0xE0, | ||||
| 0x0C,0x00,0x00,0x06,0x00,0x00,0x06,0x00,0x01,0xFF,0xFF,0x80,0x00,0x00,0x00 | ||||
| }; | ||||
|  | ||||
| #define STATUS_SCREENWIDTH 		115	//Width in pixels | ||||
| #define STATUS_SCREENHEIGHT 	19	//Height in pixels | ||||
| #define STATUS_SCREENBYTEWIDTH 	15	//Width in bytes | ||||
| unsigned char status_screen1_bmp[] PROGMEM = { //AVR-GCC, WinAVR | ||||
| 0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x7F,0xFF,0xE0, | ||||
| 0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x70,0x00,0xE0, | ||||
| 0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x61,0xF8,0x60, | ||||
| 0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x41,0xF8,0x20, | ||||
| 0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x40,0xF0,0x20, | ||||
| 0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x40,0x60,0x20, | ||||
| 0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x00,0x58,0x01,0xA0, | ||||
| 0x7F,0x80,0x00,0x3F,0xC0,0x00,0x3F,0xC0,0x00,0x41,0x04,0x00,0x5C,0x63,0xA0, | ||||
| 0xFB,0xC0,0x00,0x79,0xE0,0x00,0x79,0xE0,0x00,0x20,0x82,0x00,0x5E,0xF7,0xA0, | ||||
| 0xF3,0xC0,0x00,0x76,0xE0,0x00,0x76,0xE0,0x00,0x20,0x82,0x00,0x5E,0xF7,0xA0, | ||||
| 0xEB,0xC0,0x00,0x7E,0xE0,0x00,0x7E,0xE0,0x00,0x41,0x04,0x00,0x5C,0x63,0xA0, | ||||
| 0x7B,0x80,0x00,0x3D,0xC0,0x00,0x39,0xC0,0x00,0x82,0x08,0x00,0x58,0x01,0xA0, | ||||
| 0x7B,0x80,0x00,0x3B,0xC0,0x00,0x3E,0xC0,0x01,0x04,0x10,0x00,0x40,0x60,0x20, | ||||
| 0xFB,0xC0,0x00,0x77,0xE0,0x00,0x76,0xE0,0x01,0x04,0x10,0x00,0x40,0xF0,0x20, | ||||
| 0xFB,0xC0,0x00,0x70,0xE0,0x00,0x79,0xE0,0x00,0x82,0x08,0x00,0x41,0xF8,0x20, | ||||
| 0xFF,0xC0,0x00,0x7F,0xE0,0x00,0x7F,0xE0,0x00,0x41,0x04,0x00,0x61,0xF8,0x60, | ||||
| 0x3F,0x00,0x00,0x1F,0x80,0x00,0x1F,0x80,0x00,0x00,0x00,0x00,0x70,0x00,0xE0, | ||||
| 0x1E,0x00,0x00,0x0F,0x00,0x00,0x0F,0x00,0x01,0xFF,0xFF,0x80,0x7F,0xFF,0xE0, | ||||
| 0x0C,0x00,0x00,0x06,0x00,0x00,0x06,0x00,0x01,0xFF,0xFF,0x80,0x00,0x00,0x00 | ||||
| }; | ||||
|  | ||||
|  | ||||
| @@ -34,7 +34,11 @@ | ||||
| #include "pins.h" | ||||
|  | ||||
| #ifdef ULTRA_LCD | ||||
| #include <LiquidCrystal.h> | ||||
| 	#ifdef DOGLCD | ||||
| 		#include <U8glib.h> // library for graphics LCD by Oli Kraus (https://code.google.com/p/u8glib/) | ||||
| 	#else | ||||
| 		#include <LiquidCrystal.h> // library for character LCD | ||||
| 	#endif | ||||
| #endif | ||||
|  | ||||
| #if DIGIPOTSS_PIN > -1 | ||||
|   | ||||
| @@ -117,6 +117,7 @@ | ||||
| // M220 S<factor in percent>- set speed factor override percentage | ||||
| // M221 S<factor in percent>- set extrude factor override percentage | ||||
| // M240 - Trigger a camera to take a photograph | ||||
| // M300 - Play beepsound S<frequency Hz> P<duration ms> | ||||
| // M301 - Set PID parameters P I and D | ||||
| // M302 - Allow cold extrudes | ||||
| // M303 - PID relay autotune S<temperature> sets the target temperature. (default target temperature = 150C) | ||||
| @@ -132,6 +133,7 @@ | ||||
| // M908 - Control digital trimpot directly. | ||||
| // M350 - Set microstepping mode. | ||||
| // M351 - Toggle MS1 MS2 pins directly. | ||||
| // M928 - Start SD logging (M928 filename.g) - ended by M29 | ||||
| // M999 - Restart after being stopped by error | ||||
|  | ||||
| //Stepper Movement Variables | ||||
| @@ -361,13 +363,8 @@ void setup() | ||||
|     fromsd[i] = false; | ||||
|   } | ||||
|    | ||||
|   Config_RetrieveSettings(); // loads data from EEPROM if available | ||||
|  | ||||
|   for(int8_t i=0; i < NUM_AXIS; i++) | ||||
|   { | ||||
|     axis_steps_per_sqr_second[i] = max_acceleration_units_per_sq_second[i] * axis_steps_per_unit[i]; | ||||
|   } | ||||
|  | ||||
|   // loads data from EEPROM if available else uses defaults (and resets step acceleration rate) | ||||
|   Config_RetrieveSettings();  | ||||
|  | ||||
|   tp_init();    // Initialize temperature loop  | ||||
|   plan_init();  // Initialize planner; | ||||
| @@ -376,6 +373,14 @@ void setup() | ||||
|   setup_photpin(); | ||||
|    | ||||
|   lcd_init(); | ||||
|    | ||||
|   #ifdef CONTROLLERFAN_PIN | ||||
|     SET_OUTPUT(CONTROLLERFAN_PIN); //Set pin used for driver cooling fan | ||||
|   #endif | ||||
|    | ||||
|   #ifdef EXTRUDERFAN_PIN | ||||
|     SET_OUTPUT(EXTRUDERFAN_PIN); //Set pin used for extruder cooling fan | ||||
|   #endif | ||||
| } | ||||
|  | ||||
|  | ||||
| @@ -394,7 +399,14 @@ void loop() | ||||
| 	if(strstr_P(cmdbuffer[bufindr], PSTR("M29")) == NULL) | ||||
| 	{ | ||||
| 	  card.write_command(cmdbuffer[bufindr]); | ||||
| 	  SERIAL_PROTOCOLLNPGM(MSG_OK); | ||||
|           if(card.logging) | ||||
|           { | ||||
|             process_commands(); | ||||
|           } | ||||
|           else | ||||
|           { | ||||
|             SERIAL_PROTOCOLLNPGM(MSG_OK); | ||||
|           } | ||||
| 	} | ||||
| 	else | ||||
| 	{ | ||||
| @@ -949,6 +961,15 @@ void process_commands() | ||||
| 	 card.removeFile(strchr_pointer + 4); | ||||
| 	} | ||||
| 	break; | ||||
|     case 928: //M928 - Start SD write | ||||
|       starpos = (strchr(strchr_pointer + 5,'*')); | ||||
|       if(starpos != NULL){ | ||||
|         char* npos = strchr(cmdbuffer[bufindr], 'N'); | ||||
|         strchr_pointer = strchr(npos,' ') + 1; | ||||
|         *(starpos-1) = '\0'; | ||||
|       } | ||||
|       card.openLogFile(strchr_pointer+5); | ||||
|       break; | ||||
| 	 | ||||
| #endif //SDSUPPORT | ||||
|  | ||||
| @@ -1301,9 +1322,10 @@ void process_commands() | ||||
|         if(code_seen(axis_codes[i])) | ||||
|         { | ||||
|           max_acceleration_units_per_sq_second[i] = code_value(); | ||||
|           axis_steps_per_sqr_second[i] = code_value() * axis_steps_per_unit[i]; | ||||
|         } | ||||
|       } | ||||
|       // steps per sq second need to be updated to agree with the units per sq second (as they are what is used in the planner) | ||||
| 	  reset_acceleration_rates(); | ||||
|       break; | ||||
|     #if 0 // Not used for Sprinter/grbl gen6 | ||||
|     case 202: // M202 | ||||
| @@ -1427,27 +1449,44 @@ void process_commands() | ||||
|       } | ||||
|     } | ||||
|     break; | ||||
|      | ||||
|     #if defined(LARGE_FLASH) && LARGE_FLASH == true && defined(BEEPER) && BEEPER > -1 | ||||
|     case 300: // M300 | ||||
|     { | ||||
|       int beepS = 1; | ||||
|       int beepP = 1000; | ||||
|       if(code_seen('S')) beepS = code_value(); | ||||
|       if(code_seen('P')) beepP = code_value(); | ||||
|       tone(BEEPER, beepS); | ||||
|       delay(beepP); | ||||
|       noTone(BEEPER); | ||||
|     } | ||||
|     break; | ||||
|     #endif // M300 | ||||
|  | ||||
|     #ifdef PIDTEMP | ||||
|     case 301: // M301 | ||||
|       { | ||||
|         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; | ||||
|         if(code_seen('I')) Ki = scalePID_i(code_value()); | ||||
|         if(code_seen('D')) Kd = scalePID_d(code_value()); | ||||
|  | ||||
|         #ifdef PID_ADD_EXTRUSION_RATE | ||||
|         if(code_seen('C')) Kc = code_value(); | ||||
|         #endif | ||||
|          | ||||
|         updatePID(); | ||||
|         SERIAL_PROTOCOL(MSG_OK); | ||||
| 		SERIAL_PROTOCOL(" p:"); | ||||
|         SERIAL_PROTOCOL(Kp); | ||||
|         SERIAL_PROTOCOL(" i:"); | ||||
|         SERIAL_PROTOCOL(Ki/PID_dT); | ||||
|         SERIAL_PROTOCOL(unscalePID_i(Ki)); | ||||
|         SERIAL_PROTOCOL(" d:"); | ||||
|         SERIAL_PROTOCOL(Kd*PID_dT); | ||||
|         SERIAL_PROTOCOL(unscalePID_d(Kd)); | ||||
|         #ifdef PID_ADD_EXTRUSION_RATE | ||||
|         SERIAL_PROTOCOL(" c:"); | ||||
|         SERIAL_PROTOCOL(Kc*PID_dT); | ||||
|         //Kc does not have scaling applied above, or in resetting defaults | ||||
|         SERIAL_PROTOCOL(Kc); | ||||
|         #endif | ||||
|         SERIAL_PROTOCOLLN(""); | ||||
|       } | ||||
| @@ -1457,16 +1496,17 @@ void process_commands() | ||||
|     case 304: // M304 | ||||
|       { | ||||
|         if(code_seen('P')) bedKp = code_value(); | ||||
|         if(code_seen('I')) bedKi = code_value()*PID_dT; | ||||
|         if(code_seen('D')) bedKd = code_value()/PID_dT; | ||||
|         if(code_seen('I')) bedKi = scalePID_i(code_value()); | ||||
|         if(code_seen('D')) bedKd = scalePID_d(code_value()); | ||||
|  | ||||
|         updatePID(); | ||||
|         SERIAL_PROTOCOL(MSG_OK); | ||||
| 		SERIAL_PROTOCOL(" p:"); | ||||
|         SERIAL_PROTOCOL(bedKp); | ||||
|         SERIAL_PROTOCOL(" i:"); | ||||
|         SERIAL_PROTOCOL(bedKi/PID_dT); | ||||
|         SERIAL_PROTOCOL(unscalePID_i(bedKi)); | ||||
|         SERIAL_PROTOCOL(" d:"); | ||||
|         SERIAL_PROTOCOL(bedKd*PID_dT); | ||||
|         SERIAL_PROTOCOL(unscalePID_d(bedKd)); | ||||
|         SERIAL_PROTOCOLLN(""); | ||||
|       } | ||||
|       break; | ||||
| @@ -1957,6 +1997,27 @@ void controllerFan() | ||||
| } | ||||
| #endif | ||||
|  | ||||
| #ifdef EXTRUDERFAN_PIN | ||||
| unsigned long lastExtruderCheck = 0; | ||||
|  | ||||
| void extruderFan() | ||||
| { | ||||
|   if ((millis() - lastExtruderCheck) >= 2500) //Not a time critical function, so we only check every 2500ms | ||||
|   { | ||||
|     lastExtruderCheck = millis(); | ||||
|             | ||||
|     if (degHotend(active_extruder) < EXTRUDERFAN_DEC) | ||||
|     { | ||||
|       WRITE(EXTRUDERFAN_PIN, LOW); //... turn the fan off | ||||
|     } | ||||
|     else | ||||
|     { | ||||
|       WRITE(EXTRUDERFAN_PIN, HIGH); //... turn the fan on | ||||
|     } | ||||
|   } | ||||
| } | ||||
| #endif | ||||
|  | ||||
| void manage_inactivity()  | ||||
| {  | ||||
|   if( (millis() - previous_millis_cmd) >  max_inactive_time )  | ||||
|   | ||||
| @@ -16,6 +16,7 @@ CardReader::CardReader() | ||||
|    sdprinting = false; | ||||
|    cardOK = false; | ||||
|    saving = false; | ||||
|    logging = false; | ||||
|    autostart_atmillis=0; | ||||
|  | ||||
|    autostart_stilltocheck=true; //the sd start is delayed, because otherwise the serial cannot answer fast enought to make contact with the hostsoftware. | ||||
| @@ -145,7 +146,11 @@ void CardReader::initsd() | ||||
|   cardOK = false; | ||||
|   if(root.isOpen()) | ||||
|     root.close(); | ||||
| #ifdef SDSLOW | ||||
|   if (!card.init(SPI_HALF_SPEED,SDSS)) | ||||
| #else | ||||
|   if (!card.init(SPI_FULL_SPEED,SDSS)) | ||||
| #endif | ||||
|   { | ||||
|     //if (!card.init(SPI_HALF_SPEED,SDSS)) | ||||
|     SERIAL_ECHO_START; | ||||
| @@ -212,6 +217,11 @@ void CardReader::pauseSDPrint() | ||||
| } | ||||
|  | ||||
|  | ||||
| void CardReader::openLogFile(char* name) | ||||
| { | ||||
|   logging = true; | ||||
|   openFile(name, false); | ||||
| } | ||||
|  | ||||
| void CardReader::openFile(char* name,bool read) | ||||
| { | ||||
| @@ -471,6 +481,7 @@ void CardReader::closefile() | ||||
|   file.sync(); | ||||
|   file.close(); | ||||
|   saving = false;  | ||||
|   logging = false; | ||||
| } | ||||
|  | ||||
| void CardReader::getfilename(const uint8_t nr) | ||||
|   | ||||
| @@ -17,6 +17,7 @@ public: | ||||
|  | ||||
|   void checkautostart(bool x);  | ||||
|   void openFile(char* name,bool read); | ||||
|   void openLogFile(char* name); | ||||
|   void removeFile(char* name); | ||||
|   void closefile(); | ||||
|   void release(); | ||||
| @@ -44,6 +45,7 @@ public: | ||||
|  | ||||
| public: | ||||
|   bool saving; | ||||
|   bool logging; | ||||
|   bool sdprinting ;   | ||||
|   bool cardOK ; | ||||
|   char filename[13]; | ||||
|   | ||||
							
								
								
									
										337
									
								
								Marlin/dogm_font_data_marlin.h
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										337
									
								
								Marlin/dogm_font_data_marlin.h
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,337 @@ | ||||
| /* | ||||
|   Fontname: -Misc-Fixed-Medium-R-Normal--9-90-75-75-C-60-ISO10646-1 | ||||
|   Copyright: Public domain font.  Share and enjoy. | ||||
|   Capital A Height: 6, '1' Height: 6 | ||||
|   Calculated Max Values w= 6 h= 9 x= 2 y= 7 dx= 6 dy= 0 ascent= 7 len= 9 | ||||
|   Font Bounding box     w= 6 h= 9 x= 0 y=-2 | ||||
|   Calculated Min Values           x= 0 y=-2 dx= 0 dy= 0 | ||||
|   Pure Font   ascent = 6 descent=-2 | ||||
|   X Font      ascent = 6 descent=-2 | ||||
|   Max Font    ascent = 7 descent=-2 | ||||
| */ | ||||
| #include <utility/u8g.h> | ||||
| const u8g_fntpgm_uint8_t u8g_font_6x9[2300] U8G_SECTION(".progmem.u8g_font_6x9") = { | ||||
|   0,6,9,0,254,6,1,137,2,254,32,255,254,7,254,6, | ||||
|   254,0,0,0,6,0,7,1,6,6,6,2,0,128,128,128, | ||||
|   128,0,128,3,3,3,6,1,3,160,160,160,5,7,7,6, | ||||
|   0,255,80,80,248,80,248,80,80,5,9,9,6,0,254,32, | ||||
|   112,168,160,112,40,168,112,32,6,8,8,6,0,255,64,168, | ||||
|   72,16,32,72,84,8,5,7,7,6,0,255,96,144,144,96, | ||||
|   152,144,104,1,3,3,6,2,3,128,128,128,2,7,7,6, | ||||
|   2,255,64,128,128,128,128,128,64,2,7,7,6,2,255,128, | ||||
|   64,64,64,64,64,128,5,5,5,6,0,0,136,80,248,80, | ||||
|   136,5,5,5,6,0,0,32,32,248,32,32,2,4,4,6, | ||||
|   2,254,192,64,64,128,5,1,1,6,0,2,248,2,2,2, | ||||
|   6,2,0,192,192,4,6,6,6,1,0,16,16,32,64,128, | ||||
|   128,4,6,6,6,1,0,96,144,144,144,144,96,3,6,6, | ||||
|   6,1,0,64,192,64,64,64,224,4,6,6,6,1,0,96, | ||||
|   144,16,32,64,240,4,6,6,6,1,0,240,32,96,16,16, | ||||
|   224,5,6,6,6,0,0,16,48,80,144,248,16,4,6,6, | ||||
|   6,1,0,240,128,224,16,16,224,4,6,6,6,1,0,96, | ||||
|   128,224,144,144,96,4,6,6,6,1,0,240,16,16,32,64, | ||||
|   64,4,6,6,6,1,0,96,144,96,144,144,96,4,6,6, | ||||
|   6,1,0,96,144,144,112,16,96,2,5,5,6,2,0,192, | ||||
|   192,0,192,192,2,7,7,6,2,254,192,192,0,192,64,64, | ||||
|   128,5,5,5,6,0,0,24,96,128,96,24,5,3,3,6, | ||||
|   0,1,248,0,248,5,5,5,6,0,0,192,48,8,48,192, | ||||
|   4,7,7,6,1,0,96,144,16,96,64,0,64,5,6,6, | ||||
|   6,0,0,112,144,168,176,128,112,5,6,6,6,0,0,32, | ||||
|   80,136,248,136,136,5,6,6,6,0,0,240,136,240,136,136, | ||||
|   240,4,6,6,6,1,0,96,144,128,128,144,96,4,6,6, | ||||
|   6,1,0,224,144,144,144,144,224,4,6,6,6,1,0,240, | ||||
|   128,224,128,128,240,4,6,6,6,1,0,240,128,224,128,128, | ||||
|   128,4,6,6,6,1,0,96,144,128,176,144,96,4,6,6, | ||||
|   6,1,0,144,144,240,144,144,144,3,6,6,6,1,0,224, | ||||
|   64,64,64,64,224,5,6,6,6,0,0,56,16,16,16,144, | ||||
|   96,4,6,6,6,1,0,144,160,192,160,144,144,4,6,6, | ||||
|   6,1,0,128,128,128,128,128,240,5,6,6,6,0,0,136, | ||||
|   216,168,168,136,136,4,6,6,6,1,0,144,208,176,144,144, | ||||
|   144,5,6,6,6,0,0,112,136,136,136,136,112,4,6,6, | ||||
|   6,1,0,224,144,144,224,128,128,4,7,7,6,1,255,96, | ||||
|   144,144,208,176,96,16,4,6,6,6,1,0,224,144,144,224, | ||||
|   144,144,4,6,6,6,1,0,96,144,64,32,144,96,5,6, | ||||
|   6,6,0,0,248,32,32,32,32,32,4,6,6,6,1,0, | ||||
|   144,144,144,144,144,96,4,6,6,6,1,0,144,144,144,240, | ||||
|   96,96,5,6,6,6,0,0,136,136,168,168,216,136,5,6, | ||||
|   6,6,0,0,136,80,32,32,80,136,5,6,6,6,0,0, | ||||
|   136,136,80,32,32,32,4,6,6,6,1,0,240,16,32,64, | ||||
|   128,240,3,6,6,6,1,0,224,128,128,128,128,224,4,6, | ||||
|   6,6,1,0,128,128,64,32,16,16,3,6,6,6,1,0, | ||||
|   224,32,32,32,32,224,5,3,3,6,0,3,32,80,136,5, | ||||
|   1,1,6,0,254,248,2,2,2,6,2,4,128,64,4,4, | ||||
|   4,6,1,0,112,144,144,112,4,6,6,6,1,0,128,128, | ||||
|   224,144,144,224,4,4,4,6,1,0,112,128,128,112,4,6, | ||||
|   6,6,1,0,16,16,112,144,144,112,4,4,4,6,1,0, | ||||
|   96,176,192,112,4,6,6,6,1,0,32,80,64,224,64,64, | ||||
|   4,6,6,6,1,254,96,144,144,112,16,96,4,6,6,6, | ||||
|   1,0,128,128,224,144,144,144,3,6,6,6,1,0,64,0, | ||||
|   192,64,64,224,3,8,8,6,1,254,32,0,96,32,32,32, | ||||
|   160,64,4,6,6,6,1,0,128,128,160,192,160,144,3,6, | ||||
|   6,6,1,0,192,64,64,64,64,224,5,4,4,6,0,0, | ||||
|   208,168,168,136,4,4,4,6,1,0,224,144,144,144,4,4, | ||||
|   4,6,1,0,96,144,144,96,4,6,6,6,1,254,224,144, | ||||
|   144,224,128,128,4,6,6,6,1,254,112,144,144,112,16,16, | ||||
|   4,4,4,6,1,0,160,208,128,128,4,4,4,6,1,0, | ||||
|   112,192,48,224,4,6,6,6,1,0,64,64,224,64,80,32, | ||||
|   4,4,4,6,1,0,144,144,144,112,4,4,4,6,1,0, | ||||
|   144,144,96,96,5,4,4,6,0,0,136,168,168,80,4,4, | ||||
|   4,6,1,0,144,96,96,144,4,6,6,6,1,254,144,144, | ||||
|   144,112,144,96,4,4,4,6,1,0,240,32,64,240,3,7, | ||||
|   7,6,1,0,32,64,64,128,64,64,32,1,7,7,6,2, | ||||
|   255,128,128,128,128,128,128,128,3,7,7,6,1,0,128,64, | ||||
|   64,32,64,64,128,4,2,2,6,1,3,80,160,255,255,255, | ||||
|   255,255,255,255,255,255,255,255,255,255,255,255,255,255,255,255, | ||||
|   255,255,255,255,255,255,255,255,255,255,255,255,255,255,0,0, | ||||
|   0,6,0,7,1,6,6,6,2,0,128,0,128,128,128,128, | ||||
|   4,6,6,6,1,255,32,112,160,160,112,32,5,7,7,6, | ||||
|   0,255,48,72,64,240,64,64,248,5,5,5,6,0,0,168, | ||||
|   80,136,80,168,5,6,6,6,0,0,136,80,248,32,248,32, | ||||
|   1,7,7,6,2,255,128,128,128,0,128,128,128,4,7,7, | ||||
|   6,1,255,112,128,96,144,96,16,224,3,1,1,6,1,5, | ||||
|   160,6,7,7,6,0,0,120,132,148,164,148,132,120,3,5, | ||||
|   5,6,1,1,96,160,96,0,224,5,5,5,6,0,0,40, | ||||
|   80,160,80,40,4,3,3,6,1,0,240,16,16,4,1,1, | ||||
|   6,1,2,240,6,7,7,6,0,0,120,132,180,164,164,132, | ||||
|   120,4,1,1,6,1,5,240,4,3,3,6,1,2,96,144, | ||||
|   96,5,7,7,6,0,255,32,32,248,32,32,0,248,3,5, | ||||
|   5,6,1,1,64,160,32,64,224,3,5,5,6,1,1,192, | ||||
|   32,64,32,192,2,2,2,6,2,4,64,128,4,5,5,6, | ||||
|   1,255,144,144,176,208,128,5,6,6,6,0,0,120,232,232, | ||||
|   104,40,40,1,1,1,6,2,2,128,2,2,2,6,2,254, | ||||
|   64,128,3,5,5,6,1,1,64,192,64,64,224,3,5,5, | ||||
|   6,1,1,64,160,64,0,224,5,5,5,6,0,0,160,80, | ||||
|   40,80,160,5,8,8,6,0,255,64,192,64,80,112,48,120, | ||||
|   16,5,8,8,6,0,255,64,192,64,80,104,8,16,56,5, | ||||
|   8,8,6,0,255,192,32,64,48,240,48,120,16,4,7,7, | ||||
|   6,1,0,32,0,32,96,128,144,96,5,7,7,6,0,0, | ||||
|   64,32,32,80,112,136,136,5,7,7,6,0,0,16,32,32, | ||||
|   80,112,136,136,5,7,7,6,0,0,32,80,32,80,112,136, | ||||
|   136,5,7,7,6,0,0,40,80,32,80,112,136,136,5,7, | ||||
|   7,6,0,0,80,0,32,80,112,136,136,5,7,7,6,0, | ||||
|   0,32,80,32,80,112,136,136,5,6,6,6,0,0,120,160, | ||||
|   240,160,160,184,4,8,8,6,1,254,96,144,128,128,144,96, | ||||
|   32,64,4,7,7,6,1,0,64,32,240,128,224,128,240,4, | ||||
|   7,7,6,1,0,32,64,240,128,224,128,240,4,7,7,6, | ||||
|   1,0,32,80,240,128,224,128,240,4,7,7,6,1,0,80, | ||||
|   0,240,128,224,128,240,3,7,7,6,1,0,128,64,224,64, | ||||
|   64,64,224,3,7,7,6,1,0,32,64,224,64,64,64,224, | ||||
|   3,7,7,6,1,0,64,160,224,64,64,64,224,3,7,7, | ||||
|   6,1,0,160,0,224,64,64,64,224,5,6,6,6,0,0, | ||||
|   112,72,232,72,72,112,4,7,7,6,1,0,80,160,144,208, | ||||
|   176,144,144,4,7,7,6,1,0,64,32,96,144,144,144,96, | ||||
|   4,7,7,6,1,0,32,64,96,144,144,144,96,4,7,7, | ||||
|   6,1,0,32,80,96,144,144,144,96,4,7,7,6,1,0, | ||||
|   80,160,96,144,144,144,96,4,7,7,6,1,0,80,0,96, | ||||
|   144,144,144,96,5,5,5,6,0,0,136,80,32,80,136,4, | ||||
|   8,8,6,1,255,16,112,176,176,208,208,224,128,4,7,7, | ||||
|   6,1,0,64,32,144,144,144,144,96,4,7,7,6,1,0, | ||||
|   32,64,144,144,144,144,96,4,7,7,6,1,0,32,80,144, | ||||
|   144,144,144,96,4,7,7,6,1,0,80,0,144,144,144,144, | ||||
|   96,5,7,7,6,0,0,16,32,136,80,32,32,32,4,6, | ||||
|   6,6,1,0,128,224,144,144,224,128,4,6,6,6,1,0, | ||||
|   96,144,160,160,144,160,4,7,7,6,1,0,64,32,0,112, | ||||
|   144,144,112,4,7,7,6,1,0,32,64,0,112,144,144,112, | ||||
|   4,7,7,6,1,0,32,80,0,112,144,144,112,4,7,7, | ||||
|   6,1,0,80,160,0,112,144,144,112,4,6,6,6,1,0, | ||||
|   80,0,112,144,144,112,4,7,7,6,1,0,32,80,32,112, | ||||
|   144,144,112,5,4,4,6,0,0,112,168,176,120,4,6,6, | ||||
|   6,1,254,112,128,128,112,32,64,4,7,7,6,1,0,64, | ||||
|   32,0,96,176,192,112,4,7,7,6,1,0,32,64,0,96, | ||||
|   176,192,112,4,7,7,6,1,0,32,80,0,96,176,192,112, | ||||
|   4,6,6,6,1,0,80,0,96,176,192,112,3,7,7,6, | ||||
|   1,0,128,64,0,192,64,64,224,3,7,7,6,1,0,32, | ||||
|   64,0,192,64,64,224,3,7,7,6,1,0,64,160,0,192, | ||||
|   64,64,224,3,6,6,6,1,0,160,0,192,64,64,224,4, | ||||
|   7,7,6,1,0,48,96,16,112,144,144,96,4,7,7,6, | ||||
|   1,0,80,160,0,224,144,144,144,4,7,7,6,1,0,64, | ||||
|   32,0,96,144,144,96,4,7,7,6,1,0,32,64,0,96, | ||||
|   144,144,96,4,7,7,6,1,0,32,80,0,96,144,144,96, | ||||
|   4,7,7,6,1,0,80,160,0,96,144,144,96,4,6,6, | ||||
|   6,1,0,80,0,96,144,144,96,5,5,5,6,0,0,32, | ||||
|   0,248,0,32,4,4,4,6,1,0,112,176,208,224,4,7, | ||||
|   7,6,1,0,64,32,0,144,144,144,112,4,7,7,6,1, | ||||
|   0,32,64,0,144,144,144,112,4,7,7,6,1,0,32,80, | ||||
|   0,144,144,144,112,4,6,6,6,1,0,80,0,144,144,144, | ||||
|   112,4,9,9,6,1,254,32,64,0,144,144,144,112,144,96, | ||||
|   4,8,8,6,1,254,128,128,224,144,144,224,128,128,4,8, | ||||
|   8,6,1,254,80,0,144,144,144,112,144,96}; | ||||
|  | ||||
| // STB Marlin | ||||
| /* | ||||
|   Fontname: u8g_font_6x10_marlin | ||||
|   Copyright: Public domain terminal emulator font.  Share and enjoy. | ||||
|   Capital A Height: 7, '1' Height: 7 | ||||
|   Calculated Max Values w= 6 h=10 x= 2 y= 7 dx= 6 dy= 0 ascent= 8 len=10 | ||||
|   Font Bounding box     w= 6 h= 9 x= 0 y=-2 | ||||
|   Calculated Min Values           x= 0 y=-2 dx= 0 dy= 0 | ||||
|   Pure Font   ascent = 7 descent=-2 | ||||
|   X Font      ascent = 7 descent=-2 | ||||
|   Max Font    ascent = 8 descent=-2 | ||||
| */ | ||||
| #include <utility/u8g.h> | ||||
| const u8g_fntpgm_uint8_t u8g_font_6x10_marlin[2617] U8G_SECTION(".progmem.u8g_font_6x10_marlin") = { | ||||
|   0,6,9,0,254,7,1,153,3,43,32,255,254,8,254,7, | ||||
|   254,0,0,0,6,0,0,1,7,7,6,2,0,128,128,128, | ||||
|   128,128,0,128,3,3,3,6,1,4,160,160,160,5,7,7, | ||||
|   6,0,0,80,80,248,80,248,80,80,5,7,7,6,0,0, | ||||
|   32,112,160,112,40,112,32,5,7,7,6,0,0,72,168,80, | ||||
|   32,80,168,144,5,7,7,6,0,0,64,160,160,64,168,144, | ||||
|   104,1,3,3,6,2,4,128,128,128,3,7,7,6,1,0, | ||||
|   32,64,128,128,128,64,32,3,7,7,6,1,0,128,64,32, | ||||
|   32,32,64,128,5,5,5,6,0,1,136,80,248,80,136,5, | ||||
|   5,5,6,0,1,32,32,248,32,32,3,3,3,6,1,255, | ||||
|   96,64,128,5,1,1,6,0,3,248,3,3,3,6,1,255, | ||||
|   64,224,64,5,7,7,6,0,0,8,8,16,32,64,128,128, | ||||
|   5,7,7,6,0,0,32,80,136,136,136,80,32,5,7,7, | ||||
|   6,0,0,32,96,160,32,32,32,248,5,7,7,6,0,0, | ||||
|   112,136,8,48,64,128,248,5,7,7,6,0,0,248,8,16, | ||||
|   48,8,136,112,5,7,7,6,0,0,16,48,80,144,248,16, | ||||
|   16,5,7,7,6,0,0,248,128,176,200,8,136,112,5,7, | ||||
|   7,6,0,0,48,64,128,176,200,136,112,5,7,7,6,0, | ||||
|   0,248,8,16,16,32,64,64,5,7,7,6,0,0,112,136, | ||||
|   136,112,136,136,112,5,7,7,6,0,0,112,136,152,104,8, | ||||
|   16,96,3,7,7,6,1,255,64,224,64,0,64,224,64,3, | ||||
|   7,7,6,1,255,64,224,64,0,96,64,128,4,7,7,6, | ||||
|   1,0,16,32,64,128,64,32,16,5,3,3,6,0,2,248, | ||||
|   0,248,4,7,7,6,1,0,128,64,32,16,32,64,128,5, | ||||
|   7,7,6,0,0,112,136,16,32,32,0,32,5,7,7,6, | ||||
|   0,0,112,136,152,168,176,128,112,5,7,7,6,0,0,32, | ||||
|   80,136,136,248,136,136,5,7,7,6,0,0,240,72,72,112, | ||||
|   72,72,240,5,7,7,6,0,0,112,136,128,128,128,136,112, | ||||
|   5,7,7,6,0,0,240,72,72,72,72,72,240,5,7,7, | ||||
|   6,0,0,248,128,128,240,128,128,248,5,7,7,6,0,0, | ||||
|   248,128,128,240,128,128,128,5,7,7,6,0,0,112,136,128, | ||||
|   128,152,136,112,5,7,7,6,0,0,136,136,136,248,136,136, | ||||
|   136,3,7,7,6,1,0,224,64,64,64,64,64,224,5,7, | ||||
|   7,6,0,0,56,16,16,16,16,144,96,5,7,7,6,0, | ||||
|   0,136,144,160,192,160,144,136,5,7,7,6,0,0,128,128, | ||||
|   128,128,128,128,248,5,7,7,6,0,0,136,136,216,168,136, | ||||
|   136,136,5,7,7,6,0,0,136,136,200,168,152,136,136,5, | ||||
|   7,7,6,0,0,112,136,136,136,136,136,112,5,7,7,6, | ||||
|   0,0,240,136,136,240,128,128,128,5,8,8,6,0,255,112, | ||||
|   136,136,136,136,168,112,8,5,7,7,6,0,0,240,136,136, | ||||
|   240,160,144,136,5,7,7,6,0,0,112,136,128,112,8,136, | ||||
|   112,5,7,7,6,0,0,248,32,32,32,32,32,32,5,7, | ||||
|   7,6,0,0,136,136,136,136,136,136,112,5,7,7,6,0, | ||||
|   0,136,136,136,80,80,80,32,5,7,7,6,0,0,136,136, | ||||
|   136,168,168,216,136,5,7,7,6,0,0,136,136,80,32,80, | ||||
|   136,136,5,7,7,6,0,0,136,136,80,32,32,32,32,5, | ||||
|   7,7,6,0,0,248,8,16,32,64,128,248,3,7,7,6, | ||||
|   1,0,224,128,128,128,128,128,224,5,7,7,6,0,0,128, | ||||
|   128,64,32,16,8,8,3,7,7,6,1,0,224,32,32,32, | ||||
|   32,32,224,5,3,3,6,0,4,32,80,136,5,1,1,6, | ||||
|   0,255,248,2,2,2,6,2,6,128,64,5,5,5,6,0, | ||||
|   0,112,8,120,136,120,5,7,7,6,0,0,128,128,176,200, | ||||
|   136,200,176,5,5,5,6,0,0,112,136,128,136,112,5,7, | ||||
|   7,6,0,0,8,8,104,152,136,152,104,5,5,5,6,0, | ||||
|   0,112,136,248,128,112,5,7,7,6,0,0,48,72,64,240, | ||||
|   64,64,64,5,7,7,6,0,254,120,136,136,120,8,136,112, | ||||
|   5,7,7,6,0,0,128,128,176,200,136,136,136,3,7,7, | ||||
|   6,1,0,64,0,192,64,64,64,224,4,9,9,6,1,254, | ||||
|   16,0,48,16,16,16,144,144,96,5,7,7,6,0,0,128, | ||||
|   128,136,144,224,144,136,3,7,7,6,1,0,192,64,64,64, | ||||
|   64,64,224,5,5,5,6,0,0,208,168,168,168,136,5,5, | ||||
|   5,6,0,0,176,200,136,136,136,5,5,5,6,0,0,112, | ||||
|   136,136,136,112,5,7,7,6,0,254,176,200,136,200,176,128, | ||||
|   128,5,7,7,6,0,254,104,152,136,152,104,8,8,5,5, | ||||
|   5,6,0,0,176,200,128,128,128,5,5,5,6,0,0,112, | ||||
|   128,112,8,240,5,7,7,6,0,0,64,64,240,64,64,72, | ||||
|   48,5,5,5,6,0,0,136,136,136,152,104,5,5,5,6, | ||||
|   0,0,136,136,80,80,32,5,5,5,6,0,0,136,136,168, | ||||
|   168,80,5,5,5,6,0,0,136,80,32,80,136,5,7,7, | ||||
|   6,0,254,136,136,152,104,8,136,112,5,5,5,6,0,0, | ||||
|   248,16,32,64,248,4,7,7,6,1,0,48,64,32,192,32, | ||||
|   64,48,1,7,7,6,2,0,128,128,128,128,128,128,128,4, | ||||
|   7,7,6,1,0,192,32,64,48,64,32,192,5,3,3,6, | ||||
|   0,4,72,168,144,0,0,0,1,0,0,0,0,0,1,0, | ||||
|   0,0,0,0,1,0,0,0,0,0,1,0,0,0,0,0, | ||||
|   1,0,0,0,0,0,1,0,0,0,0,0,1,0,0,0, | ||||
|   0,0,1,0,0,0,0,0,1,0,0,0,0,0,1,0, | ||||
|   0,0,0,0,1,0,0,0,0,0,1,0,0,0,0,0, | ||||
|   1,0,0,0,0,0,1,0,0,0,0,0,1,0,0,0, | ||||
|   0,0,1,0,0,0,0,0,1,0,0,0,0,0,1,0, | ||||
|   0,0,0,0,1,0,0,0,0,0,1,0,0,0,0,0, | ||||
|   1,0,0,0,0,0,1,0,0,0,0,0,1,0,0,0, | ||||
|   0,0,1,0,0,0,0,0,1,0,0,0,0,0,1,0, | ||||
|   0,0,0,0,1,0,0,0,0,0,1,0,0,0,0,0, | ||||
|   1,0,0,0,0,0,1,0,0,0,0,0,1,0,0,0, | ||||
|   0,0,1,0,0,0,0,0,1,0,0,0,0,0,6,0, | ||||
|   0,1,7,7,6,2,0,128,0,128,128,128,128,128,5,7, | ||||
|   7,6,0,255,32,120,160,160,160,120,32,5,7,7,6,0, | ||||
|   0,48,72,64,224,64,72,176,5,5,5,6,0,0,136,112, | ||||
|   80,112,136,5,8,8,6,0,255,136,136,80,32,248,32,32, | ||||
|   32,1,7,7,6,2,0,128,128,128,0,128,128,128,5,8, | ||||
|   8,6,0,255,112,128,224,144,72,56,8,112,3,1,1,6, | ||||
|   1,7,160,5,7,7,6,0,0,112,136,168,200,168,136,112, | ||||
|   4,6,6,6,1,1,112,144,176,80,0,240,6,5,5,6, | ||||
|   0,0,36,72,144,72,36,4,2,2,6,1,2,240,16,4, | ||||
|   1,1,6,1,3,240,5,7,7,6,0,0,112,136,232,200, | ||||
|   200,136,112,5,1,1,6,0,7,248,3,3,3,6,1,4, | ||||
|   64,160,64,5,6,6,6,0,0,32,32,248,32,32,248,4, | ||||
|   5,5,6,1,3,96,144,32,64,240,4,5,5,6,1,3, | ||||
|   224,16,96,16,224,2,2,2,6,2,6,64,128,5,6,6, | ||||
|   6,0,255,136,136,136,200,176,128,5,7,7,6,0,0,120, | ||||
|   232,232,104,40,40,40,1,1,1,6,2,3,128,2,2,2, | ||||
|   6,2,254,64,128,3,5,5,6,1,3,64,192,64,64,224, | ||||
|   4,6,6,6,1,1,96,144,144,96,0,240,6,5,5,6, | ||||
|   0,0,144,72,36,72,144,6,9,9,6,0,255,64,192,64, | ||||
|   64,228,12,20,60,4,6,9,9,6,0,255,64,192,64,64, | ||||
|   232,20,4,8,28,5,9,9,6,0,255,192,32,64,32,200, | ||||
|   24,40,120,8,5,7,7,6,0,0,32,0,32,32,64,136, | ||||
|   112,5,8,8,6,0,0,64,32,112,136,136,248,136,136,5, | ||||
|   8,8,6,0,0,16,32,112,136,136,248,136,136,5,8,8, | ||||
|   6,0,0,32,80,112,136,136,248,136,136,5,8,8,6,0, | ||||
|   0,72,176,112,136,136,248,136,136,5,8,8,6,0,0,80, | ||||
|   0,112,136,136,248,136,136,5,8,8,6,0,0,32,80,112, | ||||
|   136,136,248,136,136,6,7,7,6,0,0,60,80,144,156,240, | ||||
|   144,156,5,9,9,6,0,254,112,136,128,128,128,136,112,32, | ||||
|   64,5,8,8,6,0,0,64,248,128,128,240,128,128,248,5, | ||||
|   8,8,6,0,0,16,248,128,128,240,128,128,248,5,8,8, | ||||
|   6,0,0,32,248,128,128,240,128,128,248,5,8,8,6,0, | ||||
|   0,80,248,128,128,240,128,128,248,3,8,8,6,1,0,128, | ||||
|   64,224,64,64,64,64,224,3,8,8,6,1,0,32,64,224, | ||||
|   64,64,64,64,224,3,8,8,6,1,0,64,160,224,64,64, | ||||
|   64,64,224,3,8,8,6,1,0,160,0,224,64,64,64,64, | ||||
|   224,5,7,7,6,0,0,240,72,72,232,72,72,240,5,8, | ||||
|   8,6,0,0,40,80,136,200,168,152,136,136,5,8,8,6, | ||||
|   0,0,64,32,112,136,136,136,136,112,5,8,8,6,0,0, | ||||
|   16,32,112,136,136,136,136,112,5,8,8,6,0,0,32,80, | ||||
|   112,136,136,136,136,112,5,8,8,6,0,0,40,80,112,136, | ||||
|   136,136,136,112,5,8,8,6,0,0,80,0,112,136,136,136, | ||||
|   136,112,5,5,5,6,0,0,136,80,32,80,136,5,7,7, | ||||
|   6,0,0,112,152,152,168,200,200,112,5,8,8,6,0,0, | ||||
|   64,32,136,136,136,136,136,112,5,8,8,6,0,0,16,32, | ||||
|   136,136,136,136,136,112,5,8,8,6,0,0,32,80,0,136, | ||||
|   136,136,136,112,5,8,8,6,0,0,80,0,136,136,136,136, | ||||
|   136,112,5,8,8,6,0,0,16,32,136,136,80,32,32,32, | ||||
|   5,7,7,6,0,0,128,240,136,240,128,128,128,5,7,7, | ||||
|   6,0,0,112,136,144,160,144,136,176,5,8,8,6,0,0, | ||||
|   64,32,0,112,8,120,136,120,5,8,8,6,0,0,16,32, | ||||
|   0,112,8,120,136,120,5,8,8,6,0,0,32,80,0,112, | ||||
|   8,120,136,120,5,8,8,6,0,0,40,80,0,112,8,120, | ||||
|   136,120,5,7,7,6,0,0,80,0,112,8,120,136,120,5, | ||||
|   8,8,6,0,0,32,80,32,112,8,120,136,120,6,5,5, | ||||
|   6,0,0,120,20,124,144,124,5,7,7,6,0,254,112,136, | ||||
|   128,136,112,32,64,5,8,8,6,0,0,64,32,0,112,136, | ||||
|   248,128,112,5,8,8,6,0,0,16,32,0,112,136,248,128, | ||||
|   112,5,8,8,6,0,0,32,80,0,112,136,248,128,112,5, | ||||
|   7,7,6,0,0,80,0,112,136,248,128,112,3,8,8,6, | ||||
|   1,0,128,64,0,192,64,64,64,224,3,8,8,6,1,0, | ||||
|   64,128,0,192,64,64,64,224,3,8,8,6,1,0,64,160, | ||||
|   0,192,64,64,64,224,6,10,10,6,0,254,164,168,0,252, | ||||
|   132,128,128,128,132,252,6,10,10,6,0,254,84,148,0,252, | ||||
|   132,4,4,4,132,252,5,8,8,6,0,0,40,80,0,176, | ||||
|   200,136,136,136,5,8,8,6,0,0,64,32,0,112,136,136, | ||||
|   136,112,4,10,10,6,2,254,48,64,128,144,144,144,144,144, | ||||
|   144,144,4,10,10,6,0,254,192,32,16,144,144,144,144,144, | ||||
|   144,144,6,7,7,6,0,1,68,140,140,132,128,64,60,6, | ||||
|   7,7,6,0,1,136,196,196,132,4,8,240,5,5,5,6, | ||||
|   0,1,32,0,248,0,32,5,8,8,6,0,0,64,240,200, | ||||
|   136,136,152,120,16,5,8,8,6,0,0,224,248,136,136,136, | ||||
|   136,136,248,5,5,5,6,0,1,32,48,248,48,32,5,8, | ||||
|   8,6,0,0,32,112,248,32,32,32,32,224,5,9,9,6, | ||||
|   0,255,32,112,168,168,184,136,136,80,32,5,9,9,6,0, | ||||
|   255,224,128,192,176,168,168,48,40,40,5,9,9,6,0,255, | ||||
|   248,168,136,136,136,136,136,168,248,5,10,10,6,0,254,32, | ||||
|   80,80,80,80,136,168,168,136,112}; | ||||
|    | ||||
							
								
								
									
										583
									
								
								Marlin/dogm_lcd_implementation.h
									
									
									
									
									
										Normal file
									
								
							
							
						
						
									
										583
									
								
								Marlin/dogm_lcd_implementation.h
									
									
									
									
									
										Normal file
									
								
							| @@ -0,0 +1,583 @@ | ||||
| /** | ||||
|  *dogm_lcd_implementation.h | ||||
|  * | ||||
|  *Graphics LCD implementation for 128x64 pixel LCDs by STB for ErikZalm/Marlin | ||||
|  *Demonstrator: http://www.reprap.org/wiki/STB_Electronics | ||||
|  *License: http://opensource.org/licenses/BSD-3-Clause | ||||
|  * | ||||
|  *With the use of: | ||||
|  *u8glib by Oliver Kraus | ||||
|  *http://code.google.com/p/u8glib/ | ||||
|  *License: http://opensource.org/licenses/BSD-3-Clause | ||||
|  */ | ||||
|  | ||||
|  | ||||
| #ifndef ULTRA_LCD_IMPLEMENTATION_DOGM_H | ||||
| #define ULTRA_LCD_IMPLEMENTATION_DOGM_H | ||||
|  | ||||
| /** | ||||
| * Implementation of the LCD display routines for a DOGM128 graphic display. These are common LCD 128x64 pixel graphic displays. | ||||
| **/ | ||||
|  | ||||
|  | ||||
| // CHANGE_DE begin *** | ||||
| #include <U8glib.h>	// DE_U8glib | ||||
| #include "DOGMbitmaps.h" | ||||
| #include "dogm_font_data_marlin.h" | ||||
| #include "ultralcd.h" | ||||
|  | ||||
|  | ||||
| /* Russian language not supported yet, needs custom font | ||||
|  | ||||
| #if LANGUAGE_CHOICE == 6 | ||||
| #include "LiquidCrystalRus.h" | ||||
| #define LCD_CLASS LiquidCrystalRus | ||||
| #else | ||||
| #include <LiquidCrystal.h> | ||||
| #define LCD_CLASS LiquidCrystal | ||||
| #endif | ||||
| */ | ||||
|  | ||||
| // DOGM parameters (size in pixels) | ||||
| #define DOG_CHAR_WIDTH			6 | ||||
| #define DOG_CHAR_HEIGHT			12 | ||||
| #define DOG_CHAR_WIDTH_LARGE	9 | ||||
| #define DOG_CHAR_HEIGHT_LARGE	18 | ||||
|  | ||||
|  | ||||
| #define START_ROW				0 | ||||
|  | ||||
|  | ||||
| /* Custom characters defined in font font_6x10_marlin.c */ | ||||
| #define LCD_STR_BEDTEMP     "\xFE" | ||||
| #define LCD_STR_DEGREE      "\xB0" | ||||
| #define LCD_STR_THERMOMETER "\xFF" | ||||
| #define LCD_STR_UPLEVEL     "\xFB" | ||||
| #define LCD_STR_REFRESH     "\xF8" | ||||
| #define LCD_STR_FOLDER      "\xF9" | ||||
| #define LCD_STR_FEEDRATE    "\xFD" | ||||
| #define LCD_STR_CLOCK       "\xFC" | ||||
| #define LCD_STR_ARROW_RIGHT "\xFA" | ||||
|  | ||||
| #define FONT_STATUSMENU	u8g_font_6x9 | ||||
|  | ||||
|  | ||||
| // LCD selection | ||||
| #ifdef U8GLIB_ST7920 | ||||
| // SPI Com: SCK = en = (D4), MOSI = rw = (RS), CS = di = (ENABLE) | ||||
| U8GLIB_ST7920_128X64_1X u8g(LCD_PINS_D4, LCD_PINS_ENABLE, LCD_PINS_RS); | ||||
| #else | ||||
| U8GLIB_DOGM128 u8g(DOGLCD_CS, DOGLCD_A0);	// HW-SPI Com: CS, A0 | ||||
| #endif | ||||
|  | ||||
| static void lcd_implementation_init() | ||||
| { | ||||
| 	//  Uncomment this if you have the first generation (V1.10) of STBs board | ||||
| 	//  pinMode(17, OUTPUT);	// Enable LCD backlight | ||||
| 	//  digitalWrite(17, HIGH); | ||||
| 	 | ||||
| 	u8g.firstPage(); | ||||
| 	do { | ||||
| 		u8g.setFont(u8g_font_6x10_marlin); | ||||
| 		u8g.setColorIndex(1); | ||||
| 		u8g.drawBox (0, 0, u8g.getWidth(), u8g.getHeight()); | ||||
| 		u8g.setColorIndex(1); | ||||
| 	   } while( u8g.nextPage() ); | ||||
|  | ||||
| #ifdef LCD_SCREEN_ROT_90 | ||||
| 	u8g.setRot90();	// Rotate screen by 90° | ||||
| #endif | ||||
|  | ||||
| #ifdef LCD_SCREEN_ROT_180; | ||||
| 	u8g.setRot180();	// Rotate screen by 180° | ||||
| #endif | ||||
|  | ||||
| #ifdef LCD_SCREEN_ROT_270; | ||||
| 	u8g.setRot270();	// Rotate screen by 270° | ||||
| #endif | ||||
|  | ||||
|     | ||||
| 	u8g.firstPage(); | ||||
| 	do { | ||||
| 			// RepRap init bmp | ||||
| 			u8g.drawBitmapP(0,0,START_BMPBYTEWIDTH,START_BMPHEIGHT,start_bmp); | ||||
| 			// Welcome message | ||||
| 			u8g.setFont(u8g_font_6x10_marlin); | ||||
| 			u8g.drawStr(62,10,"MARLIN");  | ||||
| 			u8g.setFont(u8g_font_5x8); | ||||
| 			u8g.drawStr(62,19,"V1.0.0 RC2"); | ||||
| 			u8g.setFont(u8g_font_6x10_marlin); | ||||
| 			u8g.drawStr(62,28,"by ErikZalm"); | ||||
| 			u8g.drawStr(62,41,"DOGM128 LCD"); | ||||
| 			u8g.setFont(u8g_font_5x8); | ||||
| 			u8g.drawStr(62,48,"enhancements"); | ||||
| 			u8g.setFont(u8g_font_5x8); | ||||
| 			u8g.drawStr(62,55,"by STB"); | ||||
| 			u8g.drawStr(62,61,"uses u"); | ||||
| 			u8g.drawStr90(92,57,"8"); | ||||
| 			u8g.drawStr(100,61,"glib"); | ||||
| 	   } while( u8g.nextPage() ); | ||||
| } | ||||
|  | ||||
| static void lcd_implementation_clear() | ||||
| { | ||||
| // NO NEED TO IMPLEMENT LIKE SO. Picture loop automatically clears the display. | ||||
| // | ||||
| // Check this article: http://arduino.cc/forum/index.php?topic=91395.25;wap2 | ||||
| // | ||||
| //	u8g.firstPage(); | ||||
| //	do {	 | ||||
| //			u8g.setColorIndex(0); | ||||
| //			u8g.drawBox (0, 0, u8g.getWidth(), u8g.getHeight()); | ||||
| //			u8g.setColorIndex(1); | ||||
| //		} while( u8g.nextPage() ); | ||||
| } | ||||
|  | ||||
| /* Arduino < 1.0.0 is missing a function to print PROGMEM strings, so we need to implement our own */ | ||||
| static void lcd_printPGM(const char* str) | ||||
| { | ||||
|     char c; | ||||
|     while((c = pgm_read_byte(str++)) != '\0') | ||||
|     { | ||||
| 			u8g.print(c); | ||||
|     } | ||||
| } | ||||
|  | ||||
|  | ||||
| static void lcd_implementation_status_screen() | ||||
| { | ||||
|  | ||||
|  static unsigned char fan_rot = 0; | ||||
|   | ||||
|  u8g.setColorIndex(1);	// black on white | ||||
|   | ||||
|  // Symbols menu graphics, animated fan | ||||
|  if ((blink % 2) &&  fanSpeed )	u8g.drawBitmapP(9,1,STATUS_SCREENBYTEWIDTH,STATUS_SCREENHEIGHT,status_screen0_bmp); | ||||
| 	else u8g.drawBitmapP(9,1,STATUS_SCREENBYTEWIDTH,STATUS_SCREENHEIGHT,status_screen1_bmp); | ||||
|   | ||||
|  #ifdef SDSUPPORT | ||||
|  //SD Card Symbol | ||||
|  u8g.drawBox(42,42,8,7); | ||||
|  u8g.drawBox(50,44,2,5); | ||||
|  u8g.drawFrame(42,49,10,4); | ||||
|  u8g.drawPixel(50,43); | ||||
|  // Progress bar | ||||
|  u8g.drawFrame(54,49,73,4); | ||||
|   | ||||
|  // SD Card Progress bar and clock | ||||
|  u8g.setFont(FONT_STATUSMENU); | ||||
|   | ||||
|  if (IS_SD_PRINTING) | ||||
|    { | ||||
| 	// Progress bar | ||||
| 	u8g.drawBox(55,50, (unsigned int)( (71 * card.percentDone())/100) ,2); | ||||
|    } | ||||
|     else { | ||||
| 			// do nothing | ||||
| 		 } | ||||
|   | ||||
|  u8g.setPrintPos(80,47); | ||||
|  if(starttime != 0) | ||||
|     { | ||||
|         uint16_t time = millis()/60000 - starttime/60000; | ||||
|  | ||||
| 		u8g.print(itostr2(time/60)); | ||||
| 		u8g.print(':'); | ||||
| 		u8g.print(itostr2(time%60)); | ||||
|     }else{ | ||||
| 			lcd_printPGM(PSTR("--:--")); | ||||
| 		 } | ||||
|  #endif | ||||
|   | ||||
|  // Extruder 1 | ||||
|  u8g.setFont(FONT_STATUSMENU); | ||||
|  u8g.setPrintPos(6,6); | ||||
|  u8g.print(itostr3(int(degTargetHotend(0) + 0.5))); | ||||
|  lcd_printPGM(PSTR(LCD_STR_DEGREE " ")); | ||||
|  u8g.setPrintPos(6,27); | ||||
|  u8g.print(itostr3(int(degHotend(0) + 0.5))); | ||||
|  lcd_printPGM(PSTR(LCD_STR_DEGREE " ")); | ||||
|  if (!isHeatingHotend(0)) u8g.drawBox(13,17,2,2); | ||||
| 	else | ||||
| 		{ | ||||
| 		 u8g.setColorIndex(0);	// white on black | ||||
| 		 u8g.drawBox(13,17,2,2); | ||||
| 		 u8g.setColorIndex(1);	// black on white | ||||
| 		} | ||||
|   | ||||
|  // Extruder 2 | ||||
|  u8g.setFont(FONT_STATUSMENU); | ||||
|  #if EXTRUDERS > 1 | ||||
|  u8g.setPrintPos(31,6); | ||||
|  u8g.print(itostr3(int(degTargetHotend(1) + 0.5))); | ||||
|  lcd_printPGM(PSTR(LCD_STR_DEGREE " ")); | ||||
|  u8g.setPrintPos(31,27); | ||||
|  u8g.print(itostr3(int(degHotend(1) + 0.5))); | ||||
|  lcd_printPGM(PSTR(LCD_STR_DEGREE " ")); | ||||
|  if (!isHeatingHotend(1)) u8g.drawBox(38,17,2,2); | ||||
| 	else | ||||
| 		{ | ||||
| 		 u8g.setColorIndex(0);	// white on black | ||||
| 		 u8g.drawBox(38,17,2,2); | ||||
| 		 u8g.setColorIndex(1);	// black on white | ||||
| 		} | ||||
|  #else | ||||
|  u8g.setPrintPos(31,27); | ||||
|  u8g.print("---"); | ||||
|  #endif | ||||
|   | ||||
|  // Extruder 3 | ||||
|  u8g.setFont(FONT_STATUSMENU); | ||||
|  # if EXTRUDERS > 2 | ||||
|  u8g.setPrintPos(55,6); | ||||
|  u8g.print(itostr3(int(degTargetHotend(2) + 0.5))); | ||||
|  lcd_printPGM(PSTR(LCD_STR_DEGREE " ")); | ||||
|  u8g.setPrintPos(55,27); | ||||
|  u8g.print(itostr3(int(degHotend(2) + 0.5))); | ||||
|  lcd_printPGM(PSTR(LCD_STR_DEGREE " ")); | ||||
|  if (!isHeatingHotend(2)) u8g.drawBox(62,17,2,2); | ||||
| 	else | ||||
| 		{ | ||||
| 		 u8g.setColorIndex(0);	// white on black | ||||
| 		 u8g.drawBox(62,17,2,2); | ||||
| 		 u8g.setColorIndex(1);	// black on white | ||||
| 		} | ||||
|  #else | ||||
|  u8g.setPrintPos(55,27); | ||||
|  u8g.print("---"); | ||||
|  #endif | ||||
|   | ||||
|  // Heatbed | ||||
|  u8g.setFont(FONT_STATUSMENU); | ||||
|  u8g.setPrintPos(81,6); | ||||
|  u8g.print(itostr3(int(degTargetBed() + 0.5))); | ||||
|  lcd_printPGM(PSTR(LCD_STR_DEGREE " ")); | ||||
|  u8g.setPrintPos(81,27); | ||||
|  u8g.print(itostr3(int(degBed() + 0.5))); | ||||
|  lcd_printPGM(PSTR(LCD_STR_DEGREE " ")); | ||||
|  if (!isHeatingBed()) u8g.drawBox(88,18,2,2); | ||||
| 	else | ||||
| 		{ | ||||
| 		 u8g.setColorIndex(0);	// white on black | ||||
| 		 u8g.drawBox(88,18,2,2); | ||||
| 		 u8g.setColorIndex(1);	// black on white | ||||
| 		} | ||||
|   | ||||
|  // Fan | ||||
|  u8g.setFont(FONT_STATUSMENU); | ||||
|  u8g.setPrintPos(104,27); | ||||
|  #if FAN_PIN > 0 | ||||
|  u8g.print(itostr3(int((fanSpeed*100)/256 + 1))); | ||||
|  u8g.print("%"); | ||||
|  #else | ||||
|  u8g.print("---"); | ||||
|  #endif | ||||
|   | ||||
|   | ||||
|  // X, Y, Z-Coordinates | ||||
|  u8g.setFont(FONT_STATUSMENU); | ||||
|  u8g.drawBox(0,29,128,10); | ||||
|  u8g.setColorIndex(0);	// white on black | ||||
|  u8g.setPrintPos(2,37); | ||||
|  u8g.print("X"); | ||||
|  u8g.drawPixel(8,33); | ||||
|  u8g.drawPixel(8,35); | ||||
|  u8g.setPrintPos(10,37); | ||||
|  u8g.print(ftostr31ns(current_position[X_AXIS])); | ||||
|  u8g.setPrintPos(43,37); | ||||
|  lcd_printPGM(PSTR("Y")); | ||||
|  u8g.drawPixel(49,33); | ||||
|  u8g.drawPixel(49,35); | ||||
|  u8g.setPrintPos(51,37); | ||||
|  u8g.print(ftostr31ns(current_position[Y_AXIS])); | ||||
|  u8g.setPrintPos(83,37); | ||||
|  u8g.print("Z"); | ||||
|  u8g.drawPixel(89,33); | ||||
|  u8g.drawPixel(89,35); | ||||
|  u8g.setPrintPos(91,37); | ||||
|  u8g.print(ftostr31(current_position[Z_AXIS])); | ||||
|  u8g.setColorIndex(1);	// black on white | ||||
|   | ||||
|  // Feedrate | ||||
|  u8g.setFont(u8g_font_6x10_marlin); | ||||
|  u8g.setPrintPos(3,49); | ||||
|  u8g.print(LCD_STR_FEEDRATE[0]); | ||||
|  u8g.setFont(FONT_STATUSMENU); | ||||
|  u8g.setPrintPos(12,48); | ||||
|  u8g.print(itostr3(feedmultiply)); | ||||
|  u8g.print('%'); | ||||
|  | ||||
|  // Status line | ||||
|  u8g.setFont(FONT_STATUSMENU); | ||||
|  u8g.setPrintPos(0,61); | ||||
|  u8g.print(lcd_status_message); | ||||
|  | ||||
| } | ||||
|  | ||||
| static void lcd_implementation_drawmenu_generic(uint8_t row, const char* pstr, char pre_char, char post_char) | ||||
| { | ||||
|     char c; | ||||
|      | ||||
|     uint8_t n = LCD_WIDTH - 1 - 2; | ||||
| 		 | ||||
| 		if ((pre_char == '>') || (pre_char == LCD_STR_UPLEVEL[0] )) | ||||
| 		   { | ||||
| 			u8g.setColorIndex(1);		// black on white | ||||
| 			u8g.drawBox (0, row*DOG_CHAR_HEIGHT + 3, 128, DOG_CHAR_HEIGHT); | ||||
| 			u8g.setColorIndex(0);		// following text must be white on black | ||||
| 		   } else u8g.setColorIndex(1); // unmarked text is black on white | ||||
| 		 | ||||
| 		u8g.setPrintPos(0 * DOG_CHAR_WIDTH, (row + 1) * DOG_CHAR_HEIGHT); | ||||
| 		if (pre_char != '>') u8g.print(pre_char); else u8g.print(' ');	// Row selector is obsolete | ||||
|  | ||||
|  | ||||
|     while( (c = pgm_read_byte(pstr)) != '\0' ) | ||||
|     { | ||||
| 		u8g.print(c); | ||||
|         pstr++; | ||||
|         n--; | ||||
|     } | ||||
|     while(n--){ | ||||
| 					u8g.print(' '); | ||||
| 		} | ||||
| 	    | ||||
| 		u8g.print(post_char); | ||||
| 		u8g.print(' '); | ||||
| 		u8g.setColorIndex(1);		// restore settings to black on white | ||||
| } | ||||
|  | ||||
| static void lcd_implementation_drawmenu_setting_edit_generic(uint8_t row, const char* pstr, char pre_char, char* data) | ||||
| { | ||||
|     static unsigned int fkt_cnt = 0; | ||||
| 	char c; | ||||
|     uint8_t n = LCD_WIDTH - 1 - 2 - strlen(data); | ||||
| 		 | ||||
| 		u8g.setPrintPos(0 * DOG_CHAR_WIDTH, (row + 1) * DOG_CHAR_HEIGHT); | ||||
| 		u8g.print(pre_char); | ||||
| 	 | ||||
|     while( (c = pgm_read_byte(pstr)) != '\0' ) | ||||
|     { | ||||
| 			u8g.print(c); | ||||
| 		 | ||||
|         pstr++; | ||||
|         n--; | ||||
|     } | ||||
| 	 | ||||
| 		u8g.print(':'); | ||||
|  | ||||
|     while(n--){ | ||||
| 					u8g.print(' '); | ||||
| 			  } | ||||
|  | ||||
| 		u8g.print(data); | ||||
| } | ||||
|  | ||||
| static void lcd_implementation_drawmenu_setting_edit_generic_P(uint8_t row, const char* pstr, char pre_char, const char* data) | ||||
| { | ||||
|     char c; | ||||
|     uint8_t n= LCD_WIDTH - 1 - 2 - strlen_P(data); | ||||
|  | ||||
| 		u8g.setPrintPos(0 * DOG_CHAR_WIDTH, (row + 1) * DOG_CHAR_HEIGHT); | ||||
| 		u8g.print(pre_char); | ||||
| 	 | ||||
|     while( (c = pgm_read_byte(pstr)) != '\0' ) | ||||
|     { | ||||
| 			u8g.print(c); | ||||
| 		 | ||||
|         pstr++; | ||||
|         n--; | ||||
|     } | ||||
|  | ||||
| 		u8g.print(':'); | ||||
| 	 | ||||
|     while(n--){ | ||||
| 					u8g.print(' '); | ||||
| 			  } | ||||
|  | ||||
| 		lcd_printPGM(data); | ||||
| } | ||||
|  | ||||
| #define lcd_implementation_drawmenu_setting_edit_int3_selected(row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, '>', itostr3(*(data))) | ||||
| #define lcd_implementation_drawmenu_setting_edit_int3(row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, ' ', itostr3(*(data))) | ||||
| #define lcd_implementation_drawmenu_setting_edit_float3_selected(row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, '>', ftostr3(*(data))) | ||||
| #define lcd_implementation_drawmenu_setting_edit_float3(row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, ' ', ftostr3(*(data))) | ||||
| #define lcd_implementation_drawmenu_setting_edit_float32_selected(row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, '>', ftostr32(*(data))) | ||||
| #define lcd_implementation_drawmenu_setting_edit_float32(row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, ' ', ftostr32(*(data))) | ||||
| #define lcd_implementation_drawmenu_setting_edit_float5_selected(row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, '>', ftostr5(*(data))) | ||||
| #define lcd_implementation_drawmenu_setting_edit_float5(row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, ' ', ftostr5(*(data))) | ||||
| #define lcd_implementation_drawmenu_setting_edit_float52_selected(row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, '>', ftostr52(*(data))) | ||||
| #define lcd_implementation_drawmenu_setting_edit_float52(row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, ' ', ftostr52(*(data))) | ||||
| #define lcd_implementation_drawmenu_setting_edit_float51_selected(row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, '>', ftostr51(*(data))) | ||||
| #define lcd_implementation_drawmenu_setting_edit_float51(row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, ' ', ftostr51(*(data))) | ||||
| #define lcd_implementation_drawmenu_setting_edit_long5_selected(row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, '>', ftostr5(*(data))) | ||||
| #define lcd_implementation_drawmenu_setting_edit_long5(row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, ' ', ftostr5(*(data))) | ||||
| #define lcd_implementation_drawmenu_setting_edit_bool_selected(row, pstr, pstr2, data) lcd_implementation_drawmenu_setting_edit_generic_P(row, pstr, '>', (*(data))?PSTR(MSG_ON):PSTR(MSG_OFF)) | ||||
| #define lcd_implementation_drawmenu_setting_edit_bool(row, pstr, pstr2, data) lcd_implementation_drawmenu_setting_edit_generic_P(row, pstr, ' ', (*(data))?PSTR(MSG_ON):PSTR(MSG_OFF)) | ||||
|  | ||||
| //Add version for callback functions | ||||
| #define lcd_implementation_drawmenu_setting_edit_callback_int3_selected(row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, '>', itostr3(*(data))) | ||||
| #define lcd_implementation_drawmenu_setting_edit_callback_int3(row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, ' ', itostr3(*(data))) | ||||
| #define lcd_implementation_drawmenu_setting_edit_callback_float3_selected(row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, '>', ftostr3(*(data))) | ||||
| #define lcd_implementation_drawmenu_setting_edit_callback_float3(row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, ' ', ftostr3(*(data))) | ||||
| #define lcd_implementation_drawmenu_setting_edit_callback_float32_selected(row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, '>', ftostr32(*(data))) | ||||
| #define lcd_implementation_drawmenu_setting_edit_callback_float32(row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, ' ', ftostr32(*(data))) | ||||
| #define lcd_implementation_drawmenu_setting_edit_callback_float5_selected(row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, '>', ftostr5(*(data))) | ||||
| #define lcd_implementation_drawmenu_setting_edit_callback_float5(row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, ' ', ftostr5(*(data))) | ||||
| #define lcd_implementation_drawmenu_setting_edit_callback_float52_selected(row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, '>', ftostr52(*(data))) | ||||
| #define lcd_implementation_drawmenu_setting_edit_callback_float52(row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, ' ', ftostr52(*(data))) | ||||
| #define lcd_implementation_drawmenu_setting_edit_callback_float51_selected(row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, '>', ftostr51(*(data))) | ||||
| #define lcd_implementation_drawmenu_setting_edit_callback_float51(row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, ' ', ftostr51(*(data))) | ||||
| #define lcd_implementation_drawmenu_setting_edit_callback_long5_selected(row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, '>', ftostr5(*(data))) | ||||
| #define lcd_implementation_drawmenu_setting_edit_callback_long5(row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, ' ', ftostr5(*(data))) | ||||
| #define lcd_implementation_drawmenu_setting_edit_callback_bool_selected(row, pstr, pstr2, data, callback) lcd_implementation_drawmenu_setting_edit_generic_P(row, pstr, '>', (*(data))?PSTR(MSG_ON):PSTR(MSG_OFF)) | ||||
| #define lcd_implementation_drawmenu_setting_edit_callback_bool(row, pstr, pstr2, data, callback) lcd_implementation_drawmenu_setting_edit_generic_P(row, pstr, ' ', (*(data))?PSTR(MSG_ON):PSTR(MSG_OFF)) | ||||
|  | ||||
| void lcd_implementation_drawedit(const char* pstr, char* value) | ||||
| { | ||||
| 		u8g.setPrintPos(0 * DOG_CHAR_WIDTH_LARGE, (u8g.getHeight() - 1 - DOG_CHAR_HEIGHT_LARGE) - (1 * DOG_CHAR_HEIGHT_LARGE) - START_ROW ); | ||||
| 		u8g.setFont(u8g_font_9x18); | ||||
| 		lcd_printPGM(pstr); | ||||
| 		u8g.print(':'); | ||||
| 		u8g.setPrintPos((14 - strlen(value)) * DOG_CHAR_WIDTH_LARGE, (u8g.getHeight() - 1 - DOG_CHAR_HEIGHT_LARGE) - (1 * DOG_CHAR_HEIGHT_LARGE) - START_ROW ); | ||||
| 		u8g.print(value); | ||||
| } | ||||
|  | ||||
| static void lcd_implementation_drawmenu_sdfile_selected(uint8_t row, const char* pstr, const char* filename, char* longFilename) | ||||
| { | ||||
|     char c; | ||||
|     uint8_t n = LCD_WIDTH - 1; | ||||
|  | ||||
|     if (longFilename[0] != '\0') | ||||
|     { | ||||
|         filename = longFilename; | ||||
|         longFilename[LCD_WIDTH-1] = '\0'; | ||||
|     } | ||||
|  | ||||
| 		u8g.setColorIndex(1);		// black on white | ||||
| 		u8g.drawBox (0, row*DOG_CHAR_HEIGHT + 3, 128, DOG_CHAR_HEIGHT); | ||||
| 		u8g.setColorIndex(0);		// following text must be white on black | ||||
| 		u8g.setPrintPos(0 * DOG_CHAR_WIDTH, (row + 1) * DOG_CHAR_HEIGHT); | ||||
| 		u8g.print(' ');	// Indent by 1 char | ||||
| 	    | ||||
|     while((c = *filename) != '\0') | ||||
|     { | ||||
| 		u8g.print(c); | ||||
|         filename++; | ||||
|         n--; | ||||
|     } | ||||
|     while(n--){ | ||||
| 					u8g.print(' '); | ||||
| 			   } | ||||
| 	u8g.setColorIndex(1);		// black on white | ||||
| } | ||||
|  | ||||
| static void lcd_implementation_drawmenu_sdfile(uint8_t row, const char* pstr, const char* filename, char* longFilename) | ||||
| { | ||||
|     char c; | ||||
|     uint8_t n = LCD_WIDTH - 1; | ||||
|  | ||||
|     if (longFilename[0] != '\0') | ||||
|     { | ||||
|         filename = longFilename; | ||||
|         longFilename[LCD_WIDTH-1] = '\0'; | ||||
|     } | ||||
|  | ||||
| 		u8g.setPrintPos(0 * DOG_CHAR_WIDTH, (row + 1) * DOG_CHAR_HEIGHT); | ||||
| 		u8g.print(' '); | ||||
| 		 | ||||
| while((c = *filename) != '\0') | ||||
|     { | ||||
| 			u8g.print(c); | ||||
| 		 | ||||
|         filename++; | ||||
|         n--; | ||||
|     } | ||||
|     while(n--){ | ||||
| 					u8g.print(' '); | ||||
| 			   } | ||||
|  | ||||
| } | ||||
|  | ||||
| static void lcd_implementation_drawmenu_sddirectory_selected(uint8_t row, const char* pstr, const char* filename, char* longFilename) | ||||
| { | ||||
|     char c; | ||||
|     uint8_t n = LCD_WIDTH - 2; | ||||
| 		 | ||||
|     if (longFilename[0] != '\0') | ||||
|     { | ||||
|         filename = longFilename; | ||||
|         longFilename[LCD_WIDTH-2] = '\0'; | ||||
|     } | ||||
| 		u8g.setColorIndex(1);		// black on white | ||||
| 		u8g.drawBox (0, row*DOG_CHAR_HEIGHT + 3, 128, DOG_CHAR_HEIGHT); | ||||
| 		u8g.setColorIndex(0);		// following text must be white on black | ||||
| 		u8g.setPrintPos(0 * DOG_CHAR_WIDTH, (row + 1) * DOG_CHAR_HEIGHT); | ||||
| 		u8g.print(' ');	// Indent by 1 char | ||||
| 		u8g.print(LCD_STR_FOLDER[0]);		 | ||||
| 	    | ||||
|     while((c = *filename) != '\0') | ||||
|     { | ||||
| 			u8g.print(c); | ||||
| 		 | ||||
|         filename++; | ||||
|         n--; | ||||
|     } | ||||
|     while(n--){ | ||||
| 					u8g.print(' '); | ||||
| 			   } | ||||
| 	u8g.setColorIndex(1);		// black on white | ||||
| } | ||||
|  | ||||
| static void lcd_implementation_drawmenu_sddirectory(uint8_t row, const char* pstr, const char* filename, char* longFilename) | ||||
| { | ||||
|     char c; | ||||
|     uint8_t n = LCD_WIDTH - 2; | ||||
|  | ||||
|     if (longFilename[0] != '\0') | ||||
|     { | ||||
|         filename = longFilename; | ||||
|         longFilename[LCD_WIDTH-2] = '\0'; | ||||
|     } | ||||
|  | ||||
| 		u8g.setPrintPos(0 * DOG_CHAR_WIDTH, (row + 1) * DOG_CHAR_HEIGHT); | ||||
| 		u8g.print(' '); | ||||
| 		u8g.print(LCD_STR_FOLDER[0]); | ||||
|  | ||||
|     while((c = *filename) != '\0') | ||||
|     { | ||||
| 			u8g.print(c); | ||||
| 		 | ||||
|         filename++; | ||||
|         n--; | ||||
|     } | ||||
|     while(n--){ | ||||
| 					u8g.print(' '); | ||||
| 			   } | ||||
| } | ||||
|  | ||||
| #define lcd_implementation_drawmenu_back_selected(row, pstr, data) lcd_implementation_drawmenu_generic(row, pstr, LCD_STR_UPLEVEL[0], LCD_STR_UPLEVEL[0]) | ||||
| #define lcd_implementation_drawmenu_back(row, pstr, data) lcd_implementation_drawmenu_generic(row, pstr, ' ', LCD_STR_UPLEVEL[0]) | ||||
| #define lcd_implementation_drawmenu_submenu_selected(row, pstr, data) lcd_implementation_drawmenu_generic(row, pstr, '>', LCD_STR_ARROW_RIGHT[0]) | ||||
| #define lcd_implementation_drawmenu_submenu(row, pstr, data) lcd_implementation_drawmenu_generic(row, pstr, ' ', LCD_STR_ARROW_RIGHT[0]) | ||||
| #define lcd_implementation_drawmenu_gcode_selected(row, pstr, gcode) lcd_implementation_drawmenu_generic(row, pstr, '>', ' ') | ||||
| #define lcd_implementation_drawmenu_gcode(row, pstr, gcode) lcd_implementation_drawmenu_generic(row, pstr, ' ', ' ') | ||||
| #define lcd_implementation_drawmenu_function_selected(row, pstr, data) lcd_implementation_drawmenu_generic(row, pstr, '>', ' ') | ||||
| #define lcd_implementation_drawmenu_function(row, pstr, data) lcd_implementation_drawmenu_generic(row, pstr, ' ', ' ') | ||||
|  | ||||
| static void lcd_implementation_quick_feedback() | ||||
| { | ||||
|  | ||||
| #if BEEPER > -1 | ||||
|     SET_OUTPUT(BEEPER); | ||||
|     for(int8_t i=0;i<10;i++) | ||||
|     { | ||||
| 		WRITE(BEEPER,HIGH); | ||||
| 		delay(3); | ||||
| 		WRITE(BEEPER,LOW); | ||||
| 		delay(3); | ||||
|     } | ||||
| #endif | ||||
| } | ||||
| #endif//ULTRA_LCD_IMPLEMENTATION_DOGM_H | ||||
|  | ||||
|  | ||||
							
								
								
									
										2947
									
								
								Marlin/language.h
									
									
									
									
									
								
							
							
						
						
									
										2947
									
								
								Marlin/language.h
									
									
									
									
									
								
							
										
											
												File diff suppressed because it is too large
												Load Diff
											
										
									
								
							
							
								
								
									
										138
									
								
								Marlin/pins.h
									
									
									
									
									
								
							
							
						
						
									
										138
									
								
								Marlin/pins.h
									
									
									
									
									
								
							| @@ -181,10 +181,10 @@ | ||||
| #define E0_DIR_PIN 18 | ||||
| #define E0_ENABLE_PIN 25 | ||||
|  | ||||
| #define TEMP_0_PIN 0 | ||||
| #define TEMP_0_PIN 1 | ||||
| #define TEMP_1_PIN -1 | ||||
| #define TEMP_2_PIN -1 | ||||
| #define TEMP_BED_PIN 1 | ||||
| #define TEMP_BED_PIN 0 | ||||
|  | ||||
| #define HEATER_0_PIN 4 | ||||
| #define HEATER_1_PIN -1 | ||||
| @@ -321,6 +321,8 @@ | ||||
|  | ||||
| #if MOTHERBOARD == 33 || MOTHERBOARD == 34 | ||||
|  | ||||
| #define LARGE_FLASH        true | ||||
|  | ||||
| #define X_STEP_PIN         54 | ||||
| #define X_DIR_PIN          55 | ||||
| #define X_ENABLE_PIN       38 | ||||
| @@ -644,10 +646,13 @@ | ||||
| * Sanguinololu pin assignment | ||||
| * | ||||
| ****************************************************************************************/ | ||||
| #if MOTHERBOARD == 64 | ||||
| #define STB | ||||
| #endif | ||||
| #if MOTHERBOARD == 63 | ||||
| #define MELZI | ||||
| #endif | ||||
| #if MOTHERBOARD == 62 || MOTHERBOARD == 63 | ||||
| #if MOTHERBOARD == 62 || MOTHERBOARD == 63 || MOTHERBOARD == 64 | ||||
| #undef MOTHERBOARD | ||||
| #define MOTHERBOARD 6 | ||||
| #define SANGUINOLOLU_V_1_2  | ||||
| @@ -687,6 +692,10 @@ | ||||
| #define FAN_PIN            4 | ||||
| #endif | ||||
|  | ||||
| #ifdef STB | ||||
| #define FAN_PIN            4 | ||||
| #endif | ||||
|  | ||||
| #define PS_ON_PIN          -1 | ||||
| #define KILL_PIN           -1 | ||||
|  | ||||
| @@ -727,13 +736,25 @@ | ||||
|      //we have no buzzer installed | ||||
|      #define BEEPER -1 | ||||
|      //LCD Pins | ||||
|      #define LCD_PINS_RS        4 | ||||
|      #define LCD_PINS_ENABLE    17 | ||||
|      #define LCD_PINS_D4        30 | ||||
|      #define LCD_PINS_D5        29 | ||||
|      #define LCD_PINS_D6        28 | ||||
|      #define LCD_PINS_D7        27 | ||||
|       | ||||
| 	 	 #ifdef DOGLCD | ||||
| 			 // Pins for DOGM SPI LCD Support | ||||
| 			 #define DOGLCD_A0	30 | ||||
| 			 #define DOGLCD_CS	29 | ||||
| 			 // GLCD features | ||||
| 			 #define LCD_CONTRAST 1 | ||||
| 			 // Uncomment screen orientation | ||||
| 		     // #define LCD_SCREEN_ROT_0 | ||||
| 		     // #define LCD_SCREEN_ROT_90 | ||||
| 			 #define LCD_SCREEN_ROT_180 | ||||
| 		     // #define LCD_SCREEN_ROT_270 | ||||
| 			 #else // standard Hitachi LCD controller | ||||
| 			 #define LCD_PINS_RS        4 | ||||
| 			 #define LCD_PINS_ENABLE    17 | ||||
| 			 #define LCD_PINS_D4        30 | ||||
| 			 #define LCD_PINS_D5        29 | ||||
| 			 #define LCD_PINS_D6        28 | ||||
| 			 #define LCD_PINS_D7        27 | ||||
|          #endif | ||||
|      //The encoder and click button | ||||
|      #define BTN_EN1 11  //must be a hardware interrupt pin | ||||
|      #define BTN_EN2 10 //must be hardware interrupt pin | ||||
| @@ -770,6 +791,8 @@ | ||||
|  #endif | ||||
| #endif | ||||
|  | ||||
| #define LARGE_FLASH true | ||||
|  | ||||
| #define X_STEP_PIN 25 | ||||
| #define X_DIR_PIN 23 | ||||
| #define X_MIN_PIN 22 | ||||
| @@ -905,6 +928,8 @@ | ||||
|  #endif | ||||
| #endif | ||||
|  | ||||
| #define LARGE_FLASH true | ||||
|  | ||||
| #define X_STEP_PIN 25 | ||||
| #define X_DIR_PIN 23 | ||||
| #define X_MIN_PIN 15 | ||||
| @@ -960,6 +985,93 @@ | ||||
|  | ||||
| #endif | ||||
|  | ||||
|  | ||||
| /**************************************************************************************** | ||||
| * RUMBA pin assignment | ||||
| * | ||||
| ****************************************************************************************/ | ||||
| #if MOTHERBOARD == 80 | ||||
| #define KNOWN_BOARD 1 | ||||
|  | ||||
| #ifndef __AVR_ATmega2560__ | ||||
|  #error Oops!  Make sure you have 'Arduino Mega' selected from the 'Tools -> Boards' menu. | ||||
| #endif | ||||
|  | ||||
| #define X_STEP_PIN         17 | ||||
| #define X_DIR_PIN          16 | ||||
| #define X_ENABLE_PIN       48 | ||||
| #define X_MIN_PIN          37 | ||||
| #define X_MAX_PIN          36  | ||||
|  | ||||
| #define Y_STEP_PIN         54 | ||||
| #define Y_DIR_PIN          47  | ||||
| #define Y_ENABLE_PIN       55 | ||||
| #define Y_MIN_PIN          35 | ||||
| #define Y_MAX_PIN          34  | ||||
|  | ||||
| #define Z_STEP_PIN         57  | ||||
| #define Z_DIR_PIN          56 | ||||
| #define Z_ENABLE_PIN       62  | ||||
| #define Z_MIN_PIN          33 | ||||
| #define Z_MAX_PIN          32 | ||||
|  | ||||
| #define E0_STEP_PIN        23 | ||||
| #define E0_DIR_PIN         22 | ||||
| #define E0_ENABLE_PIN      24 | ||||
|  | ||||
| #define E1_STEP_PIN        26 | ||||
| #define E1_DIR_PIN         25 | ||||
| #define E1_ENABLE_PIN      27 | ||||
|  | ||||
| #define E2_STEP_PIN        29 | ||||
| #define E2_DIR_PIN         28 | ||||
| #define E2_ENABLE_PIN      39 | ||||
|  | ||||
| #define LED_PIN            13 | ||||
|  | ||||
| #define FAN_PIN            7  | ||||
| //additional FAN1 PIN (e.g. useful for electronics fan or light on/off) on PIN 8 | ||||
|  | ||||
| #define PS_ON_PIN          45 | ||||
| #define KILL_PIN           46 | ||||
|  | ||||
| #define HEATER_0_PIN       2    // EXTRUDER 1 | ||||
| #define HEATER_1_PIN       3    // EXTRUDER 2 | ||||
| #define HEATER_2_PIN       6    // EXTRUDER 3 | ||||
| //optional FAN1 can be used as 4th heater output: #define HEATER_3_PIN       8    // EXTRUDER 4 | ||||
| #define HEATER_BED_PIN     9    // BED | ||||
|  | ||||
| #define TEMP_0_PIN         15   // ANALOG NUMBERING | ||||
| #define TEMP_1_PIN         14   // ANALOG NUMBERING | ||||
| #define TEMP_2_PIN         13   // ANALOG NUMBERING | ||||
| //optional for extruder 4 or chamber: #define TEMP_2_PIN         12   // ANALOG NUMBERING | ||||
| #define TEMP_BED_PIN       11   // ANALOG NUMBERING | ||||
|  | ||||
| #define SDPOWER            -1 | ||||
| #define SDSS               53 | ||||
| #define SDCARDDETECT       49 | ||||
| #define BEEPER             44 | ||||
| #define LCD_PINS_RS        19  | ||||
| #define LCD_PINS_ENABLE    42 | ||||
| #define LCD_PINS_D4        18 | ||||
| #define LCD_PINS_D5        38  | ||||
| #define LCD_PINS_D6        41 | ||||
| #define LCD_PINS_D7        40 | ||||
| #define BTN_EN1            11 | ||||
| #define BTN_EN2            12 | ||||
| #define BTN_ENC            43 | ||||
| //encoder rotation values | ||||
| #define BLEN_C 2 | ||||
| #define BLEN_B 1 | ||||
| #define BLEN_A 0 | ||||
| #define encrot0 0 | ||||
| #define encrot1 2 | ||||
| #define encrot2 3 | ||||
| #define encrot3 1 | ||||
|  | ||||
| #endif //MOTHERBOARD==80 | ||||
|  | ||||
|  | ||||
| /**************************************************************************************** | ||||
| * Teensylu 0.7 / Printrboard pin assignments (AT90USB1286) | ||||
| * Requires the Teensyduino software with Teensy++ 2.0 selected in Arduino IDE! | ||||
| @@ -974,6 +1086,8 @@ | ||||
| #error Oops!  Make sure you have 'Teensy++ 2.0' selected from the 'Tools -> Boards' menu. | ||||
| #endif | ||||
|  | ||||
| #define LARGE_FLASH        true | ||||
|  | ||||
| #define X_STEP_PIN          0 | ||||
| #define X_DIR_PIN           1 | ||||
| #define X_ENABLE_PIN       39 | ||||
| @@ -1307,6 +1421,8 @@ | ||||
| #error Oops!  Make sure you have 'Arduino Mega 2560' selected from the 'Tools -> Boards' menu. | ||||
| #endif | ||||
|  | ||||
| #define LARGE_FLASH true | ||||
|  | ||||
| #define X_STEP_PIN 37 | ||||
| #define X_DIR_PIN 48 | ||||
| #define X_MIN_PIN 12 | ||||
| @@ -1382,7 +1498,7 @@ | ||||
|  #endif | ||||
|  | ||||
|  | ||||
|  | ||||
| #define LARGE_FLASH        true | ||||
|  | ||||
| #define X_STEP_PIN         26 | ||||
| #define X_DIR_PIN          28 | ||||
|   | ||||
| @@ -478,7 +478,7 @@ void check_axes_activity() | ||||
|           tail_fan_speed = 255; | ||||
|       } else { | ||||
|         fan_kick_end = 0; | ||||
|       } | ||||
|       } | ||||
|     #endif//FAN_KICKSTART_TIME | ||||
|     analogWrite(FAN_PIN,tail_fan_speed); | ||||
|   #endif//!FAN_SOFT_PWM | ||||
| @@ -895,3 +895,11 @@ void allow_cold_extrudes(bool allow) | ||||
| #endif | ||||
| } | ||||
|  | ||||
| // Calculate the steps/s^2 acceleration rates, based on the mm/s^s | ||||
| void reset_acceleration_rates() | ||||
| { | ||||
| 	for(int8_t i=0; i < NUM_AXIS; i++) | ||||
|         { | ||||
|         axis_steps_per_sqr_second[i] = max_acceleration_units_per_sq_second[i] * axis_steps_per_unit[i]; | ||||
|         } | ||||
| } | ||||
|   | ||||
| @@ -136,4 +136,6 @@ FORCE_INLINE bool blocks_queued() | ||||
| } | ||||
|  | ||||
| void allow_cold_extrudes(bool allow); | ||||
|  | ||||
| void reset_acceleration_rates(); | ||||
| #endif | ||||
|   | ||||
| @@ -62,6 +62,7 @@ static long acceleration_time, deceleration_time; | ||||
| static unsigned short acc_step_rate; // needed for deccelaration start point | ||||
| static char step_loops; | ||||
| static unsigned short OCR1A_nominal; | ||||
| static unsigned short step_loops_nominal; | ||||
|  | ||||
| volatile long endstops_trigsteps[3]={0,0,0}; | ||||
| volatile long endstops_stepsTotal,endstops_stepsDone; | ||||
| @@ -288,6 +289,8 @@ FORCE_INLINE void trapezoid_generator_reset() { | ||||
|   deceleration_time = 0; | ||||
|   // step_rate to timer interval | ||||
|   OCR1A_nominal = calc_timer(current_block->nominal_rate); | ||||
|   // make a note of the number of step loops required at nominal speed | ||||
|   step_loops_nominal = step_loops; | ||||
|   acc_step_rate = current_block->initial_rate; | ||||
|   acceleration_time = calc_timer(acc_step_rate); | ||||
|   OCR1A = acceleration_time; | ||||
| @@ -665,6 +668,8 @@ ISR(TIMER1_COMPA_vect) | ||||
|     } | ||||
|     else { | ||||
|       OCR1A = OCR1A_nominal; | ||||
|       // ensure we're running at the correct step rate, even if we just came off an acceleration | ||||
|       step_loops = step_loops_nominal; | ||||
|     } | ||||
|  | ||||
|     // If current block is finished, reset pointer  | ||||
|   | ||||
| @@ -326,10 +326,10 @@ void manage_heater() | ||||
|     #ifndef PID_OPENLOOP | ||||
|         pid_error[e] = target_temperature[e] - pid_input; | ||||
|         if(pid_error[e] > PID_FUNCTIONAL_RANGE) { | ||||
|           pid_output = PID_MAX; | ||||
|           pid_output = BANG_MAX; | ||||
|           pid_reset[e] = true; | ||||
|         } | ||||
|         else if(pid_error[e] < -PID_FUNCTIONAL_RANGE) { | ||||
|         else if(pid_error[e] < -PID_FUNCTIONAL_RANGE || target_temperature[e] == 0) { | ||||
|           pid_output = 0; | ||||
|           pid_reset[e] = true; | ||||
|         } | ||||
| @@ -1177,3 +1177,31 @@ ISR(TIMER0_COMPB_vect) | ||||
| #endif | ||||
|   }   | ||||
| } | ||||
|  | ||||
| #ifdef PIDTEMP | ||||
| // Apply the scale factors to the PID values | ||||
|  | ||||
|  | ||||
| float scalePID_i(float i) | ||||
| { | ||||
| 	return i*PID_dT; | ||||
| } | ||||
|  | ||||
| float unscalePID_i(float i) | ||||
| { | ||||
| 	return i/PID_dT; | ||||
| } | ||||
|  | ||||
| float scalePID_d(float d) | ||||
| { | ||||
|     return d/PID_dT; | ||||
| } | ||||
|  | ||||
| float unscalePID_d(float d) | ||||
| { | ||||
| 	return d*PID_dT; | ||||
| } | ||||
|  | ||||
| #endif //PIDTEMP | ||||
|  | ||||
|  | ||||
|   | ||||
| @@ -31,8 +31,8 @@ | ||||
| void tp_init();  //initialise the heating | ||||
| void manage_heater(); //it is critical that this is called periodically. | ||||
|  | ||||
| //low leven conversion routines | ||||
| // do not use this routines and variables outsie of temperature.cpp | ||||
| // low level conversion routines | ||||
| // do not use these routines and variables outside of temperature.cpp | ||||
| extern int target_temperature[EXTRUDERS];   | ||||
| extern float current_temperature[EXTRUDERS]; | ||||
| extern int target_temperature_bed; | ||||
| @@ -40,6 +40,11 @@ extern float current_temperature_bed; | ||||
|  | ||||
| #ifdef PIDTEMP | ||||
|   extern float Kp,Ki,Kd,Kc; | ||||
|   float scalePID_i(float i); | ||||
|   float scalePID_d(float d); | ||||
|   float unscalePID_i(float i); | ||||
|   float unscalePID_d(float d); | ||||
|  | ||||
| #endif | ||||
| #ifdef PIDTEMPBED | ||||
|   extern float bedKp,bedKi,bedKd; | ||||
|   | ||||
| @@ -254,61 +254,63 @@ const short temptable_6[][2] PROGMEM = { | ||||
|  | ||||
| #if (THERMISTORHEATER_0 == 7) || (THERMISTORHEATER_1 == 7) || (THERMISTORHEATER_2 == 7) || (THERMISTORBED == 7) // 100k Honeywell 135-104LAG-J01 | ||||
| const short temptable_7[][2] PROGMEM = { | ||||
|    {1*OVERSAMPLENR, 500}, | ||||
|    {46*OVERSAMPLENR, 270}, //top rating 300C | ||||
|    {50*OVERSAMPLENR, 265}, | ||||
|    {54*OVERSAMPLENR, 260}, | ||||
|    {58*OVERSAMPLENR, 255}, | ||||
|    {62*OVERSAMPLENR, 250}, | ||||
|    {67*OVERSAMPLENR, 245}, | ||||
|    {72*OVERSAMPLENR, 240}, | ||||
|    {79*OVERSAMPLENR, 235}, | ||||
|    {85*OVERSAMPLENR, 230}, | ||||
|    {91*OVERSAMPLENR, 225}, | ||||
|    {99*OVERSAMPLENR, 220}, | ||||
|    {107*OVERSAMPLENR, 215}, | ||||
|    {116*OVERSAMPLENR, 210}, | ||||
|    {126*OVERSAMPLENR, 205}, | ||||
|    {136*OVERSAMPLENR, 200}, | ||||
|    {149*OVERSAMPLENR, 195}, | ||||
|    {160*OVERSAMPLENR, 190}, | ||||
|    {175*OVERSAMPLENR, 185}, | ||||
|    {191*OVERSAMPLENR, 180}, | ||||
|    {209*OVERSAMPLENR, 175}, | ||||
|    {224*OVERSAMPLENR, 170}, | ||||
|    {246*OVERSAMPLENR, 165}, | ||||
|    {267*OVERSAMPLENR, 160}, | ||||
|    {293*OVERSAMPLENR, 155}, | ||||
|    {316*OVERSAMPLENR, 150}, | ||||
|    {340*OVERSAMPLENR, 145}, | ||||
|    {364*OVERSAMPLENR, 140}, | ||||
|    {396*OVERSAMPLENR, 135}, | ||||
|    {425*OVERSAMPLENR, 130}, | ||||
|    {460*OVERSAMPLENR, 125}, | ||||
|    {489*OVERSAMPLENR, 120}, | ||||
|    {526*OVERSAMPLENR, 115}, | ||||
|    {558*OVERSAMPLENR, 110}, | ||||
|    {591*OVERSAMPLENR, 105}, | ||||
|    {628*OVERSAMPLENR, 100}, | ||||
|    {660*OVERSAMPLENR, 95}, | ||||
|    {696*OVERSAMPLENR, 90}, | ||||
|    {733*OVERSAMPLENR, 85}, | ||||
|    {761*OVERSAMPLENR, 80}, | ||||
|    {794*OVERSAMPLENR, 75}, | ||||
|    {819*OVERSAMPLENR, 70}, | ||||
|    {847*OVERSAMPLENR, 65}, | ||||
|    {870*OVERSAMPLENR, 60}, | ||||
|    {892*OVERSAMPLENR, 55}, | ||||
|    {911*OVERSAMPLENR, 50}, | ||||
|    {929*OVERSAMPLENR, 45}, | ||||
|    {944*OVERSAMPLENR, 40}, | ||||
|    {959*OVERSAMPLENR, 35}, | ||||
|    {971*OVERSAMPLENR, 30}, | ||||
|    {981*OVERSAMPLENR, 25}, | ||||
|    {989*OVERSAMPLENR, 20}, | ||||
|    {994*OVERSAMPLENR, 15}, | ||||
|    {1001*OVERSAMPLENR, 10}, | ||||
|    {1005*OVERSAMPLENR, 5}, | ||||
|    {1*OVERSAMPLENR, 941}, | ||||
|    {19*OVERSAMPLENR, 362}, | ||||
|    {37*OVERSAMPLENR, 299}, //top rating 300C | ||||
|    {55*OVERSAMPLENR, 266}, | ||||
|    {73*OVERSAMPLENR, 245}, | ||||
|    {91*OVERSAMPLENR, 229}, | ||||
|    {109*OVERSAMPLENR, 216}, | ||||
|    {127*OVERSAMPLENR, 206}, | ||||
|    {145*OVERSAMPLENR, 197}, | ||||
|    {163*OVERSAMPLENR, 190}, | ||||
|    {181*OVERSAMPLENR, 183}, | ||||
|    {199*OVERSAMPLENR, 177}, | ||||
|    {217*OVERSAMPLENR, 171}, | ||||
|    {235*OVERSAMPLENR, 166}, | ||||
|    {253*OVERSAMPLENR, 162}, | ||||
|    {271*OVERSAMPLENR, 157}, | ||||
|    {289*OVERSAMPLENR, 153}, | ||||
|    {307*OVERSAMPLENR, 149}, | ||||
|    {325*OVERSAMPLENR, 146}, | ||||
|    {343*OVERSAMPLENR, 142}, | ||||
|    {361*OVERSAMPLENR, 139}, | ||||
|    {379*OVERSAMPLENR, 135}, | ||||
|    {397*OVERSAMPLENR, 132}, | ||||
|    {415*OVERSAMPLENR, 129}, | ||||
|    {433*OVERSAMPLENR, 126}, | ||||
|    {451*OVERSAMPLENR, 123}, | ||||
|    {469*OVERSAMPLENR, 121}, | ||||
|    {487*OVERSAMPLENR, 118}, | ||||
|    {505*OVERSAMPLENR, 115}, | ||||
|    {523*OVERSAMPLENR, 112}, | ||||
|    {541*OVERSAMPLENR, 110}, | ||||
|    {559*OVERSAMPLENR, 107}, | ||||
|    {577*OVERSAMPLENR, 105}, | ||||
|    {595*OVERSAMPLENR, 102}, | ||||
|    {613*OVERSAMPLENR, 99}, | ||||
|    {631*OVERSAMPLENR, 97}, | ||||
|    {649*OVERSAMPLENR, 94}, | ||||
|    {667*OVERSAMPLENR, 92}, | ||||
|    {685*OVERSAMPLENR, 89}, | ||||
|    {703*OVERSAMPLENR, 86}, | ||||
|    {721*OVERSAMPLENR, 84}, | ||||
|    {739*OVERSAMPLENR, 81}, | ||||
|    {757*OVERSAMPLENR, 78}, | ||||
|    {775*OVERSAMPLENR, 75}, | ||||
|    {793*OVERSAMPLENR, 72}, | ||||
|    {811*OVERSAMPLENR, 69}, | ||||
|    {829*OVERSAMPLENR, 66}, | ||||
|    {847*OVERSAMPLENR, 62}, | ||||
|    {865*OVERSAMPLENR, 59}, | ||||
|    {883*OVERSAMPLENR, 55}, | ||||
|    {901*OVERSAMPLENR, 51}, | ||||
|    {919*OVERSAMPLENR, 46}, | ||||
|    {937*OVERSAMPLENR, 41}, | ||||
|    {955*OVERSAMPLENR, 35}, | ||||
|    {973*OVERSAMPLENR, 27}, | ||||
|    {991*OVERSAMPLENR, 17}, | ||||
|    {1009*OVERSAMPLENR, 1}, | ||||
|    {1023*OVERSAMPLENR, 0}  //to allow internal 0 degrees C | ||||
| }; | ||||
| #endif | ||||
| @@ -554,6 +556,84 @@ const short temptable_55[][2] PROGMEM = { | ||||
| }; | ||||
| #endif | ||||
|  | ||||
| #if (THERMISTORHEATER_0 == 60) || (THERMISTORHEATER_1 == 60) || (THERMISTORHEATER_2 == 60) || (THERMISTORBED == 60) // Maker's Tool Works Kapton Bed Thermister | ||||
| const short temptable_60[][2] PROGMEM = { | ||||
|    {51*OVERSAMPLENR, 272}, | ||||
|    {61*OVERSAMPLENR, 258}, | ||||
|    {71*OVERSAMPLENR, 247}, | ||||
|    {81*OVERSAMPLENR, 237}, | ||||
|    {91*OVERSAMPLENR, 229}, | ||||
|    {101*OVERSAMPLENR, 221}, | ||||
|    {131*OVERSAMPLENR, 204}, | ||||
|    {161*OVERSAMPLENR, 190}, | ||||
|    {191*OVERSAMPLENR, 179}, | ||||
|    {231*OVERSAMPLENR, 167}, | ||||
|    {271*OVERSAMPLENR, 157}, | ||||
|    {311*OVERSAMPLENR, 148}, | ||||
|    {351*OVERSAMPLENR, 140}, | ||||
|    {381*OVERSAMPLENR, 135}, | ||||
|    {411*OVERSAMPLENR, 130}, | ||||
|    {441*OVERSAMPLENR, 125}, | ||||
|    {451*OVERSAMPLENR, 123}, | ||||
|    {461*OVERSAMPLENR, 122}, | ||||
|    {471*OVERSAMPLENR, 120}, | ||||
|    {481*OVERSAMPLENR, 119}, | ||||
|    {491*OVERSAMPLENR, 117}, | ||||
|    {501*OVERSAMPLENR, 116}, | ||||
|    {511*OVERSAMPLENR, 114}, | ||||
|    {521*OVERSAMPLENR, 113}, | ||||
|    {531*OVERSAMPLENR, 111}, | ||||
|    {541*OVERSAMPLENR, 110}, | ||||
|    {551*OVERSAMPLENR, 108}, | ||||
|    {561*OVERSAMPLENR, 107}, | ||||
|    {571*OVERSAMPLENR, 105}, | ||||
|    {581*OVERSAMPLENR, 104}, | ||||
|    {591*OVERSAMPLENR, 102}, | ||||
|    {601*OVERSAMPLENR, 101}, | ||||
|    {611*OVERSAMPLENR, 100}, | ||||
|    {621*OVERSAMPLENR, 98}, | ||||
|    {631*OVERSAMPLENR, 97}, | ||||
|    {641*OVERSAMPLENR, 95}, | ||||
|    {651*OVERSAMPLENR, 94}, | ||||
|    {661*OVERSAMPLENR, 92}, | ||||
|    {671*OVERSAMPLENR, 91}, | ||||
|    {681*OVERSAMPLENR, 90}, | ||||
|    {691*OVERSAMPLENR, 88}, | ||||
|    {701*OVERSAMPLENR, 87}, | ||||
|    {711*OVERSAMPLENR, 85}, | ||||
|    {721*OVERSAMPLENR, 84}, | ||||
|    {731*OVERSAMPLENR, 82}, | ||||
|    {741*OVERSAMPLENR, 81}, | ||||
|    {751*OVERSAMPLENR, 79}, | ||||
|    {761*OVERSAMPLENR, 77}, | ||||
|    {771*OVERSAMPLENR, 76}, | ||||
|    {781*OVERSAMPLENR, 74}, | ||||
|    {791*OVERSAMPLENR, 72}, | ||||
|    {801*OVERSAMPLENR, 71}, | ||||
|    {811*OVERSAMPLENR, 69}, | ||||
|    {821*OVERSAMPLENR, 67}, | ||||
|    {831*OVERSAMPLENR, 65}, | ||||
|    {841*OVERSAMPLENR, 63}, | ||||
|    {851*OVERSAMPLENR, 62}, | ||||
|    {861*OVERSAMPLENR, 60}, | ||||
|    {871*OVERSAMPLENR, 57}, | ||||
|    {881*OVERSAMPLENR, 55}, | ||||
|    {891*OVERSAMPLENR, 53}, | ||||
|    {901*OVERSAMPLENR, 51}, | ||||
|    {911*OVERSAMPLENR, 48}, | ||||
|    {921*OVERSAMPLENR, 45}, | ||||
|    {931*OVERSAMPLENR, 42}, | ||||
|    {941*OVERSAMPLENR, 39}, | ||||
|    {951*OVERSAMPLENR, 36}, | ||||
|    {961*OVERSAMPLENR, 32}, | ||||
|    {981*OVERSAMPLENR, 23}, | ||||
|    {991*OVERSAMPLENR, 17}, | ||||
|    {1001*OVERSAMPLENR, 9}, | ||||
|    {1008*OVERSAMPLENR, 0}, | ||||
| }; | ||||
| #endif | ||||
|  | ||||
|  | ||||
| #define _TT_NAME(_N) temptable_ ## _N | ||||
| #define TT_NAME(_N) _TT_NAME(_N) | ||||
|  | ||||
|   | ||||
| @@ -24,9 +24,17 @@ typedef void (*menuFunc_t)(); | ||||
| uint8_t lcd_status_message_level; | ||||
| char lcd_status_message[LCD_WIDTH+1] = WELCOME_MSG; | ||||
|  | ||||
| #ifdef DOGLCD | ||||
| #include "dogm_lcd_implementation.h" | ||||
| #else | ||||
| #include "ultralcd_implementation_hitachi_HD44780.h" | ||||
| #endif | ||||
|  | ||||
| /** forward declerations **/ | ||||
|  | ||||
| void copy_and_scalePID_i(); | ||||
| void copy_and_scalePID_d(); | ||||
|  | ||||
| /* Different menus */ | ||||
| static void lcd_status_screen(); | ||||
| #ifdef ULTIPANEL | ||||
| @@ -59,6 +67,14 @@ static void menu_action_setting_edit_float5(const char* pstr, float* ptr, float | ||||
| static void menu_action_setting_edit_float51(const char* pstr, float* ptr, float minValue, float maxValue); | ||||
| static void menu_action_setting_edit_float52(const char* pstr, float* ptr, float minValue, float maxValue); | ||||
| static void menu_action_setting_edit_long5(const char* pstr, unsigned long* ptr, unsigned long minValue, unsigned long maxValue); | ||||
| static void menu_action_setting_edit_callback_bool(const char* pstr, bool* ptr, menuFunc_t callbackFunc); | ||||
| static void menu_action_setting_edit_callback_int3(const char* pstr, int* ptr, int minValue, int maxValue, menuFunc_t callbackFunc); | ||||
| static void menu_action_setting_edit_callback_float3(const char* pstr, float* ptr, float minValue, float maxValue, menuFunc_t callbackFunc); | ||||
| static void menu_action_setting_edit_callback_float32(const char* pstr, float* ptr, float minValue, float maxValue, menuFunc_t callbackFunc); | ||||
| static void menu_action_setting_edit_callback_float5(const char* pstr, float* ptr, float minValue, float maxValue, menuFunc_t callbackFunc); | ||||
| static void menu_action_setting_edit_callback_float51(const char* pstr, float* ptr, float minValue, float maxValue, menuFunc_t callbackFunc); | ||||
| static void menu_action_setting_edit_callback_float52(const char* pstr, float* ptr, float minValue, float maxValue, menuFunc_t callbackFunc); | ||||
| static void menu_action_setting_edit_callback_long5(const char* pstr, unsigned long* ptr, unsigned long minValue, unsigned long maxValue, menuFunc_t callbackFunc); | ||||
|  | ||||
| #define ENCODER_STEPS_PER_MENU_ITEM 5 | ||||
|  | ||||
| @@ -89,6 +105,7 @@ static void menu_action_setting_edit_long5(const char* pstr, unsigned long* ptr, | ||||
| } while(0) | ||||
| #define MENU_ITEM_DUMMY() do { _menuItemNr++; } while(0) | ||||
| #define MENU_ITEM_EDIT(type, label, args...) MENU_ITEM(setting_edit_ ## type, label, PSTR(label) , ## args ) | ||||
| #define MENU_ITEM_EDIT_CALLBACK(type, label, args...) MENU_ITEM(setting_edit_callback_ ## type, label, PSTR(label) , ## args ) | ||||
| #define END_MENU() \ | ||||
|     if (encoderPosition / ENCODER_STEPS_PER_MENU_ITEM >= _menuItemNr) encoderPosition = _menuItemNr * ENCODER_STEPS_PER_MENU_ITEM - 1; \ | ||||
|     if ((uint8_t)(encoderPosition / ENCODER_STEPS_PER_MENU_ITEM) >= currentMenuViewOffset + LCD_HEIGHT) { currentMenuViewOffset = (encoderPosition / ENCODER_STEPS_PER_MENU_ITEM) - LCD_HEIGHT + 1; lcdDrawUpdate = 1; _lineNr = currentMenuViewOffset - 1; _drawLineNr = -1; } \ | ||||
| @@ -119,6 +136,10 @@ uint16_t prevEncoderPosition; | ||||
| const char* editLabel; | ||||
| void* editValue; | ||||
| int32_t minEditValue, maxEditValue; | ||||
| menuFunc_t callbackFunc; | ||||
|  | ||||
| // placeholders for Ki and Kd edits | ||||
| float raw_Ki, raw_Kd; | ||||
|  | ||||
| /* Main status screen. It's up to the implementation specific part to show what is needed. As this is very display dependend */ | ||||
| static void lcd_status_screen() | ||||
| @@ -438,6 +459,10 @@ static void lcd_control_menu() | ||||
|  | ||||
| static void lcd_control_temperature_menu() | ||||
| { | ||||
| 	// set up temp variables - undo the default scaling | ||||
| 	raw_Ki = unscalePID_i(Ki); | ||||
| 	raw_Kd = unscalePID_d(Kd); | ||||
| 	 | ||||
|     START_MENU(); | ||||
|     MENU_ITEM(back, MSG_CONTROL, lcd_control_menu); | ||||
|     MENU_ITEM_EDIT(int3, MSG_NOZZLE, &target_temperature[0], 0, HEATER_0_MAXTEMP - 15); | ||||
| @@ -459,9 +484,9 @@ static void lcd_control_temperature_menu() | ||||
| #endif | ||||
| #ifdef PIDTEMP | ||||
|     MENU_ITEM_EDIT(float52, MSG_PID_P, &Kp, 1, 9990); | ||||
| //TODO, I and D should have a PID_dT multiplier (Ki = PID_I * PID_dT, Kd = PID_D / PID_dT) | ||||
|     MENU_ITEM_EDIT(float52, MSG_PID_I, &Ki, 1, 9990); | ||||
|     MENU_ITEM_EDIT(float52, MSG_PID_D, &Kd, 1, 9990); | ||||
| 	// i is typically a small value so allows values below 1 | ||||
|     MENU_ITEM_EDIT_CALLBACK(float52, MSG_PID_I, &raw_Ki, 0.01, 9990, copy_and_scalePID_i); | ||||
|     MENU_ITEM_EDIT_CALLBACK(float52, MSG_PID_D, &raw_Kd, 1, 9990, copy_and_scalePID_d); | ||||
| # ifdef PID_ADD_EXTRUSION_RATE | ||||
|     MENU_ITEM_EDIT(float3, MSG_PID_C, &Kc, 1, 9990); | ||||
| # endif//PID_ADD_EXTRUSION_RATE | ||||
| @@ -507,16 +532,18 @@ static void lcd_control_motion_menu() | ||||
|     MENU_ITEM(back, MSG_CONTROL, lcd_control_menu); | ||||
|     MENU_ITEM_EDIT(float5, MSG_ACC, &acceleration, 500, 99000); | ||||
|     MENU_ITEM_EDIT(float3, MSG_VXY_JERK, &max_xy_jerk, 1, 990); | ||||
|     MENU_ITEM_EDIT(float52, MSG_VZ_JERK, &max_z_jerk, 0.1, 990); | ||||
|     MENU_ITEM_EDIT(float3, MSG_VE_JERK, &max_e_jerk, 1, 990); | ||||
|     MENU_ITEM_EDIT(float3, MSG_VMAX MSG_X, &max_feedrate[X_AXIS], 1, 999); | ||||
|     MENU_ITEM_EDIT(float3, MSG_VMAX MSG_Y, &max_feedrate[Y_AXIS], 1, 999); | ||||
|     MENU_ITEM_EDIT(float3, MSG_VMAX MSG_Z, &max_feedrate[Z_AXIS], 1, 999); | ||||
|     MENU_ITEM_EDIT(float3, MSG_VMAX MSG_E, &max_feedrate[E_AXIS], 1, 999); | ||||
|     MENU_ITEM_EDIT(float3, MSG_VMIN, &minimumfeedrate, 0, 999); | ||||
|     MENU_ITEM_EDIT(float3, MSG_VTRAV_MIN, &mintravelfeedrate, 0, 999); | ||||
|     MENU_ITEM_EDIT(long5, MSG_AMAX MSG_X, &max_acceleration_units_per_sq_second[X_AXIS], 100, 99000); | ||||
|     MENU_ITEM_EDIT(long5, MSG_AMAX MSG_Y, &max_acceleration_units_per_sq_second[Y_AXIS], 100, 99000); | ||||
|     MENU_ITEM_EDIT(long5, MSG_AMAX MSG_Z, &max_acceleration_units_per_sq_second[Z_AXIS], 100, 99000); | ||||
|     MENU_ITEM_EDIT(long5, MSG_AMAX MSG_E, &max_acceleration_units_per_sq_second[E_AXIS], 100, 99000); | ||||
|     MENU_ITEM_EDIT_CALLBACK(long5, MSG_AMAX MSG_X, &max_acceleration_units_per_sq_second[X_AXIS], 100, 99000, reset_acceleration_rates); | ||||
|     MENU_ITEM_EDIT_CALLBACK(long5, MSG_AMAX MSG_Y, &max_acceleration_units_per_sq_second[Y_AXIS], 100, 99000, reset_acceleration_rates); | ||||
|     MENU_ITEM_EDIT_CALLBACK(long5, MSG_AMAX MSG_Z, &max_acceleration_units_per_sq_second[Z_AXIS], 100, 99000, reset_acceleration_rates); | ||||
|     MENU_ITEM_EDIT_CALLBACK(long5, MSG_AMAX MSG_E, &max_acceleration_units_per_sq_second[E_AXIS], 100, 99000, reset_acceleration_rates); | ||||
|     MENU_ITEM_EDIT(float5, MSG_A_RETRACT, &retract_acceleration, 100, 99000); | ||||
|     MENU_ITEM_EDIT(float52, MSG_XSTEPS, &axis_steps_per_unit[X_AXIS], 5, 9999); | ||||
|     MENU_ITEM_EDIT(float52, MSG_YSTEPS, &axis_steps_per_unit[Y_AXIS], 5, 9999); | ||||
| @@ -606,6 +633,23 @@ void lcd_sdcard_menu() | ||||
|             encoderPosition = prevEncoderPosition; \ | ||||
|         } \ | ||||
|     } \ | ||||
|     void menu_edit_callback_ ## _name () \ | ||||
|     { \ | ||||
|         if ((int32_t)encoderPosition < minEditValue) \ | ||||
|             encoderPosition = minEditValue; \ | ||||
|         if ((int32_t)encoderPosition > maxEditValue) \ | ||||
|             encoderPosition = maxEditValue; \ | ||||
|         if (lcdDrawUpdate) \ | ||||
|             lcd_implementation_drawedit(editLabel, _strFunc(((_type)encoderPosition) / scale)); \ | ||||
|         if (LCD_CLICKED) \ | ||||
|         { \ | ||||
|             *((_type*)editValue) = ((_type)encoderPosition) / scale; \ | ||||
|             lcd_quick_feedback(); \ | ||||
|             currentMenu = prevMenu; \ | ||||
|             encoderPosition = prevEncoderPosition; \ | ||||
|             (*callbackFunc)();\ | ||||
|         } \ | ||||
|     } \ | ||||
|     static void menu_action_setting_edit_ ## _name (const char* pstr, _type* ptr, _type minValue, _type maxValue) \ | ||||
|     { \ | ||||
|         prevMenu = currentMenu; \ | ||||
| @@ -619,6 +663,21 @@ void lcd_sdcard_menu() | ||||
|         minEditValue = minValue * scale; \ | ||||
|         maxEditValue = maxValue * scale; \ | ||||
|         encoderPosition = (*ptr) * scale; \ | ||||
|     }\ | ||||
|     static void menu_action_setting_edit_callback_ ## _name (const char* pstr, _type* ptr, _type minValue, _type maxValue, menuFunc_t callback) \ | ||||
|     { \ | ||||
|         prevMenu = currentMenu; \ | ||||
|         prevEncoderPosition = encoderPosition; \ | ||||
|          \ | ||||
|         lcdDrawUpdate = 2; \ | ||||
|         currentMenu = menu_edit_callback_ ## _name; \ | ||||
|          \ | ||||
|         editLabel = pstr; \ | ||||
|         editValue = ptr; \ | ||||
|         minEditValue = minValue * scale; \ | ||||
|         maxEditValue = maxValue * scale; \ | ||||
|         encoderPosition = (*ptr) * scale; \ | ||||
|         callbackFunc = callback;\ | ||||
|     } | ||||
| menu_edit_type(int, int3, itostr3, 1) | ||||
| menu_edit_type(float, float3, ftostr3, 1) | ||||
| @@ -747,8 +806,23 @@ void lcd_update() | ||||
|         if (LCD_CLICKED) | ||||
|             timeoutToStatus = millis() + LCD_TIMEOUT_TO_STATUS; | ||||
| #endif//ULTIPANEL | ||||
|          | ||||
|  | ||||
| #ifdef DOGLCD        // Changes due to different driver architecture of the DOGM display | ||||
| 		blink++;	   // Variable for fan animation and alive dot | ||||
| 		u8g.firstPage(); | ||||
| 		do { | ||||
| 				u8g.setFont(u8g_font_6x10_marlin); | ||||
| 				u8g.setPrintPos(125,0); | ||||
| 				if (blink % 2) u8g.setColorIndex(1); else u8g.setColorIndex(0); // Set color for the alive dot | ||||
| 				u8g.drawPixel(127,63);	// draw alive dot | ||||
| 				u8g.setColorIndex(1);	// black on white | ||||
| 				(*currentMenu)(); | ||||
| 				if (!lcdDrawUpdate)  break; // Terminate display update, when nothing new to draw. This must be done before the last dogm.next() | ||||
| 		   } while( u8g.nextPage() ); | ||||
| #else         | ||||
|         (*currentMenu)(); | ||||
| #endif | ||||
|  | ||||
| #ifdef ULTIPANEL | ||||
|         if(timeoutToStatus < millis() && currentMenu != lcd_status_screen) | ||||
|         { | ||||
| @@ -893,6 +967,21 @@ char *ftostr31(const float &x) | ||||
|   return conv; | ||||
| } | ||||
|  | ||||
| //  convert float to string with 123.4 format | ||||
| char *ftostr31ns(const float &x) | ||||
| { | ||||
|   int xx=x*10; | ||||
|   //conv[0]=(xx>=0)?'+':'-'; | ||||
|   xx=abs(xx); | ||||
|   conv[0]=(xx/1000)%10+'0'; | ||||
|   conv[1]=(xx/100)%10+'0'; | ||||
|   conv[2]=(xx/10)%10+'0'; | ||||
|   conv[3]='.'; | ||||
|   conv[4]=(xx)%10+'0'; | ||||
|   conv[5]=0; | ||||
|   return conv; | ||||
| } | ||||
|  | ||||
| char *ftostr32(const float &x) | ||||
| { | ||||
|   long xx=x*100; | ||||
| @@ -1036,4 +1125,20 @@ char *ftostr52(const float &x) | ||||
|   return conv; | ||||
| } | ||||
|  | ||||
| // Callback for after editing PID i value | ||||
| // grab the pid i value out of the temp variable; scale it; then update the PID driver | ||||
| void copy_and_scalePID_i() | ||||
| { | ||||
|   Ki = scalePID_i(raw_Ki); | ||||
|   updatePID(); | ||||
| }	 | ||||
|  | ||||
| // Callback for after editing PID d value | ||||
| // grab the pid d value out of the temp variable; scale it; then update the PID driver | ||||
| void copy_and_scalePID_d() | ||||
| { | ||||
|   Kd = scalePID_d(raw_Kd); | ||||
|   updatePID(); | ||||
| }	 | ||||
| 	 | ||||
| #endif //ULTRA_LCD | ||||
|   | ||||
| @@ -11,6 +11,8 @@ | ||||
|   void lcd_setstatuspgm(const char* message); | ||||
|   void lcd_setalertstatuspgm(const char* message); | ||||
|   void lcd_reset_alert_level(); | ||||
|    | ||||
|   static unsigned char blink = 0;	// Variable for visualisation of fan rotation in GLCD | ||||
|  | ||||
|   #define LCD_MESSAGEPGM(x) lcd_setstatuspgm(PSTR(x)) | ||||
|   #define LCD_ALERTMESSAGEPGM(x) lcd_setalertstatuspgm(PSTR(x)) | ||||
| @@ -71,6 +73,7 @@ char *itostr3left(const int &xx); | ||||
| char *itostr4(const int &xx); | ||||
|  | ||||
| char *ftostr3(const float &x); | ||||
| char *ftostr31ns(const float &x); // float to string without sign character | ||||
| char *ftostr31(const float &x); | ||||
| char *ftostr32(const float &x); | ||||
| char *ftostr5(const float &x); | ||||
|   | ||||
| @@ -376,6 +376,26 @@ static void lcd_implementation_drawmenu_setting_edit_generic_P(uint8_t row, cons | ||||
| #define lcd_implementation_drawmenu_setting_edit_long5(row, pstr, pstr2, data, minValue, maxValue) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, ' ', ftostr5(*(data))) | ||||
| #define lcd_implementation_drawmenu_setting_edit_bool_selected(row, pstr, pstr2, data) lcd_implementation_drawmenu_setting_edit_generic_P(row, pstr, '>', (*(data))?PSTR(MSG_ON):PSTR(MSG_OFF)) | ||||
| #define lcd_implementation_drawmenu_setting_edit_bool(row, pstr, pstr2, data) lcd_implementation_drawmenu_setting_edit_generic_P(row, pstr, ' ', (*(data))?PSTR(MSG_ON):PSTR(MSG_OFF)) | ||||
|  | ||||
| //Add version for callback functions | ||||
| #define lcd_implementation_drawmenu_setting_edit_callback_int3_selected(row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, '>', itostr3(*(data))) | ||||
| #define lcd_implementation_drawmenu_setting_edit_callback_int3(row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, ' ', itostr3(*(data))) | ||||
| #define lcd_implementation_drawmenu_setting_edit_callback_float3_selected(row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, '>', ftostr3(*(data))) | ||||
| #define lcd_implementation_drawmenu_setting_edit_callback_float3(row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, ' ', ftostr3(*(data))) | ||||
| #define lcd_implementation_drawmenu_setting_edit_callback_float32_selected(row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, '>', ftostr32(*(data))) | ||||
| #define lcd_implementation_drawmenu_setting_edit_callback_float32(row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, ' ', ftostr32(*(data))) | ||||
| #define lcd_implementation_drawmenu_setting_edit_callback_float5_selected(row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, '>', ftostr5(*(data))) | ||||
| #define lcd_implementation_drawmenu_setting_edit_callback_float5(row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, ' ', ftostr5(*(data))) | ||||
| #define lcd_implementation_drawmenu_setting_edit_callback_float52_selected(row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, '>', ftostr52(*(data))) | ||||
| #define lcd_implementation_drawmenu_setting_edit_callback_float52(row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, ' ', ftostr52(*(data))) | ||||
| #define lcd_implementation_drawmenu_setting_edit_callback_float51_selected(row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, '>', ftostr51(*(data))) | ||||
| #define lcd_implementation_drawmenu_setting_edit_callback_float51(row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, ' ', ftostr51(*(data))) | ||||
| #define lcd_implementation_drawmenu_setting_edit_callback_long5_selected(row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, '>', ftostr5(*(data))) | ||||
| #define lcd_implementation_drawmenu_setting_edit_callback_long5(row, pstr, pstr2, data, minValue, maxValue, callback) lcd_implementation_drawmenu_setting_edit_generic(row, pstr, ' ', ftostr5(*(data))) | ||||
| #define lcd_implementation_drawmenu_setting_edit_callback_bool_selected(row, pstr, pstr2, data, callback) lcd_implementation_drawmenu_setting_edit_generic_P(row, pstr, '>', (*(data))?PSTR(MSG_ON):PSTR(MSG_OFF)) | ||||
| #define lcd_implementation_drawmenu_setting_edit_callback_bool(row, pstr, pstr2, data, callback) lcd_implementation_drawmenu_setting_edit_generic_P(row, pstr, ' ', (*(data))?PSTR(MSG_ON):PSTR(MSG_OFF)) | ||||
|  | ||||
|  | ||||
| void lcd_implementation_drawedit(const char* pstr, char* value) | ||||
| { | ||||
|     lcd.setCursor(1, 1); | ||||
|   | ||||
		Reference in New Issue
	
	Block a user