Browse Source

refactured temperature.cpp so that there are now abstract functions to access temperatures.

Bernhard Kubicek 12 years ago
parent
commit
2afb7bd4cf
5 changed files with 237 additions and 179 deletions
  1. 2
    1
      Marlin/Configuration.h
  2. 34
    72
      Marlin/Marlin.pde
  3. 39
    18
      Marlin/temperature.cpp
  4. 85
    15
      Marlin/temperature.h
  5. 77
    73
      Marlin/ultralcd.pde

+ 2
- 1
Marlin/Configuration.h View File

@@ -157,6 +157,7 @@ const int dropsegments=5; //everything with this number of steps  will be ignore
157 157
 //// Experimental watchdog and minimal temp
158 158
 // The watchdog waits for the watchperiod in milliseconds whenever an M104 or M109 increases the target temperature
159 159
 // If the temperature has not increased at the end of that period, the target temperature is set to zero. It can be reset with another M104/M109
160
+/// CURRENTLY NOT IMPLEMENTED AND UNUSEABLE
160 161
 //#define WATCHPERIOD 5000 //5 seconds
161 162
 
162 163
 // Actual temperature must be close to target for this long before M109 returns success
@@ -245,4 +246,4 @@ const int dropsegments=5; //everything with this number of steps  will be ignore
245 246
 #endif
246 247
 
247 248
 
248
-#endif
249
+#endif

+ 34
- 72
Marlin/Marlin.pde View File

@@ -150,10 +150,7 @@ extern float HeaterPower;
150 150
 const int sensitive_pins[] = SENSITIVE_PINS; // Sensitive pin list for M42
151 151
 
152 152
 float tt = 0, bt = 0;
153
-#ifdef WATCHPERIOD
154
-int watch_raw = -1000;
155
-unsigned long watchmillis = 0;
156
-#endif //WATCHPERIOD
153
+
157 154
 
158 155
 //Inactivity shutdown variables
159 156
 unsigned long previous_millis_cmd = 0;
@@ -817,28 +814,18 @@ inline void process_commands()
817 814
         }
818 815
         break;
819 816
       case 104: // M104
820
-                if (code_seen('S')) target_raw[TEMPSENSOR_HOTEND_0] = temp2analog(code_value());
821
-#ifdef PIDTEMP
822
-                pid_setpoint = code_value();
823
-#endif //PIDTEM
824
-        #ifdef WATCHPERIOD
825
-            if(target_raw[TEMPSENSOR_HOTEND_0] > current_raw[TEMPSENSOR_HOTEND_0]){
826
-                watchmillis = max(1,millis());
827
-                watch_raw[TEMPSENSOR_HOTEND_0] = current_raw[TEMPSENSOR_HOTEND_0];
828
-            }else{
829
-                watchmillis = 0;
830
-            }
831
-        #endif
817
+	if (code_seen('S')) setTargetHotend0(code_value());
818
+        setWatch();
832 819
         break;
833 820
       case 140: // M140 set bed temp
834
-                if (code_seen('S')) target_raw[TEMPSENSOR_BED] = temp2analogBed(code_value());
821
+	if (code_seen('S')) setTargetBed(code_value());
835 822
         break;
836 823
       case 105: // M105
837 824
         #if (TEMP_0_PIN > -1) || defined (HEATER_USES_AD595)
838
-                tt = analog2temp(current_raw[TEMPSENSOR_HOTEND_0]);
825
+                tt = degHotend0();
839 826
         #endif
840 827
         #if TEMP_1_PIN > -1
841
-                bt = analog2tempBed(current_raw[TEMPSENSOR_BED]);
828
+                bt = degBed();
842 829
         #endif
843 830
         #if (TEMP_0_PIN > -1) || defined (HEATER_USES_AD595)
844 831
             Serial.print("ok T:");
@@ -866,36 +853,27 @@ inline void process_commands()
866 853
         //break;
