瀏覽代碼

Merge remote-tracking branch 'upstream/Marlin_v1' into Marlin_v1

Christian Thalhammer 13 年之前
父節點
當前提交
cb02914687

+ 2
- 0
Marlin/.gitignore 查看文件

1
+*.o
2
+applet/

+ 47
- 28
Marlin/Configuration.h 查看文件

8
 //User specified version info of THIS file to display in [Pronterface, etc] terminal window during startup.
8
 //User specified version info of THIS file to display in [Pronterface, etc] terminal window during startup.
9
 //Implementation of an idea by Prof Braino to inform user that any changes made
9
 //Implementation of an idea by Prof Braino to inform user that any changes made
10
 //to THIS file by the user have been successfully uploaded into firmware.
10
 //to THIS file by the user have been successfully uploaded into firmware.
11
-#define STRING_VERSION_CONFIG_H "2012-02-08j" //Personal revision number for changes to THIS file.
12
-#define STRING_CONFIG_H_AUTHOR "scuba82" //Who made the changes.
11
+#define STRING_VERSION_CONFIG_H "2012-02-25" //Personal revision number for changes to THIS file.
12
+#define STRING_CONFIG_H_AUTHOR "erik" //Who made the changes.
13
 
13
 
14
 // This determines the communication speed of the printer
14
 // This determines the communication speed of the printer
15
-//#define BAUDRATE 250000
16
-#define BAUDRATE 115200
15
+#define BAUDRATE 250000
16
+//#define BAUDRATE 115200
17
 
17
 
18
 //// The following define selects which electronics board you have. Please choose the one that matches your setup
18
 //// The following define selects which electronics board you have. Please choose the one that matches your setup
19
-// MEGA/RAMPS up to 1.2 = 3,
20
-// RAMPS 1.3 = 33
21
-// Gen6 = 5,
19
+// Gen7 custom (Alfons3 Version) = 10 "https://github.com/Alfons3/Generation_7_Electronics"
20
+// Gen7 v1.1, v1.2 = 11
21
+// Gen7 v1.3 = 12
22
+// Gen7 v1.4 = 13
23
+// MEGA/RAMPS up to 1.2 = 3
24
+// RAMPS 1.3 = 33 (Power outputs: Extruder, Bed, Fan)
25
+// RAMPS 1.3 = 34 (Power outputs: Extruder0, Extruder1, Bed)
26
+// Gen6 = 5
27
+// Gen6 deluxe = 51
22
 // Sanguinololu 1.2 and above = 62
28
 // Sanguinololu 1.2 and above = 62
23
-// Ultimaker = 7,
24
-// Gen7 custom (Alfons3 Version) = 77, "https://github.com/Alfons3/Generation_7_Electronics"
25
-// Gen7 v1.1, v1.2 = 78
26
-// Gen7 v1.3 = 79
27
-// Teensylu = 8,
29
+// Ultimaker = 7
30
+// Teensylu = 8
28
 // Gen3+ =9
31
 // Gen3+ =9
29
-#define MOTHERBOARD 77
32
+#define MOTHERBOARD 7
30
 
33
 
31
 //===========================================================================
34
 //===========================================================================
32
 //=============================Thermal Settings  ============================
35
 //=============================Thermal Settings  ============================
44
 // 6 is EPCOS 100k
47
 // 6 is EPCOS 100k
45
 // 7 is 100k Honeywell thermistor 135-104LAG-J01
48
 // 7 is 100k Honeywell thermistor 135-104LAG-J01
46
 
49
 
47
-#define TEMP_SENSOR_0 6
50
+#define TEMP_SENSOR_0 -1
48
 #define TEMP_SENSOR_1 0
51
 #define TEMP_SENSOR_1 0
49
 #define TEMP_SENSOR_2 0
52
 #define TEMP_SENSOR_2 0
50
-#define TEMP_SENSOR_BED 1
53
+#define TEMP_SENSOR_BED 0
51
 
54
 
52
 // Actual temperature must be close to target for this long before M109 returns success
55
 // Actual temperature must be close to target for this long before M109 returns success
53
-#define TEMP_RESIDENCY_TIME 30  // (seconds)
54
-#define TEMP_HYSTERESIS 3       // (C) range of +/- temperatures considered "close" to the target one
56
+#define TEMP_RESIDENCY_TIME 10	// (seconds)
57
+#define TEMP_HYSTERESIS 3       // (degC) range of +/- temperatures considered "close" to the target one
55
 
58
 
56
 // The minimal temperature defines the temperature below which the heater will not be enabled It is used
59
 // The minimal temperature defines the temperature below which the heater will not be enabled It is used
57
 // to check that the wiring to the thermistor is not broken. 
60
 // to check that the wiring to the thermistor is not broken. 
69
 #define HEATER_2_MAXTEMP 275
72
 #define HEATER_2_MAXTEMP 275
70
 #define BED_MAXTEMP 150
73
 #define BED_MAXTEMP 150
71
 
74
 
75
+
72
 // PID settings:
76
 // PID settings:
73
 // Comment the following line to disable PID and enable bang-bang.
77
 // Comment the following line to disable PID and enable bang-bang.
74
 #define PIDTEMP
78
 #define PIDTEMP
111
 #define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors
115
 #define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors
112
 
116
 
113
 // The pullups are needed if you directly connect a mechanical endswitch between the signal and ground pins.
117
 // The pullups are needed if you directly connect a mechanical endswitch between the signal and ground pins.
114
-const bool X_ENDSTOPS_INVERTING = false; // set to true to invert the logic of the endstops. 
115
-const bool Y_ENDSTOPS_INVERTING = false; // set to true to invert the logic of the endstops. 
116
-const bool Z_ENDSTOPS_INVERTING = false; // set to true to invert the logic of the endstops. 
118
+const bool X_ENDSTOPS_INVERTING = true; // set to true to invert the logic of the endstops. 
119
+const bool Y_ENDSTOPS_INVERTING = true; // set to true to invert the logic of the endstops. 
120
+const bool Z_ENDSTOPS_INVERTING = true; // set to true to invert the logic of the endstops. 
117
 
121
 
118
 // For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
122
 // For Inverting Stepper Enable Pins (Active Low) use 0, Non Inverting (Active High) use 1
119
 #define X_ENABLE_ON 0
123
 #define X_ENABLE_ON 0
127
 #define DISABLE_Z false
131
 #define DISABLE_Z false
128
 #define DISABLE_E false // For all extruders
132
 #define DISABLE_E false // For all extruders
129
 
133
 
130
-#define INVERT_X_DIR false    // for Mendel set to false, for Orca set to true
134
+#define INVERT_X_DIR true    // for Mendel set to false, for Orca set to true
131
 #define INVERT_Y_DIR false    // for Mendel set to true, for Orca set to false
135
 #define INVERT_Y_DIR false    // for Mendel set to true, for Orca set to false
132
-#define INVERT_Z_DIR false     // for Mendel set to false, for Orca set to true
136
+#define INVERT_Z_DIR true     // for Mendel set to false, for Orca set to true
133
 #define INVERT_E0_DIR false   // for direct drive extruder v9 set to true, for geared extruder set to false
137
 #define INVERT_E0_DIR false   // for direct drive extruder v9 set to true, for geared extruder set to false
134
 #define INVERT_E1_DIR false    // for direct drive extruder v9 set to true, for geared extruder set to false
138
 #define INVERT_E1_DIR false    // for direct drive extruder v9 set to true, for geared extruder set to false
135
 #define INVERT_E2_DIR false   // for direct drive extruder v9 set to true, for geared extruder set to false
139
 #define INVERT_E2_DIR false   // for direct drive extruder v9 set to true, for geared extruder set to false
140
 #define Y_HOME_DIR -1
144
 #define Y_HOME_DIR -1
141
 #define Z_HOME_DIR -1
145
 #define Z_HOME_DIR -1
142
 
146
 
143
-#define min_software_endstops false //If true, axis won't move to coordinates less than zero.
147
+#define min_software_endstops true //If true, axis won't move to coordinates less than HOME_POS.
144
 #define max_software_endstops true  //If true, axis won't move to coordinates greater than the defined lengths below.
148
 #define max_software_endstops true  //If true, axis won't move to coordinates greater than the defined lengths below.
145
 #define X_MAX_LENGTH 205
149
 #define X_MAX_LENGTH 205
146
 #define Y_MAX_LENGTH 205
150
 #define Y_MAX_LENGTH 205
147
 #define Z_MAX_LENGTH 200
151
 #define Z_MAX_LENGTH 200
148
 
152
 
153
+// The position of the homing switches. Use MAX_LENGTH * -0.5 if the center should be 0, 0, 0
154
+#define X_HOME_POS 0
155
+#define Y_HOME_POS 0
156
+#define Z_HOME_POS 0
157
+
149
 //// MOVEMENT SETTINGS
158
 //// MOVEMENT SETTINGS
150
 #define NUM_AXIS 4 // The axis order in all axis related arrays is X, Y, Z, E
159
 #define NUM_AXIS 4 // The axis order in all axis related arrays is X, Y, Z, E
151
 #define HOMING_FEEDRATE {50*60, 50*60, 4*60, 0}  // set the homing speeds (mm/min)
160
 #define HOMING_FEEDRATE {50*60, 50*60, 4*60, 0}  // set the homing speeds (mm/min)
152
 
161
 
153
 // default settings 
162
 // default settings 
154
 
163
 
155
-#define DEFAULT_AXIS_STEPS_PER_UNIT   {80,80,2560,760*1.1}                    // default steps per unit for ultimaker 
164
+#define DEFAULT_AXIS_STEPS_PER_UNIT   {78.7402,78.7402,200*8/3,760*1.1}                    // default steps per unit for ultimaker 
156
 #define DEFAULT_MAX_FEEDRATE          {500, 500, 5, 45}    // (mm/sec)    
165
 #define DEFAULT_MAX_FEEDRATE          {500, 500, 5, 45}    // (mm/sec)    
157
 #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.
166
 #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.
158
 
167
 
173
 // M501 - reads parameters from EEPROM (if you need reset them after you changed them temporarily).  
182
 // M501 - reads parameters from EEPROM (if you need reset them after you changed them temporarily).  
174
 // M502 - reverts to the default "factory settings".  You still need to store them in EEPROM afterwards if you want to.
183
 // M502 - reverts to the default "factory settings".  You still need to store them in EEPROM afterwards if you want to.
175
 //define this to enable eeprom support
184
 //define this to enable eeprom support
176
-#define EEPROM_SETTINGS
185
+//#define EEPROM_SETTINGS
177
 //to disable EEPROM Serial responses and decrease program space by ~1700 byte: comment this out:
186
 //to disable EEPROM Serial responses and decrease program space by ~1700 byte: comment this out:
178
 // please keep turned on if you can.
187
 // please keep turned on if you can.
179
-#define EEPROM_CHITCHAT
188
+//#define EEPROM_CHITCHAT
180
 
189
 
181
 //LCD and SD support
190
 //LCD and SD support
182
 //#define ULTRA_LCD  //general lcd support, also 16x2
191
 //#define ULTRA_LCD  //general lcd support, also 16x2
183
-#define SDSUPPORT // Enable SD Card Support in Hardware Console
192
+//#define SDSUPPORT // Enable SD Card Support in Hardware Console
184
 
193
 
185
-#define ULTIPANEL
194
+//#define ULTIPANEL
186
 #ifdef ULTIPANEL
195
 #ifdef ULTIPANEL
187
   #define NEWPANEL  //enable this if you have a click-encoder panel
196
   #define NEWPANEL  //enable this if you have a click-encoder panel
188
   #define SDSUPPORT
197
   #define SDSUPPORT
189
   #define ULTRA_LCD
198
   #define ULTRA_LCD
190
   #define LCD_WIDTH 20
199
   #define LCD_WIDTH 20
191
   #define LCD_HEIGHT 4
200
   #define LCD_HEIGHT 4
201
+
202
+// Preheat Constants
203
+  #define PLA_PREHEAT_HOTEND_TEMP 180 
204
+  #define PLA_PREHEAT_HPB_TEMP 70
205
+  #define PLA_PREHEAT_FAN_SPEED 255		// Insert Value between 0 and 255
206
+
207
+  #define ABS_PREHEAT_HOTEND_TEMP 240
208
+  #define ABS_PREHEAT_HPB_TEMP 100
209
+  #define ABS_PREHEAT_FAN_SPEED 255		// Insert Value between 0 and 255
210
+
192
 #else //no panel but just lcd 
211
 #else //no panel but just lcd 
193
   #ifdef ULTRA_LCD
212
   #ifdef ULTRA_LCD
194
     #define LCD_WIDTH 16
213
     #define LCD_WIDTH 16

+ 12
- 4
Marlin/Configuration_adv.h 查看文件

25
 // if CooldownNoWait is defined M109 will not wait for the cooldown to finish
25
 // if CooldownNoWait is defined M109 will not wait for the cooldown to finish
26
 #define CooldownNoWait true
26
 #define CooldownNoWait true
27
 
27
 
28
-//Do not wait for M109 to finish when printing from SD card
29
-//#define STOP_HEATING_WAIT_WHEN_SD_PRINTING
30
-
31
 #ifdef PIDTEMP
28
 #ifdef PIDTEMP
32
   // this adds an experimental additional term to the heatingpower, proportional to the extrusion speed.
29
   // this adds an experimental additional term to the heatingpower, proportional to the extrusion speed.
33
   // if Kc is choosen well, the additional required power due to increased melting should be compensated.
30
   // if Kc is choosen well, the additional required power due to increased melting should be compensated.
59
 #define EXTRUDER_RUNOUT_SPEED 1500.  //extrusion speed
56
 #define EXTRUDER_RUNOUT_SPEED 1500.  //extrusion speed
60
 #define EXTRUDER_RUNOUT_EXTRUDE 100
57
 #define EXTRUDER_RUNOUT_EXTRUDE 100
61
 
58
 
59
+//These defines help to calibrate the AD595 sensor in case you get wrong temperature measurements.
60
+//The measured temperature is defined as "actualTemp = (measuredTemp * TEMP_SENSOR_AD595_GAIN) + TEMP_SENSOR_AD595_OFFSET"
61
+#define TEMP_SENSOR_AD595_OFFSET 0.0
62
+#define TEMP_SENSOR_AD595_GAIN   1.0
63
+
62
 //===========================================================================
64
 //===========================================================================
63
 //=============================Mechanical Settings===========================
65
 //=============================Mechanical Settings===========================
64
 //===========================================================================
66
 //===========================================================================
74
 #define X_HOME_RETRACT_MM 5 
76
 #define X_HOME_RETRACT_MM 5 
75
 #define Y_HOME_RETRACT_MM 5 
77
 #define Y_HOME_RETRACT_MM 5 
76
 #define Z_HOME_RETRACT_MM 1 
78
 #define Z_HOME_RETRACT_MM 1 
77
-#define QUICK_HOME  //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially.
79
+//#define QUICK_HOME  //if this is defined, if both x and y are to be homed, a diagonal move will be performed initially.
78
 
80
 
79
 #define AXIS_RELATIVE_MODES {false, false, false, false}
81
 #define AXIS_RELATIVE_MODES {false, false, false, false}
80
 
82
 
148
 
150
 
149
 const int dropsegments=5; //everything with less than this number of steps will be ignored as move and joined with the next movement
151
 const int dropsegments=5; //everything with less than this number of steps will be ignored as move and joined with the next movement
150
 
152
 
153
+// If you are using a RAMPS board or cheap E-bay purchased boards that do not detect when an SD card is inserted
154
+// You can get round this by connecting a push button or single throw switch to the pin defined as SDCARDCARDDETECT 
155
+// in the pins.h file.  When using a push button pulling the pin to ground this will need inverted.  This setting should
156
+// be commented out otherwise
157
+#define SDCARDDETECTINVERTED 
158
+
151
 //===========================================================================
159
 //===========================================================================
152
 //=============================Buffers           ============================
160
 //=============================Buffers           ============================
153
 //===========================================================================
161
 //===========================================================================

+ 12
- 12
Marlin/Gen7/cores/arduino/pins_arduino.c 查看文件

67
 const uint8_t PROGMEM port_to_mode_PGM[] =
67
 const uint8_t PROGMEM port_to_mode_PGM[] =
68
 {
68
 {
69
 	NOT_A_PORT,
69
 	NOT_A_PORT,
70
-    &DDRA,
71
-	&DDRB,
72
-	&DDRC,
73
-	&DDRD,
70
+        (uint8_t) &DDRA,
71
+	(uint8_t) &DDRB,
72
+	(uint8_t) &DDRC,
73
+	(uint8_t) &DDRD,
74
 };
74
 };
75
 
75
 
76
 const uint8_t PROGMEM port_to_output_PGM[] =
76
 const uint8_t PROGMEM port_to_output_PGM[] =
77
 {
77
 {
78
 	NOT_A_PORT,
78
 	NOT_A_PORT,
79
-	&PORTA,
80
-	&PORTB,
81
-	&PORTC,
82
-	&PORTD,
79
+	(uint8_t) &PORTA,
80
+	(uint8_t) &PORTB,
81
+	(uint8_t) &PORTC,
82
+	(uint8_t) &PORTD,
83
 };
83
 };
84
 
84
 
85
 const uint8_t PROGMEM port_to_input_PGM[] =
85
 const uint8_t PROGMEM port_to_input_PGM[] =
86
 {
86
 {
87
 	NOT_A_PORT,
87
 	NOT_A_PORT,
88
-	&PINA,
89
-	&PINB,
90
-	&PINC,
91
-	&PIND,
88
+	(uint8_t) &PINA,
89
+	(uint8_t) &PINB,
90
+	(uint8_t) &PINC,
91
+	(uint8_t) &PIND,
92
 };
92
 };
93
 
93
 
94
 const uint8_t PROGMEM digital_pin_to_port_PGM[] =
94
 const uint8_t PROGMEM digital_pin_to_port_PGM[] =

+ 8
- 6
Marlin/Makefile 查看文件

61
 	$(ARDUINO)/wiring_pulse.c \
61
 	$(ARDUINO)/wiring_pulse.c \
62
 	$(ARDUINO)/wiring_shift.c $(ARDUINO)/WInterrupts.c
62
 	$(ARDUINO)/wiring_shift.c $(ARDUINO)/WInterrupts.c
63
 CXXSRC = $(ARDUINO)/WMath.cpp $(ARDUINO)/WString.cpp\
63
 CXXSRC = $(ARDUINO)/WMath.cpp $(ARDUINO)/WString.cpp\
64
-	$(ARDUINO)/Print.cpp Marlin.cpp MarlinSerial.cpp Sd2Card.cpp SdBaseFile.cpp SdFatUtil.cpp SdFile.cpp SdVolume.cpp motion_control.cpp planner.cpp stepper.cpp temperature.cpp cardreader.cpp
64
+	$(ARDUINO)/Print.cpp applet/Marlin.cpp MarlinSerial.cpp Sd2Card.cpp SdBaseFile.cpp SdFatUtil.cpp SdFile.cpp SdVolume.cpp motion_control.cpp planner.cpp stepper.cpp temperature.cpp cardreader.cpp
65
 FORMAT = ihex
65
 FORMAT = ihex
66
 
66
 
67
 
67
 
138
 build: elf hex 
138
 build: elf hex 
139
 
139
 
140
 applet/$(TARGET).cpp: $(TARGET).pde $(MAKEFILE)
140
 applet/$(TARGET).cpp: $(TARGET).pde $(MAKEFILE)
141
+
142
+applet/%.cpp: %.pde
141
 # Here is the "preprocessing".
143
 # Here is the "preprocessing".
142
 # It creates a .cpp file based with the same name as the .pde file.
144
 # It creates a .cpp file based with the same name as the .pde file.
143
 # On top of the new .cpp file comes the WProgram.h header.
145
 # On top of the new .cpp file comes the WProgram.h header.
145
 # Then the .cpp file will be compiled. Errors during compile will
147
 # Then the .cpp file will be compiled. Errors during compile will
146
 # refer to this new, automatically generated, file. 
148
 # refer to this new, automatically generated, file. 
147
 # Not the original .pde file you actually edit...
149
 # Not the original .pde file you actually edit...
