Browse Source

Working version of multiple extruders (up to 3)

- The temperature control is pretty much complete
  (not sure what to do w/ autotemp though)
  Changed the pins assignment to clearly separate bed and extruder heaters
  and temp sensors, changed a bit how termistor tables are handled.
- The steppers control is rudimentary
  (only chanages what pins it uses depending on the active_extruder var,
   but that's enough for switching extruder in the start.gcode in the
   the profiles)
- Tested only w/ RAMPS 1.4
Denis B 13 years ago
parent
commit
4fd75dc813
12 changed files with 702 additions and 547 deletions
  1. 40
    32
      Marlin/Configuration.h
  2. 27
    5
      Marlin/Marlin.h
  3. 63
    44
      Marlin/Marlin.pde
  4. 1
    1
      Marlin/cardreader.pde
  5. 15
    1
      Marlin/fastio.h
  6. 111
    68
      Marlin/pins.h
  7. 6
    14
      Marlin/planner.cpp
  8. 0
    2
      Marlin/planner.h
  9. 41
    20
      Marlin/stepper.cpp
  10. 278
    216
      Marlin/temperature.cpp
  11. 66
    51
      Marlin/temperature.h
  12. 54
    93
      Marlin/thermistortables.h

+ 40
- 32
Marlin/Configuration.h View File

@@ -4,11 +4,11 @@
4 4
 
5 5
 
6 6
 // This determines the communication speed of the printer
7
-#define BAUDRATE 250000
8
-//#define BAUDRATE 115200
7
+//#define BAUDRATE 250000
8
+#define BAUDRATE 115200
9 9
 //#define BAUDRATE 230400
10 10
 
11
-#define EXTRUDERS 1
11
+#define EXTRUDERS 2
12 12
 
13 13
 // Frequency limit
14 14
 // See nophead's blog for more info
@@ -32,7 +32,7 @@
32 32
 // Sanguinololu 1.2 and above = 62
33 33
 // Ultimaker = 7,
34 34
 // Teensylu = 8
35
-#define MOTHERBOARD 7
35
+#define MOTHERBOARD 33
36 36
 
37 37
 //===========================================================================
38 38
 //=============================Thermal Settings  ============================
@@ -46,17 +46,16 @@
46 46
 // 5 is ParCan supplied 104GT-2 100K
47 47
 // 6 is EPCOS 100k
48 48
 // 7 is 100k Honeywell thermistor 135-104LAG-J01
49
-//#define THERMISTORHEATER_0 3
50
-//#define THERMISTORHEATER_1 3
51
-//#define THERMISTORBED 3
52
-
53
-//#define HEATER_0_USES_THERMISTOR
54
-//#define HEATER_1_USES_THERMISTOR
55
-#define HEATER_0_USES_AD595
49
+#define THERMISTORHEATER_0 1
50
+#define THERMISTORHEATER_1 1
51
+#define HEATER_0_USES_THERMISTOR
52
+#define HEATER_1_USES_THERMISTOR
53
+//#define HEATER_0_USES_AD595
56 54
 //#define HEATER_1_USES_AD595
57 55
 
58 56
 // Select one of these only to define how the bed temp is read.
59
-//#define BED_USES_THERMISTOR
57
+#define THERMISTORBED 1
58
+#define BED_USES_THERMISTOR
60 59
 //#define BED_USES_AD595
61 60
 
62 61
 #define BED_CHECK_INTERVAL 5000 //ms
@@ -68,13 +67,13 @@
68 67
 //#define WATCHPERIOD 5000 //5 seconds
69 68
 
70 69
 // Actual temperature must be close to target for this long before M109 returns success
71
-//#define TEMP_RESIDENCY_TIME 20  // (seconds)
72
-//#define TEMP_HYSTERESIS 5       // (C°) range of +/- temperatures considered "close" to the target one
70
+#define TEMP_RESIDENCY_TIME 30  // (seconds)
71
+#define TEMP_HYSTERESIS 3       // (C°) range of +/- temperatures considered "close" to the target one
73 72
 
74 73
 //// The minimal temperature defines the temperature below which the heater will not be enabled
75 74
 #define HEATER_0_MINTEMP 5
76 75
 //#define HEATER_1_MINTEMP 5
77
-//#define BED_MINTEMP 5
76
+#define BED_MINTEMP 5
78 77
 
79 78
 
80 79
 // When temperature exceeds max temp, your heater will be switched off.
@@ -82,7 +81,7 @@
82 81
 // You should use MINTEMP for thermistor short/failure protection.
83 82
 #define HEATER_0_MAXTEMP 275
84 83
 //#define HEATER_1_MAXTEMP 275
85
-//#define BED_MAXTEMP 150
84
+#define BED_MAXTEMP 150
86 85
 
87 86
 
88 87
 // Wait for Cooldown
@@ -131,9 +130,14 @@
131 130
 //    #define  DEFAULT_Kd (PID_SWING_AT_CRITIAL/8./PID_dT)  
132 131
 
133 132
 // Ultitmaker
134
-    #define  DEFAULT_Kp  22.2
135
-    #define  DEFAULT_Ki (1.25*PID_dT)  
136
-    #define  DEFAULT_Kd (99/PID_dT)  
133
+//    #define  DEFAULT_Kp  22.2
134
+//    #define  DEFAULT_Ki (1.25*PID_dT)  
135
+//    #define  DEFAULT_Kd (99/PID_dT)  
136
+
137
+// Makergear
138
+    #define  DEFAULT_Kp 7.0
139
+    #define  DEFAULT_Ki 0.1  
140
+    #define  DEFAULT_Kd 12  
137 141
 
138 142
 // Mendel Parts V9 on 12V    
139 143
 //    #define  DEFAULT_Kp  63.0
@@ -152,7 +156,7 @@
152 156
   // if Kc is choosen well, the additional required power due to increased melting should be compensated.
153 157
   #define PID_ADD_EXTRUSION_RATE  
154 158
   #ifdef PID_ADD_EXTRUSION_RATE
155
-    #define  DEFAULT_Kc (3) //heatingpower=Kc*(e_speed)
159
+    #define  DEFAULT_Kc (1) //heatingpower=Kc*(e_speed)
156 160
   #endif
157 161
 #endif // PIDTEMP
158 162
 
@@ -164,10 +168,11 @@
164 168
 
165 169
 // Endstop Settings
166 170
 #define ENDSTOPPULLUPS // Comment this out (using // at the start of the line) to disable the endstop pullup resistors
171
+
167 172
 // The pullups are needed if you directly connect a mechanical endswitch between the signal and ground pins.
168
-const bool X_ENDSTOPS_INVERTING = true; // set to true to invert the logic of the endstops. 
169
-const bool Y_ENDSTOPS_INVERTING = true; // set to true to invert the logic of the endstops. 
170
-const bool Z_ENDSTOPS_INVERTING = true; // set to true to invert the logic of the endstops. 
173
+const bool X_ENDSTOPS_INVERTING = false; // set to true to invert the logic of the endstops. 
174
+const bool Y_ENDSTOPS_INVERTING = false; // set to true to invert the logic of the endstops. 
175
+const bool Z_ENDSTOPS_INVERTING = false; // set to true to invert the logic of the endstops. 
171 176
 // For optos H21LOB set to true, for Mendel-Parts newer optos TCST2103 set to false
172 177
 
173 178
 //#define ENDSTOPS_ONLY_FOR_HOMING // If defined the endstops will only be used for homing
@@ -176,24 +181,26 @@ const bool Z_ENDSTOPS_INVERTING = true; // set to true to invert the logic of th
176 181
 #define X_ENABLE_ON 0
177 182
 #define Y_ENABLE_ON 0
178 183
 #define Z_ENABLE_ON 0
179
-#define E_ENABLE_ON 0
184
+#define E_ENABLE_ON 0 // For all extruders
180 185
 
181 186
 // Disables axis when it's not being used.
182 187
 #define DISABLE_X false
183 188
 #define DISABLE_Y false
184
-#define DISABLE_Z false
185
-#define DISABLE_E false
189
+#define DISABLE_Z true
190
+#define DISABLE_E false // For all extruders
186 191
 
187 192
 // Inverting axis direction
188 193
 //#define INVERT_X_DIR false    // for Mendel set to false, for Orca set to true
189 194
 //#define INVERT_Y_DIR true   // for Mendel set to true, for Orca set to false
190 195
 //#define INVERT_Z_DIR false    // for Mendel set to false, for Orca set to true
191
-//#define INVERT_E_DIR true   // for direct drive extruder v9 set to true, for geared extruder set to false
196
+//#define INVERT_E*_DIR true   // for direct drive extruder v9 set to true, for geared extruder set to false, used for all extruders
192 197
 
193
-#define INVERT_X_DIR true     // for Mendel set to false, for Orca set to true
198
+#define INVERT_X_DIR false    // for Mendel set to false, for Orca set to true
194 199
 #define INVERT_Y_DIR false    // for Mendel set to true, for Orca set to false
195 200
 #define INVERT_Z_DIR true     // for Mendel set to false, for Orca set to true
196
-#define INVERT_E_DIR false    // for direct drive extruder v9 set to true, for geared extruder set to false
201
+#define INVERT_E0_DIR false   // for direct drive extruder v9 set to true, for geared extruder set to false
202
+#define INVERT_E1_DIR true    // for direct drive extruder v9 set to true, for geared extruder set to false
203
+#define INVERT_E2_DIR false   // for direct drive extruder v9 set to true, for geared extruder set to false
197 204
 
198 205
 //// ENDSTOP SETTINGS:
199 206
 // Sets direction of endstops when homing; 1=MAX, -1=MIN
@@ -209,7 +216,7 @@ const bool Z_ENDSTOPS_INVERTING = true; // set to true to invert the logic of th
209 216
 
210 217
 //// MOVEMENT SETTINGS
211 218
 #define NUM_AXIS 4 // The axis order in all axis related arrays is X, Y, Z, E
212
-#define HOMING_FEEDRATE {50*60, 50*60, 4*60, 0}  // set the homing speeds (mm/min)
219
+#define HOMING_FEEDRATE {30*60, 30*60, 2*60, 0}  // set the homing speeds (mm/min)
213 220
 
214 221
 //homing hits the endstop, then retracts by this distance, before it tries to slowly bump again:
215 222
 #define X_HOME_RETRACT_MM 5 
@@ -223,8 +230,9 @@ const bool Z_ENDSTOPS_INVERTING = true; // set to true to invert the logic of th
223 230
 
224 231
 // default settings 
225 232
 
226
-#define DEFAULT_AXIS_STEPS_PER_UNIT   {78.7402,78.7402,200*8/3,760*1.1}                    // default steps per unit for ultimaker 
233
+//#define DEFAULT_AXIS_STEPS_PER_UNIT   {78.7402,78.7402,200*8/3,760*1.1}                    // default steps per unit for ultimaker 
227 234
 //#define DEFAULT_AXIS_STEPS_PER_UNIT   {40, 40, 3333.92, 67} //sells mendel with v9 extruder
235
+#define DEFAULT_AXIS_STEPS_PER_UNIT   {80.3232, 80.8900, 2284.7651, 757.2218} // SAE Prusa w/ Wade extruder
228 236
 #define DEFAULT_MAX_FEEDRATE          {500, 500, 5, 45}    // (mm/sec)    
229 237
 #define DEFAULT_MAX_ACCELERATION      {9000,9000,100,10000}    // X, Y, Z, E maximum start speed for accelerated moves. E default values are good for skeinforge 40+, for older versions raise them a lot.
230 238
 
@@ -290,7 +298,7 @@ const bool Z_ENDSTOPS_INVERTING = true; // set to true to invert the logic of th
290 298
 
291 299
 //LCD and SD support
292 300
 //#define ULTRA_LCD  //general lcd support, also 16x2
293
-//#define SDSUPPORT // Enable SD Card Support in Hardware Console
301
+#define SDSUPPORT // Enable SD Card Support in Hardware Console
294 302
 #define SD_FINISHED_STEPPERRELEASE true  //if sd support and the file is finished: disable steppers?
295 303
 
296 304
 //#define ULTIPANEL

+ 27
- 5
Marlin/Marlin.h View File

@@ -57,6 +57,8 @@ const prog_char echomagic[] PROGMEM ="echo:";
57 57
 
58 58
 #define SERIAL_ECHOPAIR(name,value) {SERIAL_ECHOPGM(name);SERIAL_ECHO(value);}
59 59
 
60
+// Macro for getting current active extruder
61
+#define ACTIVE_EXTRUDER (active_extruder)
60 62
 
61 63
 //things to write to serial from Programmemory. saves 400 to 2k of RAM.
62 64
 #define SerialprintPGM(x) serialprintPGM(MYPGM(x))
@@ -100,14 +102,31 @@ void manage_inactivity(byte debug);
100 102
   #define disable_z() ;
101 103
 #endif
102 104
 
103
-#if E_ENABLE_PIN > -1
104
-  #define  enable_e() WRITE(E_ENABLE_PIN, E_ENABLE_ON)
105
-  #define disable_e() WRITE(E_ENABLE_PIN,!E_ENABLE_ON)
105
+#if defined(E0_ENABLE_PIN) && (E0_ENABLE_PIN > -1)
106
+  #define enable_e0() WRITE(E0_ENABLE_PIN, E_ENABLE_ON)
107
+  #define disable_e0() WRITE(E0_ENABLE_PIN,!E_ENABLE_ON)
106 108
 #else
107
-  #define enable_e() ;
108
-  #define disable_e() ;
109
+  #define enable_e0()  /* nothing */
110
+  #define disable_e0() /* nothing */
109 111
 #endif
110 112
 
113
+#if (EXTRUDERS > 1) && defined(E1_ENABLE_PIN) && (E1_ENABLE_PIN > -1)
114
+  #define enable_e1() WRITE(E1_ENABLE_PIN, E_ENABLE_ON)
115
+  #define disable_e1() WRITE(E1_ENABLE_PIN,!E_ENABLE_ON)
116
+#else
117
+  #define enable_e1()  /* nothing */
118
+  #define disable_e1() /* nothing */
119
+#endif
120
+
121
+#if (EXTRUDERS > 2) && defined(E2_ENABLE_PIN) && (E2_ENABLE_PIN > -1)
122
+  #define enable_e2() WRITE(E2_ENABLE_PIN, E_ENABLE_ON)
123
+  #define disable_e2() WRITE(E2_ENABLE_PIN,!E_ENABLE_ON)
124
+#else
125
+  #define enable_e2()  /* nothing */
126
+  #define disable_e2() /* nothing */
127
+#endif
128
+
129
+
111 130
 enum AxisEnum {X_AXIS=0, Y_AXIS=1, Z_AXIS=2, E_AXIS=3};
112 131
 
113 132
 
