Browse Source

reformating and some minor bugs/things found on the way.

Bernhard Kubicek 13 years ago
parent
commit
1d171e9e52

+ 47
- 42
Marlin/Configuration.h View File

@@ -1,5 +1,5 @@
1
-#ifndef CONFIGURATION_H
2
-#define CONFIGURATION_H
1
+#ifndef __CONFIGURATION_H
2
+#define __CONFIGURATION_H
3 3
 
4 4
 //#define DEBUG_STEPS
5 5
 
@@ -118,10 +118,7 @@ const int dropsegments=5; //everything with this number of steps  will be ignore
118 118
 #define NUM_AXIS 4 // The axis order in all axis related arrays is X, Y, Z, E
119 119
 //note: on bernhards ultimaker 200 200 12 are working well.
120 120
 #define HOMING_FEEDRATE {50*60, 50*60, 12*60, 0}  // set the homing speeds
121
-//the followint checks if an extrusion is existent in the move. if _not_, the speed of the move is set to the maximum speed. 
122
-//!!!!!!Use only if you know that your printer works at the maximum declared speeds.
123
-// works around the skeinforge cool-bug. There all moves are slowed to have a minimum layer time. However slow travel moves= ooze
124
-#define TRAVELING_AT_MAXSPEED  
121
+
125 122
 #define AXIS_RELATIVE_MODES {false, false, false, false}
126 123
 
127 124
 #define MAX_STEP_FREQUENCY 40000 // Max step frequency for Ultimaker (5000 pps / half step)
@@ -177,41 +174,50 @@ const int dropsegments=5; //everything with this number of steps  will be ignore
177 174
 //#define_HEATER_1_MAXTEMP 275
178 175
 //#define BED_MAXTEMP 150
179 176
 
180
-
181
-
182
-
183
-
184
-
185
-
177
+/// PID settings:
178
+// Uncomment the following line to enable PID support.
179
+  
186 180
 #define PIDTEMP
187 181
 #ifdef PIDTEMP
188
-  /// PID settings:
189
-  // Uncomment the following line to enable PID support.
190
-  //#define SMOOTHING
191
-  //#define SMOOTHFACTOR 5.0
192
-  //float current_raw_average=0;
193
-    #define K1 0.95 //smoothing of the PID
194 182
   //#define PID_DEBUG // Sends debug data to the serial port. 
195 183
   //#define PID_OPENLOOP 1 // Puts PID in open loop. M104 sets the output power in %
196
-  #define PID_MAX 255 // limits current to nozzle
197
-  #define PID_INTEGRAL_DRIVE_MAX 255
198
-  #define PID_dT 0.1
199
- //machine with red silicon: 1950:45 second ; with fan fully blowin 3000:47
184
+  
185
+  #define PID_MAX 255 // limits current to nozzle; 255=full current
186
+  #define PID_INTEGRAL_DRIVE_MAX 255  //limit for the integral term
187
+  #define K1 0.95 //smoothing factor withing the PID
188
+  #define PID_dT 0.1 //sampling period of the PID
189
+
190
+  //To develop some PID settings for your machine, you can initiall follow 
191
+  // the Ziegler-Nichols method.
192
+  // set Ki and Kd to zero. 
193
+  // heat with a defined Kp and see if the temperature stabilizes
194
+  // ideally you do this graphically with repg.
195
+  // the PID_CRITIAL_GAIN should be the Kp at which temperature oscillatins are not dampned out/decreas in amplitutde
196
+  // PID_SWING_AT_CRITIAL is the time for a full period of the oscillations at the critical Gain
197
+  // usually further manual tunine is necessary.
200 198
 
201 199
   #define PID_CRITIAL_GAIN 3000
202 200
   #define PID_SWING_AT_CRITIAL 45 //seconds
203
-  #define PIDIADD 5
204
-  /*
205
-  //PID according to Ziegler-Nichols method
206
-  float Kp = 0.6*PID_CRITIAL_GAIN; 
207
-  float Ki =PIDIADD+2*Kp/PID_SWING_AT_CRITIAL*PID_dT;  
208
-  float Kd = Kp*PID_SWING_AT_CRITIAL/8./PID_dT;  
209
-  */
210
-  //PI according to Ziegler-Nichols method
211
-  #define  DEFAULT_Kp (PID_CRITIAL_GAIN/2.2) 
212
-  #define  DEFAULT_Ki (1.2*Kp/PID_SWING_AT_CRITIAL*PID_dT)
213
-  #define  DEFAULT_Kd (0)
214 201
   
202
+  #define PID_PI    //no differentail term
203
+  //#define PID_PID //normal PID
204
+
205
+  #ifdef PID_PID
206
+    //PID according to Ziegler-Nichols method
207
+    #define  DEFAULT_Kp  (0.6*PID_CRITIAL_GAIN)
208
+    #define  DEFAULT_Ki (2*Kp/PID_SWING_AT_CRITIAL*PID_dT)  
209
+    #define  DEFAULT_Kd (PID_SWING_AT_CRITIAL/8./PID_dT)  
210
+  #endif
211
+ 
212
+  #ifdef PID_PI
213
+    //PI according to Ziegler-Nichols method
214
+    #define  DEFAULT_Kp (PID_CRITIAL_GAIN/2.2) 
215
+    #define  DEFAULT_Ki (1.2*Kp/PID_SWING_AT_CRITIAL*PID_dT)
216
+    #define  DEFAULT_Kd (0)
217
+  #endif
218
+  
219
+  // this adds an experimental additional term to the heatingpower, proportional to the extrusion speed.
220
+  // if Kc is choosen well, the additional required power due to increased melting should be compensated.
215 221
   #define PID_ADD_EXTRUSION_RATE  
216 222
   #ifdef PID_ADD_EXTRUSION_RATE
217 223
     #define  DEFAULT_Kc (5) //heatingpower=Kc*(e_speed)
@@ -228,22 +234,21 @@ const int dropsegments=5; //everything with this number of steps  will be ignore
228 234
 //#define ADVANCE
229 235
 
230 236
 #ifdef ADVANCE
231
-#define EXTRUDER_ADVANCE_K .3
237
+  #define EXTRUDER_ADVANCE_K .3
232 238
 
233
-#define D_FILAMENT 1.7
234
-#define STEPS_MM_E 65
235
-#define EXTRUTION_AREA (0.25 * D_FILAMENT * D_FILAMENT * 3.14159)
236
-#define STEPS_PER_CUBIC_MM_E (axis_steps_per_unit[E_AXIS]/ EXTRUTION_AREA)
239
+  #define D_FILAMENT 1.7
240
+  #define STEPS_MM_E 65
241
+  #define EXTRUTION_AREA (0.25 * D_FILAMENT * D_FILAMENT * 3.14159)
242
+  #define STEPS_PER_CUBIC_MM_E (axis_steps_per_unit[E_AXIS]/ EXTRUTION_AREA)
237 243
 
238 244
 #endif // ADVANCE
239 245
 
240
-// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2, e.g. 8,16,32 
241
-#if defined SDSUPPORT
242 246
 // The number of linear motions that can be in the plan at any give time.  
247
+// THE BLOCK_BUFFER_SIZE NEEDS TO BE A POWER OF 2, i.g. 8,16,32 because shifts and ors are used to do the ringbuffering.
248
+#if defined SDSUPPORT
243 249
   #define BLOCK_BUFFER_SIZE 16   // SD,LCD,Buttons take more memory, block buffer needs to be smaller
244 250
 #else
245 251
   #define BLOCK_BUFFER_SIZE 16 // maximize block buffer
246 252
 #endif
247 253
 
248
-
249
-#endif
254
+#endif //__CONFIGURATION_H

+ 61
- 56
Marlin/EEPROMwrite.h View File

@@ -1,39 +1,42 @@
1 1
 #ifndef __EEPROMH
2 2
 #define __EEPROMH
3
+
4
+#include "Marlin.h"
3 5
 #include "planner.h"
4 6
 #include "temperature.h"
5 7
 #include <EEPROM.h>
6
-#include "Marlin.h"
7
-#include "streaming.h"
8 8
 
9
-//======================================================================================
10 9
 template <class T> int EEPROM_writeAnything(int &ee, const T& value)
11 10
 {
12
-    const byte* p = (const byte*)(const void*)&value;
13
-    int i;
14
-    for (i = 0; i < (int)sizeof(value); i++)
15
-	  EEPROM.write(ee++, *p++);
16
-    return i;
11
+  const byte* p = (const byte*)(const void*)&value;
12
+  int i;
13
+  for (i = 0; i < (int)sizeof(value); i++)
14
+    EEPROM.write(ee++, *p++);
15
+  return i;
17 16
 }
18
-//======================================================================================
17
+
19 18
 template <class T> int EEPROM_readAnything(int &ee, T& value)
20 19
 {
21
-    byte* p = (byte*)(void*)&value;
22
-    int i;
23
-    for (i = 0; i < (int)sizeof(value); i++)
24
-	  *p++ = EEPROM.read(ee++);
25
-    return i;
20
+  byte* p = (byte*)(void*)&value;
21
+  int i;
22
+  for (i = 0; i < (int)sizeof(value); i++)
23
+    *p++ = EEPROM.read(ee++);
24
+  return i;
26 25
 }
27 26
 //======================================================================================
28 27
 
29 28
 #define EEPROM_OFFSET 100
30 29
 