148
-	@echo "  WR    applet/$(TARGET).cpp"
149
-	@test -d applet || mkdir applet
150
-	@echo '#include "WProgram.h"' > applet/$(TARGET).cpp
151
-	@cat $(TARGET).pde >> applet/$(TARGET).cpp
152
-	@cat $(ARDUINO)/main.cpp >> applet/$(TARGET).cpp
150
+	@echo "  WR    $@"
151
+	@test -d $(dir $@) || mkdir $(dir $@)
152
+	@echo '#include "WProgram.h"' > $@
153
+	@cat $< >> $@
154
+	@cat $(ARDUINO)/main.cpp >> $@
153
 
155
 
154
 elf: applet/$(TARGET).elf
156
 elf: applet/$(TARGET).elf
155
 hex: applet/$(TARGET).hex
157
 hex: applet/$(TARGET).hex

+ 0
- 1
Marlin/Marlin.h 查看文件

175
 extern bool axis_relative_modes[];
175
 extern bool axis_relative_modes[];
176
 extern float current_position[NUM_AXIS] ;
176
 extern float current_position[NUM_AXIS] ;
177
 extern float add_homeing[3];
177
 extern float add_homeing[3];
178
-extern bool stop_heating_wait;
179
 
178
 
180
 // Handling multiple extruders pins
179
 // Handling multiple extruders pins
181
 extern uint8_t active_extruder;
180
 extern uint8_t active_extruder;

+ 59
- 30
Marlin/Marlin.pde 查看文件

35
 #include "cardreader.h"
35
 #include "cardreader.h"
36
 #include "watchdog.h"
36
 #include "watchdog.h"
37
 #include "EEPROMwrite.h"
37
 #include "EEPROMwrite.h"
38
+#include "language.h"
38
 
39
 
39
-#define VERSION_STRING  "1.0.0 RC1"
40
+#define VERSION_STRING  "1.0.0 RC2"
40
 
41
 
41
 // look here for descriptions of gcodes: http://linuxcnc.org/handbook/gcode/g-code.html
42
 // look here for descriptions of gcodes: http://linuxcnc.org/handbook/gcode/g-code.html
42
 // http://objects.reprap.org/wiki/Mendel_User_Manual:_RepRapGCodes
43
 // http://objects.reprap.org/wiki/Mendel_User_Manual:_RepRapGCodes
97
 // M204 - Set default acceleration: S normal moves T filament only moves (M204 S3000 T7000) im mm/sec^2  also sets minimum segment time in ms (B20000) to prevent buffer underruns and M20 minimum feedrate
98
 // M204 - Set default acceleration: S normal moves T filament only moves (M204 S3000 T7000) im mm/sec^2  also sets minimum segment time in ms (B20000) to prevent buffer underruns and M20 minimum feedrate
98
 // M205 -  advanced settings:  minimum travel speed S=while printing T=travel only,  B=minimum segment time X= maximum xy jerk, Z=maximum Z jerk
99
 // M205 -  advanced settings:  minimum travel speed S=while printing T=travel only,  B=minimum segment time X= maximum xy jerk, Z=maximum Z jerk
99
 // M206 - set additional homeing offset
100
 // M206 - set additional homeing offset
100
-// M220 - set speed factor override percentage S:factor in percent
101
+// M220 S<factor in percent>- set speed factor override percentage
102
+// M221 S<factor in percent>- set extrude factor override percentage
101
 // M240 - Trigger a camera to take a photograph
103
 // M240 - Trigger a camera to take a photograph
102
 // M301 - Set PID parameters P I and D
104
 // M301 - Set PID parameters P I and D
103
 // M302 - Allow cold extrudes
105
 // M302 - Allow cold extrudes
125
 volatile int feedmultiply=100; //100->1 200->2
127
 volatile int feedmultiply=100; //100->1 200->2
126
 int saved_feedmultiply;
128
 int saved_feedmultiply;
127
 volatile bool feedmultiplychanged=false;
129
 volatile bool feedmultiplychanged=false;
130
+volatile int extrudemultiply=100; //100->1 200->2
128
 float current_position[NUM_AXIS] = { 0.0, 0.0, 0.0, 0.0 };
131
 float current_position[NUM_AXIS] = { 0.0, 0.0, 0.0, 0.0 };
129
 float add_homeing[3]={0,0,0};
132
 float add_homeing[3]={0,0,0};
130
 uint8_t active_extruder = 0;
133
 uint8_t active_extruder = 0;
131
-bool stop_heating_wait=false;
132
 
134
 
133
 //===========================================================================
135
 //===========================================================================
134
 //=============================private variables=============================
136
 //=============================private variables=============================
249
   MYSERIAL.begin(BAUDRATE);
251
   MYSERIAL.begin(BAUDRATE);
250
   SERIAL_PROTOCOLLNPGM("start");
252
   SERIAL_PROTOCOLLNPGM("start");
251
   SERIAL_ECHO_START;
253
   SERIAL_ECHO_START;
254
+
255
+  // Check startup - does nothing if bootloader sets MCUSR to 0
256
+  byte mcu = MCUSR;
257
+  if(mcu & 1) SERIAL_ECHOLNPGM("PowerUp");
258
+  if(mcu & 2) SERIAL_ECHOLNPGM("External Reset");
259
+  if(mcu & 4) SERIAL_ECHOLNPGM("Brown out Reset");
260
+  if(mcu & 8) SERIAL_ECHOLNPGM("Watchdog Reset");
261
+  if(mcu & 32) SERIAL_ECHOLNPGM("Software Reset");
262
+  MCUSR=0;
263
+
252
   SERIAL_ECHOPGM("Marlin: ");
264
   SERIAL_ECHOPGM("Marlin: ");
253
   SERIAL_ECHOLNPGM(VERSION_STRING);
265
   SERIAL_ECHOLNPGM(VERSION_STRING);
254
   #ifdef STRING_VERSION_CONFIG_H
266
   #ifdef STRING_VERSION_CONFIG_H
331
     serial_char = MYSERIAL.read();
343
     serial_char = MYSERIAL.read();
332
     if(serial_char == '\n' || serial_char == '\r' || serial_char == ':' || serial_count >= (MAX_CMD_SIZE - 1) ) 
344
     if(serial_char == '\n' || serial_char == '\r' || serial_char == ':' || serial_count >= (MAX_CMD_SIZE - 1) ) 
333
     {
345
     {
334
-      if(!serial_count) return; //if empty line
346
+      if(!serial_count) { //if empty line
347
+        comment_mode = false; //for new command
348
+        return;
349
+      }
335
       cmdbuffer[bufindw][serial_count] = 0; //terminate string
350
       cmdbuffer[bufindw][serial_count] = 0; //terminate string
336
       if(!comment_mode){
351
       if(!comment_mode){
352
+        comment_mode = false; //for new command
337
         fromsd[bufindw] = false;
353
         fromsd[bufindw] = false;
338
         if(strstr(cmdbuffer[bufindw], "N") != NULL)
354
         if(strstr(cmdbuffer[bufindw], "N") != NULL)
339
         {
355
         {
410
         }
426
         }
411
         bufindw = (bufindw + 1)%BUFSIZE;
427
         bufindw = (bufindw + 1)%BUFSIZE;
412
         buflen += 1;
428
         buflen += 1;
413
-
414
       }
429
       }
415
-      comment_mode = false; //for new command
416
       serial_count = 0; //clear buffer
430
       serial_count = 0; //clear buffer
417
     }
431
     }
418
     else
432
     else
446
         card.checkautostart(true);
460
         card.checkautostart(true);
447
         
461
         
448
       }
462
       }
449
-      if(serial_char=='\n')
450
-         comment_mode = false; //for new command
451
       if(!serial_count)
463
       if(!serial_count)
452
       {
464
       {
465
+        comment_mode = false; //for new command
453
         return; //if empty line
466
         return; //if empty line
454
       }
467
       }
455
       cmdbuffer[bufindw][serial_count] = 0; //terminate string
468
       cmdbuffer[bufindw][serial_count] = 0; //terminate string
458
         buflen += 1;
471
         buflen += 1;
459
         bufindw = (bufindw + 1)%BUFSIZE;
472
         bufindw = (bufindw + 1)%BUFSIZE;
460
       }     
473
       }     
474
+      comment_mode = false; //for new command
461
       serial_count = 0; //clear buffer
475
       serial_count = 0; //clear buffer
462
     }
476
     }
463
     else
477
     else
476
 { 
490
 { 
477
   return (strtod(&cmdbuffer[bufindr][strchr_pointer - cmdbuffer[bufindr] + 1], NULL)); 
491
   return (strtod(&cmdbuffer[bufindr][strchr_pointer - cmdbuffer[bufindr] + 1], NULL)); 
478
 }
492
 }
493
+
479
 long code_value_long() 
494
 long code_value_long() 
480
 { 
495
 { 
481
   return (strtol(&cmdbuffer[bufindr][strchr_pointer - cmdbuffer[bufindr] + 1], NULL, 10)); 
496
   return (strtol(&cmdbuffer[bufindr][strchr_pointer - cmdbuffer[bufindr] + 1], NULL, 10)); 
482
 }
497
 }
498
+
483
 bool code_seen(char code_string[]) //Return True if the string was found
499
 bool code_seen(char code_string[]) //Return True if the string was found
484
 { 
500
 { 
485
   return (strstr(cmdbuffer[bufindr], code_string) != NULL); 
501
   return (strstr(cmdbuffer[bufindr], code_string) != NULL); 
490
   strchr_pointer = strchr(cmdbuffer[bufindr], code);
506
   strchr_pointer = strchr(cmdbuffer[bufindr], code);
491
   return (strchr_pointer != NULL);  //Return True if a character was found
507
   return (strchr_pointer != NULL);  //Return True if a character was found
492
 }
508
 }
509
+
493
 #define HOMEAXIS(LETTER) \
510
 #define HOMEAXIS(LETTER) \