@@ -131,4 +150,7 @@ extern bool axis_relative_modes[];
131 150
 extern float current_position[NUM_AXIS] ;
132 151
 extern float add_homeing[3];
133 152
 
153
+// Handling multiple extruders pins
154
+extern uint8_t active_extruder;
155
+
134 156
 #endif

+ 63
- 44
Marlin/Marlin.pde View File

@@ -119,7 +119,6 @@
119 119
 //===========================================================================
120 120
 //=============================imported variables============================
121 121
 //===========================================================================
122
-extern float HeaterPower;
123 122
 
124 123
 
125 124
 //===========================================================================
@@ -133,8 +132,10 @@ bool axis_relative_modes[] = AXIS_RELATIVE_MODES;
133 132
 volatile int feedmultiply=100; //100->1 200->2
134 133
 int saved_feedmultiply;
135 134
 volatile bool feedmultiplychanged=false;
136
-float current_position[NUM_AXIS] = {  0.0, 0.0, 0.0, 0.0};
135
+float current_position[NUM_AXIS] = { 0.0, 0.0, 0.0, 0.0 };
137 136
 float add_homeing[3]={0,0,0};
137
+uint8_t active_extruder = 0;
138
+
138 139
 
139 140
 //===========================================================================
140 141
 //=============================private variables=============================
@@ -601,7 +602,6 @@ FORCE_INLINE void process_commands()
601 602
 
602 603
   else if(code_seen('M'))