867 854
       case 109: {// M109 - Wait for extruder heater to reach target.
868 855
             LCD_MESSAGE("Heating...");
869
-               if (code_seen('S')) target_raw[TEMPSENSOR_HOTEND_0] = temp2analog(code_value());
870
-            #ifdef PIDTEMP
871
-            pid_setpoint = code_value();
872
-            #endif //PIDTEM
873
-            #ifdef WATCHPERIOD
874
-          if(target_raw[TEMPSENSOR_HOTEND_0]>current_raw[TEMPSENSOR_HOTEND_0]){
875
-              watchmillis = max(1,millis());
876
-              watch_raw[TEMPSENSOR_HOTEND_0] = current_raw[TEMPSENSOR_HOTEND_0];
877
-            } else {
878
-              watchmillis = 0;
879
-            }
880
-            #endif //WATCHPERIOD
856
+               if (code_seen('S')) setTargetHotend0(code_value());
857
+            
858
+            setWatch();
881 859
             codenum = millis(); 
882 860
      
883 861
                /* See if we are heating up or cooling down */
884
-              bool target_direction = (current_raw[TEMPSENSOR_HOTEND_0] < target_raw[TEMPSENSOR_HOTEND_0]); // true if heating, false if cooling
862
+              bool target_direction = isHeatingHotend0(); // true if heating, false if cooling
885 863
 
886 864
             #ifdef TEMP_RESIDENCY_TIME
887 865
             long residencyStart;
888 866
             residencyStart = -1;
889 867
             /* continue to loop until we have reached the target temp   
890 868
               _and_ until TEMP_RESIDENCY_TIME hasn't passed since we reached it */
891
-            while((target_direction ? (current_raw[TEMPSENSOR_HOTEND_0] < target_raw[TEMPSENSOR_HOTEND_0]) : (current_raw[TEMPSENSOR_HOTEND_0] > target_raw[TEMPSENSOR_HOTEND_0])) ||
869
+            while((target_direction ? (isHeatingHotend0()) : (isCoolingHotend0()) ||
892 870
                     (residencyStart > -1 && (millis() - residencyStart) < TEMP_RESIDENCY_TIME*1000) ) {
893 871
             #else
894
-            while ( target_direction ? (current_raw[TEMPSENSOR_HOTEND_0] < target_raw[TEMPSENSOR_HOTEND_0]) : (current_raw[TEMPSENSOR_HOTEND_0] > target_raw[TEMPSENSOR_HOTEND_0]) ) {
872
+            while ( target_direction ? (isHeatingHotend0()) : (isCoolingHotend0()) ) {
895 873
             #endif //TEMP_RESIDENCY_TIME
896 874
               if( (millis() - codenum) > 1000 ) { //Print Temp Reading every 1 second while heating up/cooling down
897 875
                 Serial.print("T:");
898
-              Serial.println( analog2temp(current_raw[TEMPSENSOR_HOTEND_0]) ); 
876
+              Serial.println( degHotend0() ); 
899 877
                 codenum = millis();
900 878
               }
901 879
               manage_heater();
@@ -903,9 +881,9 @@ inline void process_commands()
903 881
               #ifdef TEMP_RESIDENCY_TIME
904 882
                /* start/restart the TEMP_RESIDENCY_TIME timer whenever we reach target temp for the first time
905 883
                   or when current temp falls outside the hysteresis after target temp was reached */
906
-              if ((residencyStart == -1 &&  target_direction && current_raw[TEMPSENSOR_HOTEND_0] >= target_raw[TEMPSENSOR_HOTEND_0]) ||
907
-                  (residencyStart == -1 && !target_direction && current_raw[TEMPSENSOR_HOTEND_0] <= target_raw[TEMPSENSOR_HOTEND_0]) ||
908
-                  (residencyStart > -1 && labs(analog2temp(current_raw[TEMPSENSOR_HOTEND_0]) - analog2temp(target_raw[TEMPSENSOR_HOTEND_0])) > TEMP_HYSTERESIS) ) {
884
+              if ((residencyStart == -1 &&  target_direction && !isHeatingHotend0()) ||
885
+                  (residencyStart == -1 && !target_direction && !isCoolingHotend0()) ||
886
+                  (residencyStart > -1 && labs(degHotend0() - degTargetHotend0()) > TEMP_HYSTERESIS) ) {
909 887
                 residencyStart = millis();
910 888
               }
911 889
               #endif //TEMP_RESIDENCY_TIME
@@ -915,23 +893,23 @@ inline void process_commands()
915 893
           break;
916 894
       case 190: // M190 - Wait bed for heater to reach target.
917 895
       #if TEMP_1_PIN > -1
918
-          if (code_seen('S')) target_raw[TEMPSENSOR_BED] = temp2analog(code_value());
919
-        codenum = millis(); 
920
-          while(current_raw[TEMPSENSOR_BED] < target_raw[TEMPSENSOR_BED]) 
921
-                                {
922
-          if( (millis()-codenum) > 1000 ) //Print Temp Reading every 1 second while heating up.
896
+          if (code_seen('S')) setTargetBed(code_value());
897
+	  codenum = millis(); 
898
+          while(isHeatingBed()) 
923 899
           {
924
-            float tt=analog2temp(current_raw[TEMPSENSOR_HOTEND_0]);
925
-            Serial.print("T:");
926
-            Serial.println( tt );
927
-            Serial.print("ok T:");
928
-            Serial.print( tt ); 
929
-            Serial.print(" B:");
930
-            Serial.println( analog2temp(current_raw[TEMPSENSOR_BED]) ); 
931
-            codenum = millis(); 
932
-          }
900
+	    if( (millis()-codenum) > 1000 ) //Print Temp Reading every 1 second while heating up.
901
+	    {
902
+	      float tt=degHotend0();
903
+	      Serial.print("T:");
904
+	      Serial.println( tt );
905
+	      Serial.print("ok T:");
906
+	      Serial.print( tt ); 
907
+	      Serial.print(" B:");
908
+	      Serial.println( degBed() ); 
909
+	      codenum = millis(); 
910
+	    }
933 911
             manage_heater();
934
-        }
912
+	  }
935 913
       #endif
936 914
       break;
937 915
 #if FAN_PIN > -1
@@ -1331,24 +1309,8 @@ void wd_reset() {
1331 1309
 
1332 1310
 inline void kill()
1333 1311
 {
1334
-  #if TEMP_0_PIN > -1
1335
-  target_raw[0]=0;
1336
-   #if HEATER_0_PIN > -1  
1337
-     WRITE(HEATER_0_PIN,LOW);
1338
-   #endif
1339
-  #endif
1340
-  #if TEMP_1_PIN > -1
1341
-  target_raw[1]=0;
1342
-  #if HEATER_1_PIN > -1 
1343
-    WRITE(HEATER_1_PIN,LOW);
1344
-  #endif
1345
-  #endif
1346
-  #if TEMP_2_PIN > -1
1347
-  target_raw[2]=0;
1348
-  #if HEATER_2_PIN > -1  
1349
-    WRITE(HEATER_2_PIN,LOW);
1350
-  #endif
1351
-  #endif
1312
+  disable_heater();
1313
+
1352 1314
   disable_x();
1353 1315
   disable_y();
1354 1316
   disable_z();
@@ -1369,4 +1331,4 @@ void manage_inactivity(byte debug) {
1369 1331
   }
1370 1332
   check_axes_activity();
1371 1333
 }
1372
-
1334
+

+ 39
- 18
Marlin/temperature.cpp View File

@@ -37,28 +37,27 @@
37 37
 #include "streaming.h"
38 38
 #include "temperature.h"
39 39
 
40
-int target_bed_raw = 0;
41
-int current_bed_raw = 0;
42 40
 
43 41
 int target_raw[3] = {0, 0, 0};
44 42
 int current_raw[3] = {0, 0, 0};
45
-unsigned char temp_meas_ready = false;
43
+
44
+bool temp_meas_ready = false;
46 45
 
47 46
 unsigned long previous_millis_heater, previous_millis_bed_heater;
48 47
 
49 48
 #ifdef PIDTEMP
50
-  double temp_iState = 0;
51
-  double temp_dState = 0;
52
-  double pTerm;
53
-  double iTerm;
54
-  double dTerm;
49
+  float temp_iState = 0;
50
+  float temp_dState = 0;
51
+  float pTerm;
52
+  float iTerm;
53
+  float dTerm;
55 54
       //int output;
56
-  double pid_error;
57
-  double temp_iState_min;
58
-  double temp_iState_max;
59
-  double pid_setpoint = 0.0;
60
-  double pid_input;
61
-  double pid_output;
55
+  float pid_error;
56
+  float temp_iState_min;
57
+  float temp_iState_max;
58
+  float pid_setpoint = 0.0;
59
+  float pid_input;
60
+  float pid_output;
62 61
   bool pid_reset;
63 62
   float HeaterPower;
64 63
   
@@ -67,6 +66,11 @@ unsigned long previous_millis_heater, previous_millis_bed_heater;
67 66
   float Kd=DEFAULT_Kd;
68 67
   float Kc=DEFAULT_Kc;
69 68
 #endif //PIDTEMP
69
+  
70
+#ifdef WATCHPERIOD
71
+  int watch_raw[3] = {-1000,-1000,-1000};
72
+  unsigned long watchmillis = 0;
73
+#endif //WATCHPERIOD
70 74
 
71 75
 #ifdef HEATER_0_MINTEMP
72 76
 int minttemp_0 = temp2analog(HEATER_0_MINTEMP);
@@ -91,9 +95,9 @@ int bed_maxttemp = temp2analog(BED_MAXTEMP);
91 95
 
92 96
 void manage_heater()
93 97
 {
94
-#ifdef USE_WATCHDOG
95
-  wd_reset();
96
-#endif
98
+  #ifdef USE_WATCHDOG
99
+    wd_reset();
100
+  #endif
97 101
   
98 102
   float pid_input;
99 103
   float pid_output;
@@ -330,6 +334,22 @@ void tp_init()
330 334
 
331 335
 
332 336
 
337
+void setWatch() 
338
+{  
339
+#ifdef WATCHPERIOD
340
+  if(isHeatingHotend0())
341
+  {
342
+    watchmillis = max(1,millis());
343
+    watch_raw[TEMPSENSOR_HOTEND_0] = current_raw[TEMPSENSOR_HOTEND_0];
344
+  }
345
+  else
346
+  {
347
+    watchmillis = 0;
348
+  } 
349
+#endif 
350
+}
351
+
352
+
333 353
 // Timer 0 is shared with millies
334 354
 ISR(TIMER0_COMPB_vect)
335 355
 {
@@ -500,4 +520,5 @@ ISR(TIMER0_COMPB_vect)
500 520
   #endif
501 521
 #endif
502 522
   }
503
-}

523
+}
524
+

+ 85
- 15
Marlin/temperature.h View File

@@ -22,18 +22,97 @@
22 22
 #define temperature_h 
23 23
 
24 24
 #include "Marlin.h"
25
+#include "fastio.h"
25 26
 #ifdef PID_ADD_EXTRUSION_RATE
26 27
   #include "stepper.h"
27 28
 #endif
28
-void tp_init();
29
-void manage_heater();
30
-//int temp2analogu(int celsius, const short table[][2], int numtemps);
31
-//float analog2tempu(int raw, const short table[][2], int numtemps);
29
+
30
+void tp_init();  //initialise the heating
31
+void manage_heater(); //it is critical that this is called periodically.
32
+
33
+enum TempSensor {TEMPSENSOR_HOTEND_0=0,TEMPSENSOR_BED=1, TEMPSENSOR_HOTEND_1=2};
34
+
35
+//low leven conversion routines
36
+// do not use this routines and variables outsie of temperature.cpp
32 37
 int temp2analog(int celsius);
33 38
 int temp2analogBed(int celsius);
34 39
 float analog2temp(int raw);
35 40
 float analog2tempBed(int raw);
41
+extern int target_raw[3];  
42
+extern int current_raw[3];
43
+extern float Kp,Ki,Kd,Kc;
44
+#ifdef PIDTEMP
45
+  float pid_setpoint = 0.0;
46
+#endif
47
+#ifdef WATCHPERIOD
48
+  extern int watch_raw[3] ;
49
+  extern unsigned long watchmillis;
50
+#endif
51
+
52
+
53
+
54
+//high level conversion routines, for use outside of temperature.cpp
55
+//inline so that there is no performance decrease.
56
+//deg=degreeCelsius
36 57
 
58
+inline float degHotend0(){  return analog2temp(current_raw[TEMPSENSOR_HOTEND_0]);};
59
+inline float degHotend1(){  return analog2temp(current_raw[TEMPSENSOR_HOTEND_1]);};
60
+inline float degBed() {  return analog2tempBed(current_raw[TEMPSENSOR_BED]);};
61
+
62
+inline float degTargetHotend0() {  return analog2temp(target_raw[TEMPSENSOR_HOTEND_0]);};
63
+inline float degTargetHotend1() {  return analog2temp(target_raw[TEMPSENSOR_HOTEND_1]);};
64
+inline float degTargetBed() {   return analog2tempBed(target_raw[TEMPSENSOR_BED]);};
65
+
66
+inline void setTargetHotend0(float celsius) 
67
+{  
68
+  target_raw[TEMPSENSOR_HOTEND_0]=temp2analog(celsius);
69
+  #ifdef PIDTEMP
70
+    pid_setpoint = celsius;
71
+  #endif //PIDTEMP
72
+};
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);};
75
+
76
+inline bool isHeatingHotend0() {return target_raw[TEMPSENSOR_HOTEND_0] > current_raw[TEMPSENSOR_HOTEND_0];};
77
+inline bool isHeatingHotend1() {return target_raw[TEMPSENSOR_HOTEND_1] > current_raw[TEMPSENSOR_HOTEND_1];};
78
+inline bool isHeatingBed() {return target_raw[TEMPSENSOR_BED] > current_raw[TEMPSENSOR_BED];};
79
+
80
+inline bool isCoolingHotend0() {return target_raw[TEMPSENSOR_HOTEND_0] < current_raw[TEMPSENSOR_HOTEND_0];};
81
+inline bool isCoolingHotend1() {return target_raw[TEMPSENSOR_HOTEND_1] < current_raw[TEMPSENSOR_HOTEND_1];};
82
+inline bool isCoolingBed() {return target_raw[TEMPSENSOR_BED] < current_raw[TEMPSENSOR_BED];};
83
+
84
+inline void disable_heater()
85
+{
86
+   #if TEMP_0_PIN > -1
87
+  target_raw[0]=0;
88
+   #if HEATER_0_PIN > -1  
89
+     WRITE(HEATER_0_PIN,LOW);
90
+   #endif
91
+  #endif
92
+  #if TEMP_1_PIN > -1
93
+  target_raw[1]=0;
94
+  #if HEATER_1_PIN > -1 
95
+    WRITE(HEATER_1_PIN,LOW);
96
+  #endif
97
+  #endif
98
+  #if TEMP_2_PIN > -1
99
+  target_raw[2]=0;
100
+  #if HEATER_2_PIN > -1  
101
+    WRITE(HEATER_2_PIN,LOW);
102
+  #endif
103
+  #endif 
104
+}
105
+void setWatch() {  
106
+  if(isHeatingHotend0())
107
+  {
108
+    watchmillis = max(1,millis());
109
+    watch_raw[TEMPSENSOR_HOTEND_0] = current_raw[TEMPSENSOR_HOTEND_0];
110
+  }
111
+  else
112
+  {
113
+    watchmillis = 0;
114
+  } 
115
+}
37 116
 #ifdef HEATER_0_USES_THERMISTOR
38 117
     #define HEATERSOURCE 1
39 118
 #endif
@@ -41,18 +120,9 @@ float analog2tempBed(int raw);
41 120
     #define BEDSOURCE 1
42 121
 #endif
43 122
 
44
-//#define temp2analogh( c ) temp2analogu((c),temptable,NUMTEMPS)
45
-//#define analog2temp( c ) analog2tempu((c),temptable,NUMTEMPS
46 123
 
47 124
 
48
-extern float Kp;
49
-extern float Ki;
50
-extern float Kd;
51
-extern float Kc;
52 125
 
53
-enum {TEMPSENSOR_HOTEND_0=0,TEMPSENSOR_BED=1, TEMPSENSOR_HOTEND_1=2};
54
-extern int target_raw[3];
55
-extern int current_raw[3];
56
-extern double pid_setpoint;
57 126
 
58
-#endif

127
+#endif
128
+

+ 77
- 73
Marlin/ultralcd.pde View File

@@ -12,7 +12,7 @@ LiquidCrystal lcd(LCD_PINS_RS, LCD_PINS_ENABLE, LCD_PINS_D4, LCD_PINS_D5,LCD_PIN
12 12
 
13 13
 unsigned long previous_millis_lcd=0;
14 14
 
15
-
15
+inline int intround(const float &x){return int(0.5+x);}
16 16
 
17 17
 volatile char buttons=0;  //the last checked buttons in a bit array.
18 18
 int encoderpos=0;
@@ -29,13 +29,10 @@ void lcd_status(const char* message)
29 29
   strncpy(messagetext,message,LCD_WIDTH);
30 30
 }
31 31
 
32
-void clear()
32
+inline void clear()
33 33
 {
34
-  //lcd.setCursor(0,0);
34
+  
35 35
   lcd.clear();
36
-  //delay(1);
37
- // lcd.begin(LCD_WIDTH,LCD_HEIGHT);
38
-  //lcd_init();
39 36
 }
40 37
 long previous_millis_buttons=0;
41 38
 
@@ -78,47 +75,48 @@ void lcd_init()
78 75
 void beep()
79 76
 {
80 77
   //return;
81
-#ifdef ULTIPANEL
82
-  pinMode(BEEPER,OUTPUT);
83
-  for(int i=0;i<20;i++){
84
-    WRITE(BEEPER,HIGH);
85
-    delay(5);
86
-    WRITE(BEEPER,LOW);
87
-    delay(5);
88
-  }
89
-#endif
78
+  #ifdef ULTIPANEL
79
+    pinMode(BEEPER,OUTPUT);
80
+    for(int i=0;i<20;i++){
81
+      WRITE(BEEPER,HIGH);
82
+      delay(5);
83
+      WRITE(BEEPER,LOW);
84
+      delay(5);
85
+    }
86
+  #endif
90 87
 }
91 88
 
92 89
 void beepshort()
93 90
 {
94 91
   //return;
95
-#ifdef ULTIPANEL
96
-  pinMode(BEEPER,OUTPUT);
97
-  for(int i=0;i<10;i++){
98
-    WRITE(BEEPER,HIGH);
99
-    delay(3);
100
-    WRITE(BEEPER,LOW);
101
-    delay(3);
102
-  }
103
-#endif  
92
+  #ifdef ULTIPANEL
93
+    pinMode(BEEPER,OUTPUT);
94
+    for(int i=0;i<10;i++){
95
+      WRITE(BEEPER,HIGH);
96
+      delay(3);
97
+      WRITE(BEEPER,LOW);
98
+      delay(3);
99
+    }
100
+  #endif  
104 101
 }
102
+
105 103
 void lcd_status()
106 104
 {
107
-#ifdef ULTIPANEL
108
-  static uint8_t oldbuttons=0;
109
-  static long previous_millis_buttons=0;
110
-  static long previous_lcdinit=0;
111
-//  buttons_check(); // Done in temperature interrupt
112
-  //previous_millis_buttons=millis();
113
-  
114
-  if((buttons==oldbuttons) &&  ((millis() - previous_millis_lcd) < LCD_UPDATE_INTERVAL)   )
115
-    return;
116
-  oldbuttons=buttons;
117
-#else
105
+  #ifdef ULTIPANEL
106
+    static uint8_t oldbuttons=0;
107
+    static long previous_millis_buttons=0;
108
+    static long previous_lcdinit=0;
109
+  //  buttons_check(); // Done in temperature interrupt
110
+    //previous_millis_buttons=millis();
111
+    
112
+    if((buttons==oldbuttons) &&  ((millis() - previous_millis_lcd) < LCD_UPDATE_INTERVAL)   )
113
+      return;
114
+    oldbuttons=buttons;
115
+  #else
118 116
   
119
-  if(((millis() - previous_millis_lcd) < LCD_UPDATE_INTERVAL)   )
120
-    return;
121
-#endif
117
+    if(((millis() - previous_millis_lcd) < LCD_UPDATE_INTERVAL)   )
118
+      return;
119
+  #endif
122 120
     
123 121
   previous_millis_lcd=millis();
124 122
   menu.update();
@@ -161,8 +159,7 @@ void buttons_check()
161 159
   if((blocking<millis()) &&(READ(BTN_ENC)==0))
162 160
     newbutton|=EN_C;
163 161
   buttons=newbutton;
164
-#else
165
-  //read it from the shift register
162
+#else   //read it from the shift register
166 163
   uint8_t newbutton=0;
167 164
   WRITE(SHIFT_LD,LOW);
168 165
   WRITE(SHIFT_LD,HIGH);
@@ -238,8 +235,8 @@ extern volatile bool feedmultiplychanged;
238 235
 void MainMenu::showStatus()
239 236
 { 
240 237
 #if LCD_HEIGHT==4
241
-  static int oldcurrentraw=-1;
242
-  static int oldtargetraw=-1;
238
+  static int olddegHotEnd0=-1;
239
+  static int oldtargetHotEnd0=-1;
243 240
   //force_lcd_update=true;
244 241
   if(force_lcd_update||feedmultiplychanged)  //initial display of content
245 242
   {
@@ -247,38 +244,41 @@ void MainMenu::showStatus()
247 244
     encoderpos=feedmultiply;
248 245
     clear();
249 246
     lcd.setCursor(0,0);lcd.print("\002123/567\001 ");
250
-#if defined BED_USES_THERMISTOR || defined BED_USES_AD595 
251
-    lcd.setCursor(10,0);lcd.print("B123/567\001 ");
252
-#endif
247
+    #if defined BED_USES_THERMISTOR || defined BED_USES_AD595 
248
+      lcd.setCursor(10,0);lcd.print("B123/567\001 ");
249
+    #endif
253 250
   }
254 251
     
255
-
256
-  if((abs(current_raw[TEMPSENSOR_HOTEND_0]-oldcurrentraw)>3)||force_lcd_update)
252
+  int tHotEnd0=intround(degHotend0());
253
+  if((abs(tHotEnd0-olddegHotEnd0)>1)||force_lcd_update) //>1 because otherwise the lcd is refreshed to often.
257 254
   {
258 255
     lcd.setCursor(1,0);
259
-    lcd.print(ftostr3(analog2temp(current_raw[TEMPSENSOR_HOTEND_0])));
260
-    oldcurrentraw=current_raw[TEMPSENSOR_HOTEND_0];
256
+    lcd.print(ftostr3(tHotEnd0));
257
+    olddegHotEnd0=tHotEnd0;
261 258
   }
262
-  if((target_raw[TEMPSENSOR_HOTEND_0]!=oldtargetraw)||force_lcd_update)
259
+  int ttHotEnd0=intround(degTargetHotend0());
260
+  if((ttHotEnd0!=oldtargetHotEnd0)||force_lcd_update)
263 261
   {
264 262
     lcd.setCursor(5,0);
265
-    lcd.print(ftostr3(analog2temp(target_raw[TEMPSENSOR_HOTEND_0])));
266
-    oldtargetraw=target_raw[TEMPSENSOR_HOTEND_0];
263
+    lcd.print(ftostr3(ttHotEnd0));
264
+    oldtargetHotEnd0=ttHotEnd0;
267 265
   }
268 266
   #if defined BED_USES_THERMISTOR || defined BED_USES_AD595 
269
-  static int oldcurrentbedraw=-1;
270
-  static int oldtargetbedraw=-1; 
271
-  if((current_bed_raw!=oldcurrentbedraw)||force_lcd_update)
267
+  static int oldtBed=-1;
268
+  static int oldtargetBed=-1; 
269
+  int tBed=intround(degBed());
270
+  if((tBed!=oldtBed)||force_lcd_update)
272 271
   {
273 272
     lcd.setCursor(1,0);
274
-    lcd.print(ftostr3(analog2temp(current_bed_raw)));
275
-    oldcurrentraw=current_raw[TEMPSENSOR_BED];
273
+    lcd.print(ftostr3(tBed));
274
+    olddegHotEnd0=tBed;
276 275
   }
277
-  if((target_bed_raw!=oldtargebedtraw)||force_lcd_update)
276
+  int targetBed=intround(degTargetBed());
277
+  if((targetBed!=oldtargetBed)||force_lcd_update)
278 278
   {
279 279
     lcd.setCursor(5,0);
280
-    lcd.print(ftostr3(analog2temp(target_bed_raw)));
281
-    oldtargetraw=target_bed_raw;
280
+    lcd.print(ftostr3(targetBed));
281
+    oldtargetBed=targetBed;
282 282
   }
283 283
   #endif
284 284
   //starttime=2;
@@ -327,8 +327,8 @@ void MainMenu::showStatus()
327 327
     messagetext[0]='\0';
328 328
   }
329 329
 #else //smaller LCDS----------------------------------
330
-  static int oldcurrentraw=-1;
331
-  static int oldtargetraw=-1;
330
+  static int olddegHotEnd0=-1;
331
+  static int oldtargetHotEnd0=-1;
332 332
   if(force_lcd_update)  //initial display of content
333 333
   {
334 334
     encoderpos=feedmultiply;
@@ -338,18 +338,21 @@ void MainMenu::showStatus()
338 338
     #endif
339 339
   }
340 340
     
341
+  int tHotEnd0=intround(degHotend0());
342
+  int ttHotEnd0=intround(degTargetHotend0());
341 343
 
342
-  if((abs(current_raw[TEMPSENSOR_HOTEND]-oldcurrentraw)>3)||force_lcd_update)
344
+
345
+  if((abs(tHotEnd0-olddegHotEnd0)>1)||force_lcd_update)
343 346
   {
344 347
     lcd.setCursor(1,0);
345
-    lcd.print(ftostr3(analog2temp(current_raw[TEMPSENSOR_HOTEND])));
346
-    oldcurrentraw=current_raw[TEMPSENSOR_HOTEND];
348
+    lcd.print(ftostr3(tHotEnd0));
349
+    olddegHotEnd0=tHotEnd0;
347 350
   }
348
-  if((target_raw[TEMPSENSOR_HOTEND]!=oldtargetraw)||force_lcd_update)
351
+  if((ttHotEnd0!=oldtargetHotEnd0)||force_lcd_update)
349 352
   {
350 353
     lcd.setCursor(5,0);
351
-    lcd.print(ftostr3(analog2temp(target_raw[TEMPSENSOR_HOTEND])));
352
-    oldtargetraw=target_raw[TEMPSENSOR_HOTEND];
354
+    lcd.print(ftostr3(ttHotEnd0));
355
+    oldtargetHotEnd0=ttHotEnd0;
353 356
   }
354 357
 
355 358
   if(messagetext[0]!='\0')
@@ -426,7 +429,7 @@ void MainMenu::showPrepare()
426 429
         if((activeline==line) && CLICKED)
427 430
         {
428 431
           BLOCK
429
-          target_raw[TEMPSENSOR_HOTEND_0] = temp2analog(170);
432
+          setTargetHotend0(170);
430 433
           beepshort();
431 434
         }
432 435
       }break;
@@ -531,7 +534,7 @@ void MainMenu::showControl()
531 534
         if(force_lcd_update)
532 535
         {
533 536
           lcd.setCursor(0,line);lcd.print(" \002Nozzle:");
534
-          lcd.setCursor(13,line);lcd.print(ftostr3(analog2temp(target_raw[TEMPSENSOR_HOTEND_0])));
537
+          lcd.setCursor(13,line);lcd.print(ftostr3(intround(degHotend0())));
535 538
         }
536 539
         
537 540
         if((activeline==line) )
@@ -541,11 +544,11 @@ void MainMenu::showControl()
541 544
             linechanging=!linechanging;
542 545
             if(linechanging)
543 546
             {
544
-               encoderpos=(int)analog2temp(target_raw[TEMPSENSOR_HOTEND_0]);
547
+               encoderpos=intround(degHotend0());
545 548
             }
546 549
             else
547 550
             {
548
-              target_raw[TEMPSENSOR_HOTEND_0] = temp2analog(encoderpos);
551
+              setTargetHotend0(encoderpos);
549 552
               encoderpos=activeline*lcdslow;
550 553
               beepshort();
551 554
             }
@@ -1590,4 +1593,5 @@ char *fillto(int8_t n,char *c)
1590 1593
 #else
1591 1594
 inline void lcd_status() {};
1592 1595
 #endif
1593
-

1596
+
1597
+

Loading…
Cancel
Save