494
   if ((LETTER##_MIN_PIN > -1 && LETTER##_HOME_DIR==-1) || (LETTER##_MAX_PIN > -1 && LETTER##_HOME_DIR==1))\
511
   if ((LETTER##_MIN_PIN > -1 && LETTER##_HOME_DIR==-1) || (LETTER##_MAX_PIN > -1 && LETTER##_HOME_DIR==1))\
495
     { \
512
     { \
498
     destination[LETTER##_AXIS] = 1.5 * LETTER##_MAX_LENGTH * LETTER##_HOME_DIR; \
515
     destination[LETTER##_AXIS] = 1.5 * LETTER##_MAX_LENGTH * LETTER##_HOME_DIR; \
499
     feedrate = homing_feedrate[LETTER##_AXIS]; \
516
     feedrate = homing_feedrate[LETTER##_AXIS]; \
500
     plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder); \
517
     plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder); \
518
+    st_synchronize();\
501
     \
519
     \
502
     current_position[LETTER##_AXIS] = 0;\
520
     current_position[LETTER##_AXIS] = 0;\
503
     plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);\
521
     plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);\
504
     destination[LETTER##_AXIS] = -LETTER##_HOME_RETRACT_MM * LETTER##_HOME_DIR;\
522
     destination[LETTER##_AXIS] = -LETTER##_HOME_RETRACT_MM * LETTER##_HOME_DIR;\
505
     plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder); \
523
     plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder); \
524
+    st_synchronize();\
506
     \
525
     \
507
     destination[LETTER##_AXIS] = 2*LETTER##_HOME_RETRACT_MM * LETTER##_HOME_DIR;\
526
     destination[LETTER##_AXIS] = 2*LETTER##_HOME_RETRACT_MM * LETTER##_HOME_DIR;\
508
     feedrate = homing_feedrate[LETTER##_AXIS]/2 ;  \
527
     feedrate = homing_feedrate[LETTER##_AXIS]/2 ;  \
509
     plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder); \
528
     plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder); \
529
+    st_synchronize();\
510
     \
530
     \
511
-    current_position[LETTER##_AXIS] = (LETTER##_HOME_DIR == -1) ? 0 : LETTER##_MAX_LENGTH;\
512
-    plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);\
531
+    current_position[LETTER##_AXIS] = (LETTER##_HOME_DIR == -1) ? LETTER##_HOME_POS : LETTER##_MAX_LENGTH;\
513
     destination[LETTER##_AXIS] = current_position[LETTER##_AXIS];\
532
     destination[LETTER##_AXIS] = current_position[LETTER##_AXIS];\
514
     feedrate = 0.0;\
533
     feedrate = 0.0;\
515
-    st_synchronize();\
516
-    plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);\
517
     endstops_hit_on_purpose();\
534
     endstops_hit_on_purpose();\
518
   }
535
   }
519
 
536
 
567
       feedrate = 0.0;
584
       feedrate = 0.0;
568
       home_all_axis = !((code_seen(axis_codes[0])) || (code_seen(axis_codes[1])) || (code_seen(axis_codes[2])));
585
       home_all_axis = !((code_seen(axis_codes[0])) || (code_seen(axis_codes[1])) || (code_seen(axis_codes[2])));
569
       #ifdef QUICK_HOME
586
       #ifdef QUICK_HOME
570
-      if( code_seen(axis_codes[0]) && code_seen(axis_codes[1]) )  //first diagonal move
587
+      if( code_seen(axis_codes[X_AXIS]) && code_seen(axis_codes[Y_AXIS]) )  //first diagonal move
571
       {
588
       {
572
         current_position[X_AXIS] = 0;current_position[Y_AXIS] = 0;  
589
         current_position[X_AXIS] = 0;current_position[Y_AXIS] = 0;  
573
 
590
 
576
         feedrate = homing_feedrate[X_AXIS]; 
593
         feedrate = homing_feedrate[X_AXIS]; 
577
         if(homing_feedrate[Y_AXIS]<feedrate)
594
         if(homing_feedrate[Y_AXIS]<feedrate)
578
           feedrate =homing_feedrate[Y_AXIS]; 
595
           feedrate =homing_feedrate[Y_AXIS]; 
579
-        prepare_move(); 
596
+        plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder);
597
+        st_synchronize();
580
     
598
     
581
-        current_position[X_AXIS] = (X_HOME_DIR == -1) ? 0 : X_MAX_LENGTH;
582
-        current_position[Y_AXIS] = (Y_HOME_DIR == -1) ? 0 : Y_MAX_LENGTH;
599
+        current_position[X_AXIS] = (X_HOME_DIR == -1) ? X_HOME_POS : X_MAX_LENGTH;
600
+        current_position[Y_AXIS] = (Y_HOME_DIR == -1) ? Y_HOME_POS : Y_MAX_LENGTH;
583
         plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
601
         plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
584
         destination[X_AXIS] = current_position[X_AXIS];
602
         destination[X_AXIS] = current_position[X_AXIS];
585
         destination[Y_AXIS] = current_position[Y_AXIS];
603
         destination[Y_AXIS] = current_position[Y_AXIS];
604
+        plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate/60, active_extruder);
586
         feedrate = 0.0;
605
         feedrate = 0.0;
587
         st_synchronize();
606
         st_synchronize();
588
-        plan_set_position(0, 0, current_position[Z_AXIS], current_position[E_AXIS]);
589
-        current_position[X_AXIS] = 0;current_position[Y_AXIS] = 0;
590
         endstops_hit_on_purpose();
607
         endstops_hit_on_purpose();
591
       }
608
       }
592
       #endif
609
       #endif
599
       if((home_all_axis) || (code_seen(axis_codes[Y_AXIS]))) {
616
       if((home_all_axis) || (code_seen(axis_codes[Y_AXIS]))) {
600
        HOMEAXIS(Y);
617
        HOMEAXIS(Y);
601
       }
618
       }
602
-
619
+      
603
       if((home_all_axis) || (code_seen(axis_codes[Z_AXIS]))) {
620
       if((home_all_axis) || (code_seen(axis_codes[Z_AXIS]))) {
604
         HOMEAXIS(Z);
621
         HOMEAXIS(Z);
605
       }
622
       }
606
       
623
       
607
       if(code_seen(axis_codes[X_AXIS])) 
624
       if(code_seen(axis_codes[X_AXIS])) 
608
       {
625
       {
609
-        current_position[0]=code_value()+add_homeing[0];
626
+        if(code_value_long() != 0) {
627
+          current_position[X_AXIS]=code_value()+add_homeing[0];
628
+        }
610
       }
629
       }
611
 
630
 
612
       if(code_seen(axis_codes[Y_AXIS])) {
631
       if(code_seen(axis_codes[Y_AXIS])) {
613
-        current_position[1]=code_value()+add_homeing[1];
632
+        if(code_value_long() != 0) {
633
+          current_position[Y_AXIS]=code_value()+add_homeing[1];
634
+        }
614
       }
635
       }
615
 
636
 
616
       if(code_seen(axis_codes[Z_AXIS])) {
637
       if(code_seen(axis_codes[Z_AXIS])) {
617
-        current_position[2]=code_value()+add_homeing[2];
638
+        if(code_value_long() != 0) {
639
+          current_position[Z_AXIS]=code_value()+add_homeing[2];
640
+        }
618
       }
641
       }
642
+      plan_set_position(current_position[X_AXIS], current_position[Y_AXIS], current_position[Z_AXIS], current_position[E_AXIS]);
643
+      
619
       #ifdef ENDSTOPS_ONLY_FOR_HOMING
644
       #ifdef ENDSTOPS_ONLY_FOR_HOMING
620
         enable_endstops(false);
645
         enable_endstops(false);
621
       #endif
646
       #endif
880
           }
905
           }
881
           manage_heater();
906
           manage_heater();
882
           LCD_STATUS;
907
           LCD_STATUS;
883
-        if(stop_heating_wait) break;
884
         #ifdef TEMP_RESIDENCY_TIME
908
         #ifdef TEMP_RESIDENCY_TIME
885
             /* start/restart the TEMP_RESIDENCY_TIME timer whenever we reach target temp for the first time
909
             /* start/restart the TEMP_RESIDENCY_TIME timer whenever we reach target temp for the first time
886
               or when current temp falls outside the hysteresis after target temp was reached */
910
               or when current temp falls outside the hysteresis after target temp was reached */
1112
       }
1136
       }
1113
     }
1137
     }
1114
     break;
1138
     break;
1115
-    
1116
-    
1139
+    case 221: // M221 S<factor in percent>- set extrude factor override percentage
1140
+    {
1141
+      if(code_seen('S')) 
1142
+      {
1143
+        extrudemultiply = code_value() ;
1144
+      }
1145
+    }
1146
+    break;
1117
 
1147
 
1118
     #ifdef PIDTEMP
1148
     #ifdef PIDTEMP
1119
     case 301: // M301
1149
     case 301: // M301
1265
 
1295
 
1266
 void prepare_move()
1296
 void prepare_move()
1267
 {
1297
 {
1268
-  
1269
   if (min_software_endstops) {
1298
   if (min_software_endstops) {
1270
-    if (destination[X_AXIS] < 0) destination[X_AXIS] = 0.0;
1271
-    if (destination[Y_AXIS] < 0) destination[Y_AXIS] = 0.0;
1272
-    if (destination[Z_AXIS] < 0) destination[Z_AXIS] = 0.0;
1299
+    if (destination[X_AXIS] < X_HOME_POS) destination[X_AXIS] = X_HOME_POS;
1300
+    if (destination[Y_AXIS] < Y_HOME_POS) destination[Y_AXIS] = Y_HOME_POS;
1301
+    if (destination[Z_AXIS] < Z_HOME_POS) destination[Z_AXIS] = Z_HOME_POS;
1273
   }
1302
   }
1274
 
1303
 
1275
   if (max_software_endstops) {
1304
   if (max_software_endstops) {
1277
     if (destination[Y_AXIS] > Y_MAX_LENGTH) destination[Y_AXIS] = Y_MAX_LENGTH;
1306
     if (destination[Y_AXIS] > Y_MAX_LENGTH) destination[Y_AXIS] = Y_MAX_LENGTH;
1278
     if (destination[Z_AXIS] > Z_MAX_LENGTH) destination[Z_AXIS] = Z_MAX_LENGTH;
1307
     if (destination[Z_AXIS] > Z_MAX_LENGTH) destination[Z_AXIS] = Z_MAX_LENGTH;
1279
   }
1308
   }
1280
-
1309
+  
1281
   plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate*feedmultiply/60/100.0, active_extruder);
1310
   plan_buffer_line(destination[X_AXIS], destination[Y_AXIS], destination[Z_AXIS], destination[E_AXIS], feedrate*feedmultiply/60/100.0, active_extruder);
1282
   for(int8_t i=0; i < NUM_AXIS; i++) {
1311
   for(int8_t i=0; i < NUM_AXIS; i++) {
1283
     current_position[i] = destination[i];
1312
     current_position[i] = destination[i];

+ 12
- 12
Marlin/Sanguino/cores/arduino/pins_arduino.c 查看文件

67
 const uint8_t PROGMEM port_to_mode_PGM[] =
67
 const uint8_t PROGMEM port_to_mode_PGM[] =
68
 {
68
 {
69
 	NOT_A_PORT,
69
 	NOT_A_PORT,
70
-    &DDRA,
71
-	&DDRB,
72
-	&DDRC,
73
-	&DDRD,
70
+	(uint8_t) (uint16_t) &DDRA,
71
+	(uint8_t) (uint16_t) &DDRB,
72
+	(uint8_t) (uint16_t) &DDRC,
73
+	(uint8_t) (uint16_t) &DDRD,
74
 };
74
 };
75
 
75
 
76
 const uint8_t PROGMEM port_to_output_PGM[] =
76
 const uint8_t PROGMEM port_to_output_PGM[] =
77
 {
77
 {
78
 	NOT_A_PORT,
78
 	NOT_A_PORT,
79
-	&PORTA,
80
-	&PORTB,
81
-	&PORTC,
82
-	&PORTD,
79
+	(uint8_t) (uint16_t) &PORTA,
80
+	(uint8_t) (uint16_t) &PORTB,
81
+	(uint8_t) (uint16_t) &PORTC,
82
+	(uint8_t) (uint16_t) &PORTD,
83
 };
83
 };
84
 
84
 
85
 const uint8_t PROGMEM port_to_input_PGM[] =
85
 const uint8_t PROGMEM port_to_input_PGM[] =
86
 {
86
 {
87
 	NOT_A_PORT,
87
 	NOT_A_PORT,
88
-	&PINA,
89
-	&PINB,
90
-	&PINC,
91
-	&PIND,
88
+	(uint8_t) (uint16_t) &PINA,
89
+	(uint8_t) (uint16_t) &PINB,
90
+	(uint8_t) (uint16_t) &PINC,
91
+	(uint8_t) (uint16_t) &PIND,
92
 };
92
 };
93
 
93
 
94
 const uint8_t PROGMEM digital_pin_to_port_PGM[] =
94
 const uint8_t PROGMEM digital_pin_to_port_PGM[] =

+ 3
- 3
Marlin/Sanguino/cores/arduino/pins_arduino.h 查看文件

58
 #define digitalPinToBitMask(P) ( pgm_read_byte( digital_pin_to_bit_mask_PGM + (P) ) )
58
 #define digitalPinToBitMask(P) ( pgm_read_byte( digital_pin_to_bit_mask_PGM + (P) ) )
59
 #define digitalPinToTimer(P) ( pgm_read_byte( digital_pin_to_timer_PGM + (P) ) )
59
 #define digitalPinToTimer(P) ( pgm_read_byte( digital_pin_to_timer_PGM + (P) ) )
60
 #define analogInPinToBit(P) (P)
60
 #define analogInPinToBit(P) (P)
61
-#define portOutputRegister(P) ( (volatile uint8_t *)( pgm_read_byte( port_to_output_PGM + (P))) )
62
-#define portInputRegister(P) ( (volatile uint8_t *)( pgm_read_byte( port_to_input_PGM + (P))) )
63
-#define portModeRegister(P) ( (volatile uint8_t *)( pgm_read_byte( port_to_mode_PGM + (P))) )
61
+#define portOutputRegister(P) ( (volatile uint8_t *)( (uint16_t) pgm_read_byte( port_to_output_PGM + (P))) )
62
+#define portInputRegister(P) ( (volatile uint8_t *)( (uint16_t) pgm_read_byte( port_to_input_PGM + (P))) )
63
+#define portModeRegister(P) ( (volatile uint8_t *)( (uint16_t) pgm_read_byte( port_to_mode_PGM + (P))) )
64
 
64
 
65
 #endif
65
 #endif

+ 1
- 1
Marlin/Sanguino/cores/arduino/wiring_private.h 查看文件

27
 #include <math.h>
27
 #include <math.h>
28
 #include <avr/io.h>
28
 #include <avr/io.h>
29
 #include <avr/interrupt.h>
29
 #include <avr/interrupt.h>
30
-#include <avr/delay.h>
30
+#include <util/delay.h>
31
 #include <stdio.h>
31
 #include <stdio.h>
32
 #include <stdarg.h>
32
 #include <stdarg.h>
33
 
33
 

+ 0
- 3
Marlin/cardreader.cpp 查看文件

447
  st_synchronize();
447
  st_synchronize();
448
  quickStop();
448
  quickStop();
449
  sdprinting = false;
449
  sdprinting = false;
450
- #ifdef STOP_HEATING_WAIT_FOR_SD_PRINTING
451
- stop_heating_wait=true;
452
- #endif
453
  if(SD_FINISHED_STEPPERRELEASE)
450
  if(SD_FINISHED_STEPPERRELEASE)
454
  {
451
  {
455
    //finishAndDisableSteppers();
452
    //finishAndDisableSteppers();

+ 339
- 0
Marlin/language.h 查看文件

1
+#ifndef LANGUAGE_H
2
+#define LANGUAGE_H
3
+
4
+// Languages
5
+// 1  Custom (For you to add your own messages)
6
+// 2  English 
7
+// 3  French	(Waiting translation)
8
+// 4  German	(Waiting translation)
9
+// 5  Etc
10
+
11
+#define LANGUAGE_CHOICE 1  // Pick your language from the list above
12
+
13
+#if LANGUAGE_CHOICE == 1
14
+
15
+// LCD Menu Messages
16
+
17
+	#define WELCOME_MSG "RepRap Ready."
18
+	#define MSG_SD_INSERTED "Card Ready"
19
+	#define MSG_SD_REMOVED "Card Initiate"
20
+	#define MSG_MAIN " Main \003"
21
+	#define MSG_AUTOSTART " Autostart"
22
+	#define MSG_DISABLE_STEPPERS " Disable Steppers"
23
+	#define MSG_AUTO_HOME " Auto Home"
24
+	#define MSG_SET_ORIGIN " Set Origin"
25
+	#define MSG_PREHEAT_PLA " Preheat PLA"
26
+	#define MSG_PREHEAT_ABS " Preheat ABS"
27
+	#define MSG_COOLDOWN " Cooldown"
28
+	#define MSG_EXTRUDE " Extrude"
29
+        #define MSG_MOVE_AXIS " Move Axis      \x7E"
30
+	#define MSG_SPEED " Speed:"
31
+	#define MSG_NOZZLE " \002Nozzle:"
32
+	#define MSG_BED " \002Bed:"
33
+	#define MSG_FAN_SPEED " Fan speed:"
34
+	#define MSG_FLOW " Flow:"
35
+	#define MSG_CONTROL " Control \003"
36
+	#define MSG_MIN " \002 Min:"
37
+	#define MSG_MAX " \002 Max:"
38
+	#define MSG_FACTOR " \002 Fact:"
39
+	#define MSG_AUTOTEMP " Autotemp:"
40
+	#define MSG_ON "On "
41
+	#define MSG_OFF "Off"
42
+	#define MSG_PID_P " PID-P: "
43
+	#define MSG_PID_I " PID-I: "
44
+	#define MSG_PID_D " PID-D: "
45
+	#define MSG_PID_C " PID-C: "
46
+	#define MSG_ACC  " Acc:"
47
+	#define MSG_VXY_JERK " Vxy-jerk: "
48
+	#define MSG_VMAX " Vmax "
49
+	#define MSG_X "x:"
50
+	#define MSG_Y "y:"
51
+	#define MSG_Z "z:"
52
+	#define MSG_E "e:"
53
+	#define MSG_VMIN " Vmin:"
54
+	#define MSG_VTRAV_MIN " VTrav min:"
55
+	#define MSG_AMAX " Amax "
56
+	#define MSG_A_RETRACT " A-retract:"
57
+	#define MSG_XSTEPS " Xsteps/mm:"
58
+	#define MSG_YSTEPS " Ysteps/mm:"
59
+	#define MSG_ZSTEPS " Zsteps/mm:"
60
+	#define MSG_ESTEPS " Esteps/mm:"
61
+	#define MSG_MAIN_WIDE " Main        \003"
62
+	#define MSG_TEMPERATURE_WIDE " Temperature \x7E"
63
+	#define MSG_MOTION_WIDE " Motion      \x7E"
64
+	#define MSG_STORE_EPROM " Store EPROM"
65
+	#define MSG_LOAD_EPROM " Load EPROM"
66
+	#define MSG_RESTORE_FAILSAFE " Restore Failsafe"
67
+	#define MSG_REFRESH "\004Refresh"
68
+	#define MSG_WATCH " Watch   \003"
69
+	#define MSG_PREPARE " Prepare \x7E"
70
+	#define MSG_CONTROL_ARROW " Control \x7E"
71
+	#define MSG_TUNE " Tune    \x7E"
72
+	#define MSG_STOP_PRINT " Stop Print   \x7E"
73
+	#define MSG_CARD_MENU " Card Menu    \x7E"
74
+	#define MSG_NO_CARD " No Card"
75
+	#define MSG_SERIAL_ERROR_MENU_STRUCTURE "Something is wrong in the MenuStructure."
76
+
77
+#endif
78
+
79
+#if LANGUAGE_CHOICE == 2
80
+
81
+// LCD Menu Messages
82
+
83
+	#define WELCOME_MSG "UltiMARLIN Ready."
84
+	#define MSG_SD_INSERTED "Card inserted"
85
+	#define MSG_SD_REMOVED "Card removed"
86
+	#define MSG_MAIN " Main \003"
87
+	#define MSG_AUTOSTART " Autostart"
88
+	#define MSG_DISABLE_STEPPERS " Disable Steppers"
89
+	#define MSG_AUTO_HOME " Auto Home"
90
+	#define MSG_SET_ORIGIN " Set Origin"
91
+	#define MSG_PREHEAT " Preheat"
92
+	#define MSG_COOLDOWN " Cooldown"
93
+	#define MSG_EXTRUDE " Extrude"
94
+        #define MSG_MOVE_AXIS " Move Axis      \x7E"
95
+	#define MSG_SPEED " Speed:"
96
+	#define MSG_NOZZLE " \002Nozzle:"
97
+	#define MSG_BED " \002Bed:"
98
+	#define MSG_FAN_SPEED " Fan speed:"
99
+	#define MSG_FLOW " Flow:"
100
+	#define MSG_CONTROL " Control \003"
101
+	#define MSG_MIN " \002 Min:"
102
+	#define MSG_MAX " \002 Max:"
103
+	#define MSG_FACTOR " \002 Fact:"
104
+	#define MSG_AUTOTEMP " Autotemp:"
105
+	#define MSG_ON "On "
106
+	#define MSG_OFF "Off"
107
+	#define MSG_PID_P " PID-P: "
108
+	#define MSG_PID_I " PID-I: "
109
+	#define MSG_PID_D " PID-D: "
110
+	#define MSG_PID_C " PID-C: "
111
+	#define MSG_ACC  " Acc:"
112
+	#define MSG_VXY_JERK " Vxy-jerk: "
113
+	#define MSG_VMAX " Vmax "
114
+	#define MSG_X "x:"
115
+	#define MSG_Y "y:"
116
+	#define MSG_Z "z:"
117
+	#define MSG_E "e:"
118
+	#define MSG_VMIN " Vmin:"
119
+	#define MSG_VTRAV_MIN " VTrav min:"
120
+	#define MSG_AMAX " Amax "
121
+	#define MSG_A_RETRACT " A-retract:"
122
+	#define MSG_XSTEPS " Xsteps/mm:"
123
+	#define MSG_YSTEPS " Ysteps/mm:"
124
+	#define MSG_ZSTEPS " Zsteps/mm:"
125
+	#define MSG_ESTEPS " Esteps/mm:"
126
+	#define MSG_MAIN_WIDE " Main        \003"
127
+	#define MSG_TEMPERATURE_WIDE " Temperature \x7E"
128
+	#define MSG_MOTION_WIDE " Motion      \x7E"
129
+	#define MSG_STORE_EPROM " Store EPROM"
130
+	#define MSG_LOAD_EPROM " Load EPROM"
131
+	#define MSG_RESTORE_FAILSAFE " Restore Failsafe"
132
+	#define MSG_REFRESH "\004Refresh"
133
+	#define MSG_WATCH " Watch   \003"
134
+	#define MSG_PREPARE " Prepare \x7E"
135
+	#define MSG_CONTROL_ARROW " Control \x7E"
136
+	#define MSG_TUNE " Tune    \x7E"
137
+	#define MSG_STOP_PRINT " Stop Print   \x7E"
138
+	#define MSG_CARD_MENU " Card Menu    \x7E"
139
+	#define MSG_NO_CARD " No Card"
140
+	#define MSG_SERIAL_ERROR_MENU_STRUCTURE "Something is wrong in the MenuStructure."
141
+
142
+#endif
143
+
144
+#if LANGUAGE_CHOICE == 3
145
+
146
+// LCD Menu Messages
147
+
148
+	#define WELCOME_MSG "RepRap Ready."
149
+	#define MSG_SD_INSERTED "Card Ready"
150
+	#define MSG_SD_REMOVED "Card Initiate"
151
+	#define MSG_MAIN " Main \003"
152
+	#define MSG_AUTOSTART " Autostart"
153
+	#define MSG_DISABLE_STEPPERS " Disable Steppers"
154
+	#define MSG_AUTO_HOME " Auto Home"
155
+	#define MSG_SET_ORIGIN " Set Origin"
156
+	#define MSG_PREHEAT " Preheat"
157
+	#define MSG_COOLDOWN " Cooldown"
158
+	#define MSG_EXTRUDE " Extrude"
159
+        #define MSG_MOVE_AXIS " Move Axis      \x7E"
160
+	#define MSG_SPEED " Speed:"
161
+	#define MSG_NOZZLE " \002Nozzle:"
162
+	#define MSG_BED " \002Bed:"
163
+	#define MSG_FAN_SPEED " Fan speed:"
164
+	#define MSG_FLOW " Flow:"
165
+	#define MSG_CONTROL " Control \003"
166
+	#define MSG_MIN " \002 Min:"
167
+	#define MSG_MAX " \002 Max:"
168
+	#define MSG_FACTOR " \002 Fact:"
169
+	#define MSG_AUTOTEMP " Autotemp:"
170
+	#define MSG_ON "On "
171
+	#define MSG_OFF "Off"
172
+	#define MSG_PID_P " PID-P: "
173
+	#define MSG_PID_I " PID-I: "
174
+	#define MSG_PID_D " PID-D: "
175
+	#define MSG_PID_C " PID-C: "
176
+	#define MSG_ACC  " Acc:"
177
+	#define MSG_VXY_JERK " Vxy-jerk: "
178
+	#define MSG_VMAX " Vmax "
179
+	#define MSG_X "x:"
180
+	#define MSG_Y "y:"
181
+	#define MSG_Z "z:"
182
+	#define MSG_E "e:"
183
+	#define MSG_VMIN " Vmin:"
184
+	#define MSG_VTRAV_MIN " VTrav min:"
185
+	#define MSG_AMAX " Amax "
186
+	#define MSG_A_RETRACT " A-retract:"
187
+	#define MSG_XSTEPS " Xsteps/mm:"
188
+	#define MSG_YSTEPS " Ysteps/mm:"
189
+	#define MSG_ZSTEPS " Zsteps/mm:"
190
+	#define MSG_ESTEPS " Esteps/mm:"
191
+	#define MSG_MAIN_WIDE " Main        \003"
192
+	#define MSG_TEMPERATURE_WIDE " Temperature \x7E"
193
+	#define MSG_MOTION_WIDE " Motion      \x7E"
194
+	#define MSG_STORE_EPROM " Store EPROM"
195
+	#define MSG_LOAD_EPROM " Load EPROM"
196
+	#define MSG_RESTORE_FAILSAFE " Restore Failsafe"
197
+	#define MSG_REFRESH "\004Refresh"
198
+	#define MSG_WATCH " Watch   \003"
199
+	#define MSG_PREPARE " Prepare \x7E"
200
+	#define MSG_CONTROL_ARROW " Control \x7E"
201
+	#define MSG_TUNE " Tune    \x7E"
202
+	#define MSG_STOP_PRINT " Stop Print   \x7E"
203
+	#define MSG_CARD_MENU " Card Menu    \x7E"
204
+	#define MSG_NO_CARD " No Card"
205
+	#define MSG_SERIAL_ERROR_MENU_STRUCTURE "Something is wrong in the MenuStructure."
206
+
207
+#endif
208
+
209
+#if LANGUAGE_CHOICE == 4
210
+
211
+// LCD Menu Messages
212
+
213
+	#define WELCOME_MSG "RepRap Ready."
214
+	#define MSG_SD_INSERTED "Card Ready"
215
+	#define MSG_SD_REMOVED "Card Initiate"
216
+	#define MSG_MAIN " Main \003"
217
+	#define MSG_AUTOSTART " Autostart"
218
+	#define MSG_DISABLE_STEPPERS " Disable Steppers"
219
+	#define MSG_AUTO_HOME " Auto Home"
220
+	#define MSG_SET_ORIGIN " Set Origin"
221
+	#define MSG_PREHEAT " Preheat"
222
+	#define MSG_COOLDOWN " Cooldown"
223
+	#define MSG_EXTRUDE " Extrude"
224
+        #define MSG_MOVE_AXIS " Move Axis      \x7E"
225
+	#define MSG_SPEED " Speed:"
226
+	#define MSG_NOZZLE " \002Nozzle:"
227
+	#define MSG_BED " \002Bed:"
228
+	#define MSG_FAN_SPEED " Fan speed:"
229
+	#define MSG_FLOW " Flow:"
230
+	#define MSG_CONTROL " Control \003"
231
+	#define MSG_MIN " \002 Min:"
232
+	#define MSG_MAX " \002 Max:"
233
+	#define MSG_FACTOR " \002 Fact:"
234
+	#define MSG_AUTOTEMP " Autotemp:"
235
+	#define MSG_ON "On "
236
+	#define MSG_OFF "Off"
237
+	#define MSG_PID_P " PID-P: "
238
+	#define MSG_PID_I " PID-I: "
239
+	#define MSG_PID_D " PID-D: "
240
+	#define MSG_PID_C " PID-C: "
241
+	#define MSG_ACC  " Acc:"
242
+	#define MSG_VXY_JERK " Vxy-jerk: "
243
+	#define MSG_VMAX " Vmax "
244
+	#define MSG_X "x:"
245
+	#define MSG_Y "y:"
246
+	#define MSG_Z "z:"
247
+	#define MSG_E "e:"
248
+	#define MSG_VMIN " Vmin:"
249
+	#define MSG_VTRAV_MIN " VTrav min:"
250
+	#define MSG_AMAX " Amax "
251
+	#define MSG_A_RETRACT " A-retract:"
252
+	#define MSG_XSTEPS " Xsteps/mm:"
253
+	#define MSG_YSTEPS " Ysteps/mm:"
254
+	#define MSG_ZSTEPS " Zsteps/mm:"
255
+	#define MSG_ESTEPS " Esteps/mm:"
256
+	#define MSG_MAIN_WIDE " Main        \003"
257
+	#define MSG_TEMPERATURE_WIDE " Temperature \x7E"
258
+	#define MSG_MOTION_WIDE " Motion      \x7E"
259
+	#define MSG_STORE_EPROM " Store EPROM"
260
+	#define MSG_LOAD_EPROM " Load EPROM"
261
+	#define MSG_RESTORE_FAILSAFE " Restore Failsafe"
262
+	#define MSG_REFRESH "\004Refresh"
263
+	#define MSG_WATCH " Watch   \003"
264
+	#define MSG_PREPARE " Prepare \x7E"
265
+	#define MSG_CONTROL_ARROW " Control \x7E"
266
+	#define MSG_TUNE " Tune    \x7E"
267
+	#define MSG_STOP_PRINT " Stop Print   \x7E"
268
+	#define MSG_CARD_MENU " Card Menu    \x7E"
269
+	#define MSG_NO_CARD " No Card"
270
+	#define MSG_SERIAL_ERROR_MENU_STRUCTURE "Something is wrong in the MenuStructure."
271
+
272
+#endif
273
+
274
+#if LANGUAGE_CHOICE == 5
275
+
276
+// LCD Menu Messages
277
+
278
+	#define WELCOME_MSG "RepRap Ready."
279
+	#define MSG_SD_INSERTED "Card Ready"
280
+	#define MSG_SD_REMOVED "Card Initiate"
281
+	#define MSG_MAIN " Main \003"
282
+	#define MSG_AUTOSTART " Autostart"
283
+	#define MSG_DISABLE_STEPPERS " Disable Steppers"
284
+	#define MSG_AUTO_HOME " Auto Home"
285
+	#define MSG_SET_ORIGIN " Set Origin"
286
+	#define MSG_PREHEAT " Preheat"
287
+	#define MSG_COOLDOWN " Cooldown"
288
+	#define MSG_EXTRUDE " Extrude"
289
+        #define MSG_MOVE_AXIS " Move Axis      \x7E"
290
+	#define MSG_SPEED " Speed:"
291
+	#define MSG_NOZZLE " \002Nozzle:"
292
+	#define MSG_BED " \002Bed:"
293
+	#define MSG_FAN_SPEED " Fan speed:"
294
+	#define MSG_FLOW " Flow:"
295
+	#define MSG_CONTROL " Control \003"
296
+	#define MSG_MIN " \002 Min:"
297
+	#define MSG_MAX " \002 Max:"
298
+	#define MSG_FACTOR " \002 Fact:"
299
+	#define MSG_AUTOTEMP " Autotemp:"
300
+	#define MSG_ON "On "
301
+	#define MSG_OFF "Off"
302
+	#define MSG_PID_P " PID-P: "
303
+	#define MSG_PID_I " PID-I: "
304
+	#define MSG_PID_D " PID-D: "
305
+	#define MSG_PID_C " PID-C: "
306
+	#define MSG_ACC  " Acc:"
307
+	#define MSG_VXY_JERK " Vxy-jerk: "
308
+	#define MSG_VMAX " Vmax "
309
+	#define MSG_X "x:"
310
+	#define MSG_Y "y:"
311
+	#define MSG_Z "z:"
312
+	#define MSG_E "e:"
313
+	#define MSG_VMIN " Vmin:"
314
+	#define MSG_VTRAV_MIN " VTrav min:"
315
+	#define MSG_AMAX " Amax "
316
+	#define MSG_A_RETRACT " A-retract:"
317
+	#define MSG_XSTEPS " Xsteps/mm:"
318
+	#define MSG_YSTEPS " Ysteps/mm:"
319
+	#define MSG_ZSTEPS " Zsteps/mm:"
320
+	#define MSG_ESTEPS " Esteps/mm:"
321
+	#define MSG_MAIN_WIDE " Main        \003"
322
+	#define MSG_TEMPERATURE_WIDE " Temperature \x7E"
323
+	#define MSG_MOTION_WIDE " Motion      \x7E"
324
+	#define MSG_STORE_EPROM " Store EPROM"
325
+	#define MSG_LOAD_EPROM " Load EPROM"
326
+	#define MSG_RESTORE_FAILSAFE " Restore Failsafe"
327
+	#define MSG_REFRESH "\004Refresh"
328
+	#define MSG_WATCH " Watch   \003"
329
+	#define MSG_PREPARE " Prepare \x7E"
330
+	#define MSG_CONTROL_ARROW " Control \x7E"
331
+	#define MSG_TUNE " Tune    \x7E"
332
+	#define MSG_STOP_PRINT " Stop Print   \x7E"
333
+	#define MSG_CARD_MENU " Card Menu    \x7E"
334
+	#define MSG_NO_CARD " No Card"
335
+	#define MSG_SERIAL_ERROR_MENU_STRUCTURE "Something is wrong in the MenuStructure."
336
+
337
+#endif
338
+
339
+#endif // ifndef LANGUAGE_H

+ 12
- 0
Marlin/motion_control.cpp 查看文件

122
     arc_target[axis_1] = center_axis1 + r_axis1;
122
     arc_target[axis_1] = center_axis1 + r_axis1;
123
     arc_target[axis_linear] += linear_per_segment;
123
     arc_target[axis_linear] += linear_per_segment;
124
     arc_target[E_AXIS] += extruder_per_segment;
124
     arc_target[E_AXIS] += extruder_per_segment;
125
+
126
+    if (min_software_endstops) {
127
+      if (arc_target[X_AXIS] < X_HOME_POS) arc_target[X_AXIS] = X_HOME_POS;
128
+      if (arc_target[Y_AXIS] < Y_HOME_POS) arc_target[Y_AXIS] = Y_HOME_POS;
129
+      if (arc_target[Z_AXIS] < Z_HOME_POS) arc_target[Z_AXIS] = Z_HOME_POS;
130
+    }
131
+
132
+    if (max_software_endstops) {
133
+      if (arc_target[X_AXIS] > X_MAX_LENGTH) arc_target[X_AXIS] = X_MAX_LENGTH;
134
+      if (arc_target[Y_AXIS] > Y_MAX_LENGTH) arc_target[Y_AXIS] = Y_MAX_LENGTH;
135
+      if (arc_target[Z_AXIS] > Z_MAX_LENGTH) arc_target[Z_AXIS] = Z_MAX_LENGTH;
136
+    }
125
     plan_buffer_line(arc_target[X_AXIS], arc_target[Y_AXIS], arc_target[Z_AXIS], arc_target[E_AXIS], feed_rate, extruder);
137
     plan_buffer_line(arc_target[X_AXIS], arc_target[Y_AXIS], arc_target[Z_AXIS], arc_target[E_AXIS], feed_rate, extruder);
126
     
138
     
127
   }
139
   }

+ 243
- 357
Marlin/pins.h 查看文件

45
 #endif /* 99 */
45
 #endif /* 99 */
46
 
46
 
47
 /****************************************************************************************
47
 /****************************************************************************************
48
-* Arduino pin assignment
48
+* Gen7 v1.1, v1.2, v1.3, v1.4 pin assignment
49
 *
49
 *
50
-*                  ATMega168
51
-*                   +-\/-+
52
-*             PC6  1|    |28  PC5 (AI 5 / D19)
53
-*       (D 0) PD0  2|    |27  PC4 (AI 4 / D18)
54
-*       (D 1) PD1  3|    |26  PC3 (AI 3 / D17)
55
-*       (D 2) PD2  4|    |25  PC2 (AI 2 / D16)
56
-*  PWM+ (D 3) PD3  5|    |24  PC1 (AI 1 / D15)
57
-*       (D 4) PD4  6|    |23  PC0 (AI 0 / D14)
58
-*             VCC  7|    |22  GND
59
-*             GND  8|    |21  AREF
60
-*             PB6  9|    |20  AVCC
61
-*             PB7 10|    |19  PB5 (D 13)
62
-*  PWM+ (D 5) PD5 11|    |18  PB4 (D 12)
63
-*  PWM+ (D 6) PD6 12|    |17  PB3 (D 11) PWM
64
-*       (D 7) PD7 13|    |16  PB2 (D 10) PWM
65
-*       (D 8) PB0 14|    |15  PB1 (D 9)  PWM
66
-*                   +----+
67
 ****************************************************************************************/
50
 ****************************************************************************************/
68
-#if MOTHERBOARD == 0
69
-#define KNOWN_BOARD 1
70
 
51
 
71
-#ifndef __AVR_ATmega168__
72
-#error Oops!  Make sure you have 'Arduino Diecimila' selected from the boards menu.
73
-#endif
74
 
52
 
75
-#define X_STEP_PIN          2
76
-#define X_DIR_PIN           3
77
-#define X_ENABLE_PIN       -1
78
-#define X_MIN_PIN           4
79
-#define X_MAX_PIN           9
53
+#if MOTHERBOARD == 13
54
+#define MOTHERBOARD 11
55
+#define GEN7_VERSION 14 // v1.4
56
+#endif
80
 
57
 
81
-#define Y_STEP_PIN         10
82
-#define Y_DIR_PIN           7
83
-#define Y_ENABLE_PIN       -1
84
-#define Y_MIN_PIN           8
85
-#define Y_MAX_PIN          13
58
+#if MOTHERBOARD == 12
59
+#define MOTHERBOARD 11
60
+#define GEN7_VERSION 13 // v1.3
61
+#endif
86
 
62
 
87
-#define Z_STEP_PIN         19
88
-#define Z_DIR_PIN          18
89
-#define Z_ENABLE_PIN        5
90
-#define Z_MIN_PIN          17
91
-#define Z_MAX_PIN          16
63
+#if MOTHERBOARD == 11
64
+#define KNOWN_BOARD
92
 
65
 
93
-#define E0_STEP_PIN         11
94
-#define E0_DIR_PIN          12
95
-#define E0_ENABLE_PIN       -1
66
+#if !defined(__AVR_ATmega644P__) && !defined(__AVR_ATmega644__) && !defined(__AVR_ATmega1284P__)
67
+#error Oops! Make sure you have 'Gen7' selected from the 'Tools -> Boards' menu.
96
 
68
 
97
-#define SDPOWER          -1
98
-#define SDSS          -1
99
-#define LED_PIN            -1
100
-#define FAN_PIN            -1
101
-#define PS_ON_PIN          15
102
-#define KILL_PIN           -1
69
+#endif
103
 
70
 
104
-#define HEATER_0_PIN        6
105
-#define HEATER_1_PIN        -1
106
-#define HEATER_2_PIN        -1
107
-#define TEMP_0_PIN          0    // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!!
108
-#define TEMP_1_PIN          -1   // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!!
109
-#define TEMP_2_PIN          -1   // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!!
110
-#define HEATER_BED_PIN      -1
111
-#define TEMP_BED_PIN        -1
71
+#ifndef GEN7_VERSION
72
+#define GEN7_VERSION 12 // v1.x
112
 #endif
73
 #endif
113
 
74
 
75
+//x axis pins
76
+#define X_STEP_PIN 19
77
+#define X_DIR_PIN 18
78
+#define X_ENABLE_PIN 24
79
+#define X_MIN_PIN 7
80
+#define X_MAX_PIN -1
114
 
81
 
82
+//y axis pins
83
+#define Y_STEP_PIN 23
84
+#define Y_DIR_PIN 22
85
+#define Y_ENABLE_PIN 24
86
+#define Y_MIN_PIN 5
87
+#define Y_MAX_PIN -1
115
 
88
 
116
-/****************************************************************************************
117
-* Sanguino/RepRap Motherboard with direct-drive extruders
118
-*
119
-*                        ATMega644P
120
-*
121
-*                        +---\/---+
122
-*            (D 0) PB0  1|        |40  PA0 (AI 0 / D31)
123
-*            (D 1) PB1  2|        |39  PA1 (AI 1 / D30)
124
-*       INT2 (D 2) PB2  3|        |38  PA2 (AI 2 / D29)
125
-*        PWM (D 3) PB3  4|        |37  PA3 (AI 3 / D28)
126
-*        PWM (D 4) PB4  5|        |36  PA4 (AI 4 / D27)
127
-*       MOSI (D 5) PB5  6|        |35  PA5 (AI 5 / D26)
128
-*       MISO (D 6) PB6  7|        |34  PA6 (AI 6 / D25)
129
-*        SCK (D 7) PB7  8|        |33  PA7 (AI 7 / D24)
130
-*                  RST  9|        |32  AREF
131
-*                  VCC 10|        |31  GND 
132
-*                  GND 11|        |30  AVCC
133
-*                XTAL2 12|        |29  PC7 (D 23)
134
-*                XTAL1 13|        |28  PC6 (D 22)
135
-*       RX0 (D 8)  PD0 14|        |27  PC5 (D 21) TDI
136
-*       TX0 (D 9)  PD1 15|        |26  PC4 (D 20) TDO
137
-*  INT0 RX1 (D 10) PD2 16|        |25  PC3 (D 19) TMS
138
-*  INT1 TX1 (D 11) PD3 17|        |24  PC2 (D 18) TCK
139
-*       PWM (D 12) PD4 18|        |23  PC1 (D 17) SDA
140
-*       PWM (D 13) PD5 19|        |22  PC0 (D 16) SCL
141
-*       PWM (D 14) PD6 20|        |21  PD7 (D 15) PWM
142
-*                        +--------+
143
-*
144
-****************************************************************************************/
145
-#if MOTHERBOARD == 1
146
-#define KNOWN_BOARD 1
89
+//z axis pins
90
+#define Z_STEP_PIN 26
91
+#define Z_DIR_PIN 25
92
+#define Z_ENABLE_PIN 24
93
+#define Z_MIN_PIN 1
94
+#define Z_MAX_PIN 0
147
 
95
 
148
-#ifndef __AVR_ATmega644P__
149
-#error Oops!  Make sure you have 'Sanguino' selected from the 'Tools -> Boards' menu.
150
-#endif
96
+//extruder pins
97
+#define E0_STEP_PIN 28
98
+#define E0_DIR_PIN 27
99
+#define E0_ENABLE_PIN 24
151
 
100
 
152
-#define X_STEP_PIN         15
153
-#define X_DIR_PIN          18
154
-#define X_ENABLE_PIN       19
155
-#define X_MIN_PIN          20
156
-#define X_MAX_PIN          21
101
+#define TEMP_0_PIN 1
102
+#define TEMP_1_PIN -1
103
+#define TEMP_2_PIN -1
104
+#define TEMP_BED_PIN 2
157
 
105
 
158
-#define Y_STEP_PIN         23
159
-#define Y_DIR_PIN          22
160
-#define Y_ENABLE_PIN       19
161
-#define Y_MIN_PIN          25
162
-#define Y_MAX_PIN          26
106
+#define HEATER_0_PIN 4
107
+#define HEATER_1_PIN -1
108
+#define HEATER_2_PIN -1
109
+#define HEATER_BED_PIN 3
163
 
110
 
164
-#define Z_STEP_PIN         29
165
-#define Z_DIR_PIN          30
166
-#define Z_ENABLE_PIN       31
167
-#define Z_MIN_PIN           2
168
-#define Z_MAX_PIN           1
169
 
111
 
170
-#define E0_STEP_PIN         12
171
-#define E0_DIR_PIN          16
172
-#define E0_ENABLE_PIN        3
112
+#define SDPOWER -1
113
+#define SDSS -1 // SCL pin of I2C header
114
+#define LED_PIN -1
173
 
115
 
174
-#define SDPOWER          -1
175
-#define SDSS          -1
176
-#define LED_PIN             0
177
-#define FAN_PIN            -1
178
-#define PS_ON_PIN          -1
179
-#define KILL_PIN           -1
116
+#if (GEN7_VERSION >= 13)
117
+// Gen7 v1.3 removed the fan pin
118
+#define FAN_PIN -1
119
+#else
120
+#define FAN_PIN 31
121
+#endif
122
+#define PS_ON_PIN 15
180
 
123
 
181
-#define HEATER_0_PIN       14
182
-#define HEATER_1_PIN       -1
183
-#define HEATER_2_PIN       -1
184
-#define TEMP_0_PIN          4 //D27   // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!!
185
-#define TEMP_1_PIN         -1 
186
-#define TEMP_2_PIN         -1 
187
-#define HEATER_BED_PIN     -1
188
-#define TEMP_BED_PIN       -1
189
-/*  Unused (1) (2) (3) 4 5 6 7 8 9 10 11 12 13 (14) (15) (16) 17 (18) (19) (20) (21) (22) (23) 24 (25) (26) (27) 28 (29) (30) (31)  */
124
+#if (GEN7_VERSION < 14)
125
+// Gen 1.3 and earlier supplied thermistor power via PS_ON
126
+// Need to ignore the bad thermistor readings on those units
127
+#define BOGUS_TEMPERATURE_FAILSAFE_OVERRIDE
128
+#endif
190
 
129
 
130
+//our pin for debugging.
131
+#define DEBUG_PIN 0
191
 
132
 
133
+//our RS485 pins
134
+#define TX_ENABLE_PIN 12
135
+#define RX_ENABLE_PIN 13
192
 
136
 
193
 #endif
137
 #endif
194
 
138
 
195
-
196
-/****************************************************************************************
197
-* RepRap Motherboard  ****---NOOOOOO RS485/EXTRUDER CONTROLLER!!!!!!!!!!!!!!!!!---*******
139
+/*******************************************************************************
140
+*********
141
+* Gen7 Alfons3  pin assignment
198
 *
142
 *
199
-****************************************************************************************/
200
-#if MOTHERBOARD == 2
201
-#define KNOWN_BOARD 1
143
+********************************************************************************
144
+********/
145
+/* These Pins are assigned for the modified GEN7 Board from Alfons3 Please review the pins and adjust it for your needs*/
202
 
146
 
203
-#ifndef __AVR_ATmega644P__
204
-#error Oops!  Make sure you have 'Sanguino' selected from the 'Tools -> Boards' menu.
205
-#endif
147
+#if MOTHERBOARD == 10
148
+#define KNOWN_BOARD
206
 
149
 
207
-#define X_STEP_PIN      15
208
-#define X_DIR_PIN       18
209
-#define X_ENABLE_PIN    19
210
-#define X_MIN_PIN       20
211
-#define X_MAX_PIN       21
150
+#if !defined(__AVR_ATmega644P__) && !defined(__AVR_ATmega644__) && !defined(__AVR_ATmega1284P__)
151
+    #error Oops!  Make sure you have 'Gen7' selected from the 'Tools -> Boards' menu.
212
 
152
 
213
-#define Y_STEP_PIN      23
214
-#define Y_DIR_PIN       22
215
-#define Y_ENABLE_PIN    24
216
-#define Y_MIN_PIN       25
217
-#define Y_MAX_PIN       26
153
+#endif
218
 
154
 
219
-#define Z_STEP_PINN     27
220
-#define Z_DIR_PINN      28
221
-#define Z_ENABLE_PIN    29
222
-#define Z_MIN_PIN       30
223
-#define Z_MAX_PIN       31
155
+//x axis pins
156
+    #define X_STEP_PIN      21                  //different from stanard GEN7
157
+    #define X_DIR_PIN       20				    //different from stanard GEN7
158
+    #define X_ENABLE_PIN    24
159
+    #define X_MIN_PIN       0
160
+    #define X_MAX_PIN       -1
224
 
161
 
225
-#define E0_STEP_PIN      17
226
-#define E0_DIR_PIN       16
227
-#define E0_ENABLE_PIN    -1
162
+    //y axis pins
163
+    #define Y_STEP_PIN      23
164
+    #define Y_DIR_PIN       22
165
+    #define Y_ENABLE_PIN    24
166
+    #define Y_MIN_PIN       1
167
+    #define Y_MAX_PIN       -1
228
 
168
 
229
-#define SDPOWER          -1
230
-#define SDSS          4
231
-#define LED_PIN          0
169
+    //z axis pins
170
+    #define Z_STEP_PIN      26
171
+    #define Z_DIR_PIN       25
172
+    #define Z_ENABLE_PIN    24
173
+    #define Z_MIN_PIN       2
174
+    #define Z_MAX_PIN       -1
232
 
175
 
233
-#define SD_CARD_WRITE    2
234
-#define SD_CARD_DETECT   3
235
-#define SD_CARD_SELECT   4
176
+    //extruder pins
177
+    #define E0_STEP_PIN      28
178
+    #define E0_DIR_PIN       27
179
+    #define E0_ENABLE_PIN    24
180
+    
181
+    #define TEMP_0_PIN      2
182
+    #define TEMP_1_PIN      -1
183
+    #define TEMP_2_PIN      -1
184
+    #define TEMP_BED_PIN        1   // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! (pin 34 bed)
185
+     
186
+    #define HEATER_0_PIN    4
187
+    #define HEATER_1_PIN    -1   
188
+    #define HEATER_2_PIN    -1
189
+    #define HEATER_BED_PIN      3  // (bed)
236
 
190
 
237
-//our RS485 pins
238
-#define TX_ENABLE_PIN	12
239
-#define RX_ENABLE_PIN	13
191
+    #define SDPOWER         -1
192
+    #define SDSS            31                  // SCL pin of I2C header || CS Pin for SD Card support
193
+    #define LED_PIN         -1
240
 
194
 
241
-//pin for controlling the PSU.
242
-#define PS_ON_PIN       14
195
+    #define FAN_PIN         -1
196
+    #define PS_ON_PIN       19
197
+    //our pin for debugging.
243
 
198
 
244
-#define FAN_PIN         -1
245
-#define KILL_PIN        -1
199
+    #define DEBUG_PIN        -1
246
 
200
 
247
-#define HEATER_0_PIN    -1
248
-#define HEATER_1_PIN    -1
249
-#define HEATER_2_PIN    -1
250
-#define TEMP_0_PIN      -1    // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!!
251
-#define TEMP_1_PIN      -1    
252
-#define TEMP_2_PIN      -1    
253
-#define HEATER_BED_PIN  -1
254
-#define TEMP_BED_PIN    -1
201
+    //our RS485 pins
202
+    //#define TX_ENABLE_PIN       12
203
+    //#define RX_ENABLE_PIN       13
204
+    
205
+    #define BEEPER -1	
206
+	#define SDCARDDETECT -1 		
207
+    #define SUICIDE_PIN -1						//has to be defined; otherwise Power_off doesn't work
208
+	
209
+	//Pins for 4bit LCD Support 
210
+    #define LCD_PINS_RS 18 
211
+    #define LCD_PINS_ENABLE 17
212
+    #define LCD_PINS_D4 16
213
+    #define LCD_PINS_D5 15 
214
+    #define LCD_PINS_D6 13
215
+    #define LCD_PINS_D7 14
216
+    
217
+     //buttons are directly attached
218
+    #define BTN_EN1 11
219
+    #define BTN_EN2 10
220
+    #define BTN_ENC 12  //the click
221
+    
222
+    #define BLEN_C 2
223
+    #define BLEN_B 1
224
+    #define BLEN_A 0
255
 
225
 
226
+    #define encrot0 0
227
+    #define encrot1 2
228
+    #define encrot2 3
229
+    #define encrot3 1
256
 #endif
230
 #endif
257
 
231
 
258
 /****************************************************************************************
232
 /****************************************************************************************
259
 * Arduino Mega pin assignment
233
 * Arduino Mega pin assignment
260
 *
234
 *
261
 ****************************************************************************************/
235
 ****************************************************************************************/
262
-#if MOTHERBOARD == 33
263
-#define MOTHERBOARD 3
264
-#define RAMPS_V_1_3
265
-#endif
266
-#if MOTHERBOARD == 3
236
+#if MOTHERBOARD == 3 || MOTHERBOARD == 33 || MOTHERBOARD == 34
267
 #define KNOWN_BOARD 1
237
 #define KNOWN_BOARD 1
268
 
238
 
269
 //////////////////FIX THIS//////////////
239
 //////////////////FIX THIS//////////////
277
 // #define RAMPS_V_1_3
247
 // #define RAMPS_V_1_3
278
 // #define RAMPS_V_1_0
248
 // #define RAMPS_V_1_0
279
 
249
 
280
-#ifdef RAMPS_V_1_3
250
+#ifdef MOTHERBOARD == 33 || MOTHERBOARD == 34
281
 
251
 
282
 #define X_STEP_PIN         54
252
 #define X_STEP_PIN         54
283
 #define X_DIR_PIN          55
253
 #define X_DIR_PIN          55
295
 #define Z_DIR_PIN          48
265
 #define Z_DIR_PIN          48
296
 #define Z_ENABLE_PIN       62
266
 #define Z_ENABLE_PIN       62
297
 #define Z_MIN_PIN          18
267
 #define Z_MIN_PIN          18
298
-#define Z_MAX_PIN          19   //19
268
+#define Z_MAX_PIN          19
299
 
269
 
300
 #define E0_STEP_PIN        26
270
 #define E0_STEP_PIN        26
301
 #define E0_DIR_PIN         28
271
 #define E0_DIR_PIN         28
308
 #define SDPOWER            -1
278
 #define SDPOWER            -1
309
 #define SDSS               53
279
 #define SDSS               53
310
 #define LED_PIN            13
280
 #define LED_PIN            13
311
-#define FAN_PIN            4
281
+
282
+#if MOTHERBOARD == 33
283
+#define FAN_PIN            9 // (Sprinter config)
284
+#else
285
+#define FAN_PIN            4 // IO pin. Buffer needed
286
+#endif
312
 #define PS_ON_PIN          12
287
 #define PS_ON_PIN          12
313
 #define KILL_PIN           -1
288
 #define KILL_PIN           -1
314
 
289
 
315
 #define HEATER_0_PIN       10   // EXTRUDER 1
290
 #define HEATER_0_PIN       10   // EXTRUDER 1
316
-#define HEATER_1_PIN       9    // EXTRUDER 2
317
-#define HEATER_2_PIN       -1   // EXTRUDER 2
291
+#if MOTHERBOARD == 33
292
+#define HEATER_1_PIN       -1
293
+#else
294
+#define HEATER_1_PIN       9    // EXTRUDER 2 (FAN On Sprinter)
295
+#endif
296
+#define HEATER_2_PIN       -1   
318
 #define TEMP_0_PIN         13   // ANALOG NUMBERING
297
 #define TEMP_0_PIN         13   // ANALOG NUMBERING
319
 #define TEMP_1_PIN         15   // ANALOG NUMBERING
298
 #define TEMP_1_PIN         15   // ANALOG NUMBERING
320
 #define TEMP_2_PIN         -1   // ANALOG NUMBERING
299
 #define TEMP_2_PIN         -1   // ANALOG NUMBERING
321
 #define HEATER_BED_PIN     8    // BED
300
 #define HEATER_BED_PIN     8    // BED
322
 #define TEMP_BED_PIN       14   // ANALOG NUMBERING
301
 #define TEMP_BED_PIN       14   // ANALOG NUMBERING
323
 
302
 
303
+#ifdef ULTRA_LCD
304
+
305
+  #ifdef NEWPANEL
306
+  //arduino pin which triggers an piezzo beeper
307
+    #define BEEPER 33			// Beeper on AUX-4
308
+
309
+    #define LCD_PINS_RS 16 
310
+    #define LCD_PINS_ENABLE 17
311
+    #define LCD_PINS_D4 23
312
+    #define LCD_PINS_D5 25 
313
+    #define LCD_PINS_D6 27
314
+    #define LCD_PINS_D7 29
315
+    
316
+    //buttons are directly attached using AUX-2
317
+    #define BTN_EN1 44
318
+    #define BTN_EN2 42
319
+    #define BTN_ENC 64  //the click
320
+    
321
+    #define BLEN_C 2
322
+    #define BLEN_B 1
323
+    #define BLEN_A 0
324
+    
325
+    #define SDCARDDETECT 31		// Ramps does not use this port
326
+    
327
+      //encoder rotation values
328
+    #define encrot0 0
329
+    #define encrot1 2
330
+    #define encrot2 3
331
+    #define encrot3 1
332
+
333
+  #else //old style panel with shift register
334
+    //arduino pin witch triggers an piezzo beeper
335
+    #define BEEPER 33		No Beeper added
336
+
337
+    //buttons are attached to a shift register
338
+	// Not wired this yet
339
+    //#define SHIFT_CLK 38
340
+    //#define SHIFT_LD 42
341
+    //#define SHIFT_OUT 40
342
+    //#define SHIFT_EN 17
343
+    
344
+    #define LCD_PINS_RS 16 
345
+    #define LCD_PINS_ENABLE 17
346
+    #define LCD_PINS_D4 23
347
+    #define LCD_PINS_D5 25 
348
+    #define LCD_PINS_D6 27
349
+    #define LCD_PINS_D7 29
350
+    
351
+    //encoder rotation values
352
+    #define encrot0 0
353
+    #define encrot1 2
354
+    #define encrot2 3
355
+    #define encrot3 1
356
+
357
+    
358
+    //bits in the shift register that carry the buttons for:
359
+    // left up center down right red
360
+    #define BL_LE 7
361
+    #define BL_UP 6
362
+    #define BL_MI 5
363
+    #define BL_DW 4
364
+    #define BL_RI 3
365
+    #define BL_ST 2
366
+
367
+    #define BLEN_B 1
368
+    #define BLEN_A 0
369
+  #endif 
370
+#endif //ULTRA_LCD
324
 
371
 
325
 #else // RAMPS_V_1_1 or RAMPS_V_1_2 as default
372
 #else // RAMPS_V_1_1 or RAMPS_V_1_2 as default
326
 
373
 
440
 * Gen6 pin assignment
487
 * Gen6 pin assignment
441
 *
488
 *
442
 ****************************************************************************************/
489
 ****************************************************************************************/
443
-#if MOTHERBOARD == 5
490
+#if MOTHERBOARD == 5 || MOTHERBOARD == 51
444
 #define KNOWN_BOARD 1
491
 #define KNOWN_BOARD 1
445
 
492
 
446
 #ifndef __AVR_ATmega644P__
493
 #ifndef __AVR_ATmega644P__
447
-    #error Oops!  Make sure you have 'Sanguino' selected from the 'Tools -> Boards' menu.
494
+#ifndef __AVR_ATmega1284P__
495
+#error Oops!  Make sure you have 'Sanguino' selected from the 'Tools -> Boards' menu.
496
+#endif
448
 #endif
497
 #endif
449
 
498
 
450
 //x axis pins
499
 //x axis pins
474
     #define E0_ENABLE_PIN    3    //Added @ EJE Electronics 20100715
523
     #define E0_ENABLE_PIN    3    //Added @ EJE Electronics 20100715
475
     #define TEMP_0_PIN      5     //changed @ rkoeppl 20110410
524
     #define TEMP_0_PIN      5     //changed @ rkoeppl 20110410
476
     #define TEMP_1_PIN      -1    //changed @ rkoeppl 20110410
525
     #define TEMP_1_PIN      -1    //changed @ rkoeppl 20110410
526
+
527
+
477
     #define TEMP_2_PIN      -1    //changed @ rkoeppl 20110410
528
     #define TEMP_2_PIN      -1    //changed @ rkoeppl 20110410
478
     #define HEATER_0_PIN    14    //changed @ rkoeppl 20110410
529
     #define HEATER_0_PIN    14    //changed @ rkoeppl 20110410
479
     #define HEATER_1_PIN    -1
530
     #define HEATER_1_PIN    -1
480
     #define HEATER_2_PIN    -1
531
     #define HEATER_2_PIN    -1
532
+    #if MOTHERBOARD == 5
481
     #define HEATER_BED_PIN  -1    //changed @ rkoeppl 20110410
533
     #define HEATER_BED_PIN  -1    //changed @ rkoeppl 20110410
482
     #define TEMP_BED_PIN    -1    //changed @ rkoeppl 20110410
534
     #define TEMP_BED_PIN    -1    //changed @ rkoeppl 20110410
483
-    
535
+    #else
536
+    #define HEATER_BED_PIN   1    //changed @ rkoeppl 20110410
537
+    #define TEMP_BED_PIN     0    //changed @ rkoeppl 20110410
538
+    #endif
484
     #define SDPOWER          -1
539
     #define SDPOWER          -1
485
     #define SDSS          17
540
     #define SDSS          17
486
     #define LED_PIN         -1    //changed @ rkoeppl 20110410
541
     #define LED_PIN         -1    //changed @ rkoeppl 20110410
502
 *
557
 *
503
 ****************************************************************************************/
558
 ****************************************************************************************/
504
 #if MOTHERBOARD == 62
559
 #if MOTHERBOARD == 62
560
+#undef MOTHERBOARD
505
 #define MOTHERBOARD 6
561
 #define MOTHERBOARD 6
506
 #define SANGUINOLOLU_V_1_2 
562
 #define SANGUINOLOLU_V_1_2 
507
 #endif
563
 #endif
508
 #if MOTHERBOARD == 6
564
 #if MOTHERBOARD == 6
509
 #define KNOWN_BOARD 1
565
 #define KNOWN_BOARD 1
510
 #ifndef __AVR_ATmega644P__
566
 #ifndef __AVR_ATmega644P__
567
+#ifndef __AVR_ATmega1284P__
511
 #error Oops!  Make sure you have 'Sanguino' selected from the 'Tools -> Boards' menu.
568
 #error Oops!  Make sure you have 'Sanguino' selected from the 'Tools -> Boards' menu.
512
 #endif
569
 #endif
570
+#endif
513
 
571
 
514
 #define X_STEP_PIN         15
572
 #define X_STEP_PIN         15
515
 #define X_DIR_PIN          21
573
 #define X_DIR_PIN          21
567
 
625
 
568
 #endif
626
 #endif
569
 
627
 
570
-/****************************************************************************************
571
-* Gen7 v1.1, v1.2, v1.3 pin assignment
572
-*
573
-****************************************************************************************/
574
-
575
-#if MOTHERBOARD == 79
576
-#define MOTHERBOARD 78
577
-#define GEN7_V_1_3
578
-#endif
579
-
580
-#if MOTHERBOARD == 78
581
-#define KNOWN_BOARD
582
-
583
-#if !defined(__AVR_ATmega644P__) && !defined(__AVR_ATmega644__) && !defined(__AVR_ATmega1284P__)
584
-#error Oops! Make sure you have 'Gen7' selected from the 'Tools -> Boards' menu.
585
-
586
-#endif
587
-
588
-//x axis pins
589
-#define X_STEP_PIN 19
590
-#define X_DIR_PIN 18
591
-#define X_ENABLE_PIN 24
592
-#define X_MIN_PIN 7
593
-#define X_MAX_PIN -1
594
-
595
-//y axis pins
596
-#define Y_STEP_PIN 23
597
-#define Y_DIR_PIN 22
598
-#define Y_ENABLE_PIN 24
599
-#define Y_MIN_PIN 5
600
-#define Y_MAX_PIN -1
601
-
602
-//z axis pins
603
-#define Z_STEP_PIN 26
604
-#define Z_DIR_PIN 25
605
-#define Z_ENABLE_PIN 24
606
-#define Z_MIN_PIN 1
607
-#define Z_MAX_PIN -1
608
-
609
-//extruder pins
610
-#define E0_STEP_PIN 28
611
-#define E0_DIR_PIN 27
612
-#define E0_ENABLE_PIN 24
613
-
614
-#define TEMP_0_PIN 1
615
-#define TEMP_1_PIN -1
616
-#define TEMP_2_PIN -1
617
-#define TEMP_BED_PIN 2
618
-
619
-#define HEATER_0_PIN 4
620
-#define HEATER_1_PIN -1
621
-#define HEATER_2_PIN -1
622
-#define HEATER_BED_PIN 3
623
-
624
-
625
-#define SDPOWER -1
626
-#define SDSS -1 // SCL pin of I2C header
627
-#define LED_PIN -1
628
-
629
-#ifdef GEN7_V_1_3
630
-// Gen7 v1.3 removed the fan pin
631
-#define FAN_PIN -1
632
-#else
633
-#define FAN_PIN 31
634
-#endif
635
-#define PS_ON_PIN 15
636
-
637
-//our pin for debugging.
638
-#define DEBUG_PIN 0
639
-
640
-//our RS485 pins
641
-#define TX_ENABLE_PIN 12
642
-#define RX_ENABLE_PIN 13
643
-
644
-#endif
645
-
646
-/*******************************************************************************
647
-*********
648
-* Gen7 Alfons3  pin assignment
649
-*
650
-********************************************************************************
651
-********/
652
-/* These Pins are assigned for the modified GEN7 Board from Alfons3 Please review the pins and adjust it for your needs*/
653
-
654
-#if MOTHERBOARD == 77
655
-#define KNOWN_BOARD
656
-
657
-#if !defined(__AVR_ATmega644P__) && !defined(__AVR_ATmega644__) && !defined(__AVR_ATmega1284P__)
658
-    #error Oops!  Make sure you have 'Gen7' selected from the 'Tools -> Boards' menu.
659
-
660
-#endif
661
-
662
-//x axis pins
663
-    #define X_STEP_PIN      21                  //different from stanard GEN7
664
-    #define X_DIR_PIN       20				    //different from stanard GEN7
665
-    #define X_ENABLE_PIN    24
666
-    #define X_MIN_PIN       0
667
-    #define X_MAX_PIN       -1
668
-
669
-    //y axis pins
670
-    #define Y_STEP_PIN      23
671
-    #define Y_DIR_PIN       22
672
-    #define Y_ENABLE_PIN    24
673
-    #define Y_MIN_PIN       1
674
-    #define Y_MAX_PIN       -1
675
-
676
-    //z axis pins
677
-    #define Z_STEP_PIN      26
678
-    #define Z_DIR_PIN       25
679
-    #define Z_ENABLE_PIN    24
680
-    #define Z_MIN_PIN       2
681
-    #define Z_MAX_PIN       -1
682
-
683
-    //extruder pins
684
-    #define E0_STEP_PIN      28
685
-    #define E0_DIR_PIN       27
686
-    #define E0_ENABLE_PIN    24
687
-    
688
-    #define TEMP_0_PIN      2
689
-    #define TEMP_1_PIN      -1
690
-    #define TEMP_2_PIN      -1
691
-    #define TEMP_BED_PIN        1   // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! (pin 34 bed)
692
-     
693
-    #define HEATER_0_PIN    4
694
-    #define HEATER_1_PIN    -1   
695
-    #define HEATER_2_PIN    -1
696
-    #define HEATER_BED_PIN      3  // (bed)
697
-   
698
-   
699
-
700
-    
701
-    #define SDPOWER         -1
702
-    #define SDSS            31                  // SCL pin of I2C header || CS Pin for SD Card support
703
-    #define LED_PIN         -1
704
-
705
-    #define FAN_PIN         -1
706
-    #define PS_ON_PIN       19
707
-    //our pin for debugging.
708
-
709
-    #define DEBUG_PIN        -1
710
-
711
-    //our RS485 pins
712
-    //#define TX_ENABLE_PIN       12
713
-    //#define RX_ENABLE_PIN       13
714
-    
715
-    #define BEEPER -1	
716
-	#define SDCARDDETECT -1 		
717
-    #define SUICIDE_PIN -1						//has to be defined; otherwise Power_off doesn't work
718
-	
719
-	//Pins for 4bit LCD Support 
720
-    #define LCD_PINS_RS 18 
721
-    #define LCD_PINS_ENABLE 17
722
-    #define LCD_PINS_D4 16
723
-    #define LCD_PINS_D5 15 
724
-    #define LCD_PINS_D6 13
725
-    #define LCD_PINS_D7 14
726
-    
727
-     //buttons are directly attached
728
-    #define BTN_EN1 11
729
-    #define BTN_EN2 10
730
-    #define BTN_ENC 12  //the click
731
-    
732
-    #define BLEN_C 2
733
-    #define BLEN_B 1
734
-    #define BLEN_A 0
735
-
736
-   
737
-    #define encrot0 0
738
-    #define encrot1 2
739
-    #define encrot2 3
740
-    #define encrot3 1
741
-   
742
-    
743
-#endif
744
 
628
 
745
 #if MOTHERBOARD == 7
629
 #if MOTHERBOARD == 7
746
 #define KNOWN_BOARD
630
 #define KNOWN_BOARD
1003
 #define MOTHERBOARD 6
887
 #define MOTHERBOARD 6
1004
 #define KNOWN_BOARD 1
888
 #define KNOWN_BOARD 1
1005
 #ifndef __AVR_ATmega644P__
889
 #ifndef __AVR_ATmega644P__
890
+#ifndef __AVR_ATmega1284P__
1006
 #error Oops!  Make sure you have 'Sanguino' selected from the 'Tools -> Boards' menu.
891
 #error Oops!  Make sure you have 'Sanguino' selected from the 'Tools -> Boards' menu.
1007
 #endif
892
 #endif
893
+#endif
1008
 
894
 
1009
 #define X_STEP_PIN         15
895
 #define X_STEP_PIN         15
1010
 #define X_DIR_PIN          18
896
 #define X_DIR_PIN          18

+ 14
- 9
Marlin/planner.cpp 查看文件

81
 static float previous_speed[4]; // Speed of previous path line segment
81
 static float previous_speed[4]; // Speed of previous path line segment
82
 static float previous_nominal_speed; // Nominal speed of previous path line segment
82
 static float previous_nominal_speed; // Nominal speed of previous path line segment
83
 
83
 
84
+extern volatile int extrudemultiply; // Sets extrude multiply factor (in percent)
85
+
84
 #ifdef AUTOTEMP
86
 #ifdef AUTOTEMP
85
     float autotemp_max=250;
87
     float autotemp_max=250;
86
     float autotemp_min=210;
88
     float autotemp_min=210;
439
 // Add a new linear movement to the buffer. steps_x, _y and _z is the absolute position in 
441
 // Add a new linear movement to the buffer. steps_x, _y and _z is the absolute position in 
440
 // mm. Microseconds specify how many microseconds the move should take to perform. To aid acceleration
442
 // mm. Microseconds specify how many microseconds the move should take to perform. To aid acceleration
441
 // calculation the caller must also provide the physical length of the line in millimeters.
443
 // calculation the caller must also provide the physical length of the line in millimeters.
442
-void plan_buffer_line(const float &x, const float &y, const float &z, const float &e,  float feed_rate, const uint8_t &extruder)
444
+void plan_buffer_line(float &x, float &y, float &z, float &e, float feed_rate, uint8_t &extruder)
443
 {
445
 {
444
   // Calculate the buffer head after we push this byte
446
   // Calculate the buffer head after we push this byte
445
   int next_buffer_head = next_block_index(block_buffer_head);
447
   int next_buffer_head = next_block_index(block_buffer_head);
451
     manage_inactivity(1); 
453
     manage_inactivity(1); 
452
     LCD_STATUS;
454
     LCD_STATUS;
453
   }
455
   }
454
-
456
+  
455
   // The target position of the tool in absolute steps
457
   // The target position of the tool in absolute steps
456
   // Calculate target position in absolute steps
458
   // Calculate target position in absolute steps
457
   //this should be done after the wait, because otherwise a M92 code within the gcode disrupts this calculation somehow
459
   //this should be done after the wait, because otherwise a M92 code within the gcode disrupts this calculation somehow
488
   block->steps_y = labs(target[Y_AXIS]-position[Y_AXIS]);
490
   block->steps_y = labs(target[Y_AXIS]-position[Y_AXIS]);
489
   block->steps_z = labs(target[Z_AXIS]-position[Z_AXIS]);
491
   block->steps_z = labs(target[Z_AXIS]-position[Z_AXIS]);
490
   block->steps_e = labs(target[E_AXIS]-position[E_AXIS]);
492
   block->steps_e = labs(target[E_AXIS]-position[E_AXIS]);
493
+  block->steps_e *= extrudemultiply;
494
+  block->steps_e /= 100;
491
   block->step_event_count = max(block->steps_x, max(block->steps_y, max(block->steps_z, block->steps_e)));
495
   block->step_event_count = max(block->steps_x, max(block->steps_y, max(block->steps_z, block->steps_e)));
492
 
496
 
493
   // Bail if this is a zero-length block
497
   // Bail if this is a zero-length block
512
   // Enable all
516
   // Enable all
513
   if(block->steps_e != 0) { enable_e0();enable_e1();enable_e2(); }
517
   if(block->steps_e != 0) { enable_e0();enable_e1();enable_e2(); }
514
 
518
 
519
+
520
+  // slow down when de buffer starts to empty, rather than wait at the corner for a buffer refill
521
+  int moves_queued=(block_buffer_head-block_buffer_tail + BLOCK_BUFFER_SIZE) & (BLOCK_BUFFER_SIZE - 1);
522
+  #ifdef SLOWDOWN
523
+    if(moves_queued < (BLOCK_BUFFER_SIZE * 0.5) && moves_queued > 1) feed_rate = feed_rate*moves_queued / (BLOCK_BUFFER_SIZE * 0.5); 
524
+  #endif
525
+
515
   float delta_mm[4];
526
   float delta_mm[4];
516
   delta_mm[X_AXIS] = (target[X_AXIS]-position[X_AXIS])/axis_steps_per_unit[X_AXIS];
527
   delta_mm[X_AXIS] = (target[X_AXIS]-position[X_AXIS])/axis_steps_per_unit[X_AXIS];
517
   delta_mm[Y_AXIS] = (target[Y_AXIS]-position[Y_AXIS])/axis_steps_per_unit[Y_AXIS];
528
   delta_mm[Y_AXIS] = (target[Y_AXIS]-position[Y_AXIS])/axis_steps_per_unit[Y_AXIS];
518
   delta_mm[Z_AXIS] = (target[Z_AXIS]-position[Z_AXIS])/axis_steps_per_unit[Z_AXIS];
529
   delta_mm[Z_AXIS] = (target[Z_AXIS]-position[Z_AXIS])/axis_steps_per_unit[Z_AXIS];
519
-  delta_mm[E_AXIS] = (target[E_AXIS]-position[E_AXIS])/axis_steps_per_unit[E_AXIS];
530
+  delta_mm[E_AXIS] = ((target[E_AXIS]-position[E_AXIS])/axis_steps_per_unit[E_AXIS])*extrudemultiply/100.0;
520
   if ( block->steps_x == 0 && block->steps_y == 0 && block->steps_z == 0 ) {
531
   if ( block->steps_x == 0 && block->steps_y == 0 && block->steps_z == 0 ) {
521
     block->millimeters = abs(delta_mm[E_AXIS]);
532
     block->millimeters = abs(delta_mm[E_AXIS]);
522
   } else {
533
   } else {
537
     	if(feed_rate<minimumfeedrate) feed_rate=minimumfeedrate;
548
     	if(feed_rate<minimumfeedrate) feed_rate=minimumfeedrate;
538
   } 
549
   } 
539
 
550
 
540
-  // slow down when de buffer starts to empty, rather than wait at the corner for a buffer refill
541
-  int moves_queued=(block_buffer_head-block_buffer_tail + BLOCK_BUFFER_SIZE) & (BLOCK_BUFFER_SIZE - 1);
542
-#ifdef SLOWDOWN
543
-  if(moves_queued < (BLOCK_BUFFER_SIZE * 0.5) && moves_queued > 1) feed_rate = feed_rate*moves_queued / (BLOCK_BUFFER_SIZE * 0.5); 
544
-#endif
545
-
546
 /*
551
 /*
547
   //  segment time im micro seconds
552
   //  segment time im micro seconds
548
   long segment_time = lround(1000000.0/inverse_second);
553
   long segment_time = lround(1000000.0/inverse_second);

+ 1
- 1
Marlin/planner.h 查看文件

67
 
67
 
68
 // Add a new linear movement to the buffer. x, y and z is the signed, absolute target position in 
68
 // Add a new linear movement to the buffer. x, y and z is the signed, absolute target position in 
69
 // millimaters. Feed rate specifies the speed of the motion.
69
 // millimaters. Feed rate specifies the speed of the motion.
70
-void plan_buffer_line(const float &x, const float &y, const float &z, const float &e, float feed_rate, const uint8_t &extruder);
70
+void plan_buffer_line(float &x, float &y, float &z, float &e, float feed_rate, uint8_t &extruder);
71
 
71
 
72
 // Set position. Used for G92 instructions.
72
 // Set position. Used for G92 instructions.
73
 void plan_set_position(const float &x, const float &y, const float &z, const float &e);
73
 void plan_set_position(const float &x, const float &y, const float &z, const float &e);

+ 1
- 1
Marlin/stepper.cpp 查看文件

432
       }
432
       }
433
       else { // +direction
433
       else { // +direction
434
         NORM_E_DIR();
434
         NORM_E_DIR();
435
-        count_direction[E_AXIS]=-1;
435
+        count_direction[E_AXIS]=1;
436
       }
436
       }
437
     #endif //!ADVANCE
437
     #endif //!ADVANCE
438
     
438
     

+ 8
- 8
Marlin/temperature.cpp 查看文件

312
 
312
 
313
     return (1023 * OVERSAMPLENR) - raw;
313
     return (1023 * OVERSAMPLENR) - raw;
314
   }
314
   }
315
-  return celsius * (1024.0 / (5.0 * 100.0) ) * OVERSAMPLENR;
315
+  return ((celsius-TEMP_SENSOR_AD595_OFFSET)/TEMP_SENSOR_AD595_GAIN) * (1024.0 / (5.0 * 100.0) ) * OVERSAMPLENR;
316
 }
316
 }
317
 
317
 
318
 // Takes bed temperature value as input and returns corresponding raw value. 
318
 // Takes bed temperature value as input and returns corresponding raw value. 
342
 
342
 
343
     return (1023 * OVERSAMPLENR) - raw;
343
     return (1023 * OVERSAMPLENR) - raw;
344
 #elif defined BED_USES_AD595
344
 #elif defined BED_USES_AD595
345
-    return lround(celsius * (1024.0 * OVERSAMPLENR/ (5.0 * 100.0) ) );
345
+    return lround(((celsius-TEMP_SENSOR_AD595_OFFSET)/TEMP_SENSOR_AD595_GAIN) * (1024.0 * OVERSAMPLENR/ (5.0 * 100.0) ) );
346
 #else
346
 #else
347
     #warning No heater-type defined for the bed.
347
     #warning No heater-type defined for the bed.
348
     return 0;
348
     return 0;
390
 
390
 
391
     return celsius;
391
     return celsius;
392
   }
392
   }
393
-  return raw * ((5.0 * 100.0) / 1024.0) / OVERSAMPLENR;
393
+  return ((raw * ((5.0 * 100.0) / 1024.0) / OVERSAMPLENR) * TEMP_SENSOR_AD595_GAIN) + TEMP_SENSOR_AD595_OFFSET;
394
 }
394
 }
395
 
395
 
396
 // Derived from RepRap FiveD extruder::getTemperature()
396
 // Derived from RepRap FiveD extruder::getTemperature()
421
     return celsius;
421
     return celsius;
422
     
422
     
423
   #elif defined BED_USES_AD595
423
   #elif defined BED_USES_AD595
424
-    return raw * ((5.0 * 100.0) / 1024.0) / OVERSAMPLENR;
424
+    return ((raw * ((5.0 * 100.0) / 1024.0) / OVERSAMPLENR) * TEMP_SENSOR_AD595_GAIN) + TEMP_SENSOR_AD595_OFFSET;
425
   #else
425
   #else
426
     #warning No heater-type defined for the bed.
426
     #warning No heater-type defined for the bed.
427
   #endif
427
   #endif
851
     for(unsigned char e = 0; e < EXTRUDERS; e++) {
851
     for(unsigned char e = 0; e < EXTRUDERS; e++) {
852
        if(current_raw[e] >= maxttemp[e]) {
852
        if(current_raw[e] >= maxttemp[e]) {
853
           target_raw[e] = 0;
853
           target_raw[e] = 0;
854
-          #if (PS_ON != -1)
854
+          max_temp_error(e);
855
+          #ifndef BOGUS_TEMPERATURE_FAILSAFE_OVERRIDE
855
           {
856
           {
856
-            max_temp_error(e);
857
             kill();;
857
             kill();;
858
           }
858
           }
859
           #endif
859
           #endif
860
        }
860
        }
861
        if(current_raw[e] <= minttemp[e]) {
861
        if(current_raw[e] <= minttemp[e]) {
862
           target_raw[e] = 0;
862
           target_raw[e] = 0;
863
-          #if (PS_ON != -1)
863
+          min_temp_error(e);
864
+          #ifndef BOGUS_TEMPERATURE_FAILSAFE_OVERRIDE
864
           {
865
           {
865
-            min_temp_error(e);
866
             kill();
866
             kill();
867
           }
867
           }
868
           #endif
868
           #endif

+ 8
- 13
Marlin/ultralcd.h 查看文件

9
   void beep();
9
   void beep();
10
   void buttons_check();
10
   void buttons_check();
11
 
11
 
12
-
13
   #define LCD_UPDATE_INTERVAL 100
12
   #define LCD_UPDATE_INTERVAL 100
14
   #define STATUSTIMEOUT 15000
13
   #define STATUSTIMEOUT 15000
15
-
16
-
17
-  
18
   extern LiquidCrystal lcd;
14
   extern LiquidCrystal lcd;
19
-
20
-
15
+  
21
   #ifdef NEWPANEL
16
   #ifdef NEWPANEL
22
-
23
-    
24
     #define EN_C (1<<BLEN_C)
17
     #define EN_C (1<<BLEN_C)
25
     #define EN_B (1<<BLEN_B)
18
     #define EN_B (1<<BLEN_B)
26
     #define EN_A (1<<BLEN_A)
19
     #define EN_A (1<<BLEN_A)
28
     #define CLICKED (buttons&EN_C)
21
     #define CLICKED (buttons&EN_C)
29
     #define BLOCK {blocking=millis()+blocktime;}
22
     #define BLOCK {blocking=millis()+blocktime;}
30
     #if (SDCARDDETECT > -1)
23
     #if (SDCARDDETECT > -1)
31
-    {
32
-      #define CARDINSERTED (READ(SDCARDDETECT)==0)
33
-    }
34
-    #endif
35
-    
24
+      #ifdef SDCARDDETECTINVERTED 
25
+        #define CARDINSERTED (READ(SDCARDDETECT)!=0)
26
+      #else
27
+        #define CARDINSERTED (READ(SDCARDDETECT)==0)
28
+      #endif
29
+    #endif  //SDCARDTETECTINVERTED
30
+
36
   #else
31
   #else
37
 
32
 
38
     //atomatic, do not change
33
     //atomatic, do not change

+ 117
- 99
Marlin/ultralcd.pde 查看文件

9
 extern volatile int feedmultiply;
9
 extern volatile int feedmultiply;
10
 extern volatile bool feedmultiplychanged;
10
 extern volatile bool feedmultiplychanged;
11
 
11
 
12
+extern volatile int extrudemultiply;
13
+
12
 extern long position[4];   
14
 extern long position[4];   
13
 extern CardReader card;
15
 extern CardReader card;
14
 
16
 
122
   lcd.createChar(3,uplevel);
124
   lcd.createChar(3,uplevel);
123
   lcd.createChar(4,refresh);
125
   lcd.createChar(4,refresh);
124
   lcd.createChar(5,folder);
126
   lcd.createChar(5,folder);
125
-  LCD_MESSAGEPGM("UltiMarlin ready.");
127
+  LCD_MESSAGEPGM(WELCOME_MSG);
126
 }
128
 }
127
 
129
 
128
 
130
 
372
   if((currentz!=oldzpos)||force_lcd_update)
374
   if((currentz!=oldzpos)||force_lcd_update)
373
   {
375
   {
374
     lcd.setCursor(10,1);
376
     lcd.setCursor(10,1);
375
-    lcdprintPGM("Z:");lcd.print(ftostr32(current_position[2]));
377
+    lcdprintPGM("Z:");lcd.print(ftostr52(current_position[2]));
376
     oldzpos=currentz;
378
     oldzpos=currentz;
377
   }
379
   }
378
   static int oldfeedmultiply=0;
380
   static int oldfeedmultiply=0;
411
      lcd.setCursor(7,2);
413
      lcd.setCursor(7,2);
412
     lcd.print(itostr3((int)percent));
414
     lcd.print(itostr3((int)percent));
413
     lcdprintPGM("%SD");
415
     lcdprintPGM("%SD");
414
-    
415
   }
416
   }
416
   
417
   
417
 #else //smaller LCDS----------------------------------
418
 #else //smaller LCDS----------------------------------
457
   force_lcd_update=false;
458
   force_lcd_update=false;
458
 }
459
 }
459
 
460
 
460
-enum {ItemP_exit, ItemP_autostart,ItemP_disstep,ItemP_home, ItemP_origin, ItemP_preheat, ItemP_cooldown,/*ItemP_extrude,*/ItemP_move};
461
+enum {ItemP_exit, ItemP_autostart,ItemP_disstep,ItemP_home, ItemP_origin, ItemP_preheat_pla, ItemP_preheat_abs, ItemP_cooldown,/*ItemP_extrude,*/ItemP_move};
461
 
462
 
462
 //any action must not contain a ',' character anywhere, or this breaks:
463
 //any action must not contain a ',' character anywhere, or this breaks:
463
 #define MENUITEM(repaint_action, click_action) \
464
 #define MENUITEM(repaint_action, click_action) \
476
   switch(i)
477
   switch(i)
477
   {
478
   {
478
     case ItemP_exit:
479
     case ItemP_exit:
479
-      MENUITEM(  lcdprintPGM(" Main \003")  ,  BLOCK;status=Main_Menu;beepshort(); ) ;
480
+      MENUITEM(  lcdprintPGM(MSG_MAIN)  ,  BLOCK;status=Main_Menu;beepshort(); ) ;
480
       break;
481
       break;
481
     case ItemP_autostart:
482
     case ItemP_autostart:
482
-      MENUITEM(  lcdprintPGM(" Autostart")  ,  BLOCK;card.lastnr=0;card.setroot();card.checkautostart(true);beepshort(); ) ;
483
+      MENUITEM(  lcdprintPGM(MSG_AUTOSTART)  ,  BLOCK;card.lastnr=0;card.setroot();card.checkautostart(true);beepshort(); ) ;
483
       break;
484
       break;
484
     case ItemP_disstep:
485
     case ItemP_disstep:
485
-      MENUITEM(  lcdprintPGM(" Disable Steppers")  ,  BLOCK;enquecommand("M84");beepshort(); ) ;
486
+      MENUITEM(  lcdprintPGM(MSG_DISABLE_STEPPERS)  ,  BLOCK;enquecommand("M84");beepshort(); ) ;
486
       break;
487
       break;
487
     case ItemP_home:
488
     case ItemP_home:
488
-      MENUITEM(  lcdprintPGM(" Auto Home")  ,  BLOCK;enquecommand("G28 X0 Y0 Z0");beepshort(); ) ;
489
+      MENUITEM(  lcdprintPGM(MSG_AUTO_HOME)  ,  BLOCK;enquecommand("G28");beepshort(); ) ;
489
       break;
490
       break;
490
     case ItemP_origin:
491
     case ItemP_origin:
491
-      MENUITEM(  lcdprintPGM(" Set Origin")  ,  BLOCK;enquecommand("G92 X0 Y0 Z0");beepshort(); ) ;
492
+      MENUITEM(  lcdprintPGM(MSG_SET_ORIGIN)  ,  BLOCK;enquecommand("G92 X0 Y0 Z0");beepshort(); ) ;
492
       break;
493
       break;
493
-    case ItemP_preheat:
494
-      MENUITEM(  lcdprintPGM(" Preheat")  ,  BLOCK;setTargetHotend0(227);setTargetBed(105);beepshort(); ) ;
494
+    case ItemP_preheat_pla:
495
+      MENUITEM(  lcdprintPGM(MSG_PREHEAT_PLA)  ,  BLOCK;setTargetHotend0(PLA_PREHEAT_HOTEND_TEMP);setTargetBed(PLA_PREHEAT_HPB_TEMP);analogWrite(FAN_PIN, PLA_PREHEAT_FAN_SPEED); beepshort(); ) ;
496
+      break;
497
+    case ItemP_preheat_abs:
498
+      MENUITEM(  lcdprintPGM(MSG_PREHEAT_ABS)  ,  BLOCK;setTargetHotend0(ABS_PREHEAT_HOTEND_TEMP);setTargetBed(ABS_PREHEAT_HPB_TEMP); analogWrite(FAN_PIN, ABS_PREHEAT_FAN_SPEED); beepshort(); ) ;
495
       break;
499
       break;
496
     case ItemP_cooldown:
500
     case ItemP_cooldown:
497
-      MENUITEM(  lcdprintPGM(" Cooldown")  ,  BLOCK;setTargetHotend0(0);setTargetBed(0);beepshort(); ) ;
501
+      MENUITEM(  lcdprintPGM(MSG_COOLDOWN)  ,  BLOCK;setTargetHotend0(0);setTargetBed(0);beepshort(); ) ;
498
       break;
502
       break;
499
 //    case ItemP_extrude:
503
 //    case ItemP_extrude:
500
   //    MENUITEM(  lcdprintPGM(" Extrude")  ,  BLOCK;enquecommand("G92 E0");enquecommand("G1 F700 E50");beepshort(); ) ;
504
   //    MENUITEM(  lcdprintPGM(" Extrude")  ,  BLOCK;enquecommand("G92 E0");enquecommand("G1 F700 E50");beepshort(); ) ;
501
     //  break;
505
     //  break;
502
     case ItemP_move:
506
     case ItemP_move:
503
-      MENUITEM(  lcdprintPGM(" Move Axis      \x7E") , BLOCK;status=Sub_PrepareMove;beepshort(); );
507
+      MENUITEM(  lcdprintPGM(MSG_MOVE_AXIS) , BLOCK;status=Sub_PrepareMove;beepshort(); );
504
       break;
508
       break;
505
         default:   
509
         default:   
506
       break;
510
       break;
533
                   if(force_lcd_update)
537
                   if(force_lcd_update)
534
                   {
538
                   {
535
                     lcd.setCursor(0,line);lcdprintPGM(" X:");
539
                     lcd.setCursor(0,line);lcdprintPGM(" X:");
536
-                    lcd.setCursor(13,line);lcd.print(ftostr32(current_position[X_AXIS]));
540
+                    lcd.setCursor(11,line);lcd.print(ftostr52(current_position[X_AXIS]));
537
                   }
541
                   }
538
       
542
       
539
                   if((activeline!=line) )
543
                   if((activeline!=line) )
569
 			oldencoderpos=encoderpos;
573
 			oldencoderpos=encoderpos;
570
                         encoderpos=0;
574
                         encoderpos=0;
571
 		    }
575
 		    }
572
-                    lcd.setCursor(13,line);lcd.print(ftostr32(current_position[X_AXIS]));
576
+                    lcd.setCursor(11,line);lcd.print(ftostr52(current_position[X_AXIS]));
573
                   }
577
                   }
574
           }
578
           }