31
-#define EEPROM_VERSION "V04"  // IMPORTANT:  Whenever there are changes made to the variables stored in EEPROM
32
-                              // in the functions below, also increment the version number. This makes sure that
33
-                              // the default values are used whenever there is a change to the data, to prevent
34
-                              // wrong data being written to the variables.
35
-                              // ALSO:  always make sure the variables in the Store and retrieve sections are in the same order.
36
-void StoreSettings() {
30
+
31
+// IMPORTANT:  Whenever there are changes made to the variables stored in EEPROM
32
+// in the functions below, also increment the version number. This makes sure that
33
+// the default values are used whenever there is a change to the data, to prevent
34
+// wrong data being written to the variables.
35
+// ALSO:  always make sure the variables in the Store and retrieve sections are in the same order.
36
+#define EEPROM_VERSION "V04"  
37
+
38
+void StoreSettings() 
39
+{
37 40
   char ver[4]= "000";
38 41
   int i=EEPROM_OFFSET;
39 42
   EEPROM_writeAnything(i,ver); // invalidate data first 
@@ -48,52 +51,55 @@ void StoreSettings() {
48 51
   EEPROM_writeAnything(i,max_xy_jerk);
49 52
   EEPROM_writeAnything(i,max_z_jerk);
50 53
   #ifdef PIDTEMP
51
-  EEPROM_writeAnything(i,Kp);
52
-  EEPROM_writeAnything(i,Ki);
53
-  EEPROM_writeAnything(i,Kd);
54
-#else
55
-  EEPROM_writeAnything(i,3000);
56
-  EEPROM_writeAnything(i,0);
57
-  EEPROM_writeAnything(i,0);
58
-#endif
54
+    EEPROM_writeAnything(i,Kp);
55
+    EEPROM_writeAnything(i,Ki);
56
+    EEPROM_writeAnything(i,Kd);
57
+  #else
58
+    EEPROM_writeAnything(i,3000);
59
+    EEPROM_writeAnything(i,0);
60
+    EEPROM_writeAnything(i,0);
61
+  #endif
59 62
   char ver2[4]=EEPROM_VERSION;
60 63
   i=EEPROM_OFFSET;
61 64
   EEPROM_writeAnything(i,ver2); // validate data
62
-   SERIAL_ECHOLN("Settings Stored");
63
-
65
+  SERIAL_ECHOLN("Settings Stored");
64 66
 }
65 67
 
66
-void RetrieveSettings(bool def=false){  // if def=true, the default values will be used
68
+void RetrieveSettings(bool def=false)
69
+{  // if def=true, the default values will be used
67 70
   int i=EEPROM_OFFSET;
68 71
   char stored_ver[4];
69 72
   char ver[4]=EEPROM_VERSION;
70 73
   EEPROM_readAnything(i,stored_ver); //read stored version
71
-//  SERIAL_ECHOLN("Version: [" << ver << "] Stored version: [" << stored_ver << "]");
72
-  if ((!def)&&(strncmp(ver,stored_ver,3)==0)) {   // version number match
73
-      EEPROM_readAnything(i,axis_steps_per_unit);  
74
-      EEPROM_readAnything(i,max_feedrate);  
75
-      EEPROM_readAnything(i,max_acceleration_units_per_sq_second);
76
-      EEPROM_readAnything(i,acceleration);
77
-      EEPROM_readAnything(i,retract_acceleration);
78
-      EEPROM_readAnything(i,minimumfeedrate);
79
-      EEPROM_readAnything(i,mintravelfeedrate);
80
-      EEPROM_readAnything(i,minsegmenttime);
81
-      EEPROM_readAnything(i,max_xy_jerk);
82
-      EEPROM_readAnything(i,max_z_jerk);
83
-#ifndef PIDTEMP
74
+  //  SERIAL_ECHOLN("Version: [" << ver << "] Stored version: [" << stored_ver << "]");
75
+  if ((!def)&&(strncmp(ver,stored_ver,3)==0)) 
76
+  {   // version number match
77
+    EEPROM_readAnything(i,axis_steps_per_unit);  
78
+    EEPROM_readAnything(i,max_feedrate);  
79
+    EEPROM_readAnything(i,max_acceleration_units_per_sq_second);
80
+    EEPROM_readAnything(i,acceleration);
81
+    EEPROM_readAnything(i,retract_acceleration);
82
+    EEPROM_readAnything(i,minimumfeedrate);
83
+    EEPROM_readAnything(i,mintravelfeedrate);
84
+    EEPROM_readAnything(i,minsegmenttime);
85
+    EEPROM_readAnything(i,max_xy_jerk);
86
+    EEPROM_readAnything(i,max_z_jerk);
87
+    #ifndef PIDTEMP
84 88
       float Kp,Ki,Kd;
85
-#endif
86
-      EEPROM_readAnything(i,Kp);
87
-      EEPROM_readAnything(i,Ki);
88
-      EEPROM_readAnything(i,Kd);
89
+    #endif
90
+    EEPROM_readAnything(i,Kp);
91
+    EEPROM_readAnything(i,Ki);
92
+    EEPROM_readAnything(i,Kd);
89 93
 
90
-      SERIAL_ECHOLN("Stored settings retreived:");
94
+    SERIAL_ECHOLN("Stored settings retreived:");
91 95
   }
92
-  else {
96
+  else 
97
+  {
93 98
     float tmp1[]=DEFAULT_AXIS_STEPS_PER_UNIT;
94 99
     float tmp2[]=DEFAULT_MAX_FEEDRATE;
95 100
     long tmp3[]=DEFAULT_MAX_ACCELERATION;
96
-    for (int i=0;i<4;i++) {
101
+    for (short i=0;i<4;i++) 
102
+    {
97 103
       axis_steps_per_unit[i]=tmp1[i];  
98 104
       max_feedrate[i]=tmp2[i];  
99 105
       max_acceleration_units_per_sq_second[i]=tmp3[i];
@@ -117,11 +123,10 @@ void RetrieveSettings(bool def=false){  // if def=true, the default values will
117 123
   SERIAL_ECHOLN("   M204 S"  <<_FLOAT(acceleration,2) << " T" << _FLOAT(retract_acceleration,2));
118 124
   SERIAL_ECHOLN("Advanced variables: S=Min feedrate (mm/s), T=Min travel feedrate (mm/s), B=minimum segment time (ms), X=maximum xY jerk (mm/s),  Z=maximum Z jerk (mm/s)");
119 125
   SERIAL_ECHOLN("   M205 S"  <<_FLOAT(minimumfeedrate/60,2) << " T" << _FLOAT(mintravelfeedrate/60,2) << " B" << _FLOAT(minsegmenttime,2) << " X" << _FLOAT(max_xy_jerk/60,2) << " Z" << _FLOAT(max_z_jerk/60,2));
120
-#ifdef PIDTEMP
121
-  SERIAL_ECHOLN("PID settings:");
122
-  SERIAL_ECHOLN("   M301 P"  << _FLOAT(Kp,3) << " I" << _FLOAT(Ki,3) << " D" << _FLOAT(Kd,3));  
123
-#endif
124
-  
126
+  #ifdef PIDTEMP
127
+    SERIAL_ECHOLN("PID settings:");
128
+    SERIAL_ECHOLN("   M301 P"  << _FLOAT(Kp,3) << " I" << _FLOAT(Ki,3) << " D" << _FLOAT(Kd,3));  
129
+  #endif
125 130
 }  
126 131
 
127 132
 #endif

+ 22
- 35
Marlin/Marlin.h View File

@@ -18,41 +18,39 @@ void process_commands();
18 18
 void manage_inactivity(byte debug);
19 19
 
20 20
 #if X_ENABLE_PIN > -1
21
-#define  enable_x() WRITE(X_ENABLE_PIN, X_ENABLE_ON)
22
-#define disable_x() WRITE(X_ENABLE_PIN,!X_ENABLE_ON)
21
+  #define  enable_x() WRITE(X_ENABLE_PIN, X_ENABLE_ON)
22
+  #define disable_x() WRITE(X_ENABLE_PIN,!X_ENABLE_ON)
23 23
 #else
24
-#define enable_x() ;
25
-#define disable_x() ;
24
+  #define enable_x() ;
25
+  #define disable_x() ;
26 26
 #endif
27
+
27 28
 #if Y_ENABLE_PIN > -1
28
-#define  enable_y() WRITE(Y_ENABLE_PIN, Y_ENABLE_ON)
29
-#define disable_y() WRITE(Y_ENABLE_PIN,!Y_ENABLE_ON)
29
+  #define  enable_y() WRITE(Y_ENABLE_PIN, Y_ENABLE_ON)
30
+  #define disable_y() WRITE(Y_ENABLE_PIN,!Y_ENABLE_ON)
30 31
 #else
31
-#define enable_y() ;
32
-#define disable_y() ;
32
+  #define enable_y() ;
33
+  #define disable_y() ;
33 34
 #endif
35
+
34 36
 #if Z_ENABLE_PIN > -1
35
-#define  enable_z() WRITE(Z_ENABLE_PIN, Z_ENABLE_ON)
36
-#define disable_z() WRITE(Z_ENABLE_PIN,!Z_ENABLE_ON)
37
+  #define  enable_z() WRITE(Z_ENABLE_PIN, Z_ENABLE_ON)
38
+  #define disable_z() WRITE(Z_ENABLE_PIN,!Z_ENABLE_ON)
37 39
 #else
38
-#define enable_z() ;
39
-#define disable_z() ;
40
+  #define enable_z() ;
41
+  #define disable_z() ;
40 42
 #endif
41 43
 
42 44
 #if E_ENABLE_PIN > -1
43
-
44
-	#define  enable_e() WRITE(E_ENABLE_PIN, E_ENABLE_ON)
45
-	#define disable_e() WRITE(E_ENABLE_PIN,!E_ENABLE_ON)
46
-
45
+  #define  enable_e() WRITE(E_ENABLE_PIN, E_ENABLE_ON)
46
+  #define disable_e() WRITE(E_ENABLE_PIN,!E_ENABLE_ON)
47 47
 #else
48
-#define enable_e() ;
49
-#define disable_e() ;
48
+  #define enable_e() ;
49
+  #define disable_e() ;
50 50
 #endif
51 51
 
52
-#define X_AXIS 0
53
-#define Y_AXIS 1
54
-#define Z_AXIS 2
55
-#define E_AXIS 3
52
+enum AxisEnum {X_AXIS=0, Y_AXIS=1, Z_AXIS=2, E_AXIS=3};
53
+
56 54
 
57 55
 void FlushSerialRequestResend();
58 56
 void ClearToSend();
@@ -61,26 +59,15 @@ void get_coordinates();
61 59
 void prepare_move();
62 60
 void kill();
63 61
 
64
-//void check_axes_activity();
65
-//void plan_init();
66
-//void st_init();
67
-//void tp_init();
68
-//void plan_buffer_line(float x, float y, float z, float e, float feed_rate);
69
-//void plan_set_position(float x, float y, float z, float e);
70
-//void st_wake_up();
71
-//void st_synchronize();
72 62
 void enquecommand(const char *cmd); //put an ascii command at the end of the current buffer.
73 63
 
74 64
 
75 65
 #ifndef CRITICAL_SECTION_START
76
-#define CRITICAL_SECTION_START  unsigned char _sreg = SREG; cli();
77
-#define CRITICAL_SECTION_END    SREG = _sreg;
66
+  #define CRITICAL_SECTION_START  unsigned char _sreg = SREG; cli();
67
+  #define CRITICAL_SECTION_END    SREG = _sreg;
78 68
 #endif //CRITICAL_SECTION_START
79 69
 
80 70
 extern float homing_feedrate[];
81 71
 extern bool axis_relative_modes[];
82 72
 
83
-
84
-void kill();
85
-
86 73
 #endif

+ 390
- 389
Marlin/Marlin.pde
File diff suppressed because it is too large
View File


+ 9
- 9
Marlin/motion_control.cpp View File

@@ -33,8 +33,8 @@
33 33
 void mc_arc(float *position, float *target, float *offset, uint8_t axis_0, uint8_t axis_1, 
34 34
   uint8_t axis_linear, float feed_rate, float radius, uint8_t isclockwise)
35 35
 {      
36
-//   int acceleration_manager_was_enabled = plan_is_acceleration_manager_enabled();
37
-//   plan_set_acceleration_manager_enabled(false); // disable acceleration management for the duration of the arc
36
+  //   int acceleration_manager_was_enabled = plan_is_acceleration_manager_enabled();
37
+  //   plan_set_acceleration_manager_enabled(false); // disable acceleration management for the duration of the arc
38 38
   SERIAL_ECHOLN("mc_arc.");
39 39
   float center_axis0 = position[axis_0] + offset[axis_0];
40 40
   float center_axis1 = position[axis_1] + offset[axis_1];
@@ -52,12 +52,12 @@ void mc_arc(float *position, float *target, float *offset, uint8_t axis_0, uint8
52 52
   float millimeters_of_travel = hypot(angular_travel*radius, fabs(linear_travel));
53 53
   if (millimeters_of_travel == 0.0) { return; }
54 54
   uint16_t segments = floor(millimeters_of_travel/MM_PER_ARC_SEGMENT);
55
-/*  
56
-  // Multiply inverse feed_rate to compensate for the fact that this movement is approximated
57
-  // by a number of discrete segments. The inverse feed_rate should be correct for the sum of 
58
-  // all segments.
59
-  if (invert_feed_rate) { feed_rate *= segments; }
60
-*/
55
+  /*  
56
+    // Multiply inverse feed_rate to compensate for the fact that this movement is approximated
57
+    // by a number of discrete segments. The inverse feed_rate should be correct for the sum of 
58
+    // all segments.
59
+    if (invert_feed_rate) { feed_rate *= segments; }
60
+  */
61 61
   float theta_per_segment = angular_travel/segments;
62 62
   float linear_per_segment = linear_travel/segments;
63 63
   
@@ -128,6 +128,6 @@ void mc_arc(float *position, float *target, float *offset, uint8_t axis_0, uint8
128 128
   // Ensure last segment arrives at target location.
129 129
   plan_buffer_line(target[X_AXIS], target[Y_AXIS], target[Z_AXIS], target[E_AXIS], feed_rate);
130 130
 
131
-//   plan_set_acceleration_manager_enabled(acceleration_manager_was_enabled);
131
+  //   plan_set_acceleration_manager_enabled(acceleration_manager_was_enabled);
132 132
 }
133 133
 

+ 68
- 0
Marlin/pins.h View File

@@ -557,6 +557,74 @@
557 557
 #define FAN_PIN            7
558 558
 #define PS_ON_PIN          12
559 559
 #define KILL_PIN           -1
560
+
561
+#ifdef ULTRA_LCD
562
+
563
+  #ifdef NEWPANEL
564
+  //arduino pin witch triggers an piezzo beeper
565
+    #define BEEPER 18
566
+
567
+    #define LCD_PINS_RS 20 
568
+    #define LCD_PINS_ENABLE 17
569
+    #define LCD_PINS_D4 16
570
+    #define LCD_PINS_D5 21 
571
+    #define LCD_PINS_D6 5
572
+    #define LCD_PINS_D7 6
573
+    
574
+    //buttons are directly attached
575
+    #define BTN_EN1 40
576
+    #define BTN_EN2 42
577
+    #define BTN_ENC 19  //the click
578
+    
579
+    #define BLEN_C 2
580
+    #define BLEN_B 1
581
+    #define BLEN_A 0
582
+    
583
+    #define SDCARDDETECT 38
584
+    
585
+      //encoder rotation values
586
+    #define encrot0 0
587
+    #define encrot1 2
588
+    #define encrot2 3
589
+    #define encrot3 1
590
+  #else //old style panel with shift register
591
+    //arduino pin witch triggers an piezzo beeper
592
+    #define BEEPER 18
593
+
594
+    //buttons are attached to a shift register
595
+    #define SHIFT_CLK 38
596
+    #define SHIFT_LD 42
597
+    #define SHIFT_OUT 40
598
+    #define SHIFT_EN 17
599
+    
600
+    #define LCD_PINS_RS 16 
601
+    #define LCD_PINS_ENABLE 5
602
+    #define LCD_PINS_D4 6
603
+    #define LCD_PINS_D5 21 
604
+    #define LCD_PINS_D6 20
605
+    #define LCD_PINS_D7 19
606
+    
607
+    //encoder rotation values
608
+    #define encrot0 0
609
+    #define encrot1 2
610
+    #define encrot2 3
611
+    #define encrot3 1
612
+
613
+    
614
+    //bits in the shift register that carry the buttons for:
615
+    // left up center down right red
616
+    #define BL_LE 7
617
+    #define BL_UP 6
618
+    #define BL_MI 5
619
+    #define BL_DW 4
620
+    #define BL_RI 3
621
+    #define BL_ST 2
622
+
623
+    #define BLEN_B 1
624
+    #define BLEN_A 0
625
+  #endif 
626
+#endif //ULTRA_LCD
627
+
560 628
 #endif
561 629
 
562 630
 

+ 38
- 42
Marlin/planner.cpp View File

@@ -83,7 +83,7 @@ static volatile unsigned char block_buffer_head;           // Index of the next
83 83
 static volatile unsigned char block_buffer_tail;           // Index of the block to process now
84 84
 
85 85
 // The current position of the tool in absolute steps
86
- long position[4];   
86
+long position[4];   
87 87
 
88 88
 #define ONE_MINUTE_OF_MICROSECONDS 60000000.0
89 89
 
@@ -123,10 +123,10 @@ void calculate_trapezoid_for_block(block_t *block, float entry_speed, float exit
123 123
   long initial_rate = ceil(block->nominal_rate*entry_factor);
124 124
   long final_rate = ceil(block->nominal_rate*exit_factor);
125 125
   
126
-#ifdef ADVANCE
127
-  long initial_advance = block->advance*entry_factor*entry_factor;
128
-  long final_advance = block->advance*exit_factor*exit_factor;
129
-#endif // ADVANCE
126
+  #ifdef ADVANCE
127
+    long initial_advance = block->advance*entry_factor*entry_factor;
128
+    long final_advance = block->advance*exit_factor*exit_factor;
129
+  #endif // ADVANCE
130 130
 
131 131
   // Limit minimal step rate (Otherwise the timer will overflow.)
132 132
   if(initial_rate <120) initial_rate=120;
@@ -155,10 +155,10 @@ void calculate_trapezoid_for_block(block_t *block, float entry_speed, float exit
155 155
     block->decelerate_after = decelerate_after;
156 156
     block->initial_rate = initial_rate;
157 157
     block->final_rate = final_rate;
158
-#ifdef ADVANCE
159
-    block->initial_advance = initial_advance;
160
-    block->final_advance = final_advance;
161
-#endif //ADVANCE
158
+  #ifdef ADVANCE
159
+      block->initial_advance = initial_advance;
160
+      block->final_advance = final_advance;
161
+  #endif //ADVANCE
162 162
   }
163 163
   CRITICAL_SECTION_END;
164 164
 }                    
@@ -166,18 +166,15 @@ void calculate_trapezoid_for_block(block_t *block, float entry_speed, float exit
166 166
 // Calculates the maximum allowable speed at this point when you must be able to reach target_velocity using the 
167 167
 // acceleration within the allotted distance.
168 168
 inline float max_allowable_speed(float acceleration, float target_velocity, float distance) {
169
-  return(
170
-  sqrt(target_velocity*target_velocity-2*acceleration*60*60*distance)
171
-    );
169
+  return  sqrt(target_velocity*target_velocity-2*acceleration*60*60*distance);
172 170
 }
173 171
 
174 172
 // "Junction jerk" in this context is the immediate change in speed at the junction of two blocks.
175 173
 // This method will calculate the junction jerk as the euclidean distance between the nominal 
176 174
 // velocities of the respective blocks.
177 175
 inline float junction_jerk(block_t *before, block_t *after) {
178
-  return(sqrt(
179
-    pow((before->speed_x-after->speed_x), 2)+
180
-    pow((before->speed_y-after->speed_y), 2)));
176
+  return sqrt(
177
+    pow((before->speed_x-after->speed_x), 2)+pow((before->speed_y-after->speed_y), 2));
181 178
 }
182 179
 
183 180
 // Return the safe speed which is max_jerk/2, e.g. the 
@@ -185,8 +182,10 @@ inline float junction_jerk(block_t *before, block_t *after) {
185 182
 float safe_speed(block_t *block) {
186 183
   float safe_speed;
187 184
   safe_speed = max_xy_jerk/2;  
188
-  if(abs(block->speed_z) > max_z_jerk/2) safe_speed = max_z_jerk/2;
189
-  if (safe_speed > block->nominal_speed) safe_speed = block->nominal_speed;
185
+  if(abs(block->speed_z) > max_z_jerk/2) 
186
+    safe_speed = max_z_jerk/2;
187
+  if (safe_speed > block->nominal_speed) 
188
+    safe_speed = block->nominal_speed;
190 189
   return safe_speed;  
191 190
 }
192 191
 
@@ -379,9 +378,8 @@ void check_axes_activity() {
379 378
 // Add a new linear movement to the buffer. steps_x, _y and _z is the absolute position in 
380 379
 // mm. Microseconds specify how many microseconds the move should take to perform. To aid acceleration
381 380
 // calculation the caller must also provide the physical length of the line in millimeters.
382
-void plan_buffer_line(float x, float y, float z, float e, float feed_rate) {
383
-
384
-
381
+void plan_buffer_line(const float &x, const float &y, const float &z, const float &e,  float feed_rate)
382
+{
385 383
   // Calculate the buffer head after we push this byte
386 384
   int next_buffer_head = (block_buffer_head + 1) & (BLOCK_BUFFER_SIZE - 1);
387 385
 
@@ -469,11 +467,8 @@ void plan_buffer_line(float x, float y, float z, float e, float feed_rate) {
469 467
   // Limit speed per axis
470 468
   float speed_factor = 1; //factor <=1 do decrease speed
471 469
   if(abs(block->speed_x) > max_feedrate[X_AXIS]) {
472
-    //// [ErikDeBruijn] IS THIS THE BUG WE'RE LOOING FOR????
473
-    //// [bernhard] No its not, according to Zalm.
474
-		//// the if would always be true, since tmp_speedfactor <=0 due the inial if, so its safe to set. the next lines actually compare.
475 470
     speed_factor = max_feedrate[X_AXIS] / abs(block->speed_x);
476
-    //if(speed_factor > tmp_speed_factor) speed_factor = tmp_speed_factor;
471
+    //if(speed_factor > tmp_speed_factor) speed_factor = tmp_speed_factor; /is not need here because auf the init above
477 472
   }
478 473
   if(abs(block->speed_y) > max_feedrate[Y_AXIS]){
479 474
     float tmp_speed_factor = max_feedrate[Y_AXIS] / abs(block->speed_y);
@@ -495,7 +490,8 @@ void plan_buffer_line(float x, float y, float z, float e, float feed_rate) {
495 490
   block->nominal_speed = block->millimeters * multiplier;
496 491
   block->nominal_rate = ceil(block->step_event_count * multiplier / 60);  
497 492
 
498
-  if(block->nominal_rate < 120) block->nominal_rate = 120;
493
+  if(block->nominal_rate < 120) 
494
+    block->nominal_rate = 120;
499 495
   block->entry_speed = safe_speed(block);
500 496
 
501 497
   // Compute the acceleration rate for the trapezoid generator. 
@@ -527,25 +523,25 @@ void plan_buffer_line(float x, float y, float z, float e, float feed_rate) {
527 523
   block->acceleration = block->acceleration_st * travel_per_step;
528 524
   block->acceleration_rate = (long)((float)block->acceleration_st * 8.388608);
529 525
 
530
-#ifdef ADVANCE
531
-  // Calculate advance rate
532
-  if((block->steps_e == 0) || (block->steps_x == 0 && block->steps_y == 0 && block->steps_z == 0)) {
533
-    block->advance_rate = 0;
534
-    block->advance = 0;
535
-  }
536
-  else {
537
-    long acc_dist = estimate_acceleration_distance(0, block->nominal_rate, block->acceleration_st);
538
-    float advance = (STEPS_PER_CUBIC_MM_E * EXTRUDER_ADVANCE_K) * 
539
-      (block->speed_e * block->speed_e * EXTRUTION_AREA * EXTRUTION_AREA / 3600.0)*65536;
540
-    block->advance = advance;
541
-    if(acc_dist == 0) {
526
+  #ifdef ADVANCE
527
+    // Calculate advance rate
528
+    if((block->steps_e == 0) || (block->steps_x == 0 && block->steps_y == 0 && block->steps_z == 0)) {
542 529
       block->advance_rate = 0;
543
-    } 
530
+      block->advance = 0;
531
+    }
544 532
     else {
545
-      block->advance_rate = advance / (float)acc_dist;
533
+      long acc_dist = estimate_acceleration_distance(0, block->nominal_rate, block->acceleration_st);
534
+      float advance = (STEPS_PER_CUBIC_MM_E * EXTRUDER_ADVANCE_K) * 
535
+        (block->speed_e * block->speed_e * EXTRUTION_AREA * EXTRUTION_AREA / 3600.0)*65536;
536
+      block->advance = advance;
537
+      if(acc_dist == 0) {
538
+        block->advance_rate = 0;
539
+      } 
540
+      else {
541
+        block->advance_rate = advance / (float)acc_dist;
542
+      }
546 543
     }
547
-  }
548
-#endif // ADVANCE
544
+  #endif // ADVANCE
549 545
 
550 546
   // compute a preliminary conservative acceleration trapezoid
551 547
   float safespeed = safe_speed(block);
@@ -576,7 +572,7 @@ void plan_buffer_line(float x, float y, float z, float e, float feed_rate) {
576 572
   st_wake_up();
577 573
 }
578 574
 
579
-void plan_set_position(float x, float y, float z, float e)
575
+void plan_set_position(const float &x, const float &y, const float &z, const float &e)
580 576
 {
581 577
   position[X_AXIS] = lround(x*axis_steps_per_unit[X_AXIS]);
582 578
   position[Y_AXIS] = lround(y*axis_steps_per_unit[Y_AXIS]);

+ 13
- 12
Marlin/planner.h View File

@@ -32,16 +32,16 @@ typedef struct {
32 32
   // Fields used by the bresenham algorithm for tracing the line
33 33
   long steps_x, steps_y, steps_z, steps_e;  // Step count along each axis
34 34
   long step_event_count;                    // The number of step events required to complete this block
35
-  volatile long accelerate_until;                    // The index of the step event on which to stop acceleration
36
-  volatile long decelerate_after;                    // The index of the step event on which to start decelerating
37
-  volatile long acceleration_rate;                   // The acceleration rate used for acceleration calculation
35
+  volatile long accelerate_until;           // The index of the step event on which to stop acceleration
36
+  volatile long decelerate_after;           // The index of the step event on which to start decelerating
37
+  volatile long acceleration_rate;          // The acceleration rate used for acceleration calculation
38 38
   unsigned char direction_bits;             // The direction bit set for this block (refers to *_DIRECTION_BIT in config.h)
39
-#ifdef ADVANCE
40
-  long advance_rate;
41
-  volatile long initial_advance;
42
-  volatile long final_advance;
43
-  float advance;
44
-#endif
39
+  #ifdef ADVANCE
40
+    long advance_rate;
41
+    volatile long initial_advance;
42
+    volatile long final_advance;
43
+    float advance;
44
+  #endif
45 45
 
46 46
   // Fields used by the motion planner to manage acceleration
47 47
   float speed_x, speed_y, speed_z, speed_e;          // Nominal mm/minute for each axis
@@ -57,16 +57,17 @@ typedef struct {
57 57
   long acceleration_st;                              // acceleration steps/sec^2
58 58
   volatile char busy;
59 59
 } block_t;
60
-      
60
+
61 61
 // Initialize the motion plan subsystem      
62 62
 void plan_init();
63 63
 
64 64
 // Add a new linear movement to the buffer. x, y and z is the signed, absolute target position in 
65 65
 // millimaters. Feed rate specifies the speed of the motion.
66
-void plan_buffer_line(float x, float y, float z, float e, float feed_rate);
66
+void plan_buffer_line(const float &x, const float &y, const float &z, const float &e, float feed_rate);
67 67
 
68 68
 // Set position. Used for G92 instructions.
69
-void plan_set_position(float x, float y, float z, float e);
69
+void plan_set_position(const float &x, const float &y, const float &z, const float &e);
70
+
70 71
 
71 72
 // Called when the current block is no longer needed. Discards the block and makes the memory
72 73
 // availible for new blocks.

+ 1
- 0
Marlin/speed_lookuptable.h View File

@@ -37,6 +37,7 @@ uint16_t speed_lookuptable_fast[256][2] PROGMEM = {\
37 37
 { 32, 0}, { 32, 0}, { 32, 0}, { 32, 0}, { 32, 1}, { 31, 0}, { 31, 0}, { 31, 0}, 
38 38
 { 31, 0}, { 31, 0}, { 31, 0}, { 31, 1}, { 30, 0}, { 30, 0}, { 30, 0}, { 30, 0}
39 39
 };
40
+
40 41
 uint16_t speed_lookuptable_slow[256][2] PROGMEM = {\
41 42
 { 62500, 12500}, { 50000, 8334}, { 41666, 5952}, { 35714, 4464}, { 31250, 3473}, { 27777, 2777}, { 25000, 2273}, { 22727, 1894}, 
42 43
 { 20833, 1603}, { 19230, 1373}, { 17857, 1191}, { 16666, 1041}, { 15625, 920}, { 14705, 817}, { 13888, 731}, { 13157, 657}, 

+ 202
- 200
Marlin/stepper.cpp View File

@@ -35,8 +35,8 @@
35 35
 // if DEBUG_STEPS is enabled, M114 can be used to compare two methods of determining the X,Y,Z position of the printer.
36 36
 // for debugging purposes only, should be disabled by default
37 37
 #ifdef DEBUG_STEPS
38
-volatile long count_position[NUM_AXIS] = { 0, 0, 0, 0};
39
-volatile int count_direction[NUM_AXIS] = { 1, 1, 1, 1};
38
+  volatile long count_position[NUM_AXIS] = { 0, 0, 0, 0};
39
+  volatile int count_direction[NUM_AXIS] = { 1, 1, 1, 1};
40 40
 #endif
41 41
 
42 42
 
@@ -117,6 +117,8 @@ asm volatile ( \
117 117
 
118 118
 block_t *current_block;  // A pointer to the block currently being traced
119 119
 
120
+//static makes it inpossible to be called from outside of this file by extern.!
121
+
120 122
 // Variables used by The Stepper Driver Interrupt
121 123
 static unsigned char out_bits;        // The next stepping-bits to be output
122 124
 static long counter_x,       // Counter variables for the bresenham line tracer
@@ -125,9 +127,9 @@ static long counter_x,       // Counter variables for the bresenham line tracer
125 127
             counter_e;
126 128
 static unsigned long step_events_completed; // The number of step events executed in the current block
127 129
 #ifdef ADVANCE
128
-static long advance_rate, advance, final_advance = 0;
129
-static short old_advance = 0;
130
-static short e_steps;
130
+  static long advance_rate, advance, final_advance = 0;
131
+  static short old_advance = 0;
132
+  static short e_steps;
131 133
 #endif
132 134
 static unsigned char busy = false; // TRUE when SIG_OUTPUT_COMPARE1A is being serviced. Used to avoid retriggering that handler.
133 135
 static long acceleration_time, deceleration_time;
@@ -195,10 +197,10 @@ inline unsigned short calc_timer(unsigned short step_rate) {
195 197
 // Initializes the trapezoid generator from the current block. Called whenever a new 
196 198
 // block begins.
197 199
 inline void trapezoid_generator_reset() {
198
-#ifdef ADVANCE
199
-  advance = current_block->initial_advance;
200
-  final_advance = current_block->final_advance;
201
-#endif
200
+  #ifdef ADVANCE
201
+    advance = current_block->initial_advance;
202
+    final_advance = current_block->final_advance;
203
+  #endif
202 204
   deceleration_time = 0;
203 205
   // advance_rate = current_block->advance_rate;
204 206
   // step_rate to timer interval
@@ -211,7 +213,8 @@ inline void trapezoid_generator_reset() {
211 213
 // It pops blocks from the block_buffer and executes them by pulsing the stepper pins appropriately. 
212 214
 ISR(TIMER1_COMPA_vect)
213 215
 {        
214
-  if(busy){ SERIAL_ERRORLN(*(unsigned short *)OCR1A<< " ISR overtaking itself.");
216
+  if(busy){ 
217
+    SERIAL_ERRORLN(*(unsigned short *)OCR1A<< " ISR overtaking itself.");
215 218
     return; 
216 219
   } // The busy-flag is used to avoid reentering this interrupt
217 220
 
@@ -242,74 +245,74 @@ ISR(TIMER1_COMPA_vect)
242 245
     // Set directions TO DO This should be done once during init of trapezoid. Endstops -> interrupt
243 246
     out_bits = current_block->direction_bits;
244 247
 
245
-#ifdef ADVANCE
246
-    // Calculate E early.
247
-    counter_e += current_block->steps_e;
248
-    if (counter_e > 0) {
249
-      counter_e -= current_block->step_event_count;
250
-      if ((out_bits & (1<<E_AXIS)) != 0) { // - direction
251
-        CRITICAL_SECTION_START;
252
-        e_steps--;
253
-        CRITICAL_SECTION_END;
254
-      }
255
-      else {
248
+    #ifdef ADVANCE
249
+        // Calculate E early.
250
+        counter_e += current_block->steps_e;
251
+        if (counter_e > 0) {
252
+          counter_e -= current_block->step_event_count;
253
+          if ((out_bits & (1<<E_AXIS)) != 0) { // - direction
254
+            CRITICAL_SECTION_START;
255
+            e_steps--;
256
+            CRITICAL_SECTION_END;
257
+          }
258
+          else {
259
+            CRITICAL_SECTION_START;
260
+            e_steps++;
261
+            CRITICAL_SECTION_END;
262
+          }
263
+        }    
264
+        // Do E steps + advance steps
256 265
         CRITICAL_SECTION_START;
257
-        e_steps++;
266
+        e_steps += ((advance >> 16) - old_advance);
258 267
         CRITICAL_SECTION_END;
259
-      }
260
-    }    
261
-    // Do E steps + advance steps
262
-    CRITICAL_SECTION_START;
263
-    e_steps += ((advance >> 16) - old_advance);
264
-    CRITICAL_SECTION_END;
265
-    old_advance = advance >> 16;  
266
-#endif //ADVANCE
268
+        old_advance = advance >> 16;  
269
+    #endif //ADVANCE
267 270
 
268 271
     // Set direction en check limit switches
269
-if ((out_bits & (1<<X_AXIS)) != 0) {   // -direction
272
+    if ((out_bits & (1<<X_AXIS)) != 0) {   // -direction
270 273
       WRITE(X_DIR_PIN, INVERT_X_DIR);
271 274
       #ifdef DEBUG_STEPS
272
-      count_direction[X_AXIS]=-1;
275
+        count_direction[X_AXIS]=-1;
276
+      #endif
277
+      #if X_MIN_PIN > -1
278
+            if(READ(X_MIN_PIN) != ENDSTOPS_INVERTING) {
279
+              step_events_completed = current_block->step_event_count;
280
+            }
273 281
       #endif
274
-#if X_MIN_PIN > -1
275
-      if(READ(X_MIN_PIN) != ENDSTOPS_INVERTING) {
276
-        step_events_completed = current_block->step_event_count;
277
-      }
278
-#endif
279 282
     }
280 283
     else { // +direction 
281
-        WRITE(X_DIR_PIN,!INVERT_X_DIR);
282
-        #ifdef DEBUG_STEPS
284
+      WRITE(X_DIR_PIN,!INVERT_X_DIR);
285
+      #ifdef DEBUG_STEPS
283 286
         count_direction[X_AXIS]=1;
284
-        #endif
285
-#if X_MAX_PIN > -1
287
+      #endif
288
+      #if X_MAX_PIN > -1
286 289
         if((READ(X_MAX_PIN) != ENDSTOPS_INVERTING)  && (current_block->steps_x >0)){
287 290
           step_events_completed = current_block->step_event_count;
288 291
         }
289
-#endif
292
+        #endif
290 293
     }
291 294
 
292 295
     if ((out_bits & (1<<Y_AXIS)) != 0) {   // -direction
293 296
       WRITE(Y_DIR_PIN,INVERT_Y_DIR);
294 297
       #ifdef DEBUG_STEPS
295
-      count_direction[Y_AXIS]=-1;
298
+        count_direction[Y_AXIS]=-1;
299
+      #endif
300
+      #if Y_MIN_PIN > -1
301
+        if(READ(Y_MIN_PIN) != ENDSTOPS_INVERTING) {
302
+          step_events_completed = current_block->step_event_count;
303
+        }
296 304
       #endif
297
-#if Y_MIN_PIN > -1
298
-      if(READ(Y_MIN_PIN) != ENDSTOPS_INVERTING) {
299
-        step_events_completed = current_block->step_event_count;
300
-      }
301
-#endif
302 305
     }
303 306
     else { // +direction
304 307
     WRITE(Y_DIR_PIN,!INVERT_Y_DIR);
305 308
       #ifdef DEBUG_STEPS
306
-      count_direction[Y_AXIS]=1;
309
+        count_direction[Y_AXIS]=1;
310
+      #endif
311
+      #if Y_MAX_PIN > -1
312
+      if((READ(Y_MAX_PIN) != ENDSTOPS_INVERTING) && (current_block->steps_y >0)){
313
+          step_events_completed = current_block->step_event_count;
314
+        }
307 315
       #endif
308
-#if Y_MAX_PIN > -1
309
-    if((READ(Y_MAX_PIN) != ENDSTOPS_INVERTING) && (current_block->steps_y >0)){
310
-        step_events_completed = current_block->step_event_count;
311
-      }
312
-#endif
313 316
     }
314 317
 
315 318
     if ((out_bits & (1<<Z_AXIS)) != 0) {   // -direction
@@ -317,30 +320,30 @@ if ((out_bits & (1<<X_AXIS)) != 0) {   // -direction
317 320
       #ifdef DEBUG_STEPS
318 321
       count_direction[Z_AXIS]=-1;
319 322
       #endif
320
-#if Z_MIN_PIN > -1
321
-      if(READ(Z_MIN_PIN) != ENDSTOPS_INVERTING) {
322
-        step_events_completed = current_block->step_event_count;
323
-      }
324
-#endif
323
+      #if Z_MIN_PIN > -1
324
+        if(READ(Z_MIN_PIN) != ENDSTOPS_INVERTING) {
325
+          step_events_completed = current_block->step_event_count;
326
+        }
327
+      #endif
325 328
     }
326 329
     else { // +direction
327
-        WRITE(Z_DIR_PIN,!INVERT_Z_DIR);
328
-        #ifdef DEBUG_STEPS
330
+      WRITE(Z_DIR_PIN,!INVERT_Z_DIR);
331
+      #ifdef DEBUG_STEPS
329 332
         count_direction[Z_AXIS]=1;
330
-        #endif
331
-#if Z_MAX_PIN > -1
333
+      #endif
334
+      #if Z_MAX_PIN > -1
332 335
         if((READ(Z_MAX_PIN) != ENDSTOPS_INVERTING)  && (current_block->steps_z >0)){
333 336
           step_events_completed = current_block->step_event_count;
334 337
         }
335
-#endif
338
+      #endif
336 339
     }
337 340
 
338
-#ifndef ADVANCE
339
-    if ((out_bits & (1<<E_AXIS)) != 0)   // -direction
340
-      WRITE(E_DIR_PIN,INVERT_E_DIR);
341
-    else // +direction
342
-      WRITE(E_DIR_PIN,!INVERT_E_DIR);
343
-#endif //!ADVANCE
341
+    #ifndef ADVANCE
342
+      if ((out_bits & (1<<E_AXIS)) != 0)   // -direction
343
+        WRITE(E_DIR_PIN,INVERT_E_DIR);
344
+      else // +direction
345
+        WRITE(E_DIR_PIN,!INVERT_E_DIR);
346
+    #endif //!ADVANCE
344 347
 
345 348
     for(char i=0; i < step_loops; i++) { // Take multiple steps per interrupt (For high speed moves) 
346 349
       counter_x += current_block->steps_x;
@@ -349,7 +352,7 @@ if ((out_bits & (1<<X_AXIS)) != 0) {   // -direction
349 352
         counter_x -= current_block->step_event_count;
350 353
         WRITE(X_STEP_PIN, LOW);
351 354
         #ifdef DEBUG_STEPS
352
-        count_position[X_AXIS]+=count_direction[X_AXIS];   
355
+          count_position[X_AXIS]+=count_direction[X_AXIS];   
353 356
         #endif
354 357
       }
355 358
 
@@ -359,7 +362,7 @@ if ((out_bits & (1<<X_AXIS)) != 0) {   // -direction
359 362
         counter_y -= current_block->step_event_count;
360 363
         WRITE(Y_STEP_PIN, LOW);
361 364
         #ifdef DEBUG_STEPS
362
-        count_position[Y_AXIS]+=count_direction[Y_AXIS];
365
+          count_position[Y_AXIS]+=count_direction[Y_AXIS];
363 366
         #endif
364 367
       }
365 368
 
@@ -369,18 +372,18 @@ if ((out_bits & (1<<X_AXIS)) != 0) {   // -direction
369 372
         counter_z -= current_block->step_event_count;
370 373
         WRITE(Z_STEP_PIN, LOW);
371 374
         #ifdef DEBUG_STEPS
372
-        count_position[Z_AXIS]+=count_direction[Z_AXIS];
375
+          count_position[Z_AXIS]+=count_direction[Z_AXIS];
373 376
         #endif
374 377
       }
375 378
 
376
-#ifndef ADVANCE
377
-      counter_e += current_block->steps_e;
378
-      if (counter_e > 0) {
379
-        WRITE(E_STEP_PIN, HIGH);
380
-        counter_e -= current_block->step_event_count;
381
-        WRITE(E_STEP_PIN, LOW);
382
-      }
383
-#endif //!ADVANCE
379
+      #ifndef ADVANCE
380
+        counter_e += current_block->steps_e;
381
+        if (counter_e > 0) {
382
+          WRITE(E_STEP_PIN, HIGH);
383
+          counter_e -= current_block->step_event_count;
384
+          WRITE(E_STEP_PIN, LOW);
385
+        }
386
+      #endif //!ADVANCE
384 387
       step_events_completed += 1;  
385 388
       if(step_events_completed >= current_block->step_event_count) break;
386 389
     }
@@ -397,9 +400,9 @@ if ((out_bits & (1<<X_AXIS)) != 0) {   // -direction
397 400
 
398 401
       // step_rate to timer interval
399 402
       timer = calc_timer(acc_step_rate);
400
-#ifdef ADVANCE
401
-      advance += advance_rate;
402
-#endif
403
+      #ifdef ADVANCE
404
+        advance += advance_rate;
405
+      #endif
403 406
       acceleration_time += timer;
404 407
       OCR1A = timer;
405 408
     } 
@@ -419,11 +422,11 @@ if ((out_bits & (1<<X_AXIS)) != 0) {   // -direction
419 422
 
420 423
       // step_rate to timer interval
421 424
       timer = calc_timer(step_rate);
422
-#ifdef ADVANCE
423
-      advance -= advance_rate;
424
-      if(advance < final_advance)
425
-        advance = final_advance;
426
-#endif //ADVANCE
425
+      #ifdef ADVANCE
426
+        advance -= advance_rate;
427
+        if(advance < final_advance)
428
+          advance = final_advance;
429
+      #endif //ADVANCE
427 430
       deceleration_time += timer;
428 431
       OCR1A = timer;
429 432
     }       
@@ -438,127 +441,126 @@ if ((out_bits & (1<<X_AXIS)) != 0) {   // -direction
438 441
 }
439 442
 
440 443
 #ifdef ADVANCE
441
-
442
-unsigned char old_OCR0A;
443
-// Timer interrupt for E. e_steps is set in the main routine;
444
-// Timer 0 is shared with millies
445
-ISR(TIMER0_COMPA_vect)
446
-{
447
-  // Critical section needed because Timer 1 interrupt has higher priority. 
448
-  // The pin set functions are placed on trategic position to comply with the stepper driver timing.
449
-  WRITE(E_STEP_PIN, LOW);
450
-  // Set E direction (Depends on E direction + advance)
451
-  if (e_steps < 0) {
452
-    WRITE(E_DIR_PIN,INVERT_E_DIR);    
453
-    e_steps++;
454
-    WRITE(E_STEP_PIN, HIGH);
455
-  } 
456
-  if (e_steps > 0) {
457
-    WRITE(E_DIR_PIN,!INVERT_E_DIR);
458
-    e_steps--;
459
-    WRITE(E_STEP_PIN, HIGH);
444
+  unsigned char old_OCR0A;
445
+  // Timer interrupt for E. e_steps is set in the main routine;
446
+  // Timer 0 is shared with millies
447
+  ISR(TIMER0_COMPA_vect)
448
+  {
449
+    // Critical section needed because Timer 1 interrupt has higher priority. 
450
+    // The pin set functions are placed on trategic position to comply with the stepper driver timing.
451
+    WRITE(E_STEP_PIN, LOW);
452
+    // Set E direction (Depends on E direction + advance)
453
+    if (e_steps < 0) {
454
+      WRITE(E_DIR_PIN,INVERT_E_DIR);    
455
+      e_steps++;
456
+      WRITE(E_STEP_PIN, HIGH);
457
+    } 
458
+    if (e_steps > 0) {
459
+      WRITE(E_DIR_PIN,!INVERT_E_DIR);
460
+      e_steps--;
461
+      WRITE(E_STEP_PIN, HIGH);
462
+    }
463
+    old_OCR0A += 25; // 10kHz interrupt
464
+    OCR0A = old_OCR0A;
460 465
   }
461
-  old_OCR0A += 25; // 10kHz interrupt
462
-  OCR0A = old_OCR0A;
463
-}
464 466
 #endif // ADVANCE
465 467
 
466 468
 void st_init()
467 469
 {
468 470
     //Initialize Dir Pins
469
-#if X_DIR_PIN > -1
470
-  SET_OUTPUT(X_DIR_PIN);
471
-#endif
472
-#if Y_DIR_PIN > -1 
473
-  SET_OUTPUT(Y_DIR_PIN);
474
-#endif
475
-#if Z_DIR_PIN > -1 
476
-  SET_OUTPUT(Z_DIR_PIN);
477
-#endif
478
-#if E_DIR_PIN > -1 
479
-  SET_OUTPUT(E_DIR_PIN);
480
-#endif
471
+  #if X_DIR_PIN > -1
472
+    SET_OUTPUT(X_DIR_PIN);
473
+  #endif
474
+  #if Y_DIR_PIN > -1 
475
+    SET_OUTPUT(Y_DIR_PIN);
476
+  #endif
477
+  #if Z_DIR_PIN > -1 
478
+    SET_OUTPUT(Z_DIR_PIN);
479
+  #endif
480
+  #if E_DIR_PIN > -1 
481
+    SET_OUTPUT(E_DIR_PIN);
482
+  #endif
481 483
 
482 484
   //Initialize Enable Pins - steppers default to disabled.
483 485
 
484
-#if (X_ENABLE_PIN > -1)
485
-  SET_OUTPUT(X_ENABLE_PIN);
486
-  if(!X_ENABLE_ON) WRITE(X_ENABLE_PIN,HIGH);
487
-#endif
488
-#if (Y_ENABLE_PIN > -1)
489
-  SET_OUTPUT(Y_ENABLE_PIN);
490
-  if(!Y_ENABLE_ON) WRITE(Y_ENABLE_PIN,HIGH);
491
-#endif
492
-#if (Z_ENABLE_PIN > -1)
493
-  SET_OUTPUT(Z_ENABLE_PIN);
494
-  if(!Z_ENABLE_ON) WRITE(Z_ENABLE_PIN,HIGH);
495
-#endif
496
-#if (E_ENABLE_PIN > -1)
497
-  SET_OUTPUT(E_ENABLE_PIN);
498
-  if(!E_ENABLE_ON) WRITE(E_ENABLE_PIN,HIGH);
499
-#endif
486
+  #if (X_ENABLE_PIN > -1)
487
+    SET_OUTPUT(X_ENABLE_PIN);
488
+    if(!X_ENABLE_ON) WRITE(X_ENABLE_PIN,HIGH);
489
+  #endif
490
+  #if (Y_ENABLE_PIN > -1)
491
+    SET_OUTPUT(Y_ENABLE_PIN);
492
+    if(!Y_ENABLE_ON) WRITE(Y_ENABLE_PIN,HIGH);
493
+  #endif
494
+  #if (Z_ENABLE_PIN > -1)
495
+    SET_OUTPUT(Z_ENABLE_PIN);
496
+    if(!Z_ENABLE_ON) WRITE(Z_ENABLE_PIN,HIGH);
497
+  #endif
498
+  #if (E_ENABLE_PIN > -1)
499
+    SET_OUTPUT(E_ENABLE_PIN);
500
+    if(!E_ENABLE_ON) WRITE(E_ENABLE_PIN,HIGH);
501
+  #endif
500 502
 
501 503
   //endstops and pullups
502
-#ifdef ENDSTOPPULLUPS
503
-#if X_MIN_PIN > -1
504
-  SET_INPUT(X_MIN_PIN); 
505
-  WRITE(X_MIN_PIN,HIGH);
506
-#endif
507
-#if X_MAX_PIN > -1
508
-  SET_INPUT(X_MAX_PIN); 
509
-  WRITE(X_MAX_PIN,HIGH);
510
-#endif
511
-#if Y_MIN_PIN > -1
512
-  SET_INPUT(Y_MIN_PIN); 
513
-  WRITE(Y_MIN_PIN,HIGH);
514
-#endif
515
-#if Y_MAX_PIN > -1
516
-  SET_INPUT(Y_MAX_PIN); 
517
-  WRITE(Y_MAX_PIN,HIGH);
518
-#endif
519
-#if Z_MIN_PIN > -1
520
-  SET_INPUT(Z_MIN_PIN); 
521
-  WRITE(Z_MIN_PIN,HIGH);
522
-#endif
523
-#if Z_MAX_PIN > -1
524
-  SET_INPUT(Z_MAX_PIN); 
525
-  WRITE(Z_MAX_PIN,HIGH);
526
-#endif
527
-#else //ENDSTOPPULLUPS
528
-#if X_MIN_PIN > -1
529
-  SET_INPUT(X_MIN_PIN); 
530
-#endif
531
-#if X_MAX_PIN > -1
532
-  SET_INPUT(X_MAX_PIN); 
533
-#endif
534
-#if Y_MIN_PIN > -1
535
-  SET_INPUT(Y_MIN_PIN); 
536
-#endif
537
-#if Y_MAX_PIN > -1
538
-  SET_INPUT(Y_MAX_PIN); 
539
-#endif
540
-#if Z_MIN_PIN > -1
541
-  SET_INPUT(Z_MIN_PIN); 
542
-#endif
543
-#if Z_MAX_PIN > -1
544
-  SET_INPUT(Z_MAX_PIN); 
545
-#endif
546
-#endif //ENDSTOPPULLUPS
504
+  #ifdef ENDSTOPPULLUPS
505
+    #if X_MIN_PIN > -1
506
+      SET_INPUT(X_MIN_PIN); 
507
+      WRITE(X_MIN_PIN,HIGH);
508
+    #endif
509
+    #if X_MAX_PIN > -1
510
+      SET_INPUT(X_MAX_PIN); 
511
+      WRITE(X_MAX_PIN,HIGH);
512
+    #endif
513
+    #if Y_MIN_PIN > -1
514
+      SET_INPUT(Y_MIN_PIN); 
515
+      WRITE(Y_MIN_PIN,HIGH);
516
+    #endif
517
+    #if Y_MAX_PIN > -1
518
+      SET_INPUT(Y_MAX_PIN); 
519
+      WRITE(Y_MAX_PIN,HIGH);
520
+    #endif
521
+    #if Z_MIN_PIN > -1
522
+      SET_INPUT(Z_MIN_PIN); 
523
+      WRITE(Z_MIN_PIN,HIGH);
524
+    #endif
525
+    #if Z_MAX_PIN > -1
526
+      SET_INPUT(Z_MAX_PIN); 
527
+      WRITE(Z_MAX_PIN,HIGH);
528
+    #endif
529
+  #else //ENDSTOPPULLUPS
530
+    #if X_MIN_PIN > -1
531
+      SET_INPUT(X_MIN_PIN); 
532
+    #endif
533
+    #if X_MAX_PIN > -1
534
+      SET_INPUT(X_MAX_PIN); 
535
+    #endif
536
+    #if Y_MIN_PIN > -1
537
+      SET_INPUT(Y_MIN_PIN); 
538
+    #endif
539
+    #if Y_MAX_PIN > -1
540
+      SET_INPUT(Y_MAX_PIN); 
541
+    #endif
542
+    #if Z_MIN_PIN > -1
543
+      SET_INPUT(Z_MIN_PIN); 
544
+    #endif
545
+    #if Z_MAX_PIN > -1
546
+      SET_INPUT(Z_MAX_PIN); 
547
+    #endif
548
+  #endif //ENDSTOPPULLUPS
547 549
  
548 550
 
549 551
   //Initialize Step Pins
550
-#if (X_STEP_PIN > -1) 
551
-  SET_OUTPUT(X_STEP_PIN);
552
-#endif  
553
-#if (Y_STEP_PIN > -1) 
554
-  SET_OUTPUT(Y_STEP_PIN);
555
-#endif  
556
-#if (Z_STEP_PIN > -1) 
557
-  SET_OUTPUT(Z_STEP_PIN);
558
-#endif  
559
-#if (E_STEP_PIN > -1) 
560
-  SET_OUTPUT(E_STEP_PIN);
561
-#endif  
552
+  #if (X_STEP_PIN > -1) 
553
+    SET_OUTPUT(X_STEP_PIN);
554
+  #endif  
555
+  #if (Y_STEP_PIN > -1) 
556
+    SET_OUTPUT(Y_STEP_PIN);
557
+  #endif  
558
+  #if (Z_STEP_PIN > -1) 
559
+    SET_OUTPUT(Z_STEP_PIN);
560
+  #endif  
561
+  #if (E_STEP_PIN > -1) 
562
+    SET_OUTPUT(E_STEP_PIN);
563
+  #endif  
562 564
 
563 565
   // waveform generation = 0100 = CTC
564 566
   TCCR1B &= ~(1<<WGM13);
@@ -574,10 +576,10 @@ void st_init()
574 576
   OCR1A = 0x4000;
575 577
   DISABLE_STEPPER_DRIVER_INTERRUPT();  
576 578
 
577
-#ifdef ADVANCE
578
-  e_steps = 0;
579
-  TIMSK0 |= (1<<OCIE0A);
580
-#endif //ADVANCE
579
+  #ifdef ADVANCE
580
+    e_steps = 0;
581
+    TIMSK0 |= (1<<OCIE0A);
582
+  #endif //ADVANCE
581 583
   sei();
582 584
 }
583 585
 

+ 2
- 2
Marlin/stepper.h View File

@@ -36,8 +36,8 @@ void st_wake_up();
36 36
 // if DEBUG_STEPS is enabled, M114 can be used to compare two methods of determining the X,Y,Z position of the printer.
37 37
 // for debugging purposes only, should be disabled by default
38 38
 #ifdef DEBUG_STEPS
39
-extern volatile long count_position[NUM_AXIS];
40
-extern volatile int count_direction[NUM_AXIS];
39
+  extern volatile long count_position[NUM_AXIS];
40
+  extern volatile int count_direction[NUM_AXIS];
41 41
 #endif
42 42
 
43 43
 extern block_t *current_block;  // A pointer to the block currently being traced

+ 199
- 194
Marlin/temperature.cpp View File

@@ -74,24 +74,24 @@ unsigned long previous_millis_heater, previous_millis_bed_heater;
74 74
 #endif //WATCHPERIOD
75 75
 
76 76
 #ifdef HEATER_0_MINTEMP
77
-int minttemp_0 = temp2analog(HEATER_0_MINTEMP);
77
+  int minttemp_0 = temp2analog(HEATER_0_MINTEMP);
78 78
 #endif //MINTEMP
79 79
 #ifdef HEATER_0_MAXTEMP
80
-int maxttemp_0 = temp2analog(HEATER_0_MAXTEMP);
80
+  int maxttemp_0 = temp2analog(HEATER_0_MAXTEMP);
81 81
 #endif //MAXTEMP
82 82
 
83 83
 #ifdef HEATER_1_MINTEMP
84
-int minttemp_1 = temp2analog(HEATER_1_MINTEMP);
84
+  int minttemp_1 = temp2analog(HEATER_1_MINTEMP);
85 85
 #endif //MINTEMP
86 86
 #ifdef HEATER_1_MAXTEMP
87
-int maxttemp_1 = temp2analog(HEATER_1_MAXTEMP);
87
+  int maxttemp_1 = temp2analog(HEATER_1_MAXTEMP);
88 88
 #endif //MAXTEMP
89 89
 
90 90
 #ifdef BED_MINTEMP
91
-int bed_minttemp = temp2analog(BED_MINTEMP);
91
+  int bed_minttemp = temp2analog(BED_MINTEMP);
92 92
 #endif //BED_MINTEMP
93 93
 #ifdef BED_MAXTEMP
94
-int bed_maxttemp = temp2analog(BED_MAXTEMP);
94
+  int bed_maxttemp = temp2analog(BED_MAXTEMP);
95 95
 #endif //BED_MAXTEMP
96 96
 
97 97
 void manage_heater()
@@ -105,50 +105,49 @@ void manage_heater()
105 105
   if(temp_meas_ready != true)   //better readability
106 106
     return; 
107 107
 
108
-CRITICAL_SECTION_START;
108
+  CRITICAL_SECTION_START;
109 109
     temp_meas_ready = false;
110
-CRITICAL_SECTION_END;
110
+  CRITICAL_SECTION_END;
111 111
 
112
-#ifdef PIDTEMP
112
+  #ifdef PIDTEMP
113 113
     pid_input = analog2temp(current_raw[TEMPSENSOR_HOTEND_0]);
114 114
 
115
-#ifndef PID_OPENLOOP
116
-    pid_error = pid_setpoint - pid_input;
117
-    if(pid_error > 10){
118
-      pid_output = PID_MAX;
119
-      pid_reset = true;
120
-    }
121
-    else if(pid_error < -10) {
122
-      pid_output = 0;
123
-      pid_reset = true;
124
-    }
125
-    else {
126
-      if(pid_reset == true) {
127
-        temp_iState = 0.0;
128
-        pid_reset = false;
129
-      }
130
-      pTerm = Kp * pid_error;
131
-      temp_iState += pid_error;
132
-      temp_iState = constrain(temp_iState, temp_iState_min, temp_iState_max);
133
-      iTerm = Ki * temp_iState;
134
-      //K1 defined in Configuration.h in the PID settings
135
-      #define K2 (1.0-K1)
136
-      dTerm = (Kd * (pid_input - temp_dState))*K2 + (K1 * dTerm);
137
-      temp_dState = pid_input;
138
-      #ifdef PID_ADD_EXTRUSION_RATE
139
-        pTerm+=Kc*current_block->speed_e; //additional heating if extrusion speed is high
140
-      #endif
141
-      pid_output = constrain(pTerm + iTerm - dTerm, 0, PID_MAX);
142
-    }
143
-#endif //PID_OPENLOOP
144
-#ifdef PID_DEBUG
145
-     SERIAL_ECHOLN(" PIDDEBUG Input "<<pid_input<<" Output "<<pid_output" pTerm "<<pTerm<<" iTerm "<<iTerm<<" dTerm "<<dTerm); 
146
-     
147
-#endif //PID_DEBUG
115
+    #ifndef PID_OPENLOOP
116
+        pid_error = pid_setpoint - pid_input;
117
+        if(pid_error > 10){
118
+          pid_output = PID_MAX;
119
+          pid_reset = true;
120
+        }
121
+        else if(pid_error < -10) {
122
+          pid_output = 0;
123
+          pid_reset = true;
124
+        }
125
+        else {
126
+          if(pid_reset == true) {
127
+            temp_iState = 0.0;
128
+            pid_reset = false;
129
+          }
130
+          pTerm = Kp * pid_error;
131
+          temp_iState += pid_error;
132
+          temp_iState = constrain(temp_iState, temp_iState_min, temp_iState_max);
133
+          iTerm = Ki * temp_iState;
134
+          //K1 defined in Configuration.h in the PID settings
135
+          #define K2 (1.0-K1)
136
+          dTerm = (Kd * (pid_input - temp_dState))*K2 + (K1 * dTerm);
137
+          temp_dState = pid_input;
138
+          #ifdef PID_ADD_EXTRUSION_RATE
139
+            pTerm+=Kc*current_block->speed_e; //additional heating if extrusion speed is high
140
+          #endif
141
+          pid_output = constrain(pTerm + iTerm - dTerm, 0, PID_MAX);
142
+        }
143
+    #endif //PID_OPENLOOP
144
+    #ifdef PID_DEBUG
145
+     SERIAL_ECHOLN(" PIDDEBUG Input "<<pid_input<<" Output "<<pid_output" pTerm "<<pTerm<<" iTerm "<<iTerm<<" dTerm "<<dTerm);  
146
+    #endif //PID_DEBUG
148 147
     analogWrite(HEATER_0_PIN, pid_output);
149
-#endif //PIDTEMP
148
+  #endif //PIDTEMP
150 149
 
151
-#ifndef PIDTEMP
150
+  #ifndef PIDTEMP
152 151
     if(current_raw[0] >= target_raw[0])
153 152
     {
154 153
       WRITE(HEATER_0_PIN,LOW);
@@ -157,7 +156,7 @@ CRITICAL_SECTION_END;
157 156
     {
158 157
       WRITE(HEATER_0_PIN,HIGH);
159 158
     }
160
-#endif
159
+  #endif
161 160
     
162 161
   if(millis() - previous_millis_bed_heater < BED_CHECK_INTERVAL)
163 162
     return;
@@ -173,7 +172,7 @@ CRITICAL_SECTION_END;
173 172
       WRITE(HEATER_1_PIN,HIGH);
174 173
     }
175 174
   #endif
176
-  }
175
+}
177 176
 
178 177
 // Takes hot end temperature value as input and returns corresponding raw value. 
179 178
 // For a thermistor, it uses the RepRap thermistor temp table.
@@ -300,26 +299,26 @@ float analog2tempBed(int raw) {
300 299
 
301 300
 void tp_init()
302 301
 {
303
-#if (HEATER_0_PIN > -1) 
304
-  SET_OUTPUT(HEATER_0_PIN);
305
-#endif  
306
-#if (HEATER_1_PIN > -1) 
307
-  SET_OUTPUT(HEATER_1_PIN);
308
-#endif  
309
-#if (HEATER_2_PIN > -1) 
310
-  SET_OUTPUT(HEATER_2_PIN);
311
-#endif  
312
-
313
-#ifdef PIDTEMP
314
-  temp_iState_min = 0.0;
315
-  temp_iState_max = PID_INTEGRAL_DRIVE_MAX / Ki;
316
-#endif //PIDTEMP
317
-
318
-// Set analog inputs
302
+  #if (HEATER_0_PIN > -1) 
303
+    SET_OUTPUT(HEATER_0_PIN);
304
+  #endif  
305
+  #if (HEATER_1_PIN > -1) 
306
+    SET_OUTPUT(HEATER_1_PIN);
307
+  #endif  
308
+  #if (HEATER_2_PIN > -1) 
309
+    SET_OUTPUT(HEATER_2_PIN);
310
+  #endif  
311
+
312
+  #ifdef PIDTEMP
313
+    temp_iState_min = 0.0;
314
+    temp_iState_max = PID_INTEGRAL_DRIVE_MAX / Ki;
315
+  #endif //PIDTEMP
316
+
317
+  // Set analog inputs
319 318
   ADCSRA = 1<<ADEN | 1<<ADSC | 1<<ADIF | 0x07;
320 319
   
321
-// Use timer0 for temperature measurement
322
-// Interleave temperature interrupt with millies interrupt
320
+  // Use timer0 for temperature measurement
321
+  // Interleave temperature interrupt with millies interrupt
323 322
   OCR0B = 128;
324 323
   TIMSK0 |= (1<<OCIE0B);  
325 324
 }
@@ -344,23 +343,25 @@ void setWatch()
344 343
 
345 344
 void disable_heater()
346 345
 {
347
-   #if TEMP_0_PIN > -1
346
+  #if TEMP_0_PIN > -1
348 347
   target_raw[0]=0;
349 348
    #if HEATER_0_PIN > -1  
350 349
      WRITE(HEATER_0_PIN,LOW);
351 350
    #endif
352 351
   #endif
352
+     
353 353
   #if TEMP_1_PIN > -1
354
-  target_raw[1]=0;
355
-  #if HEATER_1_PIN > -1 
356
-    WRITE(HEATER_1_PIN,LOW);
357
-  #endif
354
+    target_raw[1]=0;
355
+    #if HEATER_1_PIN > -1 
356
+      WRITE(HEATER_1_PIN,LOW);
357
+    #endif
358 358
   #endif
359
+      
359 360
   #if TEMP_2_PIN > -1
360
-  target_raw[2]=0;
361
-  #if HEATER_2_PIN > -1  
362
-    WRITE(HEATER_2_PIN,LOW);
363
-  #endif
361
+    target_raw[2]=0;
362
+    #if HEATER_2_PIN > -1  
363
+      WRITE(HEATER_2_PIN,LOW);
364
+    #endif
364 365
   #endif 
365 366
 }
366 367
 
@@ -376,75 +377,75 @@ ISR(TIMER0_COMPB_vect)
376 377
   
377 378
   switch(temp_state) {
378 379
     case 0: // Prepare TEMP_0
379
-            #if (TEMP_0_PIN > -1)
380
-              #if TEMP_0_PIN < 8
381
-                DIDR0 = 1 << TEMP_0_PIN; 
382
-              #else
383
-                DIDR2 = 1<<(TEMP_0_PIN - 8); 
384
-                ADCSRB = 1<<MUX5;
385
-              #endif
386
-              ADMUX = ((1 << REFS0) | (TEMP_0_PIN & 0x07));
387
-              ADCSRA |= 1<<ADSC; // Start conversion
388
-            #endif
389
-            #ifdef ULTIPANEL
390
-              buttons_check();
391
-            #endif
392
-            temp_state = 1;
393
-            break;
380
+      #if (TEMP_0_PIN > -1)
381
+        #if TEMP_0_PIN < 8
382
+          DIDR0 = 1 << TEMP_0_PIN; 
383
+        #else
384
+          DIDR2 = 1<<(TEMP_0_PIN - 8); 
385
+          ADCSRB = 1<<MUX5;
386
+        #endif
387
+        ADMUX = ((1 << REFS0) | (TEMP_0_PIN & 0x07));
388
+        ADCSRA |= 1<<ADSC; // Start conversion
389
+      #endif
390
+      #ifdef ULTIPANEL
391
+        buttons_check();
392
+      #endif
393
+      temp_state = 1;
394
+      break;
394 395
     case 1: // Measure TEMP_0
395
-            #if (TEMP_0_PIN > -1)
396
-              raw_temp_0_value += ADC;
397
-            #endif
398
-            temp_state = 2;
399
-            break;
396
+      #if (TEMP_0_PIN > -1)
397
+        raw_temp_0_value += ADC;
398
+      #endif
399
+      temp_state = 2;
400
+      break;
400 401
     case 2: // Prepare TEMP_1
401
-            #if (TEMP_1_PIN > -1)
402
-              #if TEMP_1_PIN < 7
403
-                DIDR0 = 1<<TEMP_1_PIN; 
404
-              #else
405
-                DIDR2 = 1<<(TEMP_1_PIN - 8); 
406
-                ADCSRB = 1<<MUX5;
407
-              #endif
408
-              ADMUX = ((1 << REFS0) | (TEMP_1_PIN & 0x07));
409
-              ADCSRA |= 1<<ADSC; // Start conversion
410
-            #endif
411
-            #ifdef ULTIPANEL
412
-              buttons_check();
413
-            #endif
414
-            temp_state = 3;
415
-            break;
402
+      #if (TEMP_1_PIN > -1)
403
+        #if TEMP_1_PIN < 7
404
+          DIDR0 = 1<<TEMP_1_PIN; 
405
+        #else
406
+          DIDR2 = 1<<(TEMP_1_PIN - 8); 
407
+          ADCSRB = 1<<MUX5;
408
+        #endif
409
+        ADMUX = ((1 << REFS0) | (TEMP_1_PIN & 0x07));
410
+        ADCSRA |= 1<<ADSC; // Start conversion
411
+      #endif
412
+      #ifdef ULTIPANEL
413
+        buttons_check();
414
+      #endif
415
+      temp_state = 3;
416
+      break;
416 417
     case 3: // Measure TEMP_1
417
-            #if (TEMP_1_PIN > -1)
418
-              raw_temp_1_value += ADC;
419
-            #endif
420
-            temp_state = 4;
421
-            break;
418
+      #if (TEMP_1_PIN > -1)
419
+        raw_temp_1_value += ADC;
420
+      #endif
421
+      temp_state = 4;
422
+      break;
422 423
     case 4: // Prepare TEMP_2
423
-            #if (TEMP_2_PIN > -1)
424
-              #if TEMP_2_PIN < 7
425
-                DIDR0 = 1 << TEMP_2_PIN; 
426
-              #else
427
-                DIDR2 = 1<<(TEMP_2_PIN - 8); 
428
-                ADCSRB = 1<<MUX5;
429
-              #endif
430
-              ADMUX = ((1 << REFS0) | (TEMP_2_PIN & 0x07));
431
-              ADCSRA |= 1<<ADSC; // Start conversion
432
-            #endif
433
-            #ifdef ULTIPANEL
434
-              buttons_check();
435
-            #endif
436
-            temp_state = 5;
437
-            break;
424
+      #if (TEMP_2_PIN > -1)
425
+        #if TEMP_2_PIN < 7
426
+          DIDR0 = 1 << TEMP_2_PIN; 
427
+        #else
428
+          DIDR2 = 1<<(TEMP_2_PIN - 8); 
429
+          ADCSRB = 1<<MUX5;
430
+        #endif
431
+        ADMUX = ((1 << REFS0) | (TEMP_2_PIN & 0x07));
432
+        ADCSRA |= 1<<ADSC; // Start conversion
433
+      #endif
434
+      #ifdef ULTIPANEL
435
+        buttons_check();
436
+      #endif
437
+      temp_state = 5;
438
+      break;
438 439
     case 5: // Measure TEMP_2
439
-            #if (TEMP_2_PIN > -1)
440
-              raw_temp_2_value += ADC;
441
-            #endif
442
-            temp_state = 0;
443
-            temp_count++;
444
-            break;
440
+      #if (TEMP_2_PIN > -1)
441
+        raw_temp_2_value += ADC;
442
+      #endif
443
+      temp_state = 0;
444
+      temp_count++;
445
+      break;
445 446
     default:
446
-            SERIAL_ERRORLN("Temp measurement error!");
447
-            break;
447
+      SERIAL_ERRORLN("Temp measurement error!");
448
+      break;
448 449
   }
449 450
     
450 451
   if(temp_count >= 16) // 6 ms * 16 = 96ms.
@@ -472,67 +473,71 @@ ISR(TIMER0_COMPB_vect)
472 473
     raw_temp_0_value = 0;
473 474
     raw_temp_1_value = 0;
474 475
     raw_temp_2_value = 0;
475
-#ifdef HEATER_0_MAXTEMP
476
-  #if (HEATER_0_PIN > -1)
477
-    if(current_raw[TEMPSENSOR_HOTEND_0] >= maxttemp_0) {
478
-      target_raw[TEMPSENSOR_HOTEND_0] = 0;
479
-      analogWrite(HEATER_0_PIN, 0);
480
-      SERIAL_ERRORLN("Temperature extruder 0 switched off. MAXTEMP triggered !!");
481
-      kill();
482
-    }
483
-  #endif
484
-#endif
485
-#ifdef HEATER_1_MAXTEMP
486
-  #if (HEATER_1_PIN > -1)
487
-    if(current_raw[TEMPSENSOR_HOTEND_1] >= maxttemp_1) {
488
-      target_raw[TEMPSENSOR_HOTEND_1] = 0;
489
-    if(current_raw[2] >= maxttemp_1) {
490
-      analogWrite(HEATER_2_PIN, 0);
491
-      SERIAL_ERRORLN("Temperature extruder 1 switched off. MAXTEMP triggered !!");
492
-      kill()
493
-    }
494
-  #endif
495
-#endif //MAXTEMP
496
-#ifdef HEATER_0_MINTEMP
497
-  #if (HEATER_0_PIN > -1)
498
-    if(current_raw[TEMPSENSOR_HOTEND_0] <= minttemp_0) {
499
-      target_raw[TEMPSENSOR_HOTEND_0] = 0;
500
-      analogWrite(HEATER_0_PIN, 0);
501
-      SERIAL_ERRORLN("Temperature extruder 0 switched off. MINTEMP triggered !!");
502
-      kill();
503
-    }
504
-  #endif
505
-#endif
506
-#ifdef HEATER_1_MINTEMP
507
-  #if (HEATER_2_PIN > -1)
508
-    if(current_raw[TEMPSENSOR_HOTEND_1] <= minttemp_1) {
509
-      target_raw[TEMPSENSOR_HOTEND_1] = 0;
510
-      analogWrite(HEATER_2_PIN, 0);
511
-      SERIAL_ERRORLN("Temperature extruder 1 switched off. MINTEMP triggered !!");
512
-      kill();
513
-    }
476
+    #ifdef HEATER_0_MAXTEMP
477
+      #if (HEATER_0_PIN > -1)
478
+        if(current_raw[TEMPSENSOR_HOTEND_0] >= maxttemp_0) {
479
+          target_raw[TEMPSENSOR_HOTEND_0] = 0;
480
+          analogWrite(HEATER_0_PIN, 0);
481
+          SERIAL_ERRORLN("Temperature extruder 0 switched off. MAXTEMP triggered !!");
482
+          kill();
483
+        }
484
+      #endif
485
+    #endif
486
+  #ifdef HEATER_1_MAXTEMP
487
+    #if (HEATER_1_PIN > -1)
488
+      if(current_raw[TEMPSENSOR_HOTEND_1] >= maxttemp_1) {
489
+        target_raw[TEMPSENSOR_HOTEND_1] = 0;
490
+      if(current_raw[2] >= maxttemp_1) {
491
+        analogWrite(HEATER_2_PIN, 0);
492
+        SERIAL_ERRORLN("Temperature extruder 1 switched off. MAXTEMP triggered !!");
493
+        kill()
494
+      }
495
+    #endif
496
+  #endif //MAXTEMP
497
+  
498
+  #ifdef HEATER_0_MINTEMP
499
+    #if (HEATER_0_PIN > -1)
500
+      if(current_raw[TEMPSENSOR_HOTEND_0] <= minttemp_0) {
501
+        target_raw[TEMPSENSOR_HOTEND_0] = 0;
502
+        analogWrite(HEATER_0_PIN, 0);
503
+        SERIAL_ERRORLN("Temperature extruder 0 switched off. MINTEMP triggered !!");
504
+        kill();
505
+      }
506
+    #endif
514 507
   #endif
515
-#endif //MAXTEMP
516
-#ifdef BED_MINTEMP
517
-  #if (HEATER_1_PIN > -1)
518
-    if(current_raw[1] <= bed_minttemp) {
519
-      target_raw[1] = 0;
520
-      WRITE(HEATER_1_PIN, 0);
521
-      SERIAL_ERRORLN("Temperatur heated bed switched off. MINTEMP triggered !!");
522
-      kill();
523
-    }
508
+  
509
+  #ifdef HEATER_1_MINTEMP
510
+    #if (HEATER_2_PIN > -1)
511
+      if(current_raw[TEMPSENSOR_HOTEND_1] <= minttemp_1) {
512
+        target_raw[TEMPSENSOR_HOTEND_1] = 0;
513
+        analogWrite(HEATER_2_PIN, 0);
514
+        SERIAL_ERRORLN("Temperature extruder 1 switched off. MINTEMP triggered !!");
515
+        kill();
516
+      }
517
+    #endif
518
+  #endif //MAXTEMP
519
+  
520
+  #ifdef BED_MINTEMP
521
+    #if (HEATER_1_PIN > -1)
522
+      if(current_raw[1] <= bed_minttemp) {
523
+        target_raw[1] = 0;
524
+        WRITE(HEATER_1_PIN, 0);
525
+        SERIAL_ERRORLN("Temperatur heated bed switched off. MINTEMP triggered !!");
526
+        kill();
527
+      }
528
+    #endif
524 529
   #endif
525
-#endif
526
-#ifdef BED_MAXTEMP
527
-  #if (HEATER_1_PIN > -1)
528
-    if(current_raw[1] >= bed_maxttemp) {
529
-      target_raw[1] = 0;
530
-      WRITE(HEATER_1_PIN, 0);
531
-      SERIAL_ERRORLN("Temperature heated bed switched off. MAXTEMP triggered !!");
532
-      kill();
533
-    }
530
+  
531
+  #ifdef BED_MAXTEMP
532
+    #if (HEATER_1_PIN > -1)
533
+      if(current_raw[1] >= bed_maxttemp) {
534
+        target_raw[1] = 0;
535
+        WRITE(HEATER_1_PIN, 0);
536
+        SERIAL_ERRORLN("Temperature heated bed switched off. MAXTEMP triggered !!");
537
+        kill();
538
+      }
539
+    #endif
534 540
   #endif
535
-#endif
536 541
   }
537 542
 }
538 543
 

+ 7
- 14
Marlin/temperature.h View File

@@ -27,9 +27,11 @@
27 27
   #include "stepper.h"
28 28
 #endif
29 29
 
30
+// public functions
30 31
 void tp_init();  //initialise the heating
31 32
 void manage_heater(); //it is critical that this is called periodically.
32 33
 
34
+
33 35
 enum TempSensor {TEMPSENSOR_HOTEND_0=0,TEMPSENSOR_BED=1, TEMPSENSOR_HOTEND_1=2};
34 36
 
35 37
 //low leven conversion routines
@@ -41,9 +43,11 @@ float analog2tempBed(int raw);
41 43
 extern int target_raw[3];  
42 44
 extern int current_raw[3];
43 45
 extern float Kp,Ki,Kd,Kc;
46
+
44 47
 #ifdef PIDTEMP
45 48
   extern float pid_setpoint ;
46 49
 #endif
50
+  
47 51
 #ifdef WATCHPERIOD
48 52
   extern int watch_raw[3] ;
49 53
   extern unsigned long watchmillis;
@@ -63,15 +67,15 @@ inline float degTargetHotend0() {  return analog2temp(target_raw[TEMPSENSOR_HOTE
63 67
 inline float degTargetHotend1() {  return analog2temp(target_raw[TEMPSENSOR_HOTEND_1]);};
64 68
 inline float degTargetBed() {   return analog2tempBed(target_raw[TEMPSENSOR_BED]);};
65 69
 
66
-inline void setTargetHotend0(float celsius) 
70
+inline void setTargetHotend0(const float &celsius) 
67 71
 {  
68 72
   target_raw[TEMPSENSOR_HOTEND_0]=temp2analog(celsius);
69 73
   #ifdef PIDTEMP
70 74
     pid_setpoint = celsius;
71 75
   #endif //PIDTEMP
72 76
 };
73
-inline void setTargetHotend1(float celsius) {  target_raw[TEMPSENSOR_HOTEND_1]=temp2analog(celsius);};
74
-inline void setTargetBed(float celsius)     {  target_raw[TEMPSENSOR_BED     ]=temp2analogBed(celsius);};
77
+inline void setTargetHotend1(const float &celsius) {  target_raw[TEMPSENSOR_HOTEND_1]=temp2analog(celsius);};
78
+inline void setTargetBed(const float &celsius)     {  target_raw[TEMPSENSOR_BED     ]=temp2analogBed(celsius);};
75 79
 
76 80
 inline bool isHeatingHotend0() {return target_raw[TEMPSENSOR_HOTEND_0] > current_raw[TEMPSENSOR_HOTEND_0];};
77 81
 inline bool isHeatingHotend1() {return target_raw[TEMPSENSOR_HOTEND_1] > current_raw[TEMPSENSOR_HOTEND_1];};
@@ -84,16 +88,5 @@ inline bool isCoolingBed() {return target_raw[TEMPSENSOR_BED] < current_raw[TEMP
84 88
 void disable_heater();
85 89
 void setWatch();
86 90
 
87
-#ifdef HEATER_0_USES_THERMISTOR
88
-    #define HEATERSOURCE 1
89
-#endif
90
-#ifdef BED_USES_THERMISTOR
91
-    #define BEDSOURCE 1
92
-#endif
93
-
94
-
95
-
96
-
97
-
98 91
 #endif
99 92
 

+ 37
- 91
Marlin/ultralcd.h View File

@@ -9,107 +9,48 @@
9 9
   void lcd_status(const char* message);
10 10
   void beep();
11 11
   void buttons_check();
12
-  #define LCDSTATUSRIGHT
12
+
13 13
 
14 14
   #define LCD_UPDATE_INTERVAL 100
15 15
   #define STATUSTIMEOUT 15000
16 16
 
17
-  #include "Configuration.h"
18 17
 
19 18
   #include <LiquidCrystal.h>
20 19
   extern LiquidCrystal lcd;
21 20
 
22
-  //lcd display size
23
-
24
-#ifdef NEWPANEL
25
- //arduino pin witch triggers an piezzo beeper
26
-  #define BEEPER 18
27 21
 
28
-  #define LCD_PINS_RS 20 
29
-  #define LCD_PINS_ENABLE 17
30
-  #define LCD_PINS_D4 16
31
-  #define LCD_PINS_D5 21 
32
-  #define LCD_PINS_D6 5
33
-  #define LCD_PINS_D7 6
34
-  
35
-  //buttons are directly attached
36
-  #define BTN_EN1 40
37
-  #define BTN_EN2 42
38
-  #define BTN_ENC 19  //the click
39
-  
40
-  #define BLEN_C 2
41
-  #define BLEN_B 1
42
-  #define BLEN_A 0
43
-  
44
-  #define SDCARDDETECT 38
45
-  
46
-  #define EN_C (1<<BLEN_C)
47
-  #define EN_B (1<<BLEN_B)
48
-  #define EN_A (1<<BLEN_A)
49
-  
50
-   //encoder rotation values
51
-  #define encrot0 0
52
-  #define encrot1 2
53
-  #define encrot2 3
54
-  #define encrot3 1
22
+  #ifdef NEWPANEL
55 23
 
56
-  
57
-  #define CLICKED (buttons&EN_C)
58
-  #define BLOCK {blocking=millis()+blocktime;}
59
-  #define CARDINSERTED (READ(SDCARDDETECT)==0)
60
-  
61
-#else
62
-  //arduino pin witch triggers an piezzo beeper
63
-  #define BEEPER 18
64
-
65
-  //buttons are attached to a shift register
66
-  #define SHIFT_CLK 38
67
-  #define SHIFT_LD 42
68
-  #define SHIFT_OUT 40
69
-  #define SHIFT_EN 17
70
-  
71
-  #define LCD_PINS_RS 16 
72
-  #define LCD_PINS_ENABLE 5
73
-  #define LCD_PINS_D4 6
74
-  #define LCD_PINS_D5 21 
75
-  #define LCD_PINS_D6 20
76
-  #define LCD_PINS_D7 19
77
-  
78
-   //bits in the shift register that carry the buttons for:
79
-  // left up center down right red
80
-  #define BL_LE 7
81
-  #define BL_UP 6
82
-  #define BL_MI 5
83
-  #define BL_DW 4
84
-  #define BL_RI 3
85
-  #define BL_ST 2
86
-
87
-  #define BLEN_B 1
88
-  #define BLEN_A 0
89
-
90
-  //encoder rotation values
91
-  #define encrot0 0
92
-  #define encrot1 2
93
-  #define encrot2 3
94
-  #define encrot3 1
95
-
96
-  //atomatic, do not change
97
-  #define B_LE (1<<BL_LE)
98
-  #define B_UP (1<<BL_UP)
99
-  #define B_MI (1<<BL_MI)
100
-  #define B_DW (1<<BL_DW)
101
-  #define B_RI (1<<BL_RI)
102
-  #define B_ST (1<<BL_ST)
103
-  #define EN_B (1<<BLEN_B)
104
-  #define EN_A (1<<BLEN_A)
105
-  
106
-  #define CLICKED ((buttons&B_MI)||(buttons&B_ST))
107
-  #define BLOCK {blocking[BL_MI]=millis()+blocktime;blocking[BL_ST]=millis()+blocktime;}
108
-  
109
-#endif
24
+    
25
+    #define EN_C (1<<BLEN_C)
26
+    #define EN_B (1<<BLEN_B)
27
+    #define EN_A (1<<BLEN_A)
28
+    
29
+    #define CLICKED (buttons&EN_C)
30
+    #define BLOCK {blocking=millis()+blocktime;}
31
+    #define CARDINSERTED (READ(SDCARDDETECT)==0)
32
+    
33
+  #else
34
+
35
+    //atomatic, do not change
36
+    #define B_LE (1<<BL_LE)
37
+    #define B_UP (1<<BL_UP)
38
+    #define B_MI (1<<BL_MI)
39
+    #define B_DW (1<<BL_DW)
40
+    #define B_RI (1<<BL_RI)
41
+    #define B_ST (1<<BL_ST)
42
+    #define EN_B (1<<BLEN_B)
43
+    #define EN_A (1<<BLEN_A)
44
+    
45
+    #define CLICKED ((buttons&B_MI)||(buttons&B_ST))
46
+    #define BLOCK {blocking[BL_MI]=millis()+blocktime;blocking[BL_ST]=millis()+blocktime;}
47
+    
48
+  #endif
49
+    
110 50
   // blocking time for recognizing a new keypress of one key, ms
111
-#define blocktime 500
112
-#define lcdslow 5
51
+  #define blocktime 500
52
+  #define lcdslow 5
53
+    
113 54
   enum MainStatus{Main_Status, Main_Menu, Main_Prepare, Main_Control, Main_SD};
114 55
 
115 56
   class MainMenu{
@@ -134,6 +75,7 @@
134 75
     bool linechanging;
135 76
   };
136 77
 
78
+  //conversion routines, could need some overworking
137 79
   char *fillto(int8_t n,char *c);
138 80
   char *ftostr51(const float &x);
139 81
   char *ftostr31(const float &x);
@@ -146,11 +88,15 @@
146 88
 #else //no lcd
147 89
   #define LCD_STATUS
148 90
   #define LCD_MESSAGE(x)
91
+  inline void lcd_status() {};
149 92
 #endif
150 93
   
151 94
 #ifndef ULTIPANEL  
152 95
  #define CLICKED false
153
-#define BLOCK ;
96
+  #define BLOCK ;
154 97
 #endif 
98
+  
99
+  
100
+  
155 101
 #endif //ULTRALCD
156 102
 

+ 98
- 99
Marlin/ultralcd.pde View File

@@ -1,7 +1,7 @@
1 1
 #include "ultralcd.h"
2
+#ifdef ULTRA_LCD
2 3
 
3 4
 
4
-#ifdef ULTRA_LCD
5 5
 extern volatile int feedmultiply;
6 6
 extern long position[4];   
7 7
 
@@ -122,58 +122,57 @@ void lcd_status()
122 122
   menu.update();
123 123
 }
124 124
 #ifdef ULTIPANEL  
125
+
126
+
125 127
 void buttons_init()
126 128
 {
127
-#ifdef NEWPANEL
128
-  pinMode(BTN_EN1,INPUT);
129
-  pinMode(BTN_EN2,INPUT); 
130
-  pinMode(BTN_ENC,INPUT); 
131
-  pinMode(SDCARDDETECT,INPUT);
132
-  WRITE(BTN_EN1,HIGH);
133
-  WRITE(BTN_EN2,HIGH);
134
-  WRITE(BTN_ENC,HIGH);
135
-  WRITE(SDCARDDETECT,HIGH);
136
-#else
137
-  pinMode(SHIFT_CLK,OUTPUT);
138
-  pinMode(SHIFT_LD,OUTPUT);
139
-  pinMode(SHIFT_EN,OUTPUT);
140
-  pinMode(SHIFT_OUT,INPUT);
141
-  WRITE(SHIFT_OUT,HIGH);
142
-  WRITE(SHIFT_LD,HIGH); 
143
-  WRITE(SHIFT_EN,LOW); 
144
-#endif
129
+  #ifdef NEWPANEL
130
+    pinMode(BTN_EN1,INPUT);
131
+    pinMode(BTN_EN2,INPUT); 
132
+    pinMode(BTN_ENC,INPUT); 
133
+    pinMode(SDCARDDETECT,INPUT);
134
+    WRITE(BTN_EN1,HIGH);
135
+    WRITE(BTN_EN2,HIGH);
136
+    WRITE(BTN_ENC,HIGH);
137
+    WRITE(SDCARDDETECT,HIGH);
138
+  #else
139
+    pinMode(SHIFT_CLK,OUTPUT);
140
+    pinMode(SHIFT_LD,OUTPUT);
141
+    pinMode(SHIFT_EN,OUTPUT);
142
+    pinMode(SHIFT_OUT,INPUT);
143
+    WRITE(SHIFT_OUT,HIGH);
144
+    WRITE(SHIFT_LD,HIGH); 
145
+    WRITE(SHIFT_EN,LOW); 
146
+  #endif
145 147
 }
146 148
 
147 149
 
148 150
 void buttons_check()
149 151
 {
150
-//  volatile static bool busy=false;
151
-//  if(busy) 
152
-//    return;
153
-//  busy=true;
154 152
   
155
-#ifdef NEWPANEL
156
-  uint8_t newbutton=0;
157
-  if(READ(BTN_EN1)==0)  newbutton|=EN_A;
158
-  if(READ(BTN_EN2)==0)  newbutton|=EN_B;
159
-  if((blocking<millis()) &&(READ(BTN_ENC)==0))
160
-    newbutton|=EN_C;
161
-  buttons=newbutton;
162
-#else   //read it from the shift register
163
-  uint8_t newbutton=0;
164
-  WRITE(SHIFT_LD,LOW);
165
-  WRITE(SHIFT_LD,HIGH);
166
-  unsigned char tmp_buttons=0;
167
-  for(unsigned char i=0;i<8;i++)
168
-  { 
169
-    newbutton = newbutton>>1;
170
-    if(READ(SHIFT_OUT))
171
-      newbutton|=(1<<7);
172
-    WRITE(SHIFT_CLK,HIGH);
173
-    WRITE(SHIFT_CLK,LOW);
174
-  }
175
-  buttons=~newbutton; //invert it, because a pressed switch produces a logical 0
176
-#endif
153
+  #ifdef NEWPANEL
154
+    uint8_t newbutton=0;
155
+    if(READ(BTN_EN1)==0)  newbutton|=EN_A;
156
+    if(READ(BTN_EN2)==0)  newbutton|=EN_B;
157
+    if((blocking<millis()) &&(READ(BTN_ENC)==0))
158
+      newbutton|=EN_C;
159
+    buttons=newbutton;
160
+  #else   //read it from the shift register
161
+    uint8_t newbutton=0;
162
+    WRITE(SHIFT_LD,LOW);
163
+    WRITE(SHIFT_LD,HIGH);
164
+    unsigned char tmp_buttons=0;
165
+    for(unsigned char i=0;i<8;i++)
166
+    { 
167
+      newbutton = newbutton>>1;
168
+      if(READ(SHIFT_OUT))
169
+        newbutton|=(1<<7);
170
+      WRITE(SHIFT_CLK,HIGH);
171
+      WRITE(SHIFT_CLK,LOW);
172
+    }
173
+    buttons=~newbutton; //invert it, because a pressed switch produces a logical 0
174
+  #endif
175
+  
177 176
   char enc=0;
178 177
   if(buttons&EN_A)
179 178
     enc|=(1<<0);
@@ -212,7 +211,6 @@ void buttons_check()
212 211
     }
213 212
   }
214 213
   lastenc=enc;
215
-//  busy=false;
216 214
 }
217 215
 
218 216
 #endif
@@ -223,9 +221,9 @@ MainMenu::MainMenu()
223 221
   displayStartingRow=0;
224 222
   activeline=0;
225 223
   force_lcd_update=true;
226
-#ifdef ULTIPANEL
227
-  buttons_init();
228
-#endif
224
+  #ifdef ULTIPANEL
225
+    buttons_init();
226
+  #endif
229 227
   lcd_init();
230 228
   linechanging=false;
231 229
 }
@@ -1154,12 +1152,13 @@ uint8_t getnrfilenames()
1154 1152
     cnt++;
1155 1153
   }
1156 1154
   return cnt;
1155
+#else
1156
+  return 0;
1157 1157
 #endif
1158 1158
 }
1159 1159
 
1160 1160
 void MainMenu::showSD()
1161 1161
 {
1162
-
1163 1162
 #ifdef SDSUPPORT
1164 1163
  uint8_t line=0;
1165 1164
 
@@ -1205,11 +1204,11 @@ void MainMenu::showSD()
1205 1204
         if(force_lcd_update)
1206 1205
         {
1207 1206
           lcd.setCursor(0,line);
1208
-#ifdef CARDINSERTED
1207
+           #ifdef CARDINSERTED
1209 1208
           if(CARDINSERTED)
1210
-#else
1209
+          #else
1211 1210
           if(true)
1212
-#endif
1211
+          #endif
1213 1212
           {
1214 1213
             lcd.print(" \004Refresh");
1215 1214
           }
@@ -1306,9 +1305,9 @@ void MainMenu::showMainMenu()
1306 1305
 {
1307 1306
    //if(int(encoderpos/lcdslow)!=int(lastencoderpos/lcdslow))
1308 1307
    //  force_lcd_update=true;
1309
-#ifndef ULTIPANEL
1310
-   force_lcd_update=false;
1311
-#endif
1308
+  #ifndef ULTIPANEL
1309
+    force_lcd_update=false;
1310
+  #endif
1312 1311
    //Serial.println((int)activeline);
1313 1312
    if(force_lcd_update)
1314 1313
      clear();
@@ -1347,17 +1346,17 @@ void MainMenu::showMainMenu()
1347 1346
           beepshort();
1348 1347
         }
1349 1348
       }break;
1350
-#ifdef SDSUPPORT
1349
+      #ifdef SDSUPPORT
1351 1350
       case ItemM_file:    
1352 1351
       {
1353 1352
         if(force_lcd_update) 
1354 1353
         {
1355 1354
           lcd.setCursor(0,line);
1356
-#ifdef CARDINSERTED
1357
-          if(CARDINSERTED)
1358
-#else
1359
-          if(true)
1360
-#endif
1355
+          #ifdef CARDINSERTED
1356
+            if(CARDINSERTED)
1357
+          #else
1358
+            if(true)
1359
+          #endif
1361 1360
           {
1362 1361
             if(sdmode)
1363 1362
               lcd.print(" Stop Print   \x7E");
@@ -1370,7 +1369,7 @@ void MainMenu::showMainMenu()
1370 1369
           }
1371 1370
         }
1372 1371
         #ifdef CARDINSERTED
1373
-        if(CARDINSERTED)
1372
+          if(CARDINSERTED)
1374 1373
         #endif
1375 1374
         if((activeline==line)&&CLICKED)
1376 1375
         {
@@ -1380,28 +1379,30 @@ void MainMenu::showMainMenu()
1380 1379
           beepshort();
1381 1380
         }
1382 1381
       }break;
1383
-#endif
1382
+      #endif
1384 1383
       default: 
1385 1384
         SERIAL_ERRORLN("Something is wrong in the MenuStructure.");
1386 1385
       break;
1387 1386
     }
1388 1387
   }
1389
-  if(activeline<0) activeline=0;
1390
-  if(activeline>=LCD_HEIGHT) activeline=LCD_HEIGHT-1;
1388
+  if(activeline<0) 
1389
+    activeline=0;
1390
+  if(activeline>=LCD_HEIGHT) 
1391
+    activeline=LCD_HEIGHT-1;
1391 1392
   if((encoderpos!=lastencoderpos)||force_lcd_update)
1392 1393
   {
1393 1394
     lcd.setCursor(0,activeline);lcd.print(activeline?' ':' ');
1394 1395
     if(encoderpos<0) encoderpos=0;
1395
-    if(encoderpos>3*lcdslow) encoderpos=3*lcdslow;
1396
+    if(encoderpos>3*lcdslow) 
1397
+      encoderpos=3*lcdslow;
1396 1398
     activeline=abs(encoderpos/lcdslow)%LCD_HEIGHT;
1397
-     if(activeline<0) activeline=0;
1398
-  if(activeline>=LCD_HEIGHT) activeline=LCD_HEIGHT-1;
1399
+    if(activeline<0) 
1400
+      activeline=0;
1401
+    if(activeline>=LCD_HEIGHT) 
1402
+      activeline=LCD_HEIGHT-1;
1399 1403
     lastencoderpos=encoderpos;
1400 1404
     lcd.setCursor(0,activeline);lcd.print(activeline?'>':'\003');
1401 1405
   }
1402
-
1403
-  
1404
-  
1405 1406
 }
1406 1407
 
1407 1408
 void MainMenu::update()
@@ -1409,25 +1410,24 @@ void MainMenu::update()
1409 1410
   static MainStatus oldstatus=Main_Menu;  //init automatically causes foce_lcd_update=true
1410 1411
   static long timeoutToStatus=0;
1411 1412
   static bool oldcardstatus=false;
1412
-#ifdef CARDINSERTED
1413
-  if((CARDINSERTED != oldcardstatus))
1414
-  {
1415
-    force_lcd_update=true;
1416
-    oldcardstatus=CARDINSERTED;
1417
-    //Serial.println("echo: SD CHANGE");
1418
-    if(CARDINSERTED)
1419
-    {
1420
-      initsd();
1421
-      lcd_status("Card inserted");
1422
-    }
1423
-    else
1413
+  #ifdef CARDINSERTED
1414
+    if((CARDINSERTED != oldcardstatus))
1424 1415
     {
1425
-      sdactive=false;
1426
-      lcd_status("Card removed");
1427
-      
1416
+      force_lcd_update=true;
1417
+      oldcardstatus=CARDINSERTED;
1418
+      //Serial.println("echo: SD CHANGE");
1419
+      if(CARDINSERTED)
1420
+      {
1421
+        initsd();
1422
+        lcd_status("Card inserted");
1423
+      }
1424
+      else
1425
+      {
1426
+        sdactive=false;
1427
+        lcd_status("Card removed");
1428
+      }
1428 1429
     }
1429
-  }
1430
-#endif
1430
+  #endif
1431 1431
  
1432 1432
   if(status!=oldstatus)
1433 1433
   {
@@ -1484,9 +1484,9 @@ void MainMenu::update()
1484 1484
 
1485 1485
 
1486 1486
 //return for string conversion routines
1487
-char conv[8];
1487
+static char conv[8];
1488 1488
 
1489
-///  convert float to string with +123.4 format
1489
+//  convert float to string with +123.4 format
1490 1490
 char *ftostr3(const float &x)
1491 1491
 {
1492 1492
   //sprintf(conv,"%5.1f",x);
@@ -1497,6 +1497,7 @@ char *ftostr3(const float &x)
1497 1497
   conv[3]=0;
1498 1498
   return conv;
1499 1499
 }
1500
+
1500 1501
 char *itostr2(const uint8_t &x)
1501 1502
 {
1502 1503
   //sprintf(conv,"%5.1f",x);
@@ -1506,10 +1507,10 @@ char *itostr2(const uint8_t &x)
1506 1507
   conv[2]=0;
1507 1508
   return conv;
1508 1509
 }
1509
-///  convert float to string with +123.4 format
1510
+
1511
+//  convert float to string with +123.4 format
1510 1512
 char *ftostr31(const float &x)
1511 1513
 {
1512
-  //sprintf(conv,"%5.1f",x);
1513 1514
   int xx=x*10;
1514 1515
   conv[0]=(xx>=0)?'+':'-';
1515 1516
   xx=abs(xx);
@@ -1524,7 +1525,6 @@ char *ftostr31(const float &x)
1524 1525
 
1525 1526
 char *itostr31(const int &xx)
1526 1527
 {
1527
-  //sprintf(conv,"%5.1f",x);
1528 1528
   conv[0]=(xx>=0)?'+':'-';
1529 1529
   conv[1]=(xx/1000)%10+'0';
1530 1530
   conv[2]=(xx/100)%10+'0';
@@ -1534,6 +1534,7 @@ char *itostr31(const int &xx)
1534 1534
   conv[6]=0;
1535 1535
   return conv;
1536 1536
 }
1537
+
1537 1538
 char *itostr3(const int &xx)
1538 1539
 {
1539 1540
   conv[0]=(xx/100)%10+'0';
@@ -1553,7 +1554,7 @@ char *itostr4(const int &xx)
1553 1554
   return conv;
1554 1555
 }
1555 1556
 
1556
-///  convert float to string with +1234.5 format
1557
+//  convert float to string with +1234.5 format
1557 1558
 char *ftostr51(const float &x)
1558 1559
 {
1559 1560
   int xx=x*10;
@@ -1587,11 +1588,9 @@ char *fillto(int8_t n,char *c)
1587 1588
   }
1588 1589
   ret[n]=0;
1589 1590
   return ret;
1590
-  
1591 1591
 }
1592 1592
 
1593
-#else
1594
-inline void lcd_status() {};
1595
-#endif
1593
+
1594
+#endif //ULTRA_LCD
1596 1595
 
1597 1596
 

+ 9
- 6
Marlin/watchdog.h View File

@@ -1,13 +1,16 @@
1 1
 #ifndef __WATCHDOGH
2 2
 #define __WATCHDOGH
3 3
 #include "Configuration.h"
4
-//#ifdef USE_WATCHDOG
4
+#ifdef USE_WATCHDOG
5 5
 
6
-/// intialise watch dog with a 1 sec interrupt time
7
-void wd_init();
8
-/// pad the dog/reset watchdog. MUST be called at least every second after the first wd_init or avr will go into emergency procedures..
9
-void wd_reset();
6
+  // intialise watch dog with a 1 sec interrupt time
7
+  void wd_init();
8
+  // pad the dog/reset watchdog. MUST be called at least every second after the first wd_init or avr will go into emergency procedures..
9
+  void wd_reset();
10 10
 
11
-//#endif
11
+#else
12
+  inline void wd_init() {};
13
+  inline void wd_reset() {};
14
+#endif
12 15
 
13 16
 #endif

+ 1
- 1
Marlin/watchdog.pde View File

@@ -3,7 +3,7 @@
3 3
 #include  <avr/wdt.h>
4 4
 #include  <avr/interrupt.h>
5 5
 
6
-volatile uint8_t timeout_seconds=0;
6
+static volatile uint8_t timeout_seconds=0;
7 7
 
8 8
 void(* ctrlaltdelete) (void) = 0; //does not work on my atmega2560
9 9
 

Loading…
Cancel
Save