603 604
   {
604
-
605 605
     switch( (int)code_value() ) 
606 606
     {
607 607
     case 17:
@@ -609,10 +609,12 @@ FORCE_INLINE void process_commands()
609 609
         enable_x(); 
610 610
         enable_y(); 
611 611
         enable_z(); 
612
-        enable_e(); 
612
+        enable_e0(); 
613
+        enable_e1(); 
614
+        enable_e2(); 
613 615
       break;
614
-    #ifdef SDSUPPORT
615 616
 
617
+#ifdef SDSUPPORT
616 618
     case 20: // M20 - list SD card
617 619
       SERIAL_PROTOCOLLNPGM("Begin file list");
618 620
       card.ls();
@@ -641,9 +643,8 @@ FORCE_INLINE void process_commands()
641 643
       card.pauseSDPrint();
642 644
       break;
643 645
     case 26: //M26 - Set SD index
644
-      if(card.cardOK && code_seen('S')){
646
+      if(card.cardOK && code_seen('S')) {
645 647
         card.setIndex(code_value_long());
646
-        
647 648
       }
648 649
       break;
649 650
     case 27: //M27 - Get SD status
@@ -657,16 +658,15 @@ FORCE_INLINE void process_commands()
657 658
         *(starpos-1) = '\0';
658 659
       }
659 660
       card.openFile(strchr_pointer+4,false);
660
-      
661 661
       break;
662 662
     case 29: //M29 - Stop SD write
663 663
       //processed in write to file routine above
664 664
       //card,saving = false;
665 665
       break;
666
-    #endif //SDSUPPORT
666
+#endif //SDSUPPORT
667 667
 
668 668
     case 30: //M30 take time since the start of the SD print or an M109 command
669
-    {
669
+      {
670 670
       stoptime=millis();
671 671
       char time[30];
672 672
       unsigned long t=(stoptime-starttime)/1000;
@@ -678,8 +678,8 @@ FORCE_INLINE void process_commands()
678 678
       SERIAL_ECHOLN(time);
679 679
       LCD_MESSAGE(time);
680 680
       autotempShutdown();
681
-    }
682
-    break;
681
+      }
682
+      break;
683 683
     case 42: //M42 -Change pin status via gcode
684 684
       if (code_seen('S'))
685 685
       {
@@ -723,7 +723,7 @@ FORCE_INLINE void process_commands()
723 723
       if (code_seen('S')) setTargetBed(code_value());
724 724
       break;
725 725
     case 105 : // M105
726
-      tmp_extruder = active_extruder;
726
+      tmp_extruder = ACTIVE_EXTRUDER;
727 727
       if(code_seen('T')) {
728 728
         tmp_extruder = code_value();
729 729
         if(tmp_extruder >= EXTRUDERS) {
@@ -733,22 +733,17 @@ FORCE_INLINE void process_commands()
733 733
           break;
734 734
         }
735 735
       }
736
-      #if (TEMP_0_PIN > -1) || (TEMP_2_PIN > -1)
736
+      #if (TEMP_0_PIN > -1)
737 737
         SERIAL_PROTOCOLPGM("ok T:");
738
-        SERIAL_PROTOCOL( degHotend(tmp_extruder)); 
739
-        #if TEMP_1_PIN > -1 
738
+        SERIAL_PROTOCOL(degHotend(tmp_extruder)); 
739
+        #if TEMP_BED_PIN > -1 
740 740
           SERIAL_PROTOCOLPGM(" B:");  
741 741
           SERIAL_PROTOCOL(degBed());
742
-        #endif //TEMP_1_PIN
742
+        #endif //TEMP_BED_PIN
743 743
       #else
744 744
         SERIAL_ERROR_START;
745 745
         SERIAL_ERRORLNPGM("No thermistors - no temp");
746 746
       #endif
747
-      #ifdef PIDTEMP
748
-        SERIAL_PROTOCOLPGM(" @:");
749
-        SERIAL_PROTOCOL( HeaterPower); 
750
-       
751
-      #endif
752 747
         SERIAL_PROTOCOLLN("");
753 748
       return;
754 749
       break;
@@ -790,19 +785,31 @@ FORCE_INLINE void process_commands()
790 785
         residencyStart = -1;
791 786
         /* continue to loop until we have reached the target temp   
792 787
           _and_ until TEMP_RESIDENCY_TIME hasn't passed since we reached it */
793
-        while((target_direction ? (isHeatingHotend(tmp_extruder)) : (isCoolingHotend(tmp_extruder))) ||
794
-                (residencyStart > -1 && (millis() - residencyStart) < TEMP_RESIDENCY_TIME*1000) ) {
788
+        while((residencyStart == -1) ||
789
+              (residencyStart > -1 && (millis() - residencyStart) < TEMP_RESIDENCY_TIME*1000) ) {
795 790
       #else
796
-        while ( target_direction ? (isHeatingHotend(tmp_extruder)) : (isCoolingHotend(tmp_extruder)&&(CooldownNoWait==false)) ) {
791
+        while ( target_direction ? (isHeatingHotend(tmp_extruder)) : (isCoolingHotend(tmp_extruder)&&(CooldownNoWait==false)) ) {
797 792
       #endif //TEMP_RESIDENCY_TIME
798
-        if( (millis() - codenum) > 1000 ) 
799
-        { //Print Temp Reading every 1 second while heating up/cooling down
800
-          SERIAL_PROTOCOLPGM("T:");
801
-          SERIAL_PROTOCOLLN( degHotend(tmp_extruder) ); 
802
-          codenum = millis();
803
-        }
804
-        manage_heater();
805
-        LCD_STATUS;
793
+          if( (millis() - codenum) > 1000 ) 
794
+          { //Print Temp Reading and remaining time every 1 second while heating up/cooling down
795
+            SERIAL_PROTOCOLPGM("T:");
796
+            SERIAL_PROTOCOLLN( degHotend(tmp_extruder) ); 
797
+            SERIAL_PROTOCOLPGM(" E:");
798
+            SERIAL_PROTOCOLLN( (int)tmp_extruder ); 
799
+            SERIAL_PROTOCOLPGM(" W:");
800
+            if(residencyStart > -1)
801
+            {
802
+               codenum = TEMP_RESIDENCY_TIME - ((millis() - residencyStart) / 1000);
803
+               SERIAL_PROTOCOLLN( codenum );
804
+            }
805
+            else 
806
+            {
807
+               SERIAL_PROTOCOLLN( "?" );
808
+            }
809
+            codenum = millis();
810
+          }
811
+          manage_heater();
812
+          LCD_STATUS;
806 813
         #ifdef TEMP_RESIDENCY_TIME
807 814
             /* start/restart the TEMP_RESIDENCY_TIME timer whenever we reach target temp for the first time
808 815
               or when current temp falls outside the hysteresis after target temp was reached */
@@ -818,8 +825,8 @@ FORCE_INLINE void process_commands()
818 825
         starttime=millis();
819 826
       }
820 827
       break;
821
-    case 190: // M190 - Wait bed for heater to reach target.
822
-    #if TEMP_1_PIN > -1
828
+    case 190: // M190 - Wait for bed heater to reach target.
829
+    #if TEMP_BED_PIN > -1
823 830
         LCD_MESSAGEPGM("Bed Heating.");
824 831
         if (code_seen('S')) setTargetBed(code_value());
825 832
         codenum = millis(); 
@@ -827,13 +834,13 @@ FORCE_INLINE void process_commands()
827 834
         {
828 835
           if( (millis()-codenum) > 1000 ) //Print Temp Reading every 1 second while heating up.
829 836
           {
830
-            float tt=degHotend0();
837
+            float tt=degHotend(ACTIVE_EXTRUDER);
831 838
             SERIAL_PROTOCOLPGM("T:");
832
-            SERIAL_PROTOCOLLN(tt );
833
-            SERIAL_PROTOCOLPGM("ok T:");
834
-            SERIAL_PROTOCOL(tt );
839
+            SERIAL_PROTOCOL(tt);
840
+            SERIAL_PROTOCOLPGM(" E:");
841
+            SERIAL_PROTOCOLLN( (int)tmp_extruder ); 
835 842
             SERIAL_PROTOCOLPGM(" B:");
836
-            SERIAL_PROTOCOLLN(degBed() ); 
843
+            SERIAL_PROTOCOLLN(degBed()); 
837 844
             codenum = millis(); 
838 845
           }
839 846
           manage_heater();
@@ -886,7 +893,9 @@ FORCE_INLINE void process_commands()
886 893
         if(code_seen('E')) {
887 894
           st_synchronize();
888 895
           LCD_MESSAGEPGM("Free Move");
889
-          disable_e();
896
+          disable_e0();
897
+          disable_e1();
898
+          disable_e2();
890 899
         }
891 900
         else {
892 901
           finishAndDisableSteppers();
@@ -1061,7 +1070,9 @@ FORCE_INLINE void process_commands()
1061 1070
 
1062 1071
     }
1063 1072
   }
1064
-  else if(code_seen('T')) {
1073
+
1074
+  else if(code_seen('T')) 
1075
+  {
1065 1076
     tmp_extruder = code_value();
1066 1077
     if(tmp_extruder >= EXTRUDERS) {
1067 1078
       SERIAL_ECHO_START;
@@ -1071,8 +1082,12 @@ FORCE_INLINE void process_commands()
1071 1082
     }
1072 1083
     else {
1073 1084
       active_extruder = tmp_extruder;
1085
+      SERIAL_ECHO_START;
1086
+      SERIAL_ECHO("Active Extruder: ");
1087
+      SERIAL_PROTOCOLLN((int)active_extruder);
1074 1088
     }
1075 1089
   }
1090
+
1076 1091
   else
1077 1092
   {
1078 1093
     SERIAL_ECHO_START;
@@ -1167,7 +1182,9 @@ void manage_inactivity(byte debug)
1167 1182
       disable_x(); 
1168 1183
       disable_y(); 
1169 1184
       disable_z(); 
1170
-      disable_e(); 
1185
+      disable_e0(); 
1186
+      disable_e1(); 
1187
+      disable_e2(); 
1171 1188
     }
1172 1189
   check_axes_activity();
1173 1190
 }
@@ -1179,7 +1196,9 @@ void kill()
1179 1196
   disable_x();
1180 1197
   disable_y();
1181 1198
   disable_z();
1182
-  disable_e();
1199
+  disable_e0();
1200
+  disable_e1();
1201
+  disable_e2();
1183 1202
   
1184 1203
   if(PS_ON_PIN > -1) pinMode(PS_ON_PIN,INPUT);
1185 1204
   SERIAL_ERROR_START;

+ 1
- 1
Marlin/cardreader.pde View File

@@ -438,4 +438,4 @@ void CardReader::printingHasFinished()
438 438
  }
439 439
  autotempShutdown();
440 440
 }
441
-#endif //SDSUPPORT
441
+#endif //SDSUPPORT

+ 15
- 1
Marlin/fastio.h View File

@@ -44,9 +44,23 @@
44 44
 //	why double up on these macros? see http://gcc.gnu.org/onlinedocs/cpp/Stringification.html
45 45
 
46 46
 /// Read a pin wrapper
47
-#define		READ(IO)					_READ(IO)
47
+#define		READ(IO)				_READ(IO)
48 48
 /// Write to a pin wrapper
49 49
 #define		WRITE(IO, v)			_WRITE(IO, v)
50
+#if EXTRUDERS > 2
51
+  #define WRITE_E_STEP(v) { if(ACTIVE_EXTRUDER == 2) { WRITE(E2_STEP_PIN, v); } else { if(ACTIVE_EXTRUDER == 1) { WRITE(E1_STEP_PIN, v); } else { WRITE(E0_STEP_PIN, v); }}}
52
+  #define NORM_E_DIR() { if(ACTIVE_EXTRUDER == 2) { WRITE(E2_DIR_PIN, INVERT_E2_DIR); } else { if(ACTIVE_EXTRUDER == 1) { WRITE(E1_DIR_PIN, INVERT_E1_DIR); } else { WRITE(E0_DIR_PIN, INVERT_E0_DIR); }}}
53
+  #define REV_E_DIR() { if(ACTIVE_EXTRUDER == 2) { WRITE(E2_DIR_PIN, !INVERT_E2_DIR); } else { if(ACTIVE_EXTRUDER == 1) { WRITE(E1_DIR_PIN, !INVERT_E1_DIR); } else { WRITE(E0_DIR_PIN, !INVERT_E0_DIR); }}}
54
+#elif EXTRUDERS > 1
55
+  #define WRITE_E_STEP(v) { if(ACTIVE_EXTRUDER == 1) { WRITE(E1_STEP_PIN, v); } else { WRITE(E0_STEP_PIN, v); }}
56
+  #define NORM_E_DIR() { if(ACTIVE_EXTRUDER == 1) { WRITE(E1_DIR_PIN, INVERT_E1_DIR); } else { WRITE(E0_DIR_PIN, INVERT_E0_DIR); }}
57
+  #define REV_E_DIR() { if(ACTIVE_EXTRUDER == 1) { WRITE(E1_DIR_PIN, !INVERT_E1_DIR); } else { WRITE(E0_DIR_PIN, !INVERT_E0_DIR); }}
58
+#else
59
+  #define WRITE_E_STEP(v) WRITE(E0_STEP_PIN, v)
60
+  #define NORM_E_DIR() WRITE(E0_DIR_PIN, INVERT_E0_DIR)
61
+  #define REV_E_DIR() WRITE(E0_DIR_PIN, !INVERT_E0_DIR)
62
+#endif
63
+
50 64
 /// toggle a pin wrapper
51 65
 #define		TOGGLE(IO)				_TOGGLE(IO)
52 66
 

+ 111
- 68
Marlin/pins.h View File

@@ -47,9 +47,9 @@
47 47
 #define Z_MIN_PIN          17
48 48
 #define Z_MAX_PIN          16
49 49
 
50
-#define E_STEP_PIN         11
51
-#define E_DIR_PIN          12
52
-#define E_ENABLE_PIN       -1
50
+#define E0_STEP_PIN         11
51
+#define E0_DIR_PIN          12
52
+#define E0_ENABLE_PIN       -1
53 53
 
54 54
 #define SDPOWER          -1
55 55
 #define SDSS          -1
@@ -59,9 +59,13 @@
59 59
 #define KILL_PIN           -1
60 60
 
61 61
 #define HEATER_0_PIN        6
62
-#define TEMP_0_PIN          0    // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!!
63 62
 #define HEATER_1_PIN        -1
64 63
 #define HEATER_2_PIN        -1
64
+#define TEMP_0_PIN          0    // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!!
65
+#define TEMP_1_PIN          -1   // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!!
66
+#define TEMP_2_PIN          -1   // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!!
67
+#define HEATER_BED_PIN      -1
68
+#define TEMP_BED_PIN        -1
65 69
 #endif
66 70
 
67 71
 
@@ -120,9 +124,9 @@
120 124
 #define Z_MIN_PIN           2
121 125
 #define Z_MAX_PIN           1
122 126
 
123
-#define E_STEP_PIN         12
124
-#define E_DIR_PIN          16
125
-#define E_ENABLE_PIN        3
127
+#define E0_STEP_PIN         12
128
+#define E0_DIR_PIN          16
129
+#define E0_ENABLE_PIN        3
126 130
 
127 131
 #define SDPOWER          -1
128 132
 #define SDSS          -1
@@ -132,9 +136,13 @@
132 136
 #define KILL_PIN           -1
133 137
 
134 138
 #define HEATER_0_PIN       14
139
+#define HEATER_1_PIN       -1
140
+#define HEATER_2_PIN       -1
135 141
 #define TEMP_0_PIN          4 //D27   // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!!
136
-#define HEATER_1_PIN        -1
137
-#define HEATER_2_PIN        -1
142
+#define TEMP_1_PIN         -1 
143
+#define TEMP_2_PIN         -1 
144
+#define HEATER_BED_PIN     -1
145
+#define TEMP_BED_PIN       -1
138 146
 /*  Unused (1) (2) (3) 4 5 6 7 8 9 10 11 12 13 (14) (15) (16) 17 (18) (19) (20) (21) (22) (23) 24 (25) (26) (27) 28 (29) (30) (31)  */
139 147
 
140 148
 
@@ -171,9 +179,9 @@
171 179
 #define Z_MIN_PIN       30
172 180
 #define Z_MAX_PIN       31
173 181
 
174
-#define E_STEP_PIN      17
175
-#define E_DIR_PIN       16
176
-#define E_ENABLE_PIN    -1
182
+#define E0_STEP_PIN      17
183
+#define E0_DIR_PIN       16
184
+#define E0_ENABLE_PIN    -1
177 185
 
178 186
 #define SDPOWER          -1
179 187
 #define SDSS          4
@@ -194,11 +202,13 @@
194 202
 #define KILL_PIN        -1
195 203
 
196 204
 #define HEATER_0_PIN    -1
205
+#define HEATER_1_PIN    -1
206
+#define HEATER_2_PIN    -1
197 207
 #define TEMP_0_PIN      -1    // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!!
198
-#define HEATER_1_PIN        -1
199
-#define HEATER_2_PIN        -1
200
-
201
-
208
+#define TEMP_1_PIN      -1    
209
+#define TEMP_2_PIN      -1    
210
+#define HEATER_BED_PIN  -1
211
+#define TEMP_BED_PIN    -1
202 212
 
203 213
 #endif
204 214
 
@@ -230,37 +240,43 @@
230 240
 #define X_DIR_PIN          55
231 241
 #define X_ENABLE_PIN       38
232 242
 #define X_MIN_PIN           3
233
-#define X_MAX_PIN          -1   //2 //Max endstops default to disabled "-1", set to commented value to enable.
243
+#define X_MAX_PIN           2   //2 //Max endstops default to disabled "-1", set to commented value to enable.
234 244
 
235 245
 #define Y_STEP_PIN         60
236 246
 #define Y_DIR_PIN          61
237 247
 #define Y_ENABLE_PIN       56
238 248
 #define Y_MIN_PIN          14
239
-#define Y_MAX_PIN          -1   //15
249
+#define Y_MAX_PIN          15   //15
240 250
 
241 251
 #define Z_STEP_PIN         46
242 252
 #define Z_DIR_PIN          48
243 253
 #define Z_ENABLE_PIN       62
244 254
 #define Z_MIN_PIN          18
245
-#define Z_MAX_PIN          -1   //19
255
+#define Z_MAX_PIN          19   //19
246 256
 
247
-#define E_STEP_PIN         26
248
-#define E_DIR_PIN          28
249
-#define E_ENABLE_PIN       24
257
+#define E0_STEP_PIN        26
258
+#define E0_DIR_PIN         28
259
+#define E0_ENABLE_PIN      24
260
+
261
+#define E1_STEP_PIN        36
262
+#define E1_DIR_PIN         34
263
+#define E1_ENABLE_PIN      30
250 264
 
251 265
 #define SDPOWER            -1
252 266
 #define SDSS               53
253 267
 #define LED_PIN            13
254
-#define FAN_PIN            9
268
+#define FAN_PIN            4
255 269
 #define PS_ON_PIN          12
256 270
 #define KILL_PIN           -1
257 271
 
258
-#define HEATER_0_PIN       10
259
-#define HEATER_1_PIN       8
260
-#define HEATER_2_PIN        -1
272
+#define HEATER_0_PIN       10   // EXTRUDER 1
273
+#define HEATER_1_PIN       9    // EXTRUDER 2
274
+#define HEATER_2_PIN       -1   // EXTRUDER 2
261 275
 #define TEMP_0_PIN         13   // ANALOG NUMBERING
262
-#define TEMP_1_PIN         14   // ANALOG NUMBERING
276
+#define TEMP_1_PIN         15   // ANALOG NUMBERING
263 277
 #define TEMP_2_PIN         -1   // ANALOG NUMBERING
278
+#define HEATER_BED_PIN     8    // BED
279
+#define TEMP_BED_PIN       14   // ANALOG NUMBERING
264 280
 
265 281
 
266 282
 #else // RAMPS_V_1_1 or RAMPS_V_1_2 as default
@@ -283,9 +299,9 @@
283 299
 #define Z_MIN_PIN          18
284 300
 #define Z_MAX_PIN          -1    //19
285 301
 
286
-#define E_STEP_PIN         32
287
-#define E_DIR_PIN          34
288
-#define E_ENABLE_PIN       30
302
+#define E0_STEP_PIN         32
303
+#define E0_DIR_PIN          34
304
+#define E0_ENABLE_PIN       30
289 305
 
290 306
 #define SDPOWER            48
291 307
 #define SDSS               53
@@ -297,18 +313,19 @@
297 313
 
298 314
 #ifdef RAMPS_V_1_0 // RAMPS_V_1_0
299 315
   #define HEATER_0_PIN     12    // RAMPS 1.0
300
-  #define HEATER_1_PIN     -1    // RAMPS 1.0
316
+  #define HEATER_BED_PIN   -1    // RAMPS 1.0
301 317
   #define FAN_PIN          11    // RAMPS 1.0
302
-
303 318
 #else // RAMPS_V_1_1 or RAMPS_V_1_2
304 319
   #define HEATER_0_PIN     10    // RAMPS 1.1
305
-  #define HEATER_1_PIN      8    // RAMPS 1.1
320
+  #define HEATER_BED_PIN    8    // RAMPS 1.1
306 321
   #define FAN_PIN           9    // RAMPS 1.1
307 322
 #endif
323
+#define HEATER_1_PIN        -1
308 324
 #define HEATER_2_PIN        -1
309 325
 #define TEMP_0_PIN          2    // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!!
310
-#define TEMP_1_PIN          1    // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!!
311
-#define TEMP_2_PIN          -1    // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!!
326
+#define TEMP_1_PIN          -1   
327
+#define TEMP_2_PIN          -1   
328
+#define TEMP_BED_PIN        1    // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!!
312 329
 #endif
313 330
 
314 331
 // SPI for Max6675 Thermocouple 
@@ -353,9 +370,9 @@
353 370
 #define Z_MIN_PIN           4
354 371
 #define Z_MAX_PIN          -1
355 372
 
356
-#define E_STEP_PIN         11
357
-#define E_DIR_PIN          12
358
-#define E_ENABLE_PIN       -1
373
+#define E0_STEP_PIN         11
374
+#define E0_DIR_PIN          12
375
+#define E0_ENABLE_PIN       -1
359 376
 
360 377
 #define SDPOWER          -1
361 378
 #define SDSS          -1
@@ -365,9 +382,13 @@
365 382
 #define KILL_PIN           -1
366 383
 
367 384
 #define HEATER_0_PIN        6
368
-#define TEMP_0_PIN          0    // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!!
369 385
 #define HEATER_1_PIN        -1
370 386
 #define HEATER_2_PIN        -1
387
+#define TEMP_0_PIN          0    // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!!
388
+#define TEMP_1_PIN          -1    
389
+#define TEMP_2_PIN          -1    
390
+#define HEATER_BED_PIN      -1
391
+#define TEMP_BED_PIN        -1
371 392
 
372 393
 #endif
373 394
 
@@ -404,19 +425,21 @@
404 425
     #define Z_MAX_PIN       -1
405 426
     
406 427
     //extruder pins
407
-    #define E_STEP_PIN      4     //Edited @ EJE Electronics 20100715
408
-    #define E_DIR_PIN       2     //Edited @ EJE Electronics 20100715
409
-    #define E_ENABLE_PIN    3     //Added @ EJE Electronics 20100715
428
+    #define E0_STEP_PIN      4    //Edited @ EJE Electronics 20100715
429
+    #define E0_DIR_PIN       2    //Edited @ EJE Electronics 20100715
430
+    #define E0_ENABLE_PIN    3    //Added @ EJE Electronics 20100715
410 431
     #define TEMP_0_PIN      5     //changed @ rkoeppl 20110410
432
+    #define TEMP_1_PIN      -1    //changed @ rkoeppl 20110410
433
+    #define TEMP_2_PIN      -1    //changed @ rkoeppl 20110410
411 434
     #define HEATER_0_PIN    14    //changed @ rkoeppl 20110410
412
-    #define HEATER_1_PIN    -1    //changed @ rkoeppl 20110410
413
-    #define HEATER_2_PIN        -1
435
+    #define HEATER_1_PIN    -1
436
+    #define HEATER_2_PIN    -1
437
+    #define HEATER_BED_PIN  -1    //changed @ rkoeppl 20110410
438
+    #define TEMP_BED_PIN    -1    //changed @ rkoeppl 20110410
414 439
     
415 440
     #define SDPOWER          -1
416 441
     #define SDSS          17
417 442
     #define LED_PIN         -1    //changed @ rkoeppl 20110410
418
-    #define TEMP_1_PIN      -1    //changed @ rkoeppl 20110410
419
-    #define TEMP_2_PIN      -1
420 443
     #define FAN_PIN         -1    //changed @ rkoeppl 20110410
421 444
     #define PS_ON_PIN       -1    //changed @ rkoeppl 20110410
422 445
     //our pin for debugging.
@@ -459,8 +482,8 @@
459 482
 #define Z_MIN_PIN          20
460 483
 #define Z_MAX_PIN          -1
461 484
 
462
-#define E_STEP_PIN         1
463
-#define E_DIR_PIN          0
485
+#define E0_STEP_PIN         1
486
+#define E0_DIR_PIN          0
464 487
 
465 488
 #define LED_PIN            -1
466 489
 
@@ -470,31 +493,33 @@
470 493
 #define KILL_PIN           -1
471 494
 
472 495
 #define HEATER_0_PIN       13 // (extruder)
496
+#define HEATER_1_PIN       -1
497
+#define HEATER_2_PIN       -1
473 498
 
474 499
 #ifdef SANGUINOLOLU_V_1_2
475 500
 
476
-#define HEATER_1_PIN       12 // (bed)
501
+#define HEATER_BED_PIN     12 // (bed)
477 502
 #define X_ENABLE_PIN       14
478 503
 #define Y_ENABLE_PIN       14
479 504
 #define Z_ENABLE_PIN       26
480
-#define E_ENABLE_PIN       14
505
+#define E0_ENABLE_PIN       14
481 506
 
482 507
 #else
483 508
 
484
-#define HEATER_1_PIN       14  // (bed)
509
+#define HEATER_BED_PIN       14  // (bed)
485 510
 #define X_ENABLE_PIN       -1
486 511
 #define Y_ENABLE_PIN       -1
487 512
 #define Z_ENABLE_PIN       -1
488
-#define E_ENABLE_PIN       -1
513
+#define E0_ENABLE_PIN       -1
489 514
 
490 515
 #endif
491 516
 
492 517
 #define TEMP_0_PIN          7   // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! (pin 33 extruder)
493
-#define TEMP_1_PIN          6   // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! (pin 34 bed)
518
+#define TEMP_1_PIN         -1
494 519
 #define TEMP_2_PIN         -1
520
+#define TEMP_BED_PIN        6   // MUST USE ANALOG INPUT NUMBERING NOT DIGITAL OUTPUT NUMBERING!!!!!!!!! (pin 34 bed)
495 521
 #define SDPOWER            -1
496 522
 #define SDSS               31
497
-#define HEATER_2_PIN       -1
498 523
 
499 524
 #endif
500 525
 
@@ -529,8 +554,8 @@
529 554
 #define Z_MAX_PIN 32
530 555
 #define Z_ENABLE_PIN 35
531 556
 
532
-#define HEATER_1_PIN 4 
533
-#define TEMP_1_PIN 11  
557
+#define HEATER_BED_PIN 4 
558
+#define TEMP_BED_PIN 11  
534 559
 
535 560
 #define EXTRUDER_0_STEP_PIN 43 
536 561
 #define EXTRUDER_0_DIR_PIN 45
@@ -543,14 +568,14 @@
543 568
 #define EXTRUDER_1_ENABLE_PIN 51
544 569
 #define EXTRUDER_1_HEATER_PIN 3
545 570
 #define EXTRUDER_1_TEMPERATURE_PIN 10 
546
-#define HEATER_2_PIN 51
547
-#define TEMP_2_PIN 3
571
+#define HEATER_1_PIN 51
572
+#define TEMP_1_PIN 3
548 573
 
549 574
 
550 575
 
551
-#define E_STEP_PIN         EXTRUDER_0_STEP_PIN
552
-#define E_DIR_PIN          EXTRUDER_0_DIR_PIN
553
-#define E_ENABLE_PIN       EXTRUDER_0_ENABLE_PIN
576
+#define E0_STEP_PIN         EXTRUDER_0_STEP_PIN
577
+#define E0_DIR_PIN          EXTRUDER_0_DIR_PIN
578
+#define E0_ENABLE_PIN       EXTRUDER_0_ENABLE_PIN
554 579
 
555 580
 #define SDPOWER            -1
556 581
 #define SDSS               53
@@ -655,20 +680,22 @@
655 680
 #define Z_MIN_PIN          15 
656 681
 #define Z_MAX_PIN          -1    
657 682
 
658
-#define E_STEP_PIN          6  
659
-#define E_DIR_PIN           7 
660
-#define E_ENABLE_PIN       19 
683
+#define E0_STEP_PIN         6  
684
+#define E0_DIR_PIN          7 
685
+#define E0_ENABLE_PIN       19 
661 686
 
662 687
 
663 688
 
664 689
 #define HEATER_0_PIN       21  // Extruder
665
-#define HEATER_1_PIN       20  // Bed
690
+#define HEATER_1_PIN       -1
666 691
 #define HEATER_2_PIN       -1
692
+#define HEATER_BED_PIN     20  // Bed
667 693
 #define FAN_PIN            22  // Fan   
668 694
 
669 695
 #define TEMP_0_PIN          7  // Extruder
670
-#define TEMP_1_PIN          6  // Bed
696
+#define TEMP_1_PIN         -1
671 697
 #define TEMP_2_PIN         -1
698
+#define TEMP_BED_PIN        6  // Bed
672 699
 
673 700
 #define SDPOWER            -1
674 701
 #define SDSS                8
@@ -690,6 +717,22 @@
690 717
 #endif
691 718
 
692 719
 //List of pins which to ignore when asked to change by gcode, 0 and 1 are RX and TX, do not mess with those!
693
-#define SENSITIVE_PINS {0, 1, X_STEP_PIN, X_DIR_PIN, X_ENABLE_PIN, X_MIN_PIN, X_MAX_PIN, Y_STEP_PIN, Y_DIR_PIN, Y_ENABLE_PIN, Y_MIN_PIN, Y_MAX_PIN, Z_STEP_PIN, Z_DIR_PIN, Z_ENABLE_PIN, Z_MIN_PIN, Z_MAX_PIN, E_STEP_PIN, E_DIR_PIN, E_ENABLE_PIN, LED_PIN, PS_ON_PIN, HEATER_0_PIN, HEATER_1_PIN, HEATER_2_PIN, FAN_PIN, TEMP_0_PIN, TEMP_1_PIN, TEMP_2_PIN}
694
-
720
+#define _E0_PINS E0_STEP_PIN, E0_DIR_PIN, E0_ENABLE_PIN
721
+#if EXTRUDERS == 3
722
+  #define _E1_PINS E1_STEP_PIN, E1_DIR_PIN, E1_ENABLE_PIN
723
+  #define _E2_PINS E2_STEP_PIN, E2_DIR_PIN, E2_ENABLE_PIN
724
+#elif EXTRUDERS == 2
725
+  #define _E1_PINS E1_STEP_PIN, E1_DIR_PIN, E1_ENABLE_PIN
726
+  #define _E2_PINS -1
727
+#elif EXTRUDERS == 1
728
+  #define _E1_PINS -1 
729
+  #define _E2_PINS -1
730
+#else
731
+  #error Unsupported number of extruders
732
+#endif
733
+#define SENSITIVE_PINS {0, 1, X_STEP_PIN, X_DIR_PIN, X_ENABLE_PIN, X_MIN_PIN, X_MAX_PIN, Y_STEP_PIN, Y_DIR_PIN, Y_ENABLE_PIN, Y_MIN_PIN, Y_MAX_PIN, Z_STEP_PIN, Z_DIR_PIN, Z_ENABLE_PIN, Z_MIN_PIN, Z_MAX_PIN, LED_PIN, PS_ON_PIN, \
734
+                        HEATER_0_PIN, HEATER_1_PIN, HEATER_2_PIN, \
735
+                        HEATER_BED_PIN, FAN_PIN,                  \
736
+                        _E0_PINS, _E1_PINS, _E2_PINS,             \
737
+                        TEMP_0_PIN, TEMP_1_PIN, TEMP_2_PIN, TEMP_BED_PIN }
695 738
 #endif

+ 6
- 14
Marlin/planner.cpp View File

@@ -56,9 +56,9 @@
56 56
 //#include <math.h>       
57 57
 //#include <stdlib.h>
58 58
 
59
-#include "Marlin.h"
60 59
 #include "Configuration.h"
61 60
 #include "pins.h"
61
+#include "Marlin.h"
62 62
 #include "fastio.h"
63 63
 #include "planner.h"
64 64
 #include "stepper.h"
@@ -81,8 +81,6 @@ float max_z_jerk;
81 81
 float mintravelfeedrate;
82 82
 unsigned long axis_steps_per_sqr_second[NUM_AXIS];
83 83
 
84
-uint8_t active_extruder = 0;
85
-
86 84
 // The current position of the tool in absolute steps
87 85
 long position[4];   //rescaled from extern when axis_steps_per_unit are changed by gcode
88 86
 static float previous_speed[4]; // Speed of previous path line segment
@@ -95,7 +93,6 @@ static float previous_nominal_speed; // Nominal speed of previous path line segm
95 93
     bool autotemp_enabled=false;
96 94
 #endif
97 95
 
98
-    
99 96
 //===========================================================================
100 97
 //=================semi-private variables, used in inline  functions    =====
101 98
 //===========================================================================
@@ -437,7 +434,7 @@ void check_axes_activity() {
437 434
   if((DISABLE_X) && (x_active == 0)) disable_x();
438 435
   if((DISABLE_Y) && (y_active == 0)) disable_y();
439 436
   if((DISABLE_Z) && (z_active == 0)) disable_z();
440
-  if((DISABLE_E) && (e_active == 0)) disable_e();
437
+  if((DISABLE_E) && (e_active == 0)) { disable_e0();disable_e1();disable_e2(); }
441 438
 }
442 439
 
443 440
 
@@ -496,15 +493,10 @@ void plan_buffer_line(const float &x, const float &y, const float &z, const floa
496 493
   if(block->steps_x != 0) enable_x();
497 494
   if(block->steps_y != 0) enable_y();
498 495
   if(block->steps_z != 0) enable_z();
499
-  if(extruder == 0) {
500
-    if(block->steps_e != 0) enable_e();
501
-  }
502
-  #if (EXTRUDERS > 1)
503
-  if(extruder == 1) {
504
-    if(block->steps_e != 0) enable_e1();
505
-  }
506
-  #endif
507
-  
496
+
497
+  // Enable all
498
+  if(block->steps_e != 0) { enable_e0();enable_e1();enable_e2(); }
499
+
508 500
   float delta_mm[4];
509 501
   delta_mm[X_AXIS] = (target[X_AXIS]-position[X_AXIS])/axis_steps_per_unit[X_AXIS];
510 502
   delta_mm[Y_AXIS] = (target[Y_AXIS]-position[Y_AXIS])/axis_steps_per_unit[Y_AXIS];

+ 0
- 2
Marlin/planner.h View File

@@ -91,8 +91,6 @@ extern float max_z_jerk;
91 91
 extern float mintravelfeedrate;
92 92
 extern unsigned long axis_steps_per_sqr_second[NUM_AXIS];
93 93
 
94
-extern uint8_t active_extruder;
95
-
96 94
 #ifdef AUTOTEMP
97 95
     extern bool autotemp_enabled;
98 96
     extern float autotemp_max;

+ 41
- 20
Marlin/stepper.cpp View File

@@ -24,9 +24,9 @@
24 24
 
25 25
 #include "stepper.h"
26 26
 #include "Configuration.h"
27
+#include "pins.h"
27 28
 #include "Marlin.h"
28 29
 #include "planner.h"
29
-#include "pins.h"
30 30
 #include "fastio.h"
31 31
 #include "temperature.h"
32 32
 #include "ultralcd.h"
@@ -41,7 +41,6 @@
41 41
 block_t *current_block;  // A pointer to the block currently being traced
42 42
 
43 43
 
44
-
45 44
 //===========================================================================
46 45
 //=============================private variables ============================
47 46
 //===========================================================================
@@ -419,11 +418,11 @@ ISR(TIMER1_COMPA_vect)
419 418
 
420 419
     #ifndef ADVANCE
421 420
       if ((out_bits & (1<<E_AXIS)) != 0) {  // -direction
422
-        WRITE(E_DIR_PIN,INVERT_E_DIR);
421
+        NORM_E_DIR();
423 422
         count_direction[E_AXIS]=-1;
424 423
       }
425 424
       else { // +direction
426
-        WRITE(E_DIR_PIN,!INVERT_E_DIR);
425
+        REV_E_DIR();
427 426
         count_direction[E_AXIS]=-1;
428 427
       }
429 428
     #endif //!ADVANCE
@@ -473,9 +472,9 @@ ISR(TIMER1_COMPA_vect)
473 472
       #ifndef ADVANCE
474 473
         counter_e += current_block->steps_e;
475 474
         if (counter_e > 0) {
476
-          WRITE(E_STEP_PIN, HIGH);
475
+          WRITE_E_STEP(HIGH);
477 476
           counter_e -= current_block->step_event_count;
478
-          WRITE(E_STEP_PIN, LOW);
477
+          WRITE_E_STEP(LOW);
479 478
           count_position[E_AXIS]+=count_direction[E_AXIS];
480 479
         }
481 480
       #endif //!ADVANCE
@@ -559,18 +558,18 @@ ISR(TIMER1_COMPA_vect)
559 558
     OCR0A = old_OCR0A;
560 559
     // Set E direction (Depends on E direction + advance)
561 560
     for(unsigned char i=0; i<4;) {
562
-      WRITE(E_STEP_PIN, LOW);
561
+      WRITE_E_STEP(LOW);
563 562
       if (e_steps == 0) break;
564 563
       i++;
565 564
       if (e_steps < 0) {
566
-        WRITE(E_DIR_PIN,INVERT_E_DIR);    
565
+        WRITE_E_DIR(INVERT_E_DIR);    
567 566
         e_steps++;
568
-        WRITE(E_STEP_PIN, HIGH);
567
+        WRITE_E_STEP(HIGH);
569 568
       } 
570 569
       else if (e_steps > 0) {
571
-        WRITE(E_DIR_PIN,!INVERT_E_DIR);
570
+        WRITE_E_DIR(!INVERT_E_DIR);
572 571
         e_steps--;
573
-        WRITE(E_STEP_PIN, HIGH);
572
+        WRITE_E_STEP(HIGH);
574 573
       }
575 574
     }
576 575
   }
@@ -578,7 +577,7 @@ ISR(TIMER1_COMPA_vect)
578 577
 
579 578
 void st_init()
580 579
 {
581
-    //Initialize Dir Pins
580
+  //Initialize Dir Pins
582 581
   #if X_DIR_PIN > -1
583 582
     SET_OUTPUT(X_DIR_PIN);
584 583
   #endif
@@ -588,8 +587,14 @@ void st_init()
588 587
   #if Z_DIR_PIN > -1 
589 588
     SET_OUTPUT(Z_DIR_PIN);
590 589
   #endif
591
-  #if E_DIR_PIN > -1 
592
-    SET_OUTPUT(E_DIR_PIN);
590
+  #if E0_DIR_PIN > -1 
591
+    SET_OUTPUT(E0_DIR_PIN);
592
+  #endif
593
+  #if defined(E1_DIR_PIN) && (E1_DIR_PIN > -1)
594
+    SET_OUTPUT(E1_DIR_PIN);
595
+  #endif
596
+  #if defined(E2_DIR_PIN) && (E2_DIR_PIN > -1)
597
+    SET_OUTPUT(E2_DIR_PIN);
593 598
   #endif
594 599
 
595 600
   //Initialize Enable Pins - steppers default to disabled.
@@ -606,9 +611,17 @@ void st_init()
606 611
     SET_OUTPUT(Z_ENABLE_PIN);
607 612
     if(!Z_ENABLE_ON) WRITE(Z_ENABLE_PIN,HIGH);
608 613
   #endif
609
-  #if (E_ENABLE_PIN > -1)
610
-    SET_OUTPUT(E_ENABLE_PIN);
611
-    if(!E_ENABLE_ON) WRITE(E_ENABLE_PIN,HIGH);
614
+  #if (E0_ENABLE_PIN > -1)
615
+    SET_OUTPUT(E0_ENABLE_PIN);
616
+    if(!E_ENABLE_ON) WRITE(E0_ENABLE_PIN,HIGH);
617
+  #endif
618
+  #if defined(E1_ENABLE_PIN) && (E1_ENABLE_PIN > -1)
619
+    SET_OUTPUT(E1_ENABLE_PIN);
620
+    if(!E_ENABLE_ON) WRITE(E1_ENABLE_PIN,HIGH);
621
+  #endif
622
+  #if defined(E2_ENABLE_PIN) && (E2_ENABLE_PIN > -1)
623
+    SET_OUTPUT(E2_ENABLE_PIN);
624
+    if(!E_ENABLE_ON) WRITE(E2_ENABLE_PIN,HIGH);
612 625
   #endif
613 626
 
614 627
   //endstops and pullups
@@ -669,8 +682,14 @@ void st_init()
669 682
   #if (Z_STEP_PIN > -1) 
670 683
     SET_OUTPUT(Z_STEP_PIN);
671 684
   #endif  
672
-  #if (E_STEP_PIN > -1) 
673
-    SET_OUTPUT(E_STEP_PIN);
685
+  #if (E0_STEP_PIN > -1) 
686
+    SET_OUTPUT(E0_STEP_PIN);
687
+  #endif  
688
+  #if defined(E1_STEP_PIN) && (E1_STEP_PIN > -1) 
689
+    SET_OUTPUT(E1_STEP_PIN);
690
+  #endif  
691
+  #if defined(E2_STEP_PIN) && (E2_STEP_PIN > -1) 
692
+    SET_OUTPUT(E2_STEP_PIN);
674 693
   #endif  
675 694
 
676 695
   // waveform generation = 0100 = CTC
@@ -749,5 +768,7 @@ void finishAndDisableSteppers()
749 768
   disable_x(); 
750 769
   disable_y(); 
751 770
   disable_z(); 
752
-  disable_e(); 
771
+  disable_e0(); 
772
+  disable_e1(); 
773
+  disable_e2(); 
753 774
 }

+ 278
- 216
Marlin/temperature.cpp View File

@@ -41,17 +41,14 @@
41 41
 //===========================================================================
42 42
 //=============================public variables============================
43 43
 //===========================================================================
44
-int target_raw[3] = {0, 0, 0};
45
-int current_raw[3] = {0, 0, 0};
46
-int heatingtarget_raw[3]= {0, 0, 0};
47
-
44
+int target_raw[EXTRUDERS] = { 0 };
45
+int target_raw_bed = 0;
46
+int current_raw[EXTRUDERS] = { 0 };
47
+int current_raw_bed = 0;
48 48
 
49 49
 #ifdef PIDTEMP
50
-  
51
-  // probably used external
52
-  float HeaterPower;
53
-  float pid_setpoint = 0.0;
54
-
50
+  // used external
51
+  float pid_setpoint[EXTRUDERS] = { 0.0 };
55 52
   
56 53
   float Kp=DEFAULT_Kp;
57 54
   float Ki=DEFAULT_Ki;
@@ -72,42 +69,74 @@ static unsigned long  previous_millis_bed_heater;
72 69
 
73 70
 #ifdef PIDTEMP
74 71
   //static cannot be external:
75
-  static float temp_iState = 0;
76
-  static float temp_dState = 0;
77
-  static float pTerm;
78
-  static float iTerm;
79
-  static float dTerm;
72
+  static float temp_iState[EXTRUDERS] = { 0 };
73
+  static float temp_dState[EXTRUDERS] = { 0 };
74
+  static float pTerm[EXTRUDERS];
75
+  static float iTerm[EXTRUDERS];
76
+  static float dTerm[EXTRUDERS];
80 77
   //int output;
81
-  static float pid_error;
82
-  static float temp_iState_min;
83
-  static float temp_iState_max;
84
- // static float pid_input; 
85
- // static float pid_output;
86
-  static bool pid_reset;
87
- 
78
+  static float pid_error[EXTRUDERS];
79
+  static float temp_iState_min[EXTRUDERS];
80
+  static float temp_iState_max[EXTRUDERS];
81
+  // static float pid_input[EXTRUDERS];
82
+  // static float pid_output[EXTRUDERS];
83
+  static bool pid_reset[EXTRUDERS];
88 84
 #endif //PIDTEMP
89 85
   
90 86
 #ifdef WATCHPERIOD
91
-  static int watch_raw[3] = {-1000,-1000,-1000};
87
+  static int watch_raw[EXTRUDERS] = { -1000 }; // the first value used for all
92 88
   static unsigned long watchmillis = 0;
93 89
 #endif //WATCHPERIOD
94 90
 
95 91
 // Init min and max temp with extreme values to prevent false errors during startup
96
-  static int minttemp_0   = 0;
97
-  static int maxttemp_0   = 16383;
98
-  //static int minttemp_1   = 0;
99
-  //static int maxttemp_1   = 16383;
92
+  static int minttemp[EXTRUDERS] = { 0 };
93
+  static int maxttemp[EXTRUDERS] = { 16383 }; // the first value used for all
100 94
   static int bed_minttemp = 0;
101 95
   static int bed_maxttemp = 16383;
96
+  static int heater_pin_map[EXTRUDERS] = { HEATER_0_PIN
97
+#if EXTRUDERS > 1
98
+                                         , HEATER_1_PIN
99
+#endif
100
+#if EXTRUDERS > 2
101
+                                         , HEATER_2_PIN
102
+#endif
103
+#if EXTRUDERS > 3
104
+  #error Unsupported number of extruders
105
+#endif
106
+  };
107
+  static void *heater_ttbl_map[EXTRUDERS] = { (void *)heater_0_temptable
108
+#if EXTRUDERS > 1
109
+                                            , (void *)heater_1_temptable
110
+#endif
111
+#if EXTRUDERS > 2
112
+                                            , (void *)heater_2_temptable
113
+#endif
114
+#if EXTRUDERS > 3
115
+  #error Unsupported number of extruders
116
+#endif
117
+  };
118
+  static int heater_ttbllen_map[EXTRUDERS] = { heater_0_temptable_len
119
+#if EXTRUDERS > 1
120
+                                             , heater_1_temptable_len
121
+#endif
122
+#if EXTRUDERS > 2
123
+                                             , heater_2_temptable_len
124
+#endif
125
+#if EXTRUDERS > 3
126
+  #error Unsupported number of extruders
127
+#endif
128
+  };
102 129
 
103 130
 //===========================================================================
104
-//=============================functions         ============================
131
+//=============================   functions      ============================
105 132
 //===========================================================================
106 133
   
107 134
 void updatePID()
108 135
 {
109 136
 #ifdef PIDTEMP
110
-  temp_iState_max = PID_INTEGRAL_DRIVE_MAX / Ki;
137
+  for(int e = 0; e < EXTRUDERS; e++) { 
138
+     temp_iState_max[e] = PID_INTEGRAL_DRIVE_MAX / Ki;  
139
+  }
111 140
 #endif
112 141
 }
113 142
   
@@ -119,92 +148,85 @@ void manage_heater()
119 148
   
120 149
   float pid_input;
121 150
   float pid_output;
151
+
122 152
   if(temp_meas_ready != true)   //better readability
123 153
     return; 
124 154
 
125 155
   CRITICAL_SECTION_START;
126
-    temp_meas_ready = false;
156
+  temp_meas_ready = false;
127 157
   CRITICAL_SECTION_END;
128 158
 
159
+  for(int e = 0; e < EXTRUDERS; e++) 
160
+  {
161
+
129 162
   #ifdef PIDTEMP
130
-    pid_input = analog2temp(current_raw[TEMPSENSOR_HOTEND_0]);
163
+    pid_input = analog2temp(current_raw[e], e);
131 164
 
132 165
     #ifndef PID_OPENLOOP
133
-        pid_error = pid_setpoint - pid_input;
134
-        if(pid_error > 10){
166
+        pid_error[e] = pid_setpoint[e] - pid_input;
167
+        if(pid_error[e] > 10) {
135 168
           pid_output = PID_MAX;
136
-          pid_reset = true;
169
+          pid_reset[e] = true;
137 170
         }
138
-        else if(pid_error < -10) {
171
+        else if(pid_error[e] < -10) {
139 172
           pid_output = 0;
140
-          pid_reset = true;
173
+          pid_reset[e] = true;
141 174
         }
142 175
         else {
143
-          if(pid_reset == true) {
144
-            temp_iState = 0.0;
145
-            pid_reset = false;
176
+          if(pid_reset[e] == true) {
177
+            temp_iState[e] = 0.0;
178
+            pid_reset[e] = false;
146 179
           }
147
-          pTerm = Kp * pid_error;
148
-          temp_iState += pid_error;
149
-          temp_iState = constrain(temp_iState, temp_iState_min, temp_iState_max);
150
-          iTerm = Ki * temp_iState;
180
+          pTerm[e] = Kp * pid_error[e];
181
+          temp_iState[e] += pid_error[e];
182
+          temp_iState[e] = constrain(temp_iState[e], temp_iState_min[e], temp_iState_max[e]);
183
+          iTerm[e] = Ki * temp_iState[e];
151 184
           //K1 defined in Configuration.h in the PID settings
152 185
           #define K2 (1.0-K1)
153
-          dTerm = (Kd * (pid_input - temp_dState))*K2 + (K1 * dTerm);
154
-          temp_dState = pid_input;
155
-//          #ifdef PID_ADD_EXTRUSION_RATE
156
-//            pTerm+=Kc*current_block->speed_e; //additional heating if extrusion speed is high
157
-//          #endif
158
-          pid_output = constrain(pTerm + iTerm - dTerm, 0, PID_MAX);
159
-          
186
+          dTerm[e] = (Kd * (pid_input - temp_dState[e]))*K2 + (K1 * dTerm[e]);
187
+          temp_dState[e] = pid_input;
188
+          pid_output = constrain(pTerm[e] + iTerm[e] - dTerm[e], 0, PID_MAX);
160 189
         }
161 190
     #endif //PID_OPENLOOP
162 191
     #ifdef PID_DEBUG
163
-     //SERIAL_ECHOLN(" PIDDEBUG Input "<<pid_input<<" Output "<<pid_output" pTerm "<<pTerm<<" iTerm "<<iTerm<<" dTerm "<<dTerm);  
192
+    SERIAL_ECHOLN(" PIDDEBUG "<<e<<": Input "<<pid_input<<" Output "<<pid_output" pTerm "<<pTerm[e]<<" iTerm "<<iTerm[e]<<" dTerm "<<dTerm[e]);  
164 193
     #endif //PID_DEBUG
165
-    HeaterPower=pid_output;
166
-    // Check if temperature is within the correct range
167
-    if((current_raw[TEMPSENSOR_HOTEND_0] > minttemp_0) && (current_raw[TEMPSENSOR_HOTEND_0] < maxttemp_0)) {
168
-      analogWrite(HEATER_0_PIN, pid_output);
169
-    }
170
-    else {
171
-      analogWrite(HEATER_0_PIN, 0);
172
-    }
173
-  #endif //PIDTEMP
174
-
175
-  #ifndef PIDTEMP
176
-    // Check if temperature is within the correct range
177
-    if((current_raw[TEMPSENSOR_HOTEND_0] > minttemp_0) && (current_raw[TEMPSENSOR_HOTEND_0] < maxttemp_0)) {
178
-      if(current_raw[TEMPSENSOR_HOTEND_0] >= target_raw[TEMPSENSOR_HOTEND_0]) {
179
-        WRITE(HEATER_0_PIN,LOW);
180
-      }
181
-      else {
182
-        WRITE(HEATER_0_PIN,HIGH);
183
-      }
194
+  #else /* PID off */
195
+    pid_output = 0;
196
+    if(current_raw[e] < target_raw[e]) {
197
+      pid_output = PID_MAX;
184 198
     }
185
-    else {
186
-      WRITE(HEATER_0_PIN,LOW);
187
-    }    
188 199
   #endif
200
+
201
+  // Check if temperature is within the correct range
202
+  if((current_raw[e] > minttemp[e]) && (current_raw[e] < maxttemp[e])) 
203
+  {
204
+    analogWrite(heater_pin_map[e], pid_output);
205
+  }
206
+  else {
207
+    analogWrite(heater_pin_map[e], 0);
208
+  }
209
+
210
+  } // End extruder for loop
189 211
     
190 212
   if(millis() - previous_millis_bed_heater < BED_CHECK_INTERVAL)
191 213
     return;
192 214
   previous_millis_bed_heater = millis();
193 215
   
194
-  #if TEMP_1_PIN > -1
216
+  #if TEMP_BED_PIN > -1
195 217
     // Check if temperature is within the correct range
196
-    if((current_raw[TEMPSENSOR_BED] > bed_minttemp) && (current_raw[TEMPSENSOR_BED] < bed_maxttemp)) {
197
-      if(current_raw[TEMPSENSOR_BED] >= target_raw[TEMPSENSOR_BED])
218
+    if((current_raw_bed > bed_minttemp) && (current_raw_bed < bed_maxttemp)) {
219
+      if(current_raw_bed >= target_raw_bed)
198 220
       {
199
-        WRITE(HEATER_1_PIN,LOW);
221
+        WRITE(HEATER_BED_PIN,LOW);
200 222
       }
201 223
       else 
202 224
       {
203
-        WRITE(HEATER_1_PIN,HIGH);
225
+        WRITE(HEATER_BED_PIN,HIGH);
204 226
       }
205 227
     }
206 228
     else {
207
-      WRITE(HEATER_1_PIN,LOW);
229
+      WRITE(HEATER_BED_PIN,LOW);
208 230
     }  
209 231
   #endif
210 232
 }
@@ -214,30 +236,38 @@ void manage_heater()
214 236
 // For a thermistor, it uses the RepRap thermistor temp table.
215 237
 // This is needed because PID in hydra firmware hovers around a given analog value, not a temp value.
216 238
 // This function is derived from inversing the logic from a portion of getTemperature() in FiveD RepRap firmware.
217
-int temp2analog(int celsius) {
218
-  #ifdef HEATER_0_USES_THERMISTOR
239
+int temp2analog(int celsius, uint8_t e) {
240
+  if(e >= EXTRUDERS)
241
+  {
242
+      SERIAL_ERROR_START;
243
+      SERIAL_ERROR((int)e);
244
+      SERIAL_ERRORLNPGM(" - Invalid extruder number!");
245
+      kill();
246
+  }
247
+  if(heater_ttbl_map[e] != 0)
248
+  {
219 249
     int raw = 0;
220 250
     byte i;
251
+    short (*tt)[][2] = (short (*)[][2])(heater_ttbl_map[e]);
221 252
 
222
-    for (i=1; i<NUMTEMPS_HEATER_0; i++)
253
+    for (i=1; i<heater_ttbllen_map[e]; i++)
223 254
     {
224
-      if (PGM_RD_W(heater_0_temptable[i][1]) < celsius)
255
+      if (PGM_RD_W((*tt)[i][1]) < celsius)
225 256
       {
226
-        raw = PGM_RD_W(heater_0_temptable[i-1][0]) + 
227
-          (celsius - PGM_RD_W(heater_0_temptable[i-1][1])) * 
228
-          (PGM_RD_W(heater_0_temptable[i][0]) - PGM_RD_W(heater_0_temptable[i-1][0])) /
229
-          (PGM_RD_W(heater_0_temptable[i][1]) - PGM_RD_W(heater_0_temptable[i-1][1]));  
257
+        raw = PGM_RD_W((*tt)[i-1][0]) + 
258
+          (celsius - PGM_RD_W((*tt)[i-1][1])) * 
259
+          (PGM_RD_W((*tt)[i][0]) - PGM_RD_W((*tt)[i-1][0])) /
260
+          (PGM_RD_W((*tt)[i][1]) - PGM_RD_W((*tt)[i-1][1]));  
230 261
         break;
231 262
       }
232 263
     }
233 264
 
234 265
     // Overflow: Set to last value in the table
235
-    if (i == NUMTEMPS_HEATER_0) raw = PGM_RD_W(heater_0_temptable[i-1][0]);
266
+    if (i == heater_ttbllen_map[e]) raw = PGM_RD_W((*tt)[i-1][0]);
236 267
 
237 268
     return (1023 * OVERSAMPLENR) - raw;
238
-  #elif defined HEATER_0_USES_AD595
239
-    return celsius * (1024.0 / (5.0 * 100.0) ) * OVERSAMPLENR;
240
-  #endif
269
+  }
270
+  return celsius * (1024.0 / (5.0 * 100.0) ) * OVERSAMPLENR;
241 271
 }
242 272
 
243 273
 // Takes bed temperature value as input and returns corresponding raw value. 
@@ -245,12 +275,11 @@ int temp2analog(int celsius) {
245 275
 // This is needed because PID in hydra firmware hovers around a given analog value, not a temp value.
246 276
 // This function is derived from inversing the logic from a portion of getTemperature() in FiveD RepRap firmware.
247 277
 int temp2analogBed(int celsius) {
248
-  #ifdef BED_USES_THERMISTOR
249
-
278
+#ifdef BED_USES_THERMISTOR
250 279
     int raw = 0;
251 280
     byte i;
252 281
     
253
-    for (i=1; i<BNUMTEMPS; i++)
282
+    for (i=1; i<bedtemptable_len; i++)
254 283
     {
255 284
       if (PGM_RD_W(bedtemptable[i][1]) < celsius)
256 285
       {
@@ -264,45 +293,52 @@ int temp2analogBed(int celsius) {
264 293
     }
265 294
 
266 295
     // Overflow: Set to last value in the table
267
-    if (i == BNUMTEMPS) raw = PGM_RD_W(bedtemptable[i-1][0]);
296
+    if (i == bedtemptable_len) raw = PGM_RD_W(bedtemptable[i-1][0]);
268 297
 
269 298
     return (1023 * OVERSAMPLENR) - raw;
270
-  #elif defined BED_USES_AD595
299
+#elif defined BED_USES_AD595
271 300
     return lround(celsius * (1024.0 * OVERSAMPLENR/ (5.0 * 100.0) ) );
272
-  #else
301
+#else
273 302
     #warning No heater-type defined for the bed.
274
-  #endif
275
-  return 0;
303
+    return 0;
304
+#endif
276 305
 }
277 306
 
278 307
 // Derived from RepRap FiveD extruder::getTemperature()
279 308
 // For hot end temperature measurement.
280
-float analog2temp(int raw) {
281
-  #ifdef HEATER_0_USES_THERMISTOR
309
+float analog2temp(int raw, uint8_t e) {
310
+  if(e >= EXTRUDERS)
311
+  {
312
+      SERIAL_ERROR_START;
313
+      SERIAL_ERROR((int)e);
314
+      SERIAL_ERRORLNPGM(" - Invalid extruder number !");
315
+      kill();
316
+  }
317
+  if(heater_ttbl_map[e] != 0)
318
+  {
282 319
     float celsius = 0;
283 320
     byte i;  
321
+    short (*tt)[][2] = (short (*)[][2])(heater_ttbl_map[e]);
322
+
284 323
     raw = (1023 * OVERSAMPLENR) - raw;
285
-    for (i=1; i<NUMTEMPS_HEATER_0; i++)
324
+    for (i=1; i<heater_ttbllen_map[e]; i++)
286 325
     {
287
-      if (PGM_RD_W(heater_0_temptable[i][0]) > raw)
326
+      if (PGM_RD_W((*tt)[i][0]) > raw)
288 327
       {
289
-        celsius  = PGM_RD_W(heater_0_temptable[i-1][1]) + 
290
-          (raw - PGM_RD_W(heater_0_temptable[i-1][0])) * 
291
-          (float)(PGM_RD_W(heater_0_temptable[i][1]) - PGM_RD_W(heater_0_temptable[i-1][1])) /
292
-          (float)(PGM_RD_W(heater_0_temptable[i][0]) - PGM_RD_W(heater_0_temptable[i-1][0]));
328
+        celsius = PGM_RD_W((*tt)[i-1][1]) + 
329
+          (raw - PGM_RD_W((*tt)[i-1][0])) * 
330
+          (float)(PGM_RD_W((*tt)[i][1]) - PGM_RD_W((*tt)[i-1][1])) /
331
+          (float)(PGM_RD_W((*tt)[i][0]) - PGM_RD_W((*tt)[i-1][0]));
293 332
         break;
294 333
       }
295 334
     }
296 335
 
297 336
     // Overflow: Set to last value in the table
298
-    if (i == NUMTEMPS_HEATER_0) celsius = PGM_RD_W(heater_0_temptable[i-1][1]);
337
+    if (i == heater_ttbllen_map[e]) celsius = PGM_RD_W((*tt)[i-1][1]);
299 338
 
300 339
     return celsius;
301
-  #elif defined HEATER_0_USES_AD595
302
-    return raw * ((5.0 * 100.0) / 1024.0) / OVERSAMPLENR;
303
-  #else
304
-    #error PLEASE DEFINE HEATER TYPE 
305
-  #endif
340
+  }
341
+  return raw * ((5.0 * 100.0) / 1024.0) / OVERSAMPLENR;
306 342
 }
307 343
 
308 344
 // Derived from RepRap FiveD extruder::getTemperature()
@@ -314,7 +350,7 @@ float analog2tempBed(int raw) {
314 350
 
315 351
     raw = (1023 * OVERSAMPLENR) - raw;
316 352
 
317
-    for (i=1; i<BNUMTEMPS; i++)
353
+    for (i=1; i<bedtemptable_len; i++)
318 354
     {
319 355
       if (PGM_RD_W(bedtemptable[i][0]) > raw)
320 356
       {
@@ -328,7 +364,7 @@ float analog2tempBed(int raw) {
328 364
     }
329 365
 
330 366
     // Overflow: Set to last value in the table
331
-    if (i == BNUMTEMPS) celsius = PGM_RD_W(bedtemptable[i-1][1]);
367
+    if (i == bedtemptable_len) celsius = PGM_RD_W(bedtemptable[i-1][1]);
332 368
 
333 369
     return celsius;
334 370
     
@@ -342,6 +378,19 @@ float analog2tempBed(int raw) {
342 378
 
343 379
 void tp_init()
344 380
 {
381
+  // Finish init of mult extruder arrays 
382
+  for(int e = 0; e < EXTRUDERS; e++) {
383
+    // populate with the first value 
384
+#ifdef WATCHPERIOD
385
+    watch_raw[e] = watch_raw[0];
386
+#endif
387
+    maxttemp[e] = maxttemp[0];
388
+#ifdef PIDTEMP
389
+    temp_iState_min[e] = 0.0;
390
+    temp_iState_max[e] = PID_INTEGRAL_DRIVE_MAX / Ki;
391
+#endif //PIDTEMP
392
+  }
393
+
345 394
   #if (HEATER_0_PIN > -1) 
346 395
     SET_OUTPUT(HEATER_0_PIN);
347 396
   #endif  
@@ -351,11 +400,12 @@ void tp_init()
351 400
   #if (HEATER_2_PIN > -1) 
352 401
     SET_OUTPUT(HEATER_2_PIN);
353 402
   #endif  
354
-
355
-  #ifdef PIDTEMP
356
-    temp_iState_min = 0.0;
357
-    temp_iState_max = PID_INTEGRAL_DRIVE_MAX / Ki;
358
-  #endif //PIDTEMP
403
+  #if (HEATER_BED_PIN > -1) 
404
+    SET_OUTPUT(HEATER_BED_PIN);
405
+  #endif  
406
+  #if (FAN_PIN > -1) 
407
+    SET_OUTPUT(FAN_PIN);
408
+  #endif  
359 409
 
360 410
   // Set analog inputs
361 411
   ADCSRA = 1<<ADEN | 1<<ADSC | 1<<ADIF | 0x07;
@@ -387,6 +437,14 @@ void tp_init()
387 437
        ADCSRB = 1<<MUX5;
388 438
     #endif
389 439
   #endif
440
+  #if (TEMP_BED_PIN > -1)
441
+    #if TEMP_BED_PIN < 8
442
+       DIDR0 |= 1<<TEMP_BED_PIN; 
443
+    #else
444
+       DIDR2 |= 1<<(TEMP_BED_PIN - 8); 
445
+       ADCSRB = 1<<MUX5;
446
+    #endif
447
+  #endif
390 448
   
391 449
   // Use timer0 for temperature measurement
392 450
   // Interleave temperature interrupt with millies interrupt
@@ -394,27 +452,34 @@ void tp_init()
394 452
   TIMSK0 |= (1<<OCIE0B);  
395 453
   
396 454
   // Wait for temperature measurement to settle
397
-  delay(200);
455
+  delay(250);
398 456
 
399 457
 #ifdef HEATER_0_MINTEMP
400
-  minttemp_0 = temp2analog(HEATER_0_MINTEMP);
458
+  minttemp[0] = temp2analog(HEATER_0_MINTEMP, 0);
401 459
 #endif //MINTEMP
402 460
 #ifdef HEATER_0_MAXTEMP
403
-  maxttemp_0 = temp2analog(HEATER_0_MAXTEMP);
461
+  maxttemp[0] = temp2analog(HEATER_0_MAXTEMP, 0);
404 462
 #endif //MAXTEMP
405 463
 
406
-#ifdef HEATER_1_MINTEMP
407
-  minttemp_1 = temp2analog(HEATER_1_MINTEMP);
408
-#endif //MINTEMP
409
-#ifdef HEATER_1_MAXTEMP
410
-  maxttemp_1 = temp2analog(HEATER_1_MAXTEMP);
411
-#endif //MAXTEMP
464
+#if (EXTRUDERS > 1) && defined(HEATER_1_MINTEMP)
465
+  minttemp[1] = temp2analog(HEATER_1_MINTEMP, 1);
466
+#endif // MINTEMP 1
467
+#if (EXTRUDERS > 1) && defined(HEATER_1_MAXTEMP)
468
+  maxttemp[1] = temp2analog(HEATER_1_MAXTEMP, 1);
469
+#endif //MAXTEMP 1
470
+
471
+#if (EXTRUDERS > 2) && defined(HEATER_2_MINTEMP)
472
+  minttemp[2] = temp2analog(HEATER_2_MINTEMP, 2);
473
+#endif //MINTEMP 2
474
+#if (EXTRUDERS > 2) && defined(HEATER_2_MAXTEMP)
475
+  maxttemp[2] = temp2analog(HEATER_2_MAXTEMP, 2);
476
+#endif //MAXTEMP 2
412 477
 
413 478
 #ifdef BED_MINTEMP
414
-  bed_minttemp = temp2analog(BED_MINTEMP);
479
+  bed_minttemp = temp2analogBed(BED_MINTEMP);
415 480
 #endif //BED_MINTEMP
416 481
 #ifdef BED_MAXTEMP
417
-  bed_maxttemp = temp2analog(BED_MAXTEMP);
482
+  bed_maxttemp = temp2analogBed(BED_MAXTEMP);
418 483
 #endif //BED_MAXTEMP
419 484
 }
420 485
 
@@ -423,15 +488,16 @@ void tp_init()
423 488
 void setWatch() 
424 489
 {  
425 490
 #ifdef WATCHPERIOD
426
-  if(isHeatingHotend0())
491
+  int t = 0;
492
+  for (int e = 0; e < EXTRUDERS; e++)
427 493
   {
428
-    watchmillis = max(1,millis());
429
-    watch_raw[TEMPSENSOR_HOTEND_0] = current_raw[TEMPSENSOR_HOTEND_0];
494
+    if(isHeatingHotend(e))
495
+    {
496
+      t = max(t,millis());
497
+      watch_raw[e] = current_raw[e];
498
+    } 
430 499
   }
431
-  else
432
-  {
433
-    watchmillis = 0;
434
-  } 
500
+  watchmillis = t;
435 501
 #endif 
436 502
 }
437 503
 
@@ -458,6 +524,13 @@ void disable_heater()
458 524
       digitalWrite(HEATER_2_PIN,LOW);
459 525
     #endif
460 526
   #endif 
527
+
528
+  #if TEMP_BED_PIN > -1
529
+    target_raw_bed=0;
530
+    #if HEATER_BED_PIN > -1  
531
+      digitalWrite(HEATER_BED_PIN,LOW);
532
+    #endif
533
+  #endif 
461 534
 }
462 535
 
463 536
 // Timer 0 is shared with millies
@@ -468,6 +541,7 @@ ISR(TIMER0_COMPB_vect)
468 541
   static unsigned long raw_temp_0_value = 0;
469 542
   static unsigned long raw_temp_1_value = 0;
470 543
   static unsigned long raw_temp_2_value = 0;
544
+  static unsigned long raw_temp_bed_value = 0;
471 545
   static unsigned char temp_state = 0;
472 546
   
473 547
   switch(temp_state) {
@@ -492,7 +566,26 @@ ISR(TIMER0_COMPB_vect)
492 566
       #endif
493 567
       temp_state = 2;
494 568
       break;
495
-    case 2: // Prepare TEMP_1
569
+    case 2: // Prepare TEMP_BED
570
+      #if (TEMP_BED_PIN > -1)
571
+        #if TEMP_BED_PIN > 7
572
+          ADCSRB = 1<<MUX5;
573
+        #endif
574
+        ADMUX = ((1 << REFS0) | (TEMP_BED_PIN & 0x07));
575
+        ADCSRA |= 1<<ADSC; // Start conversion
576
+      #endif
577
+      #ifdef ULTIPANEL
578
+        buttons_check();
579
+      #endif
580
+      temp_state = 3;
581
+      break;
582
+    case 3: // Measure TEMP_BED
583
+      #if (TEMP_BED_PIN > -1)
584
+        raw_temp_bed_value += ADC;
585
+      #endif
586
+      temp_state = 4;
587
+      break;
588
+    case 4: // Prepare TEMP_1
496 589
       #if (TEMP_1_PIN > -1)
497 590
         #if TEMP_1_PIN > 7
498 591
           ADCSRB = 1<<MUX5;
@@ -505,15 +598,15 @@ ISR(TIMER0_COMPB_vect)
505 598
       #ifdef ULTIPANEL
506 599
         buttons_check();
507 600
       #endif
508
-      temp_state = 3;
601
+      temp_state = 5;
509 602
       break;
510
-    case 3: // Measure TEMP_1
603
+    case 5: // Measure TEMP_1
511 604
       #if (TEMP_1_PIN > -1)
512 605
         raw_temp_1_value += ADC;
513 606
       #endif
514
-      temp_state = 4;
607
+      temp_state = 6;
515 608
       break;
516
-    case 4: // Prepare TEMP_2
609
+    case 6: // Prepare TEMP_2
517 610
       #if (TEMP_2_PIN > -1)
518 611
         #if TEMP_2_PIN > 7
519 612
           ADCSRB = 1<<MUX5;
@@ -526,9 +619,9 @@ ISR(TIMER0_COMPB_vect)
526 619
       #ifdef ULTIPANEL
527 620
         buttons_check();
528 621
       #endif
529
-      temp_state = 5;
622
+      temp_state = 7;
530 623
       break;
531
-    case 5: // Measure TEMP_2
624
+    case 7: // Measure TEMP_2
532 625
       #if (TEMP_2_PIN > -1)
533 626
         raw_temp_2_value += ADC;
534 627
       #endif
@@ -541,24 +634,34 @@ ISR(TIMER0_COMPB_vect)
541 634
       break;
542 635
   }
543 636
     
544
-  if(temp_count >= 16) // 6 ms * 16 = 96ms.
637
+  if(temp_count >= 16) // 8 ms * 16 = 128ms.
545 638
   {
546 639
     #ifdef HEATER_0_USES_AD595
547 640
       current_raw[0] = raw_temp_0_value;
548 641
     #else
549 642
       current_raw[0] = 16383 - raw_temp_0_value;
550 643
     #endif
551
-    
644
+
645
+#if EXTRUDERS > 1    
552 646
     #ifdef HEATER_1_USES_AD595
647
+      current_raw[1] = raw_temp_1_value;
648
+    #else
649
+      current_raw[1] = 16383 - raw_temp_1_value;
650
+    #endif
651
+#endif
652
+    
653
+#if EXTRUDERS > 2
654
+    #ifdef HEATER_2_USES_AD595
553 655
       current_raw[2] = raw_temp_2_value;
554 656
     #else
555 657
       current_raw[2] = 16383 - raw_temp_2_value;
556 658
     #endif
659
+#endif
557 660
     
558 661
     #ifdef BED_USES_AD595
559
-      current_raw[1] = raw_temp_1_value;
662
+      current_raw_bed = raw_temp_bed_value;
560 663
     #else
561
-      current_raw[1] = 16383 - raw_temp_1_value;
664
+      current_raw_bed = 16383 - raw_temp_bed_value;
562 665
     #endif
563 666
     
564 667
     temp_meas_ready = true;
@@ -566,77 +669,36 @@ ISR(TIMER0_COMPB_vect)
566 669
     raw_temp_0_value = 0;
567 670
     raw_temp_1_value = 0;
568 671
     raw_temp_2_value = 0;
569
-    #ifdef HEATER_0_MAXTEMP
570
-      #if (HEATER_0_PIN > -1)
571
-        if(current_raw[TEMPSENSOR_HOTEND_0] >= maxttemp_0) {
572
-          target_raw[TEMPSENSOR_HOTEND_0] = 0;
573
-          digitalWrite(HEATER_0_PIN, 0);
672
+    raw_temp_bed_value = 0;
673
+
674
+    for(int e = 0; e < EXTRUDERS; e++) {
675
+       if(current_raw[e] >= maxttemp[e]) {
676
+          target_raw[e] = 0;
677
+          digitalWrite(heater_pin_map[e], 0);
574 678
           SERIAL_ERROR_START;
575
-          SERIAL_ERRORLNPGM("Temperature extruder 0 switched off. MAXTEMP triggered !!");
679
+          SERIAL_ERRORLN((int)e);
680
+          SERIAL_ERRORLNPGM(": Extruder switched off. MAXTEMP triggered !");
576 681
           kill();
577
-        }
578
-      #endif
579
-    #endif
580
-  #ifdef HEATER_1_MAXTEMP
581
-    #if (HEATER_1_PIN > -1)
582
-      if(current_raw[TEMPSENSOR_HOTEND_1] >= maxttemp_1) {
583
-        target_raw[TEMPSENSOR_HOTEND_1] = 0;
584
-        digitalWrite(HEATER_2_PIN, 0);
585
-        SERIAL_ERROR_START;
586
-        SERIAL_ERRORLNPGM("Temperature extruder 1 switched off. MAXTEMP triggered !!");
587
-        kill();
588
-      }
589
-    #endif
590
-  #endif //MAXTEMP
591
-  
592
-  #ifdef HEATER_0_MINTEMP
593
-    #if (HEATER_0_PIN > -1)
594
-      if(current_raw[TEMPSENSOR_HOTEND_0] <= minttemp_0) {
595
-        target_raw[TEMPSENSOR_HOTEND_0] = 0;
596
-        digitalWrite(HEATER_0_PIN, 0);
597
-        SERIAL_ERROR_START;
598
-        SERIAL_ERRORLNPGM("Temperature extruder 0 switched off. MINTEMP triggered !!");
599
-        kill();
600
-      }
601
-    #endif
602
-  #endif
603
-  
604
-  #ifdef HEATER_1_MINTEMP
605
-    #if (HEATER_2_PIN > -1)
606
-      if(current_raw[TEMPSENSOR_HOTEND_1] <= minttemp_1) {
607
-        target_raw[TEMPSENSOR_HOTEND_1] = 0;
608
-        digitalWrite(HEATER_2_PIN, 0);
609
-        SERIAL_ERROR_START;
610
-        SERIAL_ERRORLNPGM("Temperature extruder 1 switched off. MINTEMP triggered !!");
611
-        kill();
612
-      }
613
-    #endif
614
-  #endif //MAXTEMP
615
-  
616
-  #ifdef BED_MINTEMP
617
-    #if (HEATER_1_PIN > -1)
618
-      if(current_raw[1] <= bed_minttemp) {
619
-        target_raw[1] = 0;
620
-        digitalWrite(HEATER_1_PIN, 0);
621
-        SERIAL_ERROR_START;
622
-        SERIAL_ERRORLNPGM("Temperatur heated bed switched off. MINTEMP triggered !!");
623
-        kill();
624
-      }
625
-    #endif
626
-  #endif
682
+       }
683
+       if(current_raw[e] <= minttemp[e]) {
684
+          target_raw[e] = 0;
685
+          digitalWrite(heater_pin_map[e], 0);
686
+          SERIAL_ERROR_START;
687
+          SERIAL_ERRORLN(e);
688
+          SERIAL_ERRORLNPGM(": Extruder switched off. MINTEMP triggered !");
689
+          kill();
690
+       }
691
+    }
627 692
   
628
-  #ifdef BED_MAXTEMP
629
-    #if (HEATER_1_PIN > -1)
630
-      if(current_raw[1] >= bed_maxttemp) {
631
-        target_raw[1] = 0;
632
-        digitalWrite(HEATER_1_PIN, 0);
633
-        SERIAL_ERROR_START;
634
-        SERIAL_ERRORLNPGM("Temperature heated bed switched off. MAXTEMP triggered !!");
635
-        kill();
636
-      }
637
-    #endif
638
-  #endif
693
+#if defined(BED_MAXTEMP) && (HEATER_BED_PIN > -1)
694
+    if(current_raw_bed >= bed_maxttemp) {
695
+       target_raw_bed = 0;
696
+       digitalWrite(HEATER_BED_PIN, 0);
697
+       SERIAL_ERROR_START;
698
+       SERIAL_ERRORLNPGM("Temperature heated bed switched off. MAXTEMP triggered !!");
699
+       kill();
700
+    }
701
+#endif
639 702
   }
640 703
 }
641 704
 
642
-

+ 66
- 51
Marlin/temperature.h View File

@@ -31,95 +31,110 @@
31 31
 void tp_init();  //initialise the heating
32 32
 void manage_heater(); //it is critical that this is called periodically.
33 33
 
34
-
35
-enum TempSensor {TEMPSENSOR_HOTEND_0=0,TEMPSENSOR_BED=1, TEMPSENSOR_HOTEND_1=2};
36
-
37 34
 //low leven conversion routines
38 35
 // do not use this routines and variables outsie of temperature.cpp
39
-int temp2analog(int celsius);
36
+int temp2analog(int celsius, uint8_t e);
40 37
 int temp2analogBed(int celsius);
41
-float analog2temp(int raw);
38
+float analog2temp(int raw, uint8_t e);
42 39
 float analog2tempBed(int raw);
43
-extern int target_raw[3];  
44
-extern int heatingtarget_raw[3];
45
-extern int current_raw[3];
40
+extern int target_raw[EXTRUDERS];  
41
+extern int heatingtarget_raw[EXTRUDERS];  
42
+extern int current_raw[EXTRUDERS];
43
+extern int target_raw_bed;
44
+extern int current_raw_bed;
46 45
 extern float Kp,Ki,Kd,Kc;
47 46
 
48 47
 #ifdef PIDTEMP
49
-  extern float pid_setpoint ;
48
+  extern float pid_setpoint[EXTRUDERS];
50 49
 #endif
51 50
   
52 51
 #ifdef WATCHPERIOD
53
-  extern int watch_raw[3] ;
52
+  extern int watch_raw[EXTRUDERS] ;
54 53
   extern unsigned long watchmillis;
55 54
 #endif
56 55
 
57 56
 
58
-
59 57
 //high level conversion routines, for use outside of temperature.cpp
60 58
 //inline so that there is no performance decrease.
61 59
 //deg=degreeCelsius
62 60
 
63
-FORCE_INLINE float degHotend0(){  return analog2temp(current_raw[TEMPSENSOR_HOTEND_0]);};
64
-FORCE_INLINE float degHotend1(){  return analog2temp(current_raw[TEMPSENSOR_HOTEND_1]);};
65
-FORCE_INLINE float degBed() {  return analog2tempBed(current_raw[TEMPSENSOR_BED]);};
66
-FORCE_INLINE float degHotend(uint8_t extruder){  
67
-  if(extruder == 0) return analog2temp(current_raw[TEMPSENSOR_HOTEND_0]);
68
-  if(extruder == 1) return analog2temp(current_raw[TEMPSENSOR_HOTEND_1]);
61
+FORCE_INLINE float degHotend(uint8_t extruder) {  
62
+  return analog2temp(current_raw[extruder], extruder);
69 63
 };
70 64
 
71
-FORCE_INLINE float degTargetHotend0() {  return analog2temp(target_raw[TEMPSENSOR_HOTEND_0]);};
72
-FORCE_INLINE float degTargetHotend1() {  return analog2temp(target_raw[TEMPSENSOR_HOTEND_1]);};
73
-FORCE_INLINE float degTargetHotend(uint8_t extruder){  
74
-  if(extruder == 0) return analog2temp(target_raw[TEMPSENSOR_HOTEND_0]);
75
-  if(extruder == 1) return analog2temp(target_raw[TEMPSENSOR_HOTEND_1]);
65
+FORCE_INLINE float degBed() {
66
+  return analog2tempBed(current_raw_bed);
76 67
 };
77 68
 
78
-FORCE_INLINE float degTargetBed() {   return analog2tempBed(target_raw[TEMPSENSOR_BED]);};
69
+FORCE_INLINE float degTargetHotend(uint8_t extruder) {  
70
+  return analog2temp(target_raw[extruder], extruder);
71
+};
79 72
 
80
-FORCE_INLINE void setTargetHotend0(const float &celsius) 
81
-{  
82
-  target_raw[TEMPSENSOR_HOTEND_0]=temp2analog(celsius);
83
-  heatingtarget_raw[TEMPSENSOR_HOTEND_0]=temp2analog(celsius-HEATING_EARLY_FINISH_DEG_OFFSET);
84
-  #ifdef PIDTEMP
85
-    pid_setpoint = celsius;
86
-  #endif //PIDTEMP
73
+FORCE_INLINE float degTargetBed() {   
74
+  return analog2tempBed(target_raw_bed);
87 75
 };
88
-FORCE_INLINE void setTargetHotend1(const float &celsius) {  target_raw[TEMPSENSOR_HOTEND_1]=temp2analog(celsius);};
89
-FORCE_INLINE void setTargetHotend(const float &celcius, uint8_t extruder){  
90
-  if(extruder == 0) setTargetHotend0(celcius);
91
-  if(extruder == 1) setTargetHotend1(celcius);
76
+
77
+FORCE_INLINE void setTargetHotend(const float &celsius, uint8_t extruder) {  
78
+  target_raw[extruder] = temp2analog(celsius, extruder);
79
+#ifdef PIDTEMP
80
+  pid_setpoint[extruder] = celsius;
81
+#endif //PIDTEMP
82
+};
83
+
84
+FORCE_INLINE void setTargetBed(const float &celsius) {  
85
+  target_raw_bed = temp2analogBed(celsius);
92 86
 };
93
-FORCE_INLINE void setTargetBed(const float &celsius)     {  target_raw[TEMPSENSOR_BED     ]=temp2analogBed(celsius);};
94 87
 
95
-FORCE_INLINE bool isHeatingHotend0() {return heatingtarget_raw[TEMPSENSOR_HOTEND_0] > current_raw[TEMPSENSOR_HOTEND_0];};
96
-FORCE_INLINE bool isHeatingHotend1() {return target_raw[TEMPSENSOR_HOTEND_1] > current_raw[TEMPSENSOR_HOTEND_1];};
97 88
 FORCE_INLINE bool isHeatingHotend(uint8_t extruder){  
98
-  if(extruder == 0) return heatingtarget_raw[TEMPSENSOR_HOTEND_0] > current_raw[TEMPSENSOR_HOTEND_0];
99
-  if(extruder == 1) return target_raw[TEMPSENSOR_HOTEND_1] > current_raw[TEMPSENSOR_HOTEND_1];
100
-  return false; 
89
+  return target_raw[extruder] > current_raw[extruder];
90
+};
91
+
92
+FORCE_INLINE bool isHeatingBed() {
93
+  return target_raw_bed > current_raw_bed;
101 94
 };
102
-FORCE_INLINE bool isHeatingBed() {return target_raw[TEMPSENSOR_BED] > current_raw[TEMPSENSOR_BED];};
103
-
104
-FORCE_INLINE bool isCoolingHotend0() {return target_raw[TEMPSENSOR_HOTEND_0] < current_raw[TEMPSENSOR_HOTEND_0];};
105
-FORCE_INLINE bool isCoolingHotend1() {return target_raw[TEMPSENSOR_HOTEND_1] < current_raw[TEMPSENSOR_HOTEND_1];};
106
-FORCE_INLINE bool isCoolingHotend(uint8_t extruder){  
107
-  if(extruder == 0) return target_raw[TEMPSENSOR_HOTEND_0] < current_raw[TEMPSENSOR_HOTEND_0];
108
-  if(extruder == 1) return target_raw[TEMPSENSOR_HOTEND_1] < current_raw[TEMPSENSOR_HOTEND_1];
109
-  return false; 
95
+
96
+FORCE_INLINE bool isCoolingHotend(uint8_t extruder) {  
97
+  return target_raw[extruder] < current_raw[extruder];
110 98
 };
111
-FORCE_INLINE bool isCoolingBed() {return target_raw[TEMPSENSOR_BED] < current_raw[TEMPSENSOR_BED];};
99
+
100
+FORCE_INLINE bool isCoolingBed() {
101
+  return target_raw_bed < current_raw_bed;
102
+};
103
+
104
+#define degHotend0() degHotend(0)
105
+#define degTargetHotend0() degTargetHotend(0)
106
+#define setTargetHotend0(_celsius) setTargetHotend((_celsius), 0)
107
+#define isHeatingHotend0() isHeatingHotend(0)
108
+#define isCoolingHotend0() isCoolingHotend(0)
109
+#if EXTRUDERS > 1
110
+#define degHotend1() degHotend(1)
111
+#define degTargetHotend1() degTargetHotend(1)
112
+#define setTargetHotend1(_celsius) setTargetHotend((_celsius), 1)
113
+#define isHeatingHotend1() isHeatingHotend(1)
114
+#define isCoolingHotend1() isCoolingHotend(1)
115
+#endif
116
+#if EXTRUDERS > 2
117
+#define degHotend2() degHotend(2)
118
+#define degTargetHotend2() degTargetHotend(2)
119
+#define setTargetHotend2(_celsius) setTargetHotend((_celsius), 2)
120
+#define isHeatingHotend2() isHeatingHotend(2)
121
+#define isCoolingHotend2() isCoolingHotend(2)
122
+#endif
123
+#if EXTRUDERS > 3
124
+#error Invalid number of extruders
125
+#endif
112 126
 
113 127
 FORCE_INLINE void autotempShutdown(){
114 128
  #ifdef AUTOTEMP
115 129
  if(autotemp_enabled)
116 130
  {
117 131
   autotemp_enabled=false;
118
-  if(degTargetHotend0()>autotemp_min)
119
-    setTargetHotend0(0);
132
+  if(degTargetHotend(ACTIVE_EXTRUDER)>autotemp_min)
133
+    setTargetHotend(0,ACTIVE_EXTRUDER);
120 134
  }
121 135
  #endif
122 136
 }
137
+
123 138
 void disable_heater();
124 139
 void setWatch();
125 140
 void updatePID();

+ 54
- 93
Marlin/thermistortables.h View File

@@ -5,10 +5,9 @@
5 5
 
6 6
 #define OVERSAMPLENR 16
7 7
 
8
-#if (THERMISTORHEATER_0 == 1) || (THERMISTORHEATER_1 == 1) || (THERMISTORBED == 1) //100k bed thermistor
8
+#if (THERMISTORHEATER_0 == 1) || (THERMISTORHEATER_1 == 1)  || (THERMISTORHEATER_2 == 1) || (THERMISTORBED == 1) //100k bed thermistor
9 9
 
10
-#define NUMTEMPS_1 61
11
-const short temptable_1[NUMTEMPS_1][2] PROGMEM = {
10
+const short temptable_1[][2] PROGMEM = {
12 11
 {       23*OVERSAMPLENR ,       300     },
13 12
 {       25*OVERSAMPLENR ,       295     },
14 13
 {       27*OVERSAMPLENR ,       290     },
@@ -72,9 +71,8 @@ const short temptable_1[NUMTEMPS_1][2] PROGMEM = {
72 71
 {       1008*OVERSAMPLENR       ,       0       } //safety
73 72
 };
74 73
 #endif
75
-#if (THERMISTORHEATER_0 == 2) || (THERMISTORHEATER_1 == 2) || (THERMISTORBED == 2) //200k bed thermistor
76
-#define NUMTEMPS_2 21
77
-const short temptable_2[NUMTEMPS_2][2] PROGMEM = {
74
+#if (THERMISTORHEATER_0 == 2) || (THERMISTORHEATER_1 == 2) || (THERMISTORHEATER_2 == 2) || (THERMISTORBED == 2) //200k bed thermistor
75
+const short temptable_2[][2] PROGMEM = {
78 76
    {1*OVERSAMPLENR, 848},
79 77
    {54*OVERSAMPLENR, 275},
80 78
    {107*OVERSAMPLENR, 228},
@@ -99,9 +97,8 @@ const short temptable_2[NUMTEMPS_2][2] PROGMEM = {
99 97
 };
100 98
 
101 99
 #endif
102
-#if (THERMISTORHEATER_0 == 3) || (THERMISTORHEATER_1 == 3) || (THERMISTORBED == 3) //mendel-parts
103
-#define NUMTEMPS_3 28
104
-const short temptable_3[NUMTEMPS_3][2] PROGMEM = {
100
+#if (THERMISTORHEATER_0 == 3) || (THERMISTORHEATER_1 == 3) || (THERMISTORHEATER_2 == 3) || (THERMISTORBED == 3) //mendel-parts
101
+const short temptable_3[][2] PROGMEM = {
105 102
                 {1*OVERSAMPLENR,864},
106 103
                 {21*OVERSAMPLENR,300},
107 104
                 {25*OVERSAMPLENR,290},
@@ -133,10 +130,8 @@ const short temptable_3[NUMTEMPS_3][2] PROGMEM = {
133 130
         };
134 131
 
135 132
 #endif
136
-#if (THERMISTORHEATER_0 == 4) || (THERMISTORHEATER_1 == 4) || (THERMISTORBED == 4) //10k thermistor
137
-
138
-#define NUMTEMPS_4 20
139
-const short temptable_4[NUMTEMPS_4][2] PROGMEM = {
133
+#if (THERMISTORHEATER_0 == 4) || (THERMISTORHEATER_1 == 4) || (THERMISTORHEATER_2 == 4) || (THERMISTORBED == 4) //10k thermistor
134
+const short temptable_4[][2] PROGMEM = {
140 135
    {1*OVERSAMPLENR, 430},
141 136
    {54*OVERSAMPLENR, 137},
142 137
    {107*OVERSAMPLENR, 107},
@@ -160,10 +155,8 @@ const short temptable_4[NUMTEMPS_4][2] PROGMEM = {
160 155
 };
161 156
 #endif
162 157
 
163
-#if (THERMISTORHEATER_0 == 5) || (THERMISTORHEATER_1 == 5) || (THERMISTORBED == 5) //100k ParCan thermistor (104GT-2)
164
-
165
-#define NUMTEMPS_5 61
166
-const short temptable_5[NUMTEMPS_5][2] PROGMEM = {
158
+#if (THERMISTORHEATER_0 == 5) || (THERMISTORHEATER_1 == 5) || (THERMISTORHEATER_2 == 5) || (THERMISTORBED == 5) //100k ParCan thermistor (104GT-2)
159
+const short temptable_5[][2] PROGMEM = {
167 160
 {1*OVERSAMPLENR, 713},
168 161
 {18*OVERSAMPLENR, 316},
169 162
 {35*OVERSAMPLENR, 266},
@@ -228,9 +221,8 @@ const short temptable_5[NUMTEMPS_5][2] PROGMEM = {
228 221
 };
229 222
 #endif
230 223
 
231
-#if (THERMISTORHEATER_0 == 6) || (THERMISTORHEATER_1 == 6) || (THERMISTORBED == 6) // 100k Epcos thermistor
232
-#define NUMTEMPS_6 36
233
-const short temptable_6[NUMTEMPS_6][2] PROGMEM = {
224
+#if (THERMISTORHEATER_0 == 6) || (THERMISTORHEATER_1 == 6) || (THERMISTORHEATER_2 == 6) || (THERMISTORBED == 6) // 100k Epcos thermistor
225
+const short temptable_6[][2] PROGMEM = {
234 226
    {28*OVERSAMPLENR, 250},
235 227
    {31*OVERSAMPLENR, 245},
236 228
    {35*OVERSAMPLENR, 240},
@@ -270,9 +262,8 @@ const short temptable_6[NUMTEMPS_6][2] PROGMEM = {
270 262
 };
271 263
 #endif
272 264
 
273
-#if (THERMISTORHEATER_0 == 7) || (THERMISTORHEATER_1 == 7) || (THERMISTORBED == 7) // 100k Honeywell 135-104LAG-J01
274
-#define NUMTEMPS_7 54
275
-const short temptable_7[NUMTEMPS_7][2] PROGMEM = {
265
+#if (THERMISTORHEATER_0 == 7) || (THERMISTORHEATER_1 == 7) || (THERMISTORHEATER_2 == 7) || (THERMISTORBED == 7) // 100k Honeywell 135-104LAG-J01
266
+const short temptable_7[][2] PROGMEM = {
276 267
    {46*OVERSAMPLENR, 270},
277 268
    {50*OVERSAMPLENR, 265},
278 269
    {54*OVERSAMPLENR, 260},
@@ -330,82 +321,52 @@ const short temptable_7[NUMTEMPS_7][2] PROGMEM = {
330 321
 };
331 322
 #endif
332 323
 
324
+#define _TT_NAME(_N) temptable_ ## _N
325
+#define TT_NAME(_N) _TT_NAME(_N)
333 326
 
334
-
335
-#if THERMISTORHEATER_0 == 1
336
-#define NUMTEMPS_HEATER_0 NUMTEMPS_1
337
-#define heater_0_temptable temptable_1
338
-#elif THERMISTORHEATER_0 == 2
339
-#define NUMTEMPS_HEATER_0 NUMTEMPS_2
340
-#define heater_0_temptable temptable_2
341
-#elif THERMISTORHEATER_0 == 3
342
-#define NUMTEMPS_HEATER_0 NUMTEMPS_3
343
-#define heater_0_temptable temptable_3
344
-#elif THERMISTORHEATER_0 == 4
345
-#define NUMTEMPS_HEATER_0 NUMTEMPS_4
346
-#define heater_0_temptable temptable_4
347
-#elif THERMISTORHEATER_0 == 5
348
-#define NUMTEMPS_HEATER_0 NUMTEMPS_5
349
-#define heater_0_temptable temptable_5
350
-#elif THERMISTORHEATER_0 == 6
351
-#define NUMTEMPS_HEATER_0 NUMTEMPS_6
352
-#define heater_0_temptable temptable_6
353
-#elif THERMISTORHEATER_0 == 7
354
-#define NUMTEMPS_HEATER_0 NUMTEMPS_7
355
-#define heater_0_temptable temptable_7
356
-#elif defined HEATER_0_USES_THERMISTOR
357
-#error No heater 0 thermistor table specified
327
+#ifdef THERMISTORHEATER_0
328
+  #define heater_0_temptable TT_NAME(THERMISTORHEATER_0)
329
+  #define heater_0_temptable_len (sizeof(heater_0_temptable)/sizeof(*heater_0_temptable))
330
+#else
331
+#ifdef HEATER_0_USES_THERMISTOR
332
+  #error No heater 0 thermistor table specified
333
+#else  // HEATER_0_USES_THERMISTOR
334
+  #define heater_0_temptable 0
335
+  #define heater_0_temptable_len 0
336
+#endif // HEATER_0_USES_THERMISTOR
358 337
 #endif
359 338
 
360
-#if THERMISTORHEATER_1 == 1
361
-#define NUMTEMPS_HEATER_1 NUMTEMPS_1
362
-#define heater_1_temptable temptable_1
363
-#elif THERMISTORHEATER_1 == 2
364
-#define NUMTEMPS_HEATER_1 NUMTEMPS_2
365
-#define heater_1_temptable temptable_2
366
-#elif THERMISTORHEATER_1 == 3
367
-#define NUMTEMPS_HEATER_1 NUMTEMPS_3
368
-#define heater_1_temptable temptable_3
369
-#elif THERMISTORHEATER_1 == 4
370
-#define NUMTEMPS_HEATER_1 NUMTEMPS_4
371
-#define heater_1_temptable temptable_4
372
-#elif THERMISTORHEATER_1 == 5
373
-#define NUMTEMPS_HEATER_1 NUMTEMPS_5
374
-#define heater_1_temptable temptable_5
375
-#elif THERMISTORHEATER_1 == 6
376
-#define NUMTEMPS_HEATER_1 NUMTEMPS_6
377
-#define heater_1_temptable temptable_6
378
-#elif THERMISTORHEATER_1 == 7
379
-#define NUMTEMPS_HEATER_1 NUMTEMPS_7
380
-#define heater_1_temptable temptable_7
381
-#elif defined HEATER_1_USES_THERMISTOR
382
-#error No heater 1 thermistor table specified
339
+#ifdef THERMISTORHEATER_1
340
+  #define heater_1_temptable TT_NAME(THERMISTORHEATER_1)
341
+  #define heater_1_temptable_len (sizeof(heater_1_temptable)/sizeof(*heater_1_temptable))
342
+#else
343
+#ifdef HEATER_1_USES_THERMISTOR
344
+  #error No heater 1 thermistor table specified
345
+#else  // HEATER_1_USES_THERMISTOR
346
+  #define heater_1_temptable 0
347
+  #define heater_1_temptable_len 0
348
+#endif // HEATER_1_USES_THERMISTOR
383 349
 #endif
384 350
 
351
+#ifdef THERMISTORHEATER_2
352
+  #define heater_2_temptable TT_NAME(THERMISTORHEATER_2)
353
+  #define heater_2_temptable_len (sizeof(heater_2_temptable)/sizeof(*heater_2_temptable))
354
+#else
355
+#ifdef HEATER_2_USES_THERMISTOR
356
+  #error No heater 2 thermistor table specified
357
+#else  // HEATER_2_USES_THERMISTOR
358
+  #define heater_2_temptable 0
359
+  #define heater_2_temptable_len 0
360
+#endif // HEATER_2_USES_THERMISTOR
361
+#endif
385 362
 
386
-#if THERMISTORBED == 1
387
-#define BNUMTEMPS NUMTEMPS_1
388
-#define bedtemptable temptable_1
389
-#elif THERMISTORBED == 2
390
-#define BNUMTEMPS NUMTEMPS_2
391
-#define bedtemptable temptable_2
392
-#elif THERMISTORBED == 3
393
-#define BNUMTEMPS NUMTEMPS_3
394
-#define bedtemptable temptable_3
395
-#elif THERMISTORBED == 4
396
-#define BNUMTEMPS NUMTEMPS_4
397
-#define bedtemptable temptable_4
398
-#elif THERMISTORBED == 5
399
-#define BNUMTEMPS NUMTEMPS_5
400
-#define bedtemptable temptable_5
401
-#elif THERMISTORBED == 6
402
-#define BNUMTEMPS NUMTEMPS_6
403
-#define bedtemptable temptable_6
404
-#elif THERMISTORBED == 7
405
-#define BNUMTEMPS NUMTEMPS_7
406
-#define bedtemptable temptable_7
407
-#elif defined BED_USES_THERMISTOR
408
-#error No bed thermistor table specified
363
+#ifdef THERMISTORBED
364
+  #define bedtemptable TT_NAME(THERMISTORBED)
365
+  #define bedtemptable_len (sizeof(bedtemptable)/sizeof(*bedtemptable))
366
+#else
367
+#ifdef BED_USES_THERMISTOR
368
+  #error No bed thermistor table specified
369
+#endif // BED_USES_THERMISTOR
409 370
 #endif
410 371
 
411 372
 #endif //THERMISTORTABLES_H_

Loading…
Cancel
Save