Browse Source

this is not working. Do you maybe know why?

Bernhard Kubicek 13 years ago
parent
commit
8bcdb9f5f0
8 changed files with 268 additions and 182 deletions
  1. 8
    8
      Marlin/EEPROMwrite.h
  2. 1
    0
      Marlin/Marlin.h
  3. 40
    40
      Marlin/Marlin.pde
  4. 1
    1
      Marlin/planner.cpp
  5. 1
    1
      Marlin/stepper.cpp
  6. 60
    68
      Marlin/temperature.cpp
  7. 110
    21
      Marlin/temperature.h
  8. 47
    43
      Marlin/ultralcd.pde

+ 8
- 8
Marlin/EEPROMwrite.h View File

48
   EEPROM_writeAnything(i,max_xy_jerk);
48
   EEPROM_writeAnything(i,max_xy_jerk);
49
   EEPROM_writeAnything(i,max_z_jerk);
49
   EEPROM_writeAnything(i,max_z_jerk);
50
   #ifdef PIDTEMP
50
   #ifdef PIDTEMP
51
-  EEPROM_writeAnything(i,Kp);
52
-  EEPROM_writeAnything(i,Ki);
53
-  EEPROM_writeAnything(i,Kd);
51
+  EEPROM_writeAnything(i,Heater::Kp);
52
+  EEPROM_writeAnything(i,Heater::Ki);
53
+  EEPROM_writeAnything(i,Heater::Kd);
54
 #else
54
 #else
55
   EEPROM_writeAnything(i,3000);
55
   EEPROM_writeAnything(i,3000);
56
   EEPROM_writeAnything(i,0);
56
   EEPROM_writeAnything(i,0);
81
       EEPROM_readAnything(i,max_xy_jerk);
81
       EEPROM_readAnything(i,max_xy_jerk);
82
       EEPROM_readAnything(i,max_z_jerk);
82
       EEPROM_readAnything(i,max_z_jerk);
83
 #ifndef PIDTEMP
83
 #ifndef PIDTEMP
84
-      float Kp,Ki,Kd;
84
+      float Kp,Ki,Kd; //read and ignore..
85
 #endif
85
 #endif
86
-      EEPROM_readAnything(i,Kp);
87
-      EEPROM_readAnything(i,Ki);
88
-      EEPROM_readAnything(i,Kd);
86
+      EEPROM_readAnything(i,Heater::Kp);
87
+      EEPROM_readAnything(i,Heater::Ki);
88
+      EEPROM_readAnything(i,Heater::Kd);
89
 
89
 
90
       ECHOLN("Stored settings retreived:");
90
       ECHOLN("Stored settings retreived:");
91
   }
91
   }
119
   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));
119
   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
120
 #ifdef PIDTEMP
121
   ECHOLN("PID settings:");
121
   ECHOLN("PID settings:");
122
-  ECHOLN("   M301 P"  << _FLOAT(Kp,3) << " I" << _FLOAT(Ki,3) << " D" << _FLOAT(Kd,3));  
122
+  ECHOLN("   M301 P"  << _FLOAT(Heater::Kp,3) << " I" << _FLOAT(Heater::Ki,3) << " D" << _FLOAT(Heater::Kd,3));  
123
 #endif
123
 #endif
124
   
124
   
125
 }  
125
 }  

+ 1
- 0
Marlin/Marlin.h View File

10
 #define ECHO(x) Serial << "echo: " << x;
10
 #define ECHO(x) Serial << "echo: " << x;
11
 #define ECHOLN(x) Serial << "echo: "<<x<<endl;
11
 #define ECHOLN(x) Serial << "echo: "<<x<<endl;
12
 
12
 
13
+
13
 void get_command();
14
 void get_command();
14
 void process_commands();
15
 void process_commands();
15
 
16
 

+ 40
- 40
Marlin/Marlin.pde View File

40
   #include "Simplelcd.h"
40
   #include "Simplelcd.h"
41
 #endif
41
 #endif
42
 
42
 
43
+Heater htr;
43
 char version_string[] = "1.0.0 Alpha 1";
44
 char version_string[] = "1.0.0 Alpha 1";
44
 
45
 
45
 #ifdef SDSUPPORT
46
 #ifdef SDSUPPORT
263
 #endif //SDSUPPORT
264
 #endif //SDSUPPORT
264
   plan_init();  // Initialize planner;
265
   plan_init();  // Initialize planner;
265
   st_init();    // Initialize stepper;
266
   st_init();    // Initialize stepper;
266
-  tp_init();    // Initialize temperature loop
267
+  //tp_init();    // Initialize temperature loop is now done by the constructor of the Heater class
267
 	//checkautostart();
268
 	//checkautostart();
268
 }
269
 }
269
 
270
 
367
     bufindr = (bufindr + 1)%BUFSIZE;
368
     bufindr = (bufindr + 1)%BUFSIZE;
368
   }
369
   }
369
   //check heater every n milliseconds
370
   //check heater every n milliseconds
370
-  manage_heater();
371
+  Heater::manage_heater();
371
   manage_inactivity(1);
372
   manage_inactivity(1);
372
   LCD_STATUS;
373
   LCD_STATUS;
373
 }
374
 }
547
       if(code_seen('S')) codenum = code_value() * 1000; // seconds to wait
548
       if(code_seen('S')) codenum = code_value() * 1000; // seconds to wait
548
       codenum += millis();  // keep track of when we started waiting
549
       codenum += millis();  // keep track of when we started waiting
549
       while(millis()  < codenum ){
550
       while(millis()  < codenum ){
550
-        manage_heater();
551
+        Heater::manage_heater();
551
       }
552
       }
552
       break;
553
       break;
553
     case 28: //G28 Home all Axis one at a time
554
     case 28: //G28 Home all Axis one at a time
801
         }
802
         }
802
         break;
803
         break;
803
       case 104: // M104
804
       case 104: // M104
804
-                if (code_seen('S')) target_raw[TEMPSENSOR_HOTEND] = temp2analog(code_value());
805
-#ifdef PIDTEMP
806
-                pid_setpoint = code_value();
807
-#endif //PIDTEM
805
+        if (code_seen('S')) Heater::setCelsius(TEMPSENSOR_HOTEND,code_value());
808
         #ifdef WATCHPERIOD
806
         #ifdef WATCHPERIOD