575
           break;
579
           break;
578
                   if(force_lcd_update)
582
                   if(force_lcd_update)
579
                   {
583
                   {
580
                     lcd.setCursor(0,line);lcdprintPGM(" Y:");
584
                     lcd.setCursor(0,line);lcdprintPGM(" Y:");
581
-                    lcd.setCursor(13,line);lcd.print(ftostr32(current_position[Y_AXIS]));
585
+                    lcd.setCursor(11,line);lcd.print(ftostr52(current_position[Y_AXIS]));
582
                   }
586
                   }
583
       
587
       
584
                   if((activeline!=line) )
588
                   if((activeline!=line) )
614
 			oldencoderpos=encoderpos;
618
 			oldencoderpos=encoderpos;
615
                         encoderpos=0;
619
                         encoderpos=0;
616
 		    }
620
 		    }
617
-                    lcd.setCursor(13,line);lcd.print(ftostr32(current_position[Y_AXIS]));
621
+                    lcd.setCursor(11,line);lcd.print(ftostr52(current_position[Y_AXIS]));
618
                   }
622
                   }
619
           }
623
           }
620
           break;
624
           break;
623
                   if(force_lcd_update)
627
                   if(force_lcd_update)
624
                   {
628
                   {
625
                     lcd.setCursor(0,line);lcdprintPGM(" Z:");
629
                     lcd.setCursor(0,line);lcdprintPGM(" Z:");
626
-                    lcd.setCursor(13,line);lcd.print(ftostr32(current_position[Z_AXIS]));
630
+                    lcd.setCursor(11,line);lcd.print(ftostr52(current_position[Z_AXIS]));
627
                   }
631
                   }