809
-            if(target_raw[TEMPSENSOR_HOTEND] > current_raw[TEMPSENSOR_HOTEND]){
807
+            if(Heater::isHeating(TEMPSENSOR_HOTEND)){
810
                 watchmillis = max(1,millis());
808
                 watchmillis = max(1,millis());
811
                 watch_raw[TEMPSENSOR_HOTEND] = current_raw[TEMPSENSOR_HOTEND];
809
                 watch_raw[TEMPSENSOR_HOTEND] = current_raw[TEMPSENSOR_HOTEND];
812
             }else{
810
             }else{
815
         #endif
813
         #endif
816
         break;
814
         break;
817
       case 140: // M140 set bed temp
815
       case 140: // M140 set bed temp
818
-                if (code_seen('S')) target_raw[TEMPSENSOR_BED] = temp2analogBed(code_value());
816
+                if (code_seen('S')) Heater::setCelsius(TEMPSENSOR_BED,code_value());
819
         break;
817
         break;
820
       case 105: // M105
818
       case 105: // M105
821
         #if (TEMP_0_PIN > -1) || defined (HEATER_USES_AD595)
819
         #if (TEMP_0_PIN > -1) || defined (HEATER_USES_AD595)
822
-                tt = analog2temp(current_raw[TEMPSENSOR_HOTEND]);
820
+                tt = Heater::celsius(TEMPSENSOR_HOTEND);
823
         #endif
821
         #endif
824
         #if TEMP_1_PIN > -1
822
         #if TEMP_1_PIN > -1
825
-                bt = analog2tempBed(current_raw[TEMPSENSOR_BED]);
823
+                bt = Heater::celsius(TEMPSENSOR_BED);
826
         #endif
824
         #endif
827
         #if (TEMP_0_PIN > -1) || defined (HEATER_USES_AD595)
825
         #if (TEMP_0_PIN > -1) || defined (HEATER_USES_AD595)
828
             Serial.print("ok T:");
826
             Serial.print("ok T:");
833
 #ifdef PIDTEMP
831
 #ifdef PIDTEMP
834
             Serial.print(" B:");
832
             Serial.print(" B:");
835
             #if TEMP_1_PIN > -1
833
             #if TEMP_1_PIN > -1
836
-            Serial.println(bt); 
834
+	      Serial.println(bt); 
837
             #else
835
             #else
838
-            Serial.println(HeaterPower); 
836
+	      Serial.println(Heater::HeaterPower); 
839
             #endif
837
             #endif
840
 #else
838
 #else
841
             Serial.println();
839
             Serial.println();
842
 #endif
840
 #endif
843
-          #else
841
+          #else<
844
             Serial.println();
842
             Serial.println();
845
           #endif
843
           #endif
846
         #else
844
         #else
850
         //break;
848
         //break;
851
       case 109: {// M109 - Wait for extruder heater to reach target.
849
       case 109: {// M109 - Wait for extruder heater to reach target.
852
             LCD_MESSAGE("Heating...");
850
             LCD_MESSAGE("Heating...");
853
-               if (code_seen('S')) target_raw[TEMPSENSOR_HOTEND] = temp2analog(code_value());
854
-            #ifdef PIDTEMP
855
-            pid_setpoint = code_value();
856
-            #endif //PIDTEM
851
+               if (code_seen('S')) Heater::setCelsius(TEMPSENSOR_HOTEND,code_value());
852
+            
857
             #ifdef WATCHPERIOD
853
             #ifdef WATCHPERIOD
858
-          if(target_raw[TEMPSENSOR_HOTEND]>current_raw[TEMPSENSOR_HOTEND]){
854
+          if(Heater::isHeating(TEMPSENSOR_HOTEND)){
859
               watchmillis = max(1,millis());
855
               watchmillis = max(1,millis());
860
-              watch_raw[TEMPSENSOR_HOTEND] = current_raw[TEMPSENSOR_HOTEND];
856
+              watch_raw[TEMPSENSOR_HOTEND] = Heater::current_raw[TEMPSENSOR_HOTEND];
861
             } else {
857
             } else {
862
               watchmillis = 0;
858
               watchmillis = 0;
863
             }
859
             }
865
             codenum = millis(); 
861
             codenum = millis(); 
866
      
862
      
867
                /* See if we are heating up or cooling down */
863
                /* See if we are heating up or cooling down */
868
-              bool target_direction = (current_raw[0] < target_raw[0]); // true if heating, false if cooling
864
+              bool target_direction = Heater::isHeating(TEMPSENSOR_HOTEND); // true if heating, false if cooling
869
 
865
 
870
             #ifdef TEMP_RESIDENCY_TIME
866
             #ifdef TEMP_RESIDENCY_TIME
871
             long residencyStart;
867
             long residencyStart;
872
             residencyStart = -1;
868
             residencyStart = -1;
873
             /* continue to loop until we have reached the target temp   
869
             /* continue to loop until we have reached the target temp   
874
               _and_ until TEMP_RESIDENCY_TIME hasn't passed since we reached it */
870
               _and_ until TEMP_RESIDENCY_TIME hasn't passed since we reached it */
875
-            while((target_direction ? (current_raw[0] < target_raw[0]) : (current_raw[0] > target_raw[0])) ||
871
+            while((target_direction ? Heater::isHeating(TEMPSENSOR_HOTEND) : Heater::isCooling(TEMPSENSOR_HOTEND)) ||
876
                     (residencyStart > -1 && (millis() - residencyStart) < TEMP_RESIDENCY_TIME*1000) ) {
872
                     (residencyStart > -1 && (millis() - residencyStart) < TEMP_RESIDENCY_TIME*1000) ) {
877
             #else
873
             #else
878
-            while ( target_direction ? (current_raw[0] < target_raw[0]) : (current_raw[0] > target_raw[0]) ) {
874
+            while ( target_direction ? Heater::isHeating(TEMPSENSOR_HOTEND) : Heater::isCooling(TEMPSENSOR_HOTEND) ) {
879
             #endif //TEMP_RESIDENCY_TIME
875
             #endif //TEMP_RESIDENCY_TIME
880
               if( (millis() - codenum) > 1000 ) { //Print Temp Reading every 1 second while heating up/cooling down
876
               if( (millis() - codenum) > 1000 ) { //Print Temp Reading every 1 second while heating up/cooling down
881
                 Serial.print("T:");
877
                 Serial.print("T:");
882
-              Serial.println( analog2temp(current_raw[TEMPSENSOR_HOTEND]) ); 
878
+              Serial.println( Heater::celsius(TEMPSENSOR_HOTEND) ); 
883
                 codenum = millis();
879
                 codenum = millis();
884
               }
880
               }
885
-              manage_heater();
881
+              Heater::manage_heater();
886
               LCD_STATUS;
882
               LCD_STATUS;
887
               #ifdef TEMP_RESIDENCY_TIME
883
               #ifdef TEMP_RESIDENCY_TIME
888
                /* start/restart the TEMP_RESIDENCY_TIME timer whenever we reach target temp for the first time
884
                /* start/restart the TEMP_RESIDENCY_TIME timer whenever we reach target temp for the first time
889
                   or when current temp falls outside the hysteresis after target temp was reached */
885
                   or when current temp falls outside the hysteresis after target temp was reached */
890
-              if ((residencyStart == -1 &&  target_direction && current_raw[0] >= target_raw[0]) ||
891
-                  (residencyStart == -1 && !target_direction && current_raw[0] <= target_raw[0]) ||
892
-                  (residencyStart > -1 && labs(analog2temp(current_raw[0]) - analog2temp(target_raw[0])) > TEMP_HYSTERESIS) ) {
886
+              if ((residencyStart == -1 &&  target_direction && !Heater::isHeating(TEMPSENSOR_HOTEND)) ||
887
+                  (residencyStart == -1 && !target_direction && !Heater::isCooling(TEMPSENSOR_HOTEND)) ||
888
+                  (residencyStart > -1 && labs(Heater::celsius(TEMPSENSOR_HOTEND) - Heater::celsiusTarget(TEMPSENSOR_HOTEND)) > TEMP_HYSTERESIS) ) {
893
                 residencyStart = millis();
889
                 residencyStart = millis();
894
               }
890
               }
895
               #endif //TEMP_RESIDENCY_TIME
891
               #endif //TEMP_RESIDENCY_TIME
899
           break;
895
           break;
900
       case 190: // M190 - Wait bed for heater to reach target.
896
       case 190: // M190 - Wait bed for heater to reach target.
901
       #if TEMP_1_PIN > -1
897
       #if TEMP_1_PIN > -1
902
-          if (code_seen('S')) target_raw[TEMPSENSOR_BED] = temp2analog(code_value());
898
+          if (code_seen('S')) Heater::setCelsius(TEMPSENSOR_BED,code_value());
903
         codenum = millis(); 
899
         codenum = millis(); 
904
-          while(current_raw[TEMPSENSOR_BED] < target_raw[TEMPSENSOR_BED]) 
905
-                                {
900
+          while(Heater::isHeating(TEMPSENSOR_BED)) 
901
+          {
906
           if( (millis()-codenum) > 1000 ) //Print Temp Reading every 1 second while heating up.
902
           if( (millis()-codenum) > 1000 ) //Print Temp Reading every 1 second while heating up.
907
           {
903
           {
908
-            float tt=analog2temp(current_raw[TEMPSENSOR_HOTEND]);
904
+            float tt=Heater::celsius(TEMPSENSOR_HOTEND);
909
             Serial.print("T:");
905
             Serial.print("T:");
910
             Serial.println( tt );
906
             Serial.println( tt );
911
             Serial.print("ok T:");
907
             Serial.print("ok T:");
912
             Serial.print( tt ); 
908
             Serial.print( tt ); 
913
             Serial.print(" B:");
909
             Serial.print(" B:");
914
-            Serial.println( analog2temp(current_raw[TEMPSENSOR_BED]) ); 
910
+            Serial.println( Heater::celsius(TEMPSENSOR_BED) ); 
915
             codenum = millis(); 
911
             codenum = millis(); 
916
           }
912
           }
917
-            manage_heater();
913
+            Heater::manage_heater();
918
         }
914
         }
919
       #endif
915
       #endif
920
       break;
916
       break;
1066
       break;
1062
       break;
1067
 #ifdef PIDTEMP
1063
 #ifdef PIDTEMP
1068
     case 301: // M301
1064
     case 301: // M301
1069
-      if(code_seen('P')) Kp = code_value();
1070
-      if(code_seen('I')) Ki = code_value()*PID_dT;
1071
-      if(code_seen('D')) Kd = code_value()/PID_dT;
1065
+      if(code_seen('P')) Heater::Kp = code_value();
1066
+      if(code_seen('I')) Heater::Ki = code_value()*PID_dT;
1067
+      if(code_seen('D')) Heater::Kd = code_value()/PID_dT;
1068
+      #ifdef PID_ADD_EXTRUSION_RATE
1069
+	 if(code_seen('C')) Heater::Kc = code_value();
1070
+      #endif
1071
+
1072
 //      ECHOLN("Kp "<<_FLOAT(Kp,2));
1072
 //      ECHOLN("Kp "<<_FLOAT(Kp,2));
1073
 //      ECHOLN("Ki "<<_FLOAT(Ki/PID_dT,2));
1073
 //      ECHOLN("Ki "<<_FLOAT(Ki/PID_dT,2));
1074
 //      ECHOLN("Kd "<<_FLOAT(Kd*PID_dT,2));
1074
 //      ECHOLN("Kd "<<_FLOAT(Kd*PID_dT,2));
1194
 inline void kill()
1194
 inline void kill()
1195
 {
1195
 {
1196
   #if TEMP_0_PIN > -1
1196
   #if TEMP_0_PIN > -1
1197
-  target_raw[0]=0;
1197
+  Heater::setCelsius(TEMPSENSOR_HOTEND,0);
1198
    #if HEATER_0_PIN > -1  
1198
    #if HEATER_0_PIN > -1  
1199
      WRITE(HEATER_0_PIN,LOW);
1199
      WRITE(HEATER_0_PIN,LOW);
1200
    #endif
1200
    #endif
1201
   #endif
1201
   #endif
1202
   #if TEMP_1_PIN > -1
1202
   #if TEMP_1_PIN > -1
1203
-  target_raw[1]=0;
1203
+  Heater::setCelsius(TEMPSENSOR_BED,0);
1204
   #if HEATER_1_PIN > -1 
1204
   #if HEATER_1_PIN > -1 
1205
     WRITE(HEATER_1_PIN,LOW);
1205
     WRITE(HEATER_1_PIN,LOW);
1206
   #endif
1206
   #endif
1207
   #endif
1207
   #endif
1208
   #if TEMP_2_PIN > -1
1208
   #if TEMP_2_PIN > -1
1209
-  target_raw[2]=0;
1209
+  Heater::setCelsius(TEMPSENSOR_AUX,0);
1210
   #if HEATER_2_PIN > -1  
1210
   #if HEATER_2_PIN > -1  
1211
     WRITE(HEATER_2_PIN,LOW);
1211
     WRITE(HEATER_2_PIN,LOW);
1212
   #endif
1212
   #endif

+ 1
- 1
Marlin/planner.cpp View File

388
   // If the buffer is full: good! That means we are well ahead of the robot. 
388
   // If the buffer is full: good! That means we are well ahead of the robot. 
389
   // Rest here until there is room in the buffer.
389
   // Rest here until there is room in the buffer.
390
   while(block_buffer_tail == next_buffer_head) { 
390
   while(block_buffer_tail == next_buffer_head) { 
391
-    manage_heater(); 
391
+    htr.manage_heater(); 
392
     manage_inactivity(1); 
392
     manage_inactivity(1); 
393
     LCD_STATUS;
393
     LCD_STATUS;
394
   }
394
   }

+ 1
- 1
Marlin/stepper.cpp View File

585
 void st_synchronize()
585
 void st_synchronize()
586
 {
586
 {
587
   while(plan_get_current_block()) {
587
   while(plan_get_current_block()) {
588
-    manage_heater();
588
+    htr.manage_heater();
589
     manage_inactivity(1);
589
     manage_inactivity(1);
590
     LCD_STATUS;
590
     LCD_STATUS;
591
   }   
591
   }   

+ 60
- 68
Marlin/temperature.cpp View File

37
 #include "streaming.h"
37
 #include "streaming.h"
38
 #include "temperature.h"
38
 #include "temperature.h"
39
 
39
 
40
-int target_bed_raw = 0;
41
-int current_bed_raw = 0;
42
 
40
 
43
-int target_raw[3] = {0, 0, 0};
44
-int current_raw[3] = {0, 0, 0};
45
-unsigned char temp_meas_ready = false;
46
 
41
 
47
-unsigned long previous_millis_heater, previous_millis_bed_heater;
48
 
42
 
49
-#ifdef PIDTEMP
50
-  double temp_iState = 0;
51
-  double temp_dState = 0;
52
-  double pTerm;
53
-  double iTerm;
54
-  double dTerm;
55
-      //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;
62
-  bool pid_reset;
63
-  float HeaterPower;
64
-  
65
-  float Kp=DEFAULT_Kp;
66
-  float Ki=DEFAULT_Ki;
67
-  float Kd=DEFAULT_Kd;
68
-  float Kc=DEFAULT_Kc;
69
-#endif //PIDTEMP
70
-
71
-#ifdef MINTEMP
72
-int minttemp = temp2analog(MINTEMP);
73
-#endif //MINTEMP
74
-#ifdef MAXTEMP
75
-int maxttemp = temp2analog(MAXTEMP);
76
-#endif //MAXTEMP
77
-
78
-#ifdef BED_MINTEMP
79
-int bed_minttemp = temp2analog(BED_MINTEMP);
80
-#endif //BED_MINTEMP
81
-#ifdef BED_MAXTEMP
82
-int bed_maxttemp = temp2analog(BED_MAXTEMP);
83
-#endif //BED_MAXTEMP
84
 
43
 
85
-void manage_heater()
44
+void static Heater::manage_heater()
86
 {
45
 {
87
 #ifdef USE_WATCHDOG
46
 #ifdef USE_WATCHDOG
88
   wd_reset();
47
   wd_reset();
90
   
49
   
91
   float pid_input;
50
   float pid_input;
92
   float pid_output;
51
   float pid_output;
93
-  if(temp_meas_ready != true)   //better readability
52
+  if(htr.temp_meas_ready != true)   //better readability
94
     return; 
53
     return; 
95
 
54
 
96
 CRITICAL_SECTION_START;
55
 CRITICAL_SECTION_START;
97
-    temp_meas_ready = false;
56
+    htr.temp_meas_ready = false;
98
 CRITICAL_SECTION_END;
57
 CRITICAL_SECTION_END;
99
 
58
 
100
 #ifdef PIDTEMP
59
 #ifdef PIDTEMP
176
 // For a thermistor, it uses the RepRap thermistor temp table.
135
 // For a thermistor, it uses the RepRap thermistor temp table.
177
 // This is needed because PID in hydra firmware hovers around a given analog value, not a temp value.
136
 // This is needed because PID in hydra firmware hovers around a given analog value, not a temp value.
178
 // This function is derived from inversing the logic from a portion of getTemperature() in FiveD RepRap firmware.
137
 // This function is derived from inversing the logic from a portion of getTemperature() in FiveD RepRap firmware.
179
-float temp2analog(int celsius) {
138
+float const static temp2analog(const int celsius)
139
+{
180
   #ifdef HEATER_USES_THERMISTOR_1
140
   #ifdef HEATER_USES_THERMISTOR_1
181
     int raw = 0;
141
     int raw = 0;
182
     byte i;
142
     byte i;
207
 // For a thermistor, it uses the RepRap thermistor temp table.
167
 // For a thermistor, it uses the RepRap thermistor temp table.
208
 // This is needed because PID in hydra firmware hovers around a given analog value, not a temp value.
168
 // This is needed because PID in hydra firmware hovers around a given analog value, not a temp value.
209
 // This function is derived from inversing the logic from a portion of getTemperature() in FiveD RepRap firmware.
169
 // This function is derived from inversing the logic from a portion of getTemperature() in FiveD RepRap firmware.
210
-float temp2analogBed(int celsius) {
170
+float const static temp2analogBed(const int celsius)
171
+{
211
   #ifdef BED_USES_THERMISTOR
172
   #ifdef BED_USES_THERMISTOR
212
 
173
 
213
     int raw = 0;
174
     int raw = 0;
237
 
198
 
238
 // Derived from RepRap FiveD extruder::getTemperature()
199
 // Derived from RepRap FiveD extruder::getTemperature()
239
 // For hot end temperature measurement.
200
 // For hot end temperature measurement.
240
-float analog2temp(int raw) {
201
+float const static Heater::analog2temp(const int raw) {
241
   #ifdef HEATER_1_USES_THERMISTOR
202
   #ifdef HEATER_1_USES_THERMISTOR
242
     int celsius = 0;
203
     int celsius = 0;
243
     byte i;  
204
     byte i;  
266
 
227
 
267
 // Derived from RepRap FiveD extruder::getTemperature()
228
 // Derived from RepRap FiveD extruder::getTemperature()
268
 // For bed temperature measurement.
229
 // For bed temperature measurement.
269
-float analog2tempBed(int raw) {
230
+float const static Heater::analog2tempBed(const int raw) {
270
   #ifdef BED_USES_THERMISTOR
231
   #ifdef BED_USES_THERMISTOR
271
     int celsius = 0;
232
     int celsius = 0;
272
     byte i;
233
     byte i;
296
   #endif
257
   #endif
297
 }
258
 }
298
 
259
 
299
-void tp_init()
260
+Heater::Heater()
300
 {
261
 {
262
+  for(short i=0;i<3;i++)
263
+  {
264
+    target_raw[i]=0;
265
+    current_raw[i] =0;
266
+  }
267
+  htr.temp_meas_ready = false;
268
+  #ifdef MINTEMP
269
+  minttemp = temp2analog(MINTEMP);
270
+  #endif //MINTEMP
271
+  #ifdef MAXTEMP
272
+  maxttemp = temp2analog(MAXTEMP);
273
+  #endif //MAXTEMP
274
+
275
+  #ifdef BED_MINTEMP
276
+  bed_minttemp = temp2analog(BED_MINTEMP);
277
+  #endif //BED_MINTEMP
278
+  #ifdef BED_MAXTEMP
279
+  bed_maxttemp = temp2analog(BED_MAXTEMP);
280
+  #endif //BED_MAXTEMP
281
+  
301
 #if (HEATER_0_PIN > -1) 
282
 #if (HEATER_0_PIN > -1) 
302
   SET_OUTPUT(HEATER_0_PIN);
283
   SET_OUTPUT(HEATER_0_PIN);
303
 #endif  
284
 #endif  
311
 #ifdef PIDTEMP
292
 #ifdef PIDTEMP
312
   temp_iState_min = 0.0;
293
   temp_iState_min = 0.0;
313
   temp_iState_max = PID_INTEGRAL_DRIVE_MAX / Ki;
294
   temp_iState_max = PID_INTEGRAL_DRIVE_MAX / Ki;
295
+  temp_iState = 0;
296
+  temp_dState = 0;
297
+  Kp=DEFAULT_Kp;
298
+  Ki=DEFAULT_Ki;
299
+  Kd=DEFAULT_Kd;
300
+  Kc=DEFAULT_Kc;
301
+  pid_setpoint = 0.0;
302
+
314
 #endif //PIDTEMP
303
 #endif //PIDTEMP
315
 
304
 
316
 // Set analog inputs
305
 // Set analog inputs
407
   if(temp_count >= 16) // 6 ms * 16 = 96ms.
396
   if(temp_count >= 16) // 6 ms * 16 = 96ms.
408
   {
397
   {
409
     #ifdef HEATER_1_USES_AD595
398
     #ifdef HEATER_1_USES_AD595
410
-      current_raw[0] = raw_temp_0_value;
399
+      htr.current_raw[0] = raw_temp_0_value;
411
     #else
400
     #else
412
-      current_raw[0] = 16383 - raw_temp_0_value;
401
+      htr.current_raw[0] = 16383 - raw_temp_0_value;
413
     #endif
402
     #endif
414
     
403
     
415
     #ifdef HEATER_2_USES_AD595
404
     #ifdef HEATER_2_USES_AD595
416
-      current_raw[2] = raw_temp_2_value;
405
+      htr.current_raw[2] = raw_temp_2_value;
417
     #else
406
     #else
418
-      current_raw[2] = 16383 - raw_temp_2_value;
407
+      htr.current_raw[2] = 16383 - raw_temp_2_value;
419
     #endif
408
     #endif
420
     
409
     
421
     #ifdef BED_USES_AD595
410
     #ifdef BED_USES_AD595
422
-      current_raw[1] = raw_temp_1_value;
411
+      htr.current_raw[1] = raw_temp_1_value;
423
     #else
412
     #else
424
-      current_raw[1] = 16383 - raw_temp_1_value;
413
+      htr.current_raw[1] = 16383 - raw_temp_1_value;
425
     #endif
414
     #endif
426
     
415
     
427
-    temp_meas_ready = true;
416
+   htr.temp_meas_ready = true;
428
     temp_count = 0;
417
     temp_count = 0;
429
     raw_temp_0_value = 0;
418
     raw_temp_0_value = 0;
430
     raw_temp_1_value = 0;
419
     raw_temp_1_value = 0;
431
     raw_temp_2_value = 0;
420
     raw_temp_2_value = 0;
432
 #ifdef MAXTEMP
421
 #ifdef MAXTEMP
433
   #if (HEATER_0_PIN > -1)
422
   #if (HEATER_0_PIN > -1)
434
-    if(current_raw[TEMPSENSOR_HOTEND] >= maxttemp) {
435
-      target_raw[TEMPSENSOR_HOTEND] = 0;
423
+    if(htr.current_raw[TEMPSENSOR_HOTEND] >= htr.maxttemp) {
424
+      htr.target_raw[TEMPSENSOR_HOTEND] = 0;
436
       analogWrite(HEATER_0_PIN, 0);
425
       analogWrite(HEATER_0_PIN, 0);
437
       Serial.println("!! Temperature extruder 0 switched off. MAXTEMP triggered !!");
426
       Serial.println("!! Temperature extruder 0 switched off. MAXTEMP triggered !!");
438
     }
427
     }
439
   #endif
428
   #endif
440
   #if (HEATER_2_PIN > -1)
429
   #if (HEATER_2_PIN > -1)
441
-    if(current_raw[TEMPSENSOR_AUX] >= maxttemp) {
442
-      target_raw[TEMPSENSOR_AUX] = 0;
430
+    if(htr.current_raw[TEMPSENSOR_AUX] >= htr.maxttemp) {
431
+      htr.target_raw[TEMPSENSOR_AUX] = 0;
443
       analogWrite(HEATER_2_PIN, 0);
432
       analogWrite(HEATER_2_PIN, 0);
444
       Serial.println("!! Temperature extruder 1 switched off. MAXTEMP triggered !!");
433
       Serial.println("!! Temperature extruder 1 switched off. MAXTEMP triggered !!");
445
     }
434
     }
447
 #endif //MAXTEMP
436
 #endif //MAXTEMP
448
 #ifdef MINTEMP
437
 #ifdef MINTEMP
449
   #if (HEATER_0_PIN > -1)
438
   #if (HEATER_0_PIN > -1)
450
-    if(current_raw[TEMPSENSOR_HOTEND] <= minttemp) {
451
-      target_raw[TEMPSENSOR_HOTEND] = 0;
439
+    if(htr.current_raw[TEMPSENSOR_HOTEND] <= htr.minttemp) {
440
+      htr.target_raw[TEMPSENSOR_HOTEND] = 0;
452
       analogWrite(HEATER_0_PIN, 0);
441
       analogWrite(HEATER_0_PIN, 0);
453
       Serial.println("!! Temperature extruder 0 switched off. MINTEMP triggered !!");
442
       Serial.println("!! Temperature extruder 0 switched off. MINTEMP triggered !!");
454
     }
443
     }
455
   #endif
444
   #endif
456
   #if (HEATER_2_PIN > -1)
445
   #if (HEATER_2_PIN > -1)
457
-    if(current_raw[TEMPSENSOR_AUX] <= minttemp) {
458
-      target_raw[TEMPSENSOR_AUX] = 0;
446
+    if(htr.current_raw[TEMPSENSOR_AUX] <= htr.minttemp) {
447
+      htr.target_raw[TEMPSENSOR_AUX] = 0;
459
       analogWrite(HEATER_2_PIN, 0);
448
       analogWrite(HEATER_2_PIN, 0);
460
       Serial.println("!! Temperature extruder 1 switched off. MINTEMP triggered !!");
449
       Serial.println("!! Temperature extruder 1 switched off. MINTEMP triggered !!");
461
     }
450
     }
463
 #endif //MAXTEMP
452
 #endif //MAXTEMP
464
 #ifdef BED_MINTEMP
453
 #ifdef BED_MINTEMP
465
   #if (HEATER_1_PIN > -1)
454
   #if (HEATER_1_PIN > -1)
466
-    if(current_raw[1] <= bed_minttemp) {
467
-      target_raw[1] = 0;
455
+    if(htr.current_raw[1] <= htr.bed_minttemp) {
456
+      htr.target_raw[1] = 0;
468
       WRITE(HEATER_1_PIN, 0);
457
       WRITE(HEATER_1_PIN, 0);
469
       Serial.println("!! Temperatur heated bed switched off. MINTEMP triggered !!");
458
       Serial.println("!! Temperatur heated bed switched off. MINTEMP triggered !!");
470
     }
459
     }
472
 #endif
461
 #endif
473
 #ifdef BED_MAXTEMP
462
 #ifdef BED_MAXTEMP
474
   #if (HEATER_1_PIN > -1)
463
   #if (HEATER_1_PIN > -1)
475
-    if(current_raw[1] >= bed_maxttemp) {
476
-      target_raw[1] = 0;
464
+    if(htr.current_raw[1] >= htr.bed_maxttemp) {
465
+      htr.target_raw[1] = 0;
477
       WRITE(HEATER_1_PIN, 0);
466
       WRITE(HEATER_1_PIN, 0);
478
       Serial.println("!! Temperature heated bed switched off. MAXTEMP triggered !!");
467
       Serial.println("!! Temperature heated bed switched off. MAXTEMP triggered !!");
479
     }
468
     }
481
 #endif
470
 #endif
482
   }
471
   }
483
 }
472
 }
473
+
474
+//Heater htr;
475
+

+ 110
- 21
Marlin/temperature.h View File

25
 #ifdef PID_ADD_EXTRUSION_RATE
25
 #ifdef PID_ADD_EXTRUSION_RATE
26
   #include "stepper.h"
26
   #include "stepper.h"
27
 #endif
27
 #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);
32
-float temp2analog(int celsius);
33
-float temp2analogBed(int celsius);
34
-float analog2temp(int raw);
35
-float analog2tempBed(int raw);
28
+
29
+enum TempSensor {TEMPSENSOR_HOTEND=0,TEMPSENSOR_BED=1, TEMPSENSOR_AUX=2};
30
+
31
+// ther must be only one instance of this class, and it is created in temperature.cpp by itself and is called "htr".
32
+// all the variables are static, so that of the compiler optimization is more easy.
33
+// I honestly hope that this increases readability and structure.
34
+// none of the variables or routines should be called from an secondary process/interrupt with the exceptino of current_raw[].
35
+
36
+class Heater
37
+{
38
+public:
39
+  Heater(); //treplaces tp_init();
40
+  ~Heater(); 
41
+  
42
+  void static manage_heater(); /// it is critical that this is called continously. 
43
+  
44
+  // conversion routines, const since they don't change any class variables.
45
+  float const static temp2analog(const int celsius);
46
+  float const static temp2analogBed(const int celsius);
47
+  float const static analog2temp(const int raw);
48
+  float const static analog2tempBed(const int raw);
49
+  
50
+  inline float const static celsius(const TempSensor s) 
51
+    {
52
+      if(s==TEMPSENSOR_BED) 
53
+	return analog2tempBed(Heater::current_raw[s]); 
54
+      else 
55
+	return analog2temp(Heater::current_raw[s]);
56
+    };
57
+  inline float const static celsiusTarget(const TempSensor s) 
58
+    {
59
+      if(s==TEMPSENSOR_BED) 
60
+	return analog2tempBed(Heater::target_raw[s]); 
61
+      else 
62
+	return analog2temp(Heater::target_raw[s]);
63
+    };
64
+  inline float static setCelsius(const TempSensor s, const int celsius) 
65
+    {
66
+      #ifdef PIDTEMP
67
+	if(s==TEMPSENSOR_HOTEND)
68
+            Heater::pid_setpoint = celsius;
69
+      #endif //PIDTEM
70
+      if(s==TEMPSENSOR_BED) 
71
+	Heater::target_raw[s] = temp2analog(celsius); 
72
+      else 
73
+	Heater::target_raw[s] = temp2analogBed(celsius); 
74
+    };
75
+
76
+   inline bool const static isHeating(TempSensor s)
77
+   { return (Heater::target_raw[s]>Heater::current_raw[s]);};
78
+   inline bool const static isCooling(TempSensor s)
79
+   { return (Heater::target_raw[s]<Heater::current_raw[s]);};
80
+
81
+public:
82
+  #ifdef PIDTEMP
83
+    static float Kp;
84
+    static float Ki;
85
+    static float Kd;
86
+    static float Kc;
87
+  #endif
88
+  
89
+  static int target_raw[3];
90
+  static float pid_setpoint;
91
+  
92
+  volatile static int current_raw[3]; //this are written by an ISR, so volatile.
93
+  volatile static bool temp_meas_ready ; //also this is set by the ISR
94
+  
95
+  
96
+private:
97
+ 
98
+  
99
+
100
+  static unsigned long previous_millis_heater, previous_millis_bed_heater;
101
+
102
+  #ifdef PIDTEMP
103
+    static float temp_iState;
104
+    static float temp_dState;
105
+    static float pTerm;
106
+    static float iTerm;
107
+    static float dTerm;
108
+	//int output;
109
+    static float pid_error;
110
+    static float temp_iState_min;
111
+    static float temp_iState_max;
112
+    static float pid_input;
113
+    static float pid_output;
114
+    
115
+    static bool pid_reset;
116
+    static float HeaterPower;
117
+    
118
+  #endif //PIDTEMP
119
+
120
+public: //but only accesed from the ISR hence not volatile
121
+   #ifdef MINTEMP
122
+  static int minttemp;
123
+  #endif //MINTEMP
124
+  #ifdef MAXTEMP
125
+  static int maxttemp;
126
+  #endif //MAXTEMP
127
+
128
+  #ifdef BED_MINTEMP
129
+  static int bed_minttemp ;
130
+  #endif //BED_MINTEMP
131
+  #ifdef BED_MAXTEMP
132
+  static int bed_maxttemp;
133
+  #endif //BED_MAXTEMP
134
+  
135
+};
136
+
137
+extern Heater htr; //this creates the single, global instance 
36
 
138
 
37
 #ifdef HEATER_USES_THERMISTOR
139
 #ifdef HEATER_USES_THERMISTOR
38
     #define HEATERSOURCE 1
140
     #define HEATERSOURCE 1
41
     #define BEDSOURCE 1
143
     #define BEDSOURCE 1
42
 #endif
144
 #endif
43
 
145
 
44
-//#define temp2analogh( c ) temp2analogu((c),temptable,NUMTEMPS)
45
-//#define analog2temp( c ) analog2tempu((c),temptable,NUMTEMPS
46
-
47
-
48
-extern float Kp;
49
-extern float Ki;
50
-extern float Kd;
51
-extern float Kc;
52
-
53
-enum {TEMPSENSOR_HOTEND=0,TEMPSENSOR_BED=1, TEMPSENSOR_AUX=2};
54
-extern int target_raw[3];
55
-extern int current_raw[3];
56
-extern double pid_setpoint;
57
 
146
 
58
 #endif
147
 #endif

+ 47
- 43
Marlin/ultralcd.pde View File

1
 #include "ultralcd.h"
1
 #include "ultralcd.h"
2
-
2
+#include "temperature.h"
3
 
3
 
4
 #ifdef ULTRA_LCD
4
 #ifdef ULTRA_LCD
5
 extern volatile int feedmultiply;
5
 extern volatile int feedmultiply;
238
 void MainMenu::showStatus()
238
 void MainMenu::showStatus()
239
 { 
239
 { 
240
 #if LCD_HEIGHT==4
240
 #if LCD_HEIGHT==4
241
-  static int oldcurrentraw=-1;
242
-  static int oldtargetraw=-1;
241
+  static int oldcurrent=-1;
242
+  static int oldtarget=-1;
243
   //force_lcd_update=true;
243
   //force_lcd_update=true;
244
   if(force_lcd_update||feedmultiplychanged)  //initial display of content
244
   if(force_lcd_update||feedmultiplychanged)  //initial display of content
245
   {
245
   {
252
 #endif
252
 #endif
253
   }
253
   }
254
     
254
     
255
-
256
-  if((abs(current_raw[TEMPSENSOR_HOTEND]-oldcurrentraw)>3)||force_lcd_update)
255
+  int tt=Heater::celsius(TEMPSENSOR_HOTEND);
256
+  if((abs(tt-oldcurrent)>1)||force_lcd_update)
257
   {
257
   {
258
     lcd.setCursor(1,0);
258
     lcd.setCursor(1,0);
259
-    lcd.print(ftostr3(analog2temp(current_raw[TEMPSENSOR_HOTEND])));
260
-    oldcurrentraw=current_raw[TEMPSENSOR_HOTEND];
259
+    lcd.print(ftostr3(tt));
260
+    oldcurrent=tt;
261
   }
261
   }
262
-  if((target_raw[TEMPSENSOR_HOTEND]!=oldtargetraw)||force_lcd_update)
262
+  int ttg=Heater::celsiusTarget(TEMPSENSOR_HOTEND);
263
+  if((ttg!=oldtarget)||force_lcd_update)
263
   {
264
   {
264
     lcd.setCursor(5,0);
265
     lcd.setCursor(5,0);
265
-    lcd.print(ftostr3(analog2temp(target_raw[TEMPSENSOR_HOTEND])));
266
-    oldtargetraw=target_raw[TEMPSENSOR_HOTEND];
266
+    lcd.print(ftostr3(ttg));
267
+    oldtarget=ttg;
267
   }
268
   }
268
   #if defined BED_USES_THERMISTOR || defined BED_USES_AD595 
269
   #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)
270
+  static int oldcurrentbed=-1;
271
+  static int oldtargetbed=-1;
272
+  int tb=Heater::celsius(TEMPSENSOR_BED);
273
+  if((tb!=oldcurrentbed)||force_lcd_update)
272
   {
274
   {
273
     lcd.setCursor(1,0);
275
     lcd.setCursor(1,0);
274
-    lcd.print(ftostr3(analog2temp(current_bed_raw)));
275
-    oldcurrentraw=current_raw[TEMPSENSOR_BED];
276
+    lcd.print(ftostr3(tb));
277
+    oldcurrentbed=tb;
276
   }
278
   }
277
-  if((target_bed_raw!=oldtargebedtraw)||force_lcd_update)
279
+  int tg=Heater::celsiusTarget(TEMPSENSOR_BED);
280
+  if((tg!=oldtargebed)||force_lcd_update)
278
   {
281
   {
279
     lcd.setCursor(5,0);
282
     lcd.setCursor(5,0);
280
-    lcd.print(ftostr3(analog2temp(target_bed_raw)));
281
-    oldtargetraw=target_bed_raw;
283
+    lcd.print(Heater::celsiusTarget(TEMPSENSOR_BED));
284
+    oldtargebed=tg;
282
   }
285
   }
283
   #endif
286
   #endif
284
   //starttime=2;
287
   //starttime=2;
327
     messagetext[0]='\0';
330
     messagetext[0]='\0';
328
   }
331
   }
329
 #else //smaller LCDS----------------------------------
332
 #else //smaller LCDS----------------------------------
330
-  static int oldcurrentraw=-1;
331
-  static int oldtargetraw=-1;
333
+  static int oldcurrent=-1;
334
+  static int oldtarget=-1;
332
   if(force_lcd_update)  //initial display of content
335
   if(force_lcd_update)  //initial display of content
333
   {
336
   {
334
     encoderpos=feedmultiply;
337
     encoderpos=feedmultiply;
338
     #endif
341
     #endif
339
   }
342
   }
340
     
343
     
341
-
342
-  if((abs(current_raw[TEMPSENSOR_HOTEND]-oldcurrentraw)>3)||force_lcd_update)
344
+  int tt=Heater::celsius(TEMPSENSOR_HOTEND);
345
+  if((abs(tt-oldcurrent)>1)||force_lcd_update)
343
   {
346
   {
344
     lcd.setCursor(1,0);
347
     lcd.setCursor(1,0);
345
-    lcd.print(ftostr3(analog2temp(current_raw[TEMPSENSOR_HOTEND])));
346
-    oldcurrentraw=current_raw[TEMPSENSOR_HOTEND];
348
+    lcd.print(ftostr3(tt));
349
+    oldcurrent=tt;
347
   }
350
   }
348
-  if((target_raw[TEMPSENSOR_HOTEND]!=oldtargetraw)||force_lcd_update)
351
+  int ttg=Heater::celsiusTarget(TEMPSENSOR_HOTEND);
352
+  if((ttg!=oldtarget)||force_lcd_update)
349
   {
353
   {
350
     lcd.setCursor(5,0);
354
     lcd.setCursor(5,0);
351
-    lcd.print(ftostr3(analog2temp(target_raw[TEMPSENSOR_HOTEND])));
352
-    oldtargetraw=target_raw[TEMPSENSOR_HOTEND];
355
+    lcd.print(ftostr3(ttg));
356
+    oldtarge=ttg;
353
   }
357
   }
354
 
358
 
355
   if(messagetext[0]!='\0')
359
   if(messagetext[0]!='\0')
426
         if((activeline==line) && CLICKED)
430
         if((activeline==line) && CLICKED)
427
         {
431
         {
428
           BLOCK
432
           BLOCK
429
-          target_raw[TEMPSENSOR_HOTEND] = temp2analog(170);
433
+          Heater::setCelsius(TEMPSENSOR_HOTEND, 170);
430
           beepshort();
434
           beepshort();
431
         }
435
         }
432
       }break;
436
       }break;
531
         if(force_lcd_update)
535
         if(force_lcd_update)
532
         {
536
         {
533
           lcd.setCursor(0,line);lcd.print(" \002Nozzle:");
537
           lcd.setCursor(0,line);lcd.print(" \002Nozzle:");
534
-          lcd.setCursor(13,line);lcd.print(ftostr3(analog2temp(target_raw[TEMPSENSOR_HOTEND])));
538
+          lcd.setCursor(13,line);lcd.print(ftostr3(Heater::celsiusTarget(TEMPSENSOR_HOTEND)));
535
         }
539
         }
536
         
540
         
537
         if((activeline==line) )
541
         if((activeline==line) )
541
             linechanging=!linechanging;
545
             linechanging=!linechanging;
542
             if(linechanging)
546
             if(linechanging)
543
             {
547
             {
544
-               encoderpos=(int)analog2temp(target_raw[TEMPSENSOR_HOTEND]);
548
+               encoderpos=(int)Heater::celsiusTarget(TEMPSENSOR_HOTEND);
545
             }
549
             }
546
             else
550
             else
547
             {
551
             {
548
-              target_raw[TEMPSENSOR_HOTEND] = temp2analog(encoderpos);
552
+              Heater::setCelsius(TEMPSENSOR_HOTEND,encoderpos);
549
               encoderpos=activeline*lcdslow;
553
               encoderpos=activeline*lcdslow;
550
               beepshort();
554
               beepshort();
551
             }
555
             }
669
       if(force_lcd_update)
673
       if(force_lcd_update)
670
         {
674
         {
671
           lcd.setCursor(0,line);lcd.print(" PID-P: ");
675
           lcd.setCursor(0,line);lcd.print(" PID-P: ");
672
-          lcd.setCursor(13,line);lcd.print(itostr4(Kp));
676
+          lcd.setCursor(13,line);lcd.print(itostr4(Heater::Kp));
673
         }
677
         }
674
         
678
         
675
         if((activeline==line) )
679
         if((activeline==line) )
679
             linechanging=!linechanging;
683
             linechanging=!linechanging;
680
             if(linechanging)
684
             if(linechanging)
681
             {
685
             {
682
-               encoderpos=(int)Kp/5;
686
+               encoderpos=(int)Heater::Kp/5;
683
             }
687
             }
684
             else
688
             else
685
             {
689
             {
686
-              Kp= encoderpos*5;
690
+              Heater::Kp= encoderpos*5;
687
               encoderpos=activeline*lcdslow;
691
               encoderpos=activeline*lcdslow;
688
                 
692
                 
689
             }
693
             }
703
       if(force_lcd_update)
707
       if(force_lcd_update)
704
         {
708
         {
705
           lcd.setCursor(0,line);lcd.print(" PID-I: ");
709
           lcd.setCursor(0,line);lcd.print(" PID-I: ");
706
-          lcd.setCursor(13,line);lcd.print(ftostr51(Ki));
710
+          lcd.setCursor(13,line);lcd.print(ftostr51(Heater::Ki));
707
         }
711
         }
708
         
712
         
709
         if((activeline==line) )
713
         if((activeline==line) )
713
             linechanging=!linechanging;
717
             linechanging=!linechanging;
714
             if(linechanging)
718
             if(linechanging)
715
             {
719
             {
716
-               encoderpos=(int)(Ki*10);
720
+               encoderpos=(int)(Heater::Ki*10);
717
             }
721
             }
718
             else
722
             else
719
             {
723
             {
720
-              Ki= encoderpos/10.;
724
+              Heater::Ki= encoderpos/10.;
721
               encoderpos=activeline*lcdslow;
725
               encoderpos=activeline*lcdslow;
722
                 
726
                 
723
             }
727
             }
737
       if(force_lcd_update)
741
       if(force_lcd_update)
738
         {
742
         {
739
           lcd.setCursor(0,line);lcd.print(" PID-D: ");
743
           lcd.setCursor(0,line);lcd.print(" PID-D: ");
740
-          lcd.setCursor(13,line);lcd.print(itostr4(Kd));
744
+          lcd.setCursor(13,line);lcd.print(itostr4(Heater::Kd));
741
         }
745
         }
742
         
746
         
743
         if((activeline==line) )
747
         if((activeline==line) )
747
             linechanging=!linechanging;
751
             linechanging=!linechanging;
748
             if(linechanging)
752
             if(linechanging)
749
             {
753
             {
750
-               encoderpos=(int)Kd/5;
754
+               encoderpos=(int)(Heater::Kd/5.);
751
             }
755
             }
752
             else
756
             else
753
             {
757
             {
754
-              Kd= encoderpos*5;
758
+              Heater::Kd= encoderpos*5;
755
               encoderpos=activeline*lcdslow;
759
               encoderpos=activeline*lcdslow;
756
                 
760
                 
757
             }
761
             }
774
       if(force_lcd_update)
778
       if(force_lcd_update)
775
         {
779
         {
776
           lcd.setCursor(0,line);lcd.print(" PID-C: ");
780
           lcd.setCursor(0,line);lcd.print(" PID-C: ");
777
-          lcd.setCursor(13,line);lcd.print(itostr3(Kc));
781
+          lcd.setCursor(13,line);lcd.print(itostr3(Heater::Kc));
778
         }
782
         }
779
         
783
         
780
         if((activeline==line) )
784
         if((activeline==line) )
784
             linechanging=!linechanging;
788
             linechanging=!linechanging;
785
             if(linechanging)
789
             if(linechanging)
786
             {
790
             {
787
-               encoderpos=(int)Kc;
791
+               encoderpos=(int)Heater::Kc;
788
             }
792
             }
789
             else
793
             else
790
             {
794
             {
791
-              Kc= encoderpos;
795
+              Heater::Kc= encoderpos;
792
               encoderpos=activeline*lcdslow;
796
               encoderpos=activeline*lcdslow;
793
                 
797
                 
794
             }
798
             }

Loading…
Cancel
Save