628
       
632
       
629
                   if((activeline!=line) )
633
                   if((activeline!=line) )
659
 			oldencoderpos=encoderpos;
663
 			oldencoderpos=encoderpos;
660
                         encoderpos=0;
664
                         encoderpos=0;
661
 		    }
665
 		    }
662
-                    lcd.setCursor(13,line);lcd.print(ftostr32(current_position[Z_AXIS]));
666
+                    lcd.setCursor(11,line);lcd.print(ftostr52(current_position[Z_AXIS]));
663
                   }
667
                   }
664
           }
668
           }
665
           break;
669
           break;
666
           case ItemAM_E:
670
           case ItemAM_E:
667
-          MENUITEM(  lcdprintPGM(" Extrude")  ,  BLOCK;enquecommand("G92 E0");enquecommand("G1 F700 E5");beepshort(); ) ;
671
+          MENUITEM(  lcdprintPGM(MSG_EXTRUDE)  ,  BLOCK;enquecommand("G92 E0");enquecommand("G1 F700 E5");beepshort(); ) ;
668
           break;
672
           break;
669
           default:
673
           default:
670
           break;
674
           break;
690
   switch(i)
694
   switch(i)
691
   {
695
   {
692
   case ItemT_exit:
696
   case ItemT_exit:
693
-      MENUITEM(  lcdprintPGM(" Main \003")  ,  BLOCK;status=Main_Menu;beepshort(); ) ;
697
+      MENUITEM(  lcdprintPGM(MSG_MAIN)  ,  BLOCK;status=Main_Menu;beepshort(); ) ;
694
       break;
698
       break;
695
   case ItemT_speed:
699
   case ItemT_speed:
696
     {
700
     {
697
       if(force_lcd_update)
701
       if(force_lcd_update)
698
       {
702
       {
699
-        lcd.setCursor(0,line);lcdprintPGM(" Speed:");
703
+        lcd.setCursor(0,line);lcdprintPGM(MSG_SPEED);
700
         lcd.setCursor(13,line);lcd.print(ftostr3(feedmultiply));
704
         lcd.setCursor(13,line);lcd.print(ftostr3(feedmultiply));
701
       }
705
       }
702
       
706
       
703
       if((activeline!=line) )
707
       if((activeline!=line) )
704
         break;
708
         break;
705
       
709
       
706
-      if(CLICKED) //nalogWrite(FAN_PIN,  fanpwm);
710
+      if(CLICKED) //AnalogWrite(FAN_PIN,  fanpwm);
707
       {
711
       {
708
         linechanging=!linechanging;
712
         linechanging=!linechanging;
709
         if(linechanging)
713
         if(linechanging)
731
       {
735
       {
732
         if(force_lcd_update)
736
         if(force_lcd_update)
733
         {
737
         {
734
-          lcd.setCursor(0,line);lcdprintPGM(" \002Nozzle:");
738
+          lcd.setCursor(0,line);lcdprintPGM(MSG_NOZZLE);
735
           lcd.setCursor(13,line);lcd.print(ftostr3(intround(degTargetHotend0())));
739
           lcd.setCursor(13,line);lcd.print(ftostr3(intround(degTargetHotend0())));
736
         }
740
         }
737
         
741
         
765
       {
769
       {
766
         if(force_lcd_update)
770
         if(force_lcd_update)
767
         {
771
         {
768
-          lcd.setCursor(0,line);lcdprintPGM(" \002Bed:");
772
+          lcd.setCursor(0,line);lcdprintPGM(MSG_BED);
769
           lcd.setCursor(13,line);lcd.print(ftostr3(intround(degTargetBed())));
773
           lcd.setCursor(13,line);lcd.print(ftostr3(intround(degTargetBed())));
770
         }
774
         }
771
         
775
         
836
          {
840
          {
837
       if(force_lcd_update)
841
       if(force_lcd_update)
838
         {
842
         {
839
-          lcd.setCursor(0,line);lcdprintPGM(" Flow:");
843
+          lcd.setCursor(0,line);lcdprintPGM(MSG_FLOW);
840
           lcd.setCursor(13,line);lcd.print(itostr4(axis_steps_per_unit[3]));
844
           lcd.setCursor(13,line);lcd.print(itostr4(axis_steps_per_unit[3]));
841
         }
845
         }
842
         
846
         
917
   switch(i)
921
   switch(i)
918
   {
922
   {
919
     case ItemCT_exit:
923
     case ItemCT_exit:
920
-      MENUITEM(  lcdprintPGM(" Control \003")  ,  BLOCK;status=Main_Control;beepshort(); ) ;
924
+      MENUITEM(  lcdprintPGM(MSG_CONTROL)  ,  BLOCK;status=Main_Control;beepshort(); ) ;
921
       break;
925
       break;
922
     case ItemCT_nozzle:
926
     case ItemCT_nozzle:
923
       {
927
       {
924
         if(force_lcd_update)
928
         if(force_lcd_update)
925
         {
929
         {
926
-          lcd.setCursor(0,line);lcdprintPGM(" \002Nozzle:");
930
+          lcd.setCursor(0,line);lcdprintPGM(MSG_NOZZLE);
927
           lcd.setCursor(13,line);lcd.print(ftostr3(intround(degTargetHotend0())));
931
           lcd.setCursor(13,line);lcd.print(ftostr3(intround(degTargetHotend0())));
928
         }
932
         }
929
         
933
         
958
       {
962
       {
959
         if(force_lcd_update)
963
         if(force_lcd_update)
960
         {
964
         {
961
-          lcd.setCursor(0,line);lcdprintPGM(" \002 Min:");
965
+          lcd.setCursor(0,line);lcdprintPGM(MSG_MIN);
962
           lcd.setCursor(13,line);lcd.print(ftostr3(autotemp_min));
966
           lcd.setCursor(13,line);lcd.print(ftostr3(autotemp_min));
963
         }
967
         }
964
         
968
         
992
       {
996
       {
993
         if(force_lcd_update)
997
         if(force_lcd_update)
994
         {
998
         {
995
-          lcd.setCursor(0,line);lcdprintPGM(" \002 Max:");
999
+          lcd.setCursor(0,line);lcdprintPGM(MSG_MAX);
996
           lcd.setCursor(13,line);lcd.print(ftostr3(autotemp_max));
1000
           lcd.setCursor(13,line);lcd.print(ftostr3(autotemp_max));
997
         }
1001
         }
998
         
1002
         
1026
       {
1030
       {
1027
         if(force_lcd_update)
1031
         if(force_lcd_update)
1028
         {
1032
         {
1029
-          lcd.setCursor(0,line);lcdprintPGM(" \002 Fact:");
1033
+          lcd.setCursor(0,line);lcdprintPGM(MSG_FACTOR);
1030
           lcd.setCursor(13,line);lcd.print(ftostr32(autotemp_factor));
1034
           lcd.setCursor(13,line);lcd.print(ftostr32(autotemp_factor));
1031
         }
1035
         }
1032
         
1036
         
1060
       {
1064
       {
1061
         if(force_lcd_update)
1065
         if(force_lcd_update)
1062
         {
1066
         {
1063
-          lcd.setCursor(0,line);lcdprintPGM(" Autotemp:");
1067
+          lcd.setCursor(0,line);lcdprintPGM(MSG_AUTOTEMP);
1064
           lcd.setCursor(13,line);
1068
           lcd.setCursor(13,line);
1065
           if(autotemp_enabled)
1069
           if(autotemp_enabled)
1066
-            lcdprintPGM("On");
1070
+            lcdprintPGM(MSG_ON);
1067
           else
1071
           else
1068
-            lcdprintPGM("Off");
1072
+            lcdprintPGM(MSG_OFF);
1069
         }
1073
         }
1070
         
1074
         
1071
         if((activeline!=line) )
1075
         if((activeline!=line) )
1076
           autotemp_enabled=!autotemp_enabled;
1080
           autotemp_enabled=!autotemp_enabled;
1077
           lcd.setCursor(13,line);
1081
           lcd.setCursor(13,line);
1078
           if(autotemp_enabled)
1082
           if(autotemp_enabled)
1079
-            lcdprintPGM("On ");
1083
+            lcdprintPGM(MSG_ON);
1080
           else
1084
           else
1081
-            lcdprintPGM("Off");
1085
+            lcdprintPGM(MSG_OFF);
1082
           BLOCK;
1086
           BLOCK;
1083
         }
1087
         }
1084
         
1088
         
1089
       {
1093
       {
1090
         if(force_lcd_update)
1094
         if(force_lcd_update)
1091
         {
1095
         {
1092
-          lcd.setCursor(0,line);lcdprintPGM(" \002Bed:");
1096
+          lcd.setCursor(0,line);lcdprintPGM(MSG_BED);
1093
           lcd.setCursor(13,line);lcd.print(ftostr3(intround(degTargetBed())));
1097
           lcd.setCursor(13,line);lcd.print(ftostr3(intround(degTargetBed())));
1094
         }
1098
         }
1095
         
1099
         
1123
       {
1127
       {
1124
         if(force_lcd_update)
1128
         if(force_lcd_update)
1125
         {
1129
         {
1126
-          lcd.setCursor(0,line);lcdprintPGM(" Fan speed:");
1130
+          lcd.setCursor(0,line);lcdprintPGM(MSG_FAN_SPEED);
1127
           lcd.setCursor(13,line);lcd.print(ftostr3(fanpwm));
1131
           lcd.setCursor(13,line);lcd.print(ftostr3(fanpwm));
1128
         }
1132
         }
1129
         
1133
         
1193
       {
1197
       {
1194
       if(force_lcd_update)
1198
       if(force_lcd_update)
1195
         {
1199
         {
1196
-          lcd.setCursor(0,line);lcdprintPGM(" PID-I: ");
1200
+          lcd.setCursor(0,line);lcdprintPGM(MSG_PID_I);
1197
           lcd.setCursor(13,line);lcd.print(ftostr51(Ki/PID_dT));
1201
           lcd.setCursor(13,line);lcd.print(ftostr51(Ki/PID_dT));
1198
         }
1202
         }
1199
         
1203
         
1228
       {
1232
       {
1229
       if(force_lcd_update)
1233
       if(force_lcd_update)
1230
         {
1234
         {
1231
-          lcd.setCursor(0,line);lcdprintPGM(" PID-D: ");
1235
+          lcd.setCursor(0,line);lcdprintPGM(MSG_PID_D);
1232
           lcd.setCursor(13,line);lcd.print(itostr4(Kd*PID_dT));
1236
           lcd.setCursor(13,line);lcd.print(itostr4(Kd*PID_dT));
1233
         }
1237
         }
1234
         
1238
         
1265
       {
1269
       {
1266
       if(force_lcd_update)
1270
       if(force_lcd_update)
1267
         {
1271
         {
1268
-          lcd.setCursor(0,line);lcdprintPGM(" PID-C: ");
1272
+          lcd.setCursor(0,line);lcdprintPGM(MSG_PID_C);
1269
           lcd.setCursor(13,line);lcd.print(itostr3(Kc));
1273
           lcd.setCursor(13,line);lcd.print(itostr3(Kc));
1270
         }
1274
         }
1271
         
1275
         
1331
   switch(i)
1335
   switch(i)
1332
   {
1336
   {
1333
     case ItemCM_exit:
1337
     case ItemCM_exit:
1334
-      MENUITEM(  lcdprintPGM(" Control \003")  ,  BLOCK;status=Main_Control;beepshort(); ) ;
1338
+      MENUITEM(  lcdprintPGM(MSG_CONTROL)  ,  BLOCK;status=Main_Control;beepshort(); ) ;
1335
       break;
1339
       break;
1336
     case ItemCM_acc:
1340
     case ItemCM_acc:
1337
     {
1341
     {
1338
       if(force_lcd_update)
1342
       if(force_lcd_update)
1339
         {
1343
         {
1340
-          lcd.setCursor(0,line);lcdprintPGM(" Acc:");
1344
+          lcd.setCursor(0,line);lcdprintPGM(MSG_ACC);
1341
           lcd.setCursor(13,line);lcd.print(itostr3(acceleration/100));lcdprintPGM("00");
1345
           lcd.setCursor(13,line);lcd.print(itostr3(acceleration/100));lcdprintPGM("00");
1342
         }
1346
         }
1343
         
1347
         
1371
       {
1375
       {
1372
       if(force_lcd_update)
1376
       if(force_lcd_update)
1373
         {
1377
         {
1374
-          lcd.setCursor(0,line);lcdprintPGM(" Vxy-jerk: ");
1378
+          lcd.setCursor(0,line);lcdprintPGM(MSG_VXY_JERK);
1375
           lcd.setCursor(13,line);lcd.print(itostr3(max_xy_jerk));
1379
           lcd.setCursor(13,line);lcd.print(itostr3(max_xy_jerk));
1376
         }
1380
         }
1377
         
1381
         
1410
       {
1414
       {
1411
       if(force_lcd_update)
1415
       if(force_lcd_update)
1412
         {
1416
         {
1413
-          lcd.setCursor(0,line);lcdprintPGM(" Vmax ");
1414
-          if(i==ItemCM_vmaxx)lcdprintPGM("x:");
1415
-          if(i==ItemCM_vmaxy)lcdprintPGM("y:");
1416
-          if(i==ItemCM_vmaxz)lcdprintPGM("z:");
1417
-          if(i==ItemCM_vmaxe)lcdprintPGM("e:");
1417
+          lcd.setCursor(0,line);lcdprintPGM(MSG_VMAX);
1418
+          if(i==ItemCM_vmaxx)lcdprintPGM(MSG_X);
1419
+          if(i==ItemCM_vmaxy)lcdprintPGM(MSG_Y);
1420
+          if(i==ItemCM_vmaxz)lcdprintPGM(MSG_Z);
1421
+          if(i==ItemCM_vmaxe)lcdprintPGM(MSG_E);
1418
           lcd.setCursor(13,line);lcd.print(itostr3(max_feedrate[i-ItemCM_vmaxx]));
1422
           lcd.setCursor(13,line);lcd.print(itostr3(max_feedrate[i-ItemCM_vmaxx]));
1419
         }
1423
         }
1420
         
1424
         
1450
     {
1454
     {
1451
       if(force_lcd_update)
1455
       if(force_lcd_update)
1452
         {
1456
         {
1453
-          lcd.setCursor(0,line);lcdprintPGM(" Vmin:");
1457
+          lcd.setCursor(0,line);lcdprintPGM(MSG_VMIN);
1454
           lcd.setCursor(13,line);lcd.print(itostr3(minimumfeedrate));
1458
           lcd.setCursor(13,line);lcd.print(itostr3(minimumfeedrate));
1455
         }
1459
         }
1456
         
1460
         
1485
     {
1489
     {
1486
       if(force_lcd_update)
1490
       if(force_lcd_update)
1487
         {
1491
         {
1488
-          lcd.setCursor(0,line);lcdprintPGM(" VTrav min:");
1492
+          lcd.setCursor(0,line);lcdprintPGM(MSG_VTRAV_MIN);
1489
           lcd.setCursor(13,line);lcd.print(itostr3(mintravelfeedrate));
1493
           lcd.setCursor(13,line);lcd.print(itostr3(mintravelfeedrate));
1490
         }
1494
         }
1491
         
1495
         
1525
       if(force_lcd_update)
1529
       if(force_lcd_update)
1526
         {
1530
         {
1527
           lcd.setCursor(0,line);lcdprintPGM(" Amax ");
1531
           lcd.setCursor(0,line);lcdprintPGM(" Amax ");
1528
-          if(i==ItemCM_amaxx)lcdprintPGM("x:");
1529
-          if(i==ItemCM_amaxy)lcdprintPGM("y:");
1530
-          if(i==ItemCM_amaxz)lcdprintPGM("z:");
1531
-          if(i==ItemCM_amaxe)lcdprintPGM("e:");
1532
+          if(i==ItemCM_amaxx)lcdprintPGM(MSG_X);
1533
+          if(i==ItemCM_amaxy)lcdprintPGM(MSG_Y);
1534
+          if(i==ItemCM_amaxz)lcdprintPGM(MSG_Z);
1535
+          if(i==ItemCM_amaxe)lcdprintPGM(MSG_E);
1532
           lcd.setCursor(13,line);lcd.print(itostr3(max_acceleration_units_per_sq_second[i-ItemCM_amaxx]/100));lcdprintPGM("00");
1536
           lcd.setCursor(13,line);lcd.print(itostr3(max_acceleration_units_per_sq_second[i-ItemCM_amaxx]/100));lcdprintPGM("00");
1533
         }
1537
         }
1534
         
1538
         
1562
     {
1566
     {
1563
         if(force_lcd_update)
1567
         if(force_lcd_update)
1564
         {
1568
         {
1565
-          lcd.setCursor(0,line);lcdprintPGM(" A-retract:");
1569
+          lcd.setCursor(0,line);lcdprintPGM(MSG_A_RETRACT);
1566
           lcd.setCursor(13,line);lcd.print(ftostr3(retract_acceleration/100));lcdprintPGM("00");
1570
           lcd.setCursor(13,line);lcd.print(ftostr3(retract_acceleration/100));lcdprintPGM("00");
1567
         }
1571
         }
1568
         
1572
         
1597
          {
1601
          {
1598
       if(force_lcd_update)
1602
       if(force_lcd_update)
1599
         {
1603
         {
1600
-          lcd.setCursor(0,line);lcdprintPGM(" X steps/mm:");
1601
-          lcd.setCursor(13,line);lcd.print(itostr4(axis_steps_per_unit[0]));
1604
+          lcd.setCursor(0,line);lcdprintPGM(MSG_XSTEPS);
1605
+          lcd.setCursor(11,line);lcd.print(ftostr52(axis_steps_per_unit[0]));
1602
         }
1606
         }
1603
         
1607
         
1604
         if((activeline!=line) )
1608
         if((activeline!=line) )
1609
           linechanging=!linechanging;
1613
           linechanging=!linechanging;
1610
           if(linechanging)
1614
           if(linechanging)
1611
           {
1615
           {
1612
-              encoderpos=(int)axis_steps_per_unit[0];
1616
+              encoderpos=(int)(axis_steps_per_unit[0]*100.0);
1613
           }
1617
           }
1614
           else
1618
           else
1615
           {
1619
           {
1616
-            float factor=float(encoderpos)/float(axis_steps_per_unit[0]);
1620
+            float factor=float(encoderpos)/100.0/float(axis_steps_per_unit[0]);
1617
             position[X_AXIS]=lround(position[X_AXIS]*factor);
1621
             position[X_AXIS]=lround(position[X_AXIS]*factor);
1618
             //current_position[3]*=factor;
1622
             //current_position[3]*=factor;
1619
-            axis_steps_per_unit[X_AXIS]= encoderpos;
1623
+            axis_steps_per_unit[X_AXIS]= encoderpos/100.0;
1620
             encoderpos=activeline*lcdslow;
1624
             encoderpos=activeline*lcdslow;
1621
-              
1622
           }
1625
           }
1623
           BLOCK;
1626
           BLOCK;
1624
           beepshort();
1627
           beepshort();
1626
         if(linechanging)
1629
         if(linechanging)
1627
         {
1630
         {
1628
           if(encoderpos<5) encoderpos=5;
1631
           if(encoderpos<5) encoderpos=5;
1629
-          if(encoderpos>9999) encoderpos=9999;
1630
-          lcd.setCursor(13,line);lcd.print(itostr4(encoderpos));
1632
+          if(encoderpos>99999) encoderpos=99999;
1633
+          lcd.setCursor(11,line);lcd.print(ftostr52(encoderpos/100.0));
1631
         }
1634
         }
1632
         
1635
         
1633
       }break;
1636
       }break;
1635
          {
1638
          {
1636
       if(force_lcd_update)
1639
       if(force_lcd_update)
1637
         {
1640
         {
1638
-          lcd.setCursor(0,line);lcdprintPGM(" Y steps/mm:");
1639
-          lcd.setCursor(13,line);lcd.print(itostr4(axis_steps_per_unit[1]));
1641
+          lcd.setCursor(0,line);lcdprintPGM(MSG_YSTEPS);
1642
+          lcd.setCursor(11,line);lcd.print(ftostr52(axis_steps_per_unit[1]));
1640
         }
1643
         }
1641
         
1644
         
1642
         if((activeline!=line) )
1645
         if((activeline!=line) )
1647
           linechanging=!linechanging;
1650
           linechanging=!linechanging;
1648
           if(linechanging)
1651
           if(linechanging)
1649
           {
1652
           {
1650
-              encoderpos=(int)axis_steps_per_unit[1];
1653
+              encoderpos=(int)(axis_steps_per_unit[1]*100.0);
1651
           }
1654
           }
1652
           else
1655
           else
1653
           {
1656
           {
1654
-            float factor=float(encoderpos)/float(axis_steps_per_unit[1]);
1657
+            float factor=float(encoderpos)/100.0/float(axis_steps_per_unit[1]);
1655
             position[Y_AXIS]=lround(position[Y_AXIS]*factor);
1658
             position[Y_AXIS]=lround(position[Y_AXIS]*factor);
1656
             //current_position[3]*=factor;
1659
             //current_position[3]*=factor;
1657
-            axis_steps_per_unit[Y_AXIS]= encoderpos;
1660
+            axis_steps_per_unit[Y_AXIS]= encoderpos/100.0;
1658
             encoderpos=activeline*lcdslow;
1661
             encoderpos=activeline*lcdslow;
1659
               
1662
               
1660
           }
1663
           }
1665
         {
1668
         {
1666
           if(encoderpos<5) encoderpos=5;
1669
           if(encoderpos<5) encoderpos=5;
1667
           if(encoderpos>9999) encoderpos=9999;
1670
           if(encoderpos>9999) encoderpos=9999;
1668
-          lcd.setCursor(13,line);lcd.print(itostr4(encoderpos));
1671
+          lcd.setCursor(11,line);lcd.print(ftostr52(encoderpos/100.0));
1669
         }
1672
         }
1670
         
1673
         
1671
       }break;
1674
       }break;
1673
          {
1676
          {
1674
       if(force_lcd_update)
1677
       if(force_lcd_update)
1675
         {
1678
         {
1676
-          lcd.setCursor(0,line);lcdprintPGM(" Z steps/mm:");
1677
-          lcd.setCursor(13,line);lcd.print(itostr4(axis_steps_per_unit[2]));
1679
+          lcd.setCursor(0,line);lcdprintPGM(MSG_ZSTEPS);
1680
+          lcd.setCursor(11,line);lcd.print(ftostr52(axis_steps_per_unit[2]));
1678
         }
1681
         }
1679
         
1682
         
1680
         if((activeline!=line) )
1683
         if((activeline!=line) )
1685
           linechanging=!linechanging;
1688
           linechanging=!linechanging;
1686
           if(linechanging)
1689
           if(linechanging)
1687
           {
1690
           {
1688
-              encoderpos=(int)axis_steps_per_unit[2];
1691
+              encoderpos=(int)(axis_steps_per_unit[2]*100.0);
1689
           }
1692
           }
1690
           else
1693
           else
1691
           {
1694
           {
1692
-            float factor=float(encoderpos)/float(axis_steps_per_unit[2]);
1695
+            float factor=float(encoderpos)/100.0/float(axis_steps_per_unit[2]);
1693
             position[Z_AXIS]=lround(position[Z_AXIS]*factor);
1696
             position[Z_AXIS]=lround(position[Z_AXIS]*factor);
1694
             //current_position[3]*=factor;
1697
             //current_position[3]*=factor;
1695
-            axis_steps_per_unit[Z_AXIS]= encoderpos;
1698
+            axis_steps_per_unit[Z_AXIS]= encoderpos/100.0;
1696
             encoderpos=activeline*lcdslow;
1699
             encoderpos=activeline*lcdslow;
1697
               
1700
               
1698
           }
1701
           }
1703
         {
1706
         {
1704
           if(encoderpos<5) encoderpos=5;
1707
           if(encoderpos<5) encoderpos=5;
1705
           if(encoderpos>9999) encoderpos=9999;
1708
           if(encoderpos>9999) encoderpos=9999;
1706
-          lcd.setCursor(13,line);lcd.print(itostr4(encoderpos));
1709
+          lcd.setCursor(11,line);lcd.print(ftostr52(encoderpos/100.0));
1707
         }
1710
         }
1708
         
1711
         
1709
       }break;
1712
       }break;
1712
          {
1715
          {
1713
       if(force_lcd_update)
1716
       if(force_lcd_update)
1714
         {
1717
         {
1715
-          lcd.setCursor(0,line);lcdprintPGM(" E steps/mm:");
1716
-          lcd.setCursor(13,line);lcd.print(itostr4(axis_steps_per_unit[3]));
1718
+          lcd.setCursor(0,line);lcdprintPGM(MSG_ESTEPS);
1719
+          lcd.setCursor(11,line);lcd.print(ftostr52(axis_steps_per_unit[3]));
1717
         }
1720
         }
1718
         
1721
         
1719
         if((activeline!=line) )
1722
         if((activeline!=line) )
1724
           linechanging=!linechanging;
1727
           linechanging=!linechanging;
1725
           if(linechanging)
1728
           if(linechanging)
1726
           {
1729
           {
1727
-              encoderpos=(int)axis_steps_per_unit[3];
1730
+              encoderpos=(int)(axis_steps_per_unit[3]*100.0);
1728
           }
1731
           }
1729
           else
1732
           else
1730
           {
1733
           {
1731
-            float factor=float(encoderpos)/float(axis_steps_per_unit[3]);
1734
+            float factor=float(encoderpos)/100.0/float(axis_steps_per_unit[3]);
1732
             position[E_AXIS]=lround(position[E_AXIS]*factor);
1735
             position[E_AXIS]=lround(position[E_AXIS]*factor);
1733
             //current_position[3]*=factor;
1736
             //current_position[3]*=factor;
1734
-            axis_steps_per_unit[E_AXIS]= encoderpos;
1737
+            axis_steps_per_unit[E_AXIS]= encoderpos/100.0;
1735
             encoderpos=activeline*lcdslow;
1738
             encoderpos=activeline*lcdslow;
1736
               
1739
               
1737
           }
1740
           }
1742
         {
1745
         {
1743
           if(encoderpos<5) encoderpos=5;
1746
           if(encoderpos<5) encoderpos=5;
1744
           if(encoderpos>9999) encoderpos=9999;
1747
           if(encoderpos>9999) encoderpos=9999;
1745
-          lcd.setCursor(13,line);lcd.print(itostr4(encoderpos));
1748
+          lcd.setCursor(11,line);lcd.print(ftostr52(encoderpos/100.0));
1746
         }
1749
         }
1747
         
1750
         
1748
       }break; 
1751
       }break; 
1769
   switch(i)
1772
   switch(i)
1770
   {
1773
   {
1771
     case ItemC_exit:
1774
     case ItemC_exit:
1772
-      MENUITEM(  lcdprintPGM(" Main        \003")  ,  BLOCK;status=Main_Menu;beepshort(); ) ;
1775
+      MENUITEM(  lcdprintPGM(MSG_MAIN_WIDE)  ,  BLOCK;status=Main_Menu;beepshort(); ) ;
1773
       break;
1776
       break;
1774
     case ItemC_temp:
1777
     case ItemC_temp:
1775
-      MENUITEM(  lcdprintPGM(" Temperature \x7E")  ,  BLOCK;status=Sub_TempControl;beepshort(); ) ;
1778
+      MENUITEM(  lcdprintPGM(MSG_TEMPERATURE_WIDE)  ,  BLOCK;status=Sub_TempControl;beepshort(); ) ;
1776
       break;
1779
       break;
1777
    case ItemC_move:
1780
    case ItemC_move:
1778
-      MENUITEM(  lcdprintPGM(" Motion      \x7E")  ,  BLOCK;status=Sub_MotionControl;beepshort(); ) ;
1781
+      MENUITEM(  lcdprintPGM(MSG_MOTION_WIDE)  ,  BLOCK;status=Sub_MotionControl;beepshort(); ) ;
1779
       break;
1782
       break;
1780
     case ItemC_store:
1783
     case ItemC_store:
1781
     {
1784
     {
1782
       if(force_lcd_update)
1785
       if(force_lcd_update)
1783
       {
1786
       {
1784
-        lcd.setCursor(0,line);lcdprintPGM(" Store EPROM");
1787
+        lcd.setCursor(0,line);lcdprintPGM(MSG_STORE_EPROM);
1785
       }
1788
       }
1786
       if((activeline==line) && CLICKED)
1789
       if((activeline==line) && CLICKED)
1787
       {
1790
       {
1795
     {
1798
     {
1796
       if(force_lcd_update)
1799
       if(force_lcd_update)
1797
       {
1800
       {
1798
-        lcd.setCursor(0,line);lcdprintPGM(" Load EPROM");
1801
+        lcd.setCursor(0,line);lcdprintPGM(MSG_LOAD_EPROM);
1799
       }
1802
       }
1800
       if((activeline==line) && CLICKED)
1803
       if((activeline==line) && CLICKED)
1801
       {
1804
       {
1809
     {
1812
     {
1810
       if(force_lcd_update)
1813
       if(force_lcd_update)
1811
       {
1814
       {
1812
-        lcd.setCursor(0,line);lcdprintPGM(" Restore Failsafe");
1815
+        lcd.setCursor(0,line);lcdprintPGM(MSG_RESTORE_FAILSAFE);
1813
       }
1816
       }
1814
       if((activeline==line) && CLICKED)
1817
       if((activeline==line) && CLICKED)
1815
       {
1818
       {
1856
   switch(i)
1859
   switch(i)
1857
   {
1860
   {
1858
     case 0:
1861
     case 0:
1859
-      MENUITEM(  lcdprintPGM(" Main \003")  ,  BLOCK;status=Main_Menu;beepshort(); ) ;
1862
+      MENUITEM(  lcdprintPGM(MSG_MAIN)  ,  BLOCK;status=Main_Menu;beepshort(); ) ;
1860
       break;
1863
       break;
1861
 //     case 1:
1864
 //     case 1:
1862
 //       {
1865
 //       {
1887
 //         }
1890
 //         }
1888
 //       }break;
1891
 //       }break;
1889
     case 1:
1892
     case 1:
1890
-      MENUITEM(  lcd.print(" ");card.getWorkDirName();if(card.filename[0]=='/') lcdprintPGM("\004Refresh");else {lcd.print("\005");lcd.print(card.filename);lcd.print("/..");}  ,  BLOCK;card.updir();enforceupdate=true;lineoffset=0;beepshort(); ) ;
1893
+      MENUITEM(  lcd.print(" ");card.getWorkDirName();if(card.filename[0]=='/') lcdprintPGM(MSG_REFRESH);else {lcd.print("\005");lcd.print(card.filename);lcd.print("/..");}  ,  BLOCK;card.updir();enforceupdate=true;lineoffset=0;beepshort(); ) ;
1891
       
1894
       
1892
       break;
1895
       break;
1893
     default:
1896
     default:
1974
     switch(line)
1977
     switch(line)
1975
     { 
1978
     { 
1976
       case ItemM_watch:
1979
       case ItemM_watch:
1977
-        MENUITEM(  lcdprintPGM(" Watch   \003")  ,  BLOCK;status=Main_Status;beepshort(); ) ;
1980
+        MENUITEM(  lcdprintPGM(MSG_WATCH)  ,  BLOCK;status=Main_Status;beepshort(); ) ;
1978
        break;
1981
        break;
1979
       case ItemM_prepare:
1982
       case ItemM_prepare:
1980
-        MENUITEM(  if(!tune) lcdprintPGM(" Prepare \x7E");else  lcdprintPGM(" Tune    \x7E"); ,  BLOCK;status=Main_Prepare;beepshort(); ) ;
1983
+        MENUITEM(  if(!tune) lcdprintPGM(MSG_PREPARE);else  lcdprintPGM(MSG_TUNE); ,  BLOCK;status=Main_Prepare;beepshort(); ) ;
1981
       break;
1984
       break;
1982
        
1985
        
1983
       case ItemM_control:
1986
       case ItemM_control:
1984
-        MENUITEM(  lcdprintPGM(" Control \x7E")  ,  BLOCK;status=Main_Control;beepshort(); ) ;
1987
+        MENUITEM(  lcdprintPGM(MSG_CONTROL_ARROW)  ,  BLOCK;status=Main_Control;beepshort(); ) ;
1985
       break;
1988
       break;
1986
       #ifdef SDSUPPORT
1989
       #ifdef SDSUPPORT
1987
       case ItemM_file:    
1990
       case ItemM_file:    
1996
           #endif
1999
           #endif
1997
           {
2000
           {
1998
             if(card.sdprinting)
2001
             if(card.sdprinting)
1999
-              lcdprintPGM(" Stop Print   \x7E");
2002
+              lcdprintPGM(MSG_STOP_PRINT);
2000
             else
2003
             else
2001
-              lcdprintPGM(" Card Menu    \x7E");
2004
+              lcdprintPGM(MSG_CARD_MENU);
2002
           }
2005
           }
2003
           else
2006
           else
2004
           {
2007
           {
2005
-           lcdprintPGM(" No Card"); 
2008
+           lcdprintPGM(MSG_NO_CARD); 
2006
           }
2009
           }
2007
         }
2010
         }
2008
         #ifdef CARDINSERTED
2011
         #ifdef CARDINSERTED
2022
       #endif
2025
       #endif
2023
       default: 
2026
       default: 
2024
         SERIAL_ERROR_START;
2027
         SERIAL_ERROR_START;
2025
-        SERIAL_ERRORLNPGM("Something is wrong in the MenuStructure.");
2028
+        SERIAL_ERRORLNPGM(MSG_SERIAL_ERROR_MENU_STRUCTURE);
2026
       break;
2029
       break;
2027
     }
2030
     }
2028
   }
2031
   }
2043
       if(CARDINSERTED)
2046
       if(CARDINSERTED)
2044
       {
2047
       {
2045
         card.initsd();
2048
         card.initsd();
2046
-        LCD_MESSAGEPGM("Card inserted");
2049
+        LCD_MESSAGEPGM(MSG_SD_INSERTED);
2047
       }
2050
       }
2048
       else
2051
       else
2049
       {
2052
       {
2050
         card.release();
2053
         card.release();
2051
-        LCD_MESSAGEPGM("Card removed");
2054
+        LCD_MESSAGEPGM(MSG_SD_REMOVED);
2052
       }
2055
       }
2053
     }
2056
     }
2054
   #endif
2057
   #endif
2223
   return conv;
2226
   return conv;
2224
 }
2227
 }
2225
 
2228
 
2229
+//  convert float to string with +123.45 format
2230
+char *ftostr52(const float &x)
2231
+{
2232
+  int xx=x*100;
2233
+  conv[0]=(xx>=0)?'+':'-';
2234
+  xx=abs(xx);
2235
+  conv[1]=(xx/10000)%10+'0';
2236
+  conv[2]=(xx/1000)%10+'0';
2237
+  conv[3]=(xx/100)%10+'0';
2238
+  conv[4]='.';
2239
+  conv[5]=(xx/10)%10+'0';
2240
+  conv[6]=(xx)%10+'0';
2241
+  conv[7]=0;
2242
+  return conv;
2243
+}
2226
 
2244
 
2227
 #endif //ULTRA_LCD
2245
 #endif //ULTRA_LCD
2228
 
2246
 

+ 1
- 21
README.md 查看文件

1
-SCUBA82's fork:
2
------------------
3
-
4
-The main goal of my fork is porting the brilliant Marlin firmware to GEN7 Boards.
5
-I'm working on a 16MHz GEN7 board and have only tested with this configuration.
6
-But there were reports about successfully running it at 20 MHz. Expect 25% faster moves and maybe some other issues.
7
-
8
-Using lcd and sdcard support on an ATMega644(P) is not possible cause the sketch is way too big for its memory.
9
-I switched to an ATMega1284P which has double size program memory. Unfortunately it's not supported in Arduino IDE out of the box but expect a tutorial on how to compile for it soon. 
10
-For the necessary pin breakouts I used Alfons3 design of GEN7 (https://github.com/Alfons3/Generation_7_Electronics) with an additional breakout for pin A0/D31. 
11
-I'll publish my desing as soon as possible.
12
-
13
-You have to use different chip fuses to get Marlin running.
14
-The fuses I'm using are lfuse: 0xF7 hfuse: 0xD4 efuse: 0xFD
15
-
16
-For questions take a look into http://forums.reprap.org/read.php?181,118329 or send me an e-mail: christian_thalhammer@gmx.at
17
-
18
-
19
-Expect this fork to be highly experimental. 
20
-
21
 WARNING: 
1
 WARNING: 
22
 --------
2
 --------
23
-THIS IS RELEASE CANDIDATE 1 FOR MARLIN 1.0.0
3
+THIS IS RELEASE CANDIDATE 2 FOR MARLIN 1.0.0
24
 
4
 
25
 The configuration is now split in two files
5
 The configuration is now split in two files
26
 Configuration.h for the normal settings
6
 Configuration.h for the normal settings

Loading…
取消
儲存