Browse Source

Revert and extend previous change pin check change

Reviert previous change of #if BLAH_PIN > 0 to #if defined(BLAH_PIN) &&
BLAH_PIN > -1. Unfortunately some times pin 0 is used. For my sins I've
gone through and replaced all unsafe checks of #if BLAH_PIN > -1 with
the safe version.
Robert F-C 11 years ago
parent
commit
40eb07bad4
7 changed files with 135 additions and 133 deletions
  1. 3
    3
      Marlin/Marlin.h
  2. 1
    1
      Marlin/Marlin.pde
  3. 52
    56
      Marlin/Marlin_main.cpp
  4. 1
    1
      Marlin/dogm_lcd_implementation.h
  5. 3
    3
      Marlin/planner.cpp
  6. 32
    32
      Marlin/stepper.cpp
  7. 43
    37
      Marlin/temperature.cpp

+ 3
- 3
Marlin/Marlin.h View File

96
 
96
 
97
 void manage_inactivity();
97
 void manage_inactivity();
98
 
98
 
99
-#if X_ENABLE_PIN > -1
99
+#if defined(X_ENABLE_PIN) && X_ENABLE_PIN > -1
100
   #define  enable_x() WRITE(X_ENABLE_PIN, X_ENABLE_ON)
100
   #define  enable_x() WRITE(X_ENABLE_PIN, X_ENABLE_ON)
101
   #define disable_x() WRITE(X_ENABLE_PIN,!X_ENABLE_ON)
101
   #define disable_x() WRITE(X_ENABLE_PIN,!X_ENABLE_ON)
102
 #else
102
 #else
104
   #define disable_x() ;
104
   #define disable_x() ;
105
 #endif
105
 #endif
106
 
106
 
107
-#if Y_ENABLE_PIN > -1
107
+#if defined(Y_ENABLE_PIN) && Y_ENABLE_PIN > -1
108
   #define  enable_y() WRITE(Y_ENABLE_PIN, Y_ENABLE_ON)
108
   #define  enable_y() WRITE(Y_ENABLE_PIN, Y_ENABLE_ON)
109
   #define disable_y() WRITE(Y_ENABLE_PIN,!Y_ENABLE_ON)
109
   #define disable_y() WRITE(Y_ENABLE_PIN,!Y_ENABLE_ON)
110
 #else
110
 #else
112
   #define disable_y() ;
112
   #define disable_y() ;
113
 #endif
113
 #endif
114
 
114
 
115
-#if Z_ENABLE_PIN > -1
115
+#if defined(Z_ENABLE_PIN) && Z_ENABLE_PIN > -1
116
   #ifdef Z_DUAL_STEPPER_DRIVERS
116
   #ifdef Z_DUAL_STEPPER_DRIVERS
117
     #define  enable_z() { WRITE(Z_ENABLE_PIN, Z_ENABLE_ON); WRITE(Z2_ENABLE_PIN, Z_ENABLE_ON); }
117
     #define  enable_z() { WRITE(Z_ENABLE_PIN, Z_ENABLE_ON); WRITE(Z2_ENABLE_PIN, Z_ENABLE_ON); }
118
     #define disable_z() { WRITE(Z_ENABLE_PIN,!Z_ENABLE_ON); WRITE(Z2_ENABLE_PIN,!Z_ENABLE_ON); }
118
     #define disable_z() { WRITE(Z_ENABLE_PIN,!Z_ENABLE_ON); WRITE(Z2_ENABLE_PIN,!Z_ENABLE_ON); }

+ 1
- 1
Marlin/Marlin.pde View File

47
   #endif
47
   #endif
48
 #endif
48
 #endif
49
 
49
 
50
-#if DIGIPOTSS_PIN > -1
50
+#if defined(DIGIPOTSS_PIN) && DIGIPOTSS_PIN > -1
51
 #include <SPI.h>
51
 #include <SPI.h>
52
 #endif
52
 #endif

+ 52
- 56
Marlin/Marlin_main.cpp View File

44
 #include "Servo.h"
44
 #include "Servo.h"
45
 #endif
45
 #endif
46
 
46
 
47
-#if DIGIPOTSS_PIN > 0
47
+#if defined(DIGIPOTSS_PIN) && DIGIPOTSS_PIN > -1
48
 #include <SPI.h>
48
 #include <SPI.h>
49
 #endif
49
 #endif
50
 
50
 
300
 
300
 
301
 void setup_killpin()
301
 void setup_killpin()
302
 {
302
 {
303
-  #if( KILL_PIN>-1 )
303
+  #if defined(KILL_PIN) && KILL_PIN > -1
304
     pinMode(KILL_PIN,INPUT);
304
     pinMode(KILL_PIN,INPUT);
305
     WRITE(KILL_PIN,HIGH);
305
     WRITE(KILL_PIN,HIGH);
306
   #endif
306
   #endif
308
 
308
 
309
 void setup_photpin()
309
 void setup_photpin()
310
 {
310
 {
311
-  #ifdef PHOTOGRAPH_PIN
312
-    #if (PHOTOGRAPH_PIN > 0)
311
+  #if defined(PHOTOGRAPH_PIN) && PHOTOGRAPH_PIN > -1
313
     SET_OUTPUT(PHOTOGRAPH_PIN);
312
     SET_OUTPUT(PHOTOGRAPH_PIN);
314
     WRITE(PHOTOGRAPH_PIN, LOW);
313
     WRITE(PHOTOGRAPH_PIN, LOW);
315
-    #endif
316
   #endif
314
   #endif
317
 }
315
 }
318
 
316
 
319
 void setup_powerhold()
317
 void setup_powerhold()
320
 {
318
 {
321
- #ifdef SUICIDE_PIN
322
-   #if (SUICIDE_PIN> 0)
323
-      SET_OUTPUT(SUICIDE_PIN);
324
-      WRITE(SUICIDE_PIN, HIGH);
325
-   #endif
326
- #endif
327
- #if (PS_ON_PIN > 0)
328
-   SET_OUTPUT(PS_ON_PIN);
329
-   WRITE(PS_ON_PIN, PS_ON_AWAKE);
330
- #endif
319
+  #if defined(SUICIDE_PIN) && SUICIDE_PIN > -1
320
+    SET_OUTPUT(SUICIDE_PIN);
321
+    WRITE(SUICIDE_PIN, HIGH);
322
+  #endif
323
+  #if defined(PS_ON_PIN) && PS_ON_PIN > -1
324
+    SET_OUTPUT(PS_ON_PIN);
325
+    WRITE(PS_ON_PIN, PS_ON_AWAKE);
326
+  #endif
331
 }
327
 }
332
 
328
 
333
 void suicide()
329
 void suicide()
334
 {
330
 {
335
- #ifdef SUICIDE_PIN
336
-    #if (SUICIDE_PIN > 0)
337
-      SET_OUTPUT(SUICIDE_PIN);
338
-      WRITE(SUICIDE_PIN, LOW);
339
-    #endif
331
+  #if defined(SUICIDE_PIN) && SUICIDE_PIN > -1
332
+    SET_OUTPUT(SUICIDE_PIN);
333
+    WRITE(SUICIDE_PIN, LOW);
340
   #endif
334
   #endif
341
 }
335
 }
342
 
336
 
343
 void servo_init()
337
 void servo_init()
344
 {
338
 {
345
-  #if (NUM_SERVOS >= 1) && (SERVO0_PIN > 0)
339
+  #if (NUM_SERVOS >= 1) && defined(SERVO0_PIN) && (SERVO0_PIN > -1)
346
     servos[0].attach(SERVO0_PIN);
340
     servos[0].attach(SERVO0_PIN);
347
   #endif
341
   #endif
348
-  #if (NUM_SERVOS >= 2) && (SERVO1_PIN > 0)
342
+  #if (NUM_SERVOS >= 2) && defined(SERVO1_PIN) && (SERVO1_PIN > -1)
349
     servos[1].attach(SERVO1_PIN);
343
     servos[1].attach(SERVO1_PIN);
350
   #endif
344
   #endif
351
-  #if (NUM_SERVOS >= 3) && (SERVO2_PIN > 0)
345
+  #if (NUM_SERVOS >= 3) && defined(SERVO2_PIN) && (SERVO2_PIN > -1)
352
     servos[2].attach(SERVO2_PIN);
346
     servos[2].attach(SERVO2_PIN);
353
   #endif
347
   #endif
354
-  #if (NUM_SERVOS >= 4) && (SERVO3_PIN > 0)
348
+  #if (NUM_SERVOS >= 4) && defined(SERVO3_PIN) && (SERVO3_PIN > -1)
355
     servos[3].attach(SERVO3_PIN);
349
     servos[3].attach(SERVO3_PIN);
356
   #endif
350
   #endif
357
   #if (NUM_SERVOS >= 5)
351
   #if (NUM_SERVOS >= 5)
411
 
405
 
412
   lcd_init();
406
   lcd_init();
413
   
407
   
414
-  #if CONTROLLERFAN_PIN > 0
408
+  #if defined(CONTROLLERFAN_PIN) && CONTROLLERFAN_PIN > -1
415
     SET_OUTPUT(CONTROLLERFAN_PIN); //Set pin used for driver cooling fan
409
     SET_OUTPUT(CONTROLLERFAN_PIN); //Set pin used for driver cooling fan
416
   #endif 
410
   #endif 
417
 }
411
 }
669
 
663
 
670
 static void homeaxis(int axis) {
664
 static void homeaxis(int axis) {
671
 #define HOMEAXIS_DO(LETTER) \
665
 #define HOMEAXIS_DO(LETTER) \
672
-  ((LETTER##_MIN_PIN > 0 && LETTER##_HOME_DIR==-1) || (LETTER##_MAX_PIN > 0 && LETTER##_HOME_DIR==1))
666
+  ((LETTER##_MIN_PIN > -1 && LETTER##_HOME_DIR==-1) || (LETTER##_MAX_PIN > -1 && LETTER##_HOME_DIR==1))
673
 
667
 
674
   if (axis==X_AXIS ? HOMEAXIS_DO(X) :
668
   if (axis==X_AXIS ? HOMEAXIS_DO(X) :
675
       axis==Y_AXIS ? HOMEAXIS_DO(Y) :
669
       axis==Y_AXIS ? HOMEAXIS_DO(Y) :
1036
             break;
1030
             break;
1037
           }
1031
           }
1038
         }
1032
         }
1039
-      #if FAN_PIN > 0
1033
+      #if defined(FAN_PIN) && FAN_PIN > -1
1040
         if (pin_number == FAN_PIN)
1034
         if (pin_number == FAN_PIN)
1041
           fanSpeed = pin_status;
1035
           fanSpeed = pin_status;
1042
       #endif
1036
       #endif
1062
       if(setTargetedHotend(105)){
1056
       if(setTargetedHotend(105)){
1063
         break;
1057
         break;
1064
       }
1058
       }
1065
-      #if (TEMP_0_PIN > 0)
1059
+      #if defined(TEMP_0_PIN) && TEMP_0_PIN > -1
1066
         SERIAL_PROTOCOLPGM("ok T:");
1060
         SERIAL_PROTOCOLPGM("ok T:");
1067
         SERIAL_PROTOCOL_F(degHotend(tmp_extruder),1);
1061
         SERIAL_PROTOCOL_F(degHotend(tmp_extruder),1);
1068
         SERIAL_PROTOCOLPGM(" /");
1062
         SERIAL_PROTOCOLPGM(" /");
1069
         SERIAL_PROTOCOL_F(degTargetHotend(tmp_extruder),1);
1063
         SERIAL_PROTOCOL_F(degTargetHotend(tmp_extruder),1);
1070
-        #if TEMP_BED_PIN > 0
1064
+        #if defined(TEMP_BED_PIN) && TEMP_BED_PIN > -1
1071
           SERIAL_PROTOCOLPGM(" B:");
1065
           SERIAL_PROTOCOLPGM(" B:");
1072
           SERIAL_PROTOCOL_F(degBed(),1);
1066
           SERIAL_PROTOCOL_F(degBed(),1);
1073
           SERIAL_PROTOCOLPGM(" /");
1067
           SERIAL_PROTOCOLPGM(" /");
1165
       }
1159
       }
1166
       break;
1160
       break;
1167
     case 190: // M190 - Wait for bed heater to reach target.
1161
     case 190: // M190 - Wait for bed heater to reach target.
1168
-    #if TEMP_BED_PIN > 0
1162
+    #if defined(TEMP_BED_PIN) && TEMP_BED_PIN > -1
1169
         LCD_MESSAGEPGM(MSG_BED_HEATING);
1163
         LCD_MESSAGEPGM(MSG_BED_HEATING);
1170
         if (code_seen('S')) setTargetBed(code_value());
1164
         if (code_seen('S')) setTargetBed(code_value());
1171
         codenum = millis();
1165
         codenum = millis();
1192
     #endif
1186
     #endif
1193
         break;
1187
         break;
1194
 
1188
 
1195
-    #if FAN_PIN > 0
1189
+    #if defined(FAN_PIN) && FAN_PIN > -1
1196
       case 106: //M106 Fan On
1190
       case 106: //M106 Fan On
1197
         if (code_seen('S')){
1191
         if (code_seen('S')){
1198
            fanSpeed=constrain(code_value(),0,255);
1192
            fanSpeed=constrain(code_value(),0,255);
1207
     #endif //FAN_PIN
1201
     #endif //FAN_PIN
1208
     #ifdef BARICUDA
1202
     #ifdef BARICUDA
1209
       // PWM for HEATER_1_PIN
1203
       // PWM for HEATER_1_PIN
1210
-      #if HEATER_1_PIN > 0
1204
+      #if defined(HEATER_1_PIN) && HEATER_1_PIN > -1
1211
         case 126: //M126 valve open
1205
         case 126: //M126 valve open
1212
           if (code_seen('S')){
1206
           if (code_seen('S')){
1213
              ValvePressure=constrain(code_value(),0,255);
1207
              ValvePressure=constrain(code_value(),0,255);
1222
       #endif //HEATER_1_PIN
1216
       #endif //HEATER_1_PIN
1223
 
1217
 
1224
       // PWM for HEATER_2_PIN
1218
       // PWM for HEATER_2_PIN
1225
-      #if HEATER_2_PIN > 0
1219
+      #if defined(HEATER_2_PIN) && HEATER_2_PIN > -1
1226
         case 128: //M128 valve open
1220
         case 128: //M128 valve open
1227
           if (code_seen('S')){
1221
           if (code_seen('S')){
1228
              EtoPPressure=constrain(code_value(),0,255);
1222
              EtoPPressure=constrain(code_value(),0,255);
1237
       #endif //HEATER_2_PIN
1231
       #endif //HEATER_2_PIN
1238
     #endif
1232
     #endif
1239
 
1233
 
1240
-    #if (PS_ON_PIN > 0)
1234
+    #if defined(PS_ON_PIN) && PS_ON_PIN > -1
1241
       case 80: // M80 - ATX Power On
1235
       case 80: // M80 - ATX Power On
1242
         SET_OUTPUT(PS_ON_PIN); //GND
1236
         SET_OUTPUT(PS_ON_PIN); //GND
1243
         WRITE(PS_ON_PIN, PS_ON_AWAKE);
1237
         WRITE(PS_ON_PIN, PS_ON_AWAKE);
1246
 
1240
 
1247
       case 81: // M81 - ATX Power Off
1241
       case 81: // M81 - ATX Power Off
1248
 
1242
 
1249
-      #if defined SUICIDE_PIN && SUICIDE_PIN > 0
1243
+      #if defined(SUICIDE_PIN) && SUICIDE_PIN > -1
1250
         st_synchronize();
1244
         st_synchronize();
1251
         suicide();
1245
         suicide();
1252
-      #elif (PS_ON_PIN > 0)
1246
+      #elif defined(PS_ON_PIN) && PS_ON_PIN > -1
1253
         SET_OUTPUT(PS_ON_PIN);
1247
         SET_OUTPUT(PS_ON_PIN);
1254
         WRITE(PS_ON_PIN, PS_ON_ASLEEP);
1248
         WRITE(PS_ON_PIN, PS_ON_ASLEEP);
1255
       #endif
1249
       #endif
1354
       break;
1348
       break;
1355
     case 119: // M119
1349
     case 119: // M119
1356
     SERIAL_PROTOCOLLN(MSG_M119_REPORT);
1350
     SERIAL_PROTOCOLLN(MSG_M119_REPORT);
1357
-      #if (X_MIN_PIN > 0)
1351
+      #if defined(X_MIN_PIN) && X_MIN_PIN > -1
1358
         SERIAL_PROTOCOLPGM(MSG_X_MIN);
1352
         SERIAL_PROTOCOLPGM(MSG_X_MIN);
1359
         SERIAL_PROTOCOLLN(((READ(X_MIN_PIN)^X_ENDSTOPS_INVERTING)?MSG_ENDSTOP_HIT:MSG_ENDSTOP_OPEN));
1353
         SERIAL_PROTOCOLLN(((READ(X_MIN_PIN)^X_ENDSTOPS_INVERTING)?MSG_ENDSTOP_HIT:MSG_ENDSTOP_OPEN));
1360
       #endif
1354
       #endif
1361
-      #if (X_MAX_PIN > 0)
1355
+      #if defined(X_MAX_PIN) && X_MAX_PIN > -1
1362
         SERIAL_PROTOCOLPGM(MSG_X_MAX);
1356
         SERIAL_PROTOCOLPGM(MSG_X_MAX);
1363
         SERIAL_PROTOCOLLN(((READ(X_MAX_PIN)^X_ENDSTOPS_INVERTING)?MSG_ENDSTOP_HIT:MSG_ENDSTOP_OPEN));
1357
         SERIAL_PROTOCOLLN(((READ(X_MAX_PIN)^X_ENDSTOPS_INVERTING)?MSG_ENDSTOP_HIT:MSG_ENDSTOP_OPEN));
1364
       #endif
1358
       #endif
1365
-      #if (Y_MIN_PIN > 0)
1359
+      #if defined(Y_MIN_PIN) && Y_MIN_PIN > -1
1366
         SERIAL_PROTOCOLPGM(MSG_Y_MIN);
1360
         SERIAL_PROTOCOLPGM(MSG_Y_MIN);
1367
         SERIAL_PROTOCOLLN(((READ(Y_MIN_PIN)^Y_ENDSTOPS_INVERTING)?MSG_ENDSTOP_HIT:MSG_ENDSTOP_OPEN));
1361
         SERIAL_PROTOCOLLN(((READ(Y_MIN_PIN)^Y_ENDSTOPS_INVERTING)?MSG_ENDSTOP_HIT:MSG_ENDSTOP_OPEN));
1368
       #endif
1362
       #endif
1369
-      #if (Y_MAX_PIN > 0)
1363
+      #if defined(Y_MAX_PIN) && Y_MAX_PIN > -1
1370
         SERIAL_PROTOCOLPGM(MSG_Y_MAX);
1364
         SERIAL_PROTOCOLPGM(MSG_Y_MAX);
1371
         SERIAL_PROTOCOLLN(((READ(Y_MAX_PIN)^Y_ENDSTOPS_INVERTING)?MSG_ENDSTOP_HIT:MSG_ENDSTOP_OPEN));
1365
         SERIAL_PROTOCOLLN(((READ(Y_MAX_PIN)^Y_ENDSTOPS_INVERTING)?MSG_ENDSTOP_HIT:MSG_ENDSTOP_OPEN));
1372
       #endif
1366
       #endif
1373
-      #if (Z_MIN_PIN > 0)
1367
+      #if defined(Z_MIN_PIN) && Z_MIN_PIN > -1
1374
         SERIAL_PROTOCOLPGM(MSG_Z_MIN);
1368
         SERIAL_PROTOCOLPGM(MSG_Z_MIN);
1375
         SERIAL_PROTOCOLLN(((READ(Z_MIN_PIN)^Z_ENDSTOPS_INVERTING)?MSG_ENDSTOP_HIT:MSG_ENDSTOP_OPEN));
1369
         SERIAL_PROTOCOLLN(((READ(Z_MIN_PIN)^Z_ENDSTOPS_INVERTING)?MSG_ENDSTOP_HIT:MSG_ENDSTOP_OPEN));
1376
       #endif
1370
       #endif
1377
-      #if (Z_MAX_PIN > 0)
1371
+      #if defined(Z_MAX_PIN) && Z_MAX_PIN > -1
1378
         SERIAL_PROTOCOLPGM(MSG_Z_MAX);
1372
         SERIAL_PROTOCOLPGM(MSG_Z_MAX);
1379
         SERIAL_PROTOCOLLN(((READ(Z_MAX_PIN)^Z_ENDSTOPS_INVERTING)?MSG_ENDSTOP_HIT:MSG_ENDSTOP_OPEN));
1373
         SERIAL_PROTOCOLLN(((READ(Z_MAX_PIN)^Z_ENDSTOPS_INVERTING)?MSG_ENDSTOP_HIT:MSG_ENDSTOP_OPEN));
1380
       #endif
1374
       #endif
1612
     #endif //PIDTEMP
1606
     #endif //PIDTEMP
1613
     case 240: // M240  Triggers a camera by emulating a Canon RC-1 : http://www.doc-diy.net/photo/rc-1_hacked/
1607
     case 240: // M240  Triggers a camera by emulating a Canon RC-1 : http://www.doc-diy.net/photo/rc-1_hacked/
1614
      {
1608
      {
1615
-      #ifdef PHOTOGRAPH_PIN
1616
-        #if (PHOTOGRAPH_PIN > 0)
1609
+      #if defined(PHOTOGRAPH_PIN) && PHOTOGRAPH_PIN > -1
1617
         const uint8_t NUM_PULSES=16;
1610
         const uint8_t NUM_PULSES=16;
1618
         const float PULSE_LENGTH=0.01524;
1611
         const float PULSE_LENGTH=0.01524;
1619
         for(int i=0; i < NUM_PULSES; i++) {
1612
         for(int i=0; i < NUM_PULSES; i++) {
1629
           WRITE(PHOTOGRAPH_PIN, LOW);
1622
           WRITE(PHOTOGRAPH_PIN, LOW);
1630
           _delay_ms(PULSE_LENGTH);
1623
           _delay_ms(PULSE_LENGTH);
1631
         }
1624
         }
1632
-        #endif
1633
       #endif
1625
       #endif
1634
      }
1626
      }
1635
     break;
1627
     break;
1811
     #endif //FILAMENTCHANGEENABLE
1803
     #endif //FILAMENTCHANGEENABLE
1812
     case 907: // M907 Set digital trimpot motor current using axis codes.
1804
     case 907: // M907 Set digital trimpot motor current using axis codes.
1813
     {
1805
     {
1814
-      #if DIGIPOTSS_PIN > 0
1806
+      #if defined(DIGIPOTSS_PIN) && DIGIPOTSS_PIN > -1
1815
         for(int i=0;i<NUM_AXIS;i++) if(code_seen(axis_codes[i])) digipot_current(i,code_value());
1807
         for(int i=0;i<NUM_AXIS;i++) if(code_seen(axis_codes[i])) digipot_current(i,code_value());
1816
         if(code_seen('B')) digipot_current(4,code_value());
1808
         if(code_seen('B')) digipot_current(4,code_value());
1817
         if(code_seen('S')) for(int i=0;i<=4;i++) digipot_current(i,code_value());
1809
         if(code_seen('S')) for(int i=0;i<=4;i++) digipot_current(i,code_value());
1820
     break;
1812
     break;
1821
     case 908: // M908 Control digital trimpot directly.
1813
     case 908: // M908 Control digital trimpot directly.
1822
     {
1814
     {
1823
-      #if DIGIPOTSS_PIN > 0
1815
+      #if defined(DIGIPOTSS_PIN) && DIGIPOTSS_PIN > -1
1824
         uint8_t channel,current;
1816
         uint8_t channel,current;
1825
         if(code_seen('P')) channel=code_value();
1817
         if(code_seen('P')) channel=code_value();
1826
         if(code_seen('S')) current=code_value();
1818
         if(code_seen('S')) current=code_value();
1830
     break;
1822
     break;
1831
     case 350: // M350 Set microstepping mode. Warning: Steps per unit remains unchanged. S code sets stepping mode for all drivers.
1823
     case 350: // M350 Set microstepping mode. Warning: Steps per unit remains unchanged. S code sets stepping mode for all drivers.
1832
     {
1824
     {
1833
-      #if X_MS1_PIN > 0
1825
+      #if defined(X_MS1_PIN) && X_MS1_PIN > -1
1834
         if(code_seen('S')) for(int i=0;i<=4;i++) microstep_mode(i,code_value());
1826
         if(code_seen('S')) for(int i=0;i<=4;i++) microstep_mode(i,code_value());
1835
         for(int i=0;i<NUM_AXIS;i++) if(code_seen(axis_codes[i])) microstep_mode(i,(uint8_t)code_value());
1827
         for(int i=0;i<NUM_AXIS;i++) if(code_seen(axis_codes[i])) microstep_mode(i,(uint8_t)code_value());
1836
         if(code_seen('B')) microstep_mode(4,code_value());
1828
         if(code_seen('B')) microstep_mode(4,code_value());
1840
     break;
1832
     break;
1841
     case 351: // M351 Toggle MS1 MS2 pins directly, S# determines MS1 or MS2, X# sets the pin high/low.
1833
     case 351: // M351 Toggle MS1 MS2 pins directly, S# determines MS1 or MS2, X# sets the pin high/low.
1842
     {
1834
     {
1843
-      #if X_MS1_PIN > 0
1835
+      #if defined(X_MS1_PIN) && X_MS1_PIN > -1
1844
       if(code_seen('S')) switch((int)code_value())
1836
       if(code_seen('S')) switch((int)code_value())
1845
       {
1837
       {
1846
         case 1:
1838
         case 1:
2064
   previous_millis_cmd = millis();
2056
   previous_millis_cmd = millis();
2065
 }
2057
 }
2066
 
2058
 
2067
-#if CONTROLLERFAN_PIN > 0
2059
+#if defined(CONTROLLERFAN_PIN) && CONTROLLERFAN_PIN > -1
2068
 
2060
 
2069
-#if CONTROLLERFAN_PIN == FAN_PIN 
2070
-   #error "You cannot set CONTROLLERFAN_PIN equal to FAN_PIN"
2071
-#endif
2061
+#if defined(FAN_PIN)
2062
+  #if CONTROLLERFAN_PIN == FAN_PIN 
2063
+    #error "You cannot set CONTROLLERFAN_PIN equal to FAN_PIN"
2064
+  #endif
2065
+#endif  
2072
 
2066
 
2073
 unsigned long lastMotor = 0; //Save the time for when a motor was turned on last
2067
 unsigned long lastMotor = 0; //Save the time for when a motor was turned on last
2074
 unsigned long lastMotorCheck = 0;
2068
 unsigned long lastMotorCheck = 0;
2124
       }
2118
       }
2125
     }
2119
     }
2126
   }
2120
   }
2127
-  #if KILL_PIN > 0
2121
+  #if defined(KILL_PIN) && KILL_PIN > -1
2128
     if( 0 == READ(KILL_PIN) )
2122
     if( 0 == READ(KILL_PIN) )
2129
       kill();
2123
       kill();
2130
   #endif
2124
   #endif
2131
-  #if CONTROLLERFAN_PIN > 0
2125
+  #if defined(CONTROLLERFAN_PIN) && CONTROLLERFAN_PIN > -1
2132
     controllerFan(); //Check if fan should be turned on to cool stepper drivers down
2126
     controllerFan(); //Check if fan should be turned on to cool stepper drivers down
2133
   #endif
2127
   #endif
2134
   #ifdef EXTRUDER_RUNOUT_PREVENT
2128
   #ifdef EXTRUDER_RUNOUT_PREVENT
2165
   disable_e1();
2159
   disable_e1();
2166
   disable_e2();
2160
   disable_e2();
2167
 
2161
 
2168
-  if(PS_ON_PIN > 0) pinMode(PS_ON_PIN,INPUT);
2162
+#if defined(PS_ON_PIN) && PS_ON_PIN > -1
2163
+  pinMode(PS_ON_PIN,INPUT);
2164
+#endif  
2169
   SERIAL_ERROR_START;
2165
   SERIAL_ERROR_START;
2170
   SERIAL_ERRORLNPGM(MSG_ERR_KILLED);
2166
   SERIAL_ERRORLNPGM(MSG_ERR_KILLED);
2171
   LCD_ALERTMESSAGEPGM(MSG_KILLED);
2167
   LCD_ALERTMESSAGEPGM(MSG_KILLED);

+ 1
- 1
Marlin/dogm_lcd_implementation.h View File

279
  // Fan
279
  // Fan
280
  u8g.setFont(FONT_STATUSMENU);
280
  u8g.setFont(FONT_STATUSMENU);
281
  u8g.setPrintPos(104,27);
281
  u8g.setPrintPos(104,27);
282
- #if FAN_PIN > 0
282
+ #if defined(FAN_PIN) && FAN_PIN > -1
283
  u8g.print(itostr3(int((fanSpeed*100)/256 + 1)));
283
  u8g.print(itostr3(int((fanSpeed*100)/256 + 1)));
284
  u8g.print("%");
284
  u8g.print("%");
285
  #else
285
  #else

+ 3
- 3
Marlin/planner.cpp View File

472
     disable_e1();
472
     disable_e1();
473
     disable_e2(); 
473
     disable_e2(); 
474
   }
474
   }
475
-#if FAN_PIN > -1
475
+#if defined(FAN_PIN) && FAN_PIN > -1
476
   #ifndef FAN_SOFT_PWM
476
   #ifndef FAN_SOFT_PWM
477
     #ifdef FAN_KICKSTART_TIME
477
     #ifdef FAN_KICKSTART_TIME
478
       static unsigned long fan_kick_end;
478
       static unsigned long fan_kick_end;
496
 #endif
496
 #endif
497
 
497
 
498
 #ifdef BARICUDA
498
 #ifdef BARICUDA
499
-  #if HEATER_1_PIN > -1
499
+  #if defined(HEATER_1_PIN) && HEATER_1_PIN > -1
500
       analogWrite(HEATER_1_PIN,tail_valve_pressure);
500
       analogWrite(HEATER_1_PIN,tail_valve_pressure);
501
   #endif
501
   #endif
502
 
502
 
503
-  #if HEATER_2_PIN > -1
503
+  #if defined(HEATER_2_PIN) && HEATER_2_PIN > -1
504
       analogWrite(HEATER_2_PIN,tail_e_to_p_pressure);
504
       analogWrite(HEATER_2_PIN,tail_e_to_p_pressure);
505
   #endif
505
   #endif
506
 #endif
506
 #endif

+ 32
- 32
Marlin/stepper.cpp View File

29
 #include "language.h"
29
 #include "language.h"
30
 #include "cardreader.h"
30
 #include "cardreader.h"
31
 #include "speed_lookuptable.h"
31
 #include "speed_lookuptable.h"
32
-#if DIGIPOTSS_PIN > -1
32
+#if defined(DIGIPOTSS_PIN) && DIGIPOTSS_PIN > -1
33
 #include <SPI.h>
33
 #include <SPI.h>
34
 #endif
34
 #endif
35
 
35
 
353
       count_direction[X_AXIS]=-1;
353
       count_direction[X_AXIS]=-1;
354
       CHECK_ENDSTOPS
354
       CHECK_ENDSTOPS
355
       {
355
       {
356
-        #if X_MIN_PIN > -1
356
+        #if defined(X_MIN_PIN) && X_MIN_PIN > -1
357
           bool x_min_endstop=(READ(X_MIN_PIN) != X_ENDSTOPS_INVERTING);
357
           bool x_min_endstop=(READ(X_MIN_PIN) != X_ENDSTOPS_INVERTING);
358
           if(x_min_endstop && old_x_min_endstop && (current_block->steps_x > 0)) {
358
           if(x_min_endstop && old_x_min_endstop && (current_block->steps_x > 0)) {
359
             endstops_trigsteps[X_AXIS] = count_position[X_AXIS];
359
             endstops_trigsteps[X_AXIS] = count_position[X_AXIS];
372
       count_direction[X_AXIS]=1;
372
       count_direction[X_AXIS]=1;
373
       CHECK_ENDSTOPS 
373
       CHECK_ENDSTOPS 
374
       {
374
       {
375
-        #if X_MAX_PIN > -1
375
+        #if defined(X_MAX_PIN) && X_MAX_PIN > -1
376
           bool x_max_endstop=(READ(X_MAX_PIN) != X_ENDSTOPS_INVERTING);
376
           bool x_max_endstop=(READ(X_MAX_PIN) != X_ENDSTOPS_INVERTING);
377
           if(x_max_endstop && old_x_max_endstop && (current_block->steps_x > 0)){
377
           if(x_max_endstop && old_x_max_endstop && (current_block->steps_x > 0)){
378
             endstops_trigsteps[X_AXIS] = count_position[X_AXIS];
378
             endstops_trigsteps[X_AXIS] = count_position[X_AXIS];
391
       count_direction[Y_AXIS]=-1;
391
       count_direction[Y_AXIS]=-1;
392
       CHECK_ENDSTOPS
392
       CHECK_ENDSTOPS
393
       {
393
       {
394
-        #if Y_MIN_PIN > -1
394
+        #if defined(Y_MIN_PIN) && Y_MIN_PIN > -1
395
           bool y_min_endstop=(READ(Y_MIN_PIN) != Y_ENDSTOPS_INVERTING);
395
           bool y_min_endstop=(READ(Y_MIN_PIN) != Y_ENDSTOPS_INVERTING);
396
           if(y_min_endstop && old_y_min_endstop && (current_block->steps_y > 0)) {
396
           if(y_min_endstop && old_y_min_endstop && (current_block->steps_y > 0)) {
397
             endstops_trigsteps[Y_AXIS] = count_position[Y_AXIS];
397
             endstops_trigsteps[Y_AXIS] = count_position[Y_AXIS];
409
       count_direction[Y_AXIS]=1;
409
       count_direction[Y_AXIS]=1;
410
       CHECK_ENDSTOPS
410
       CHECK_ENDSTOPS
411
       {
411
       {
412
-        #if Y_MAX_PIN > -1
412
+        #if defined(Y_MAX_PIN) && Y_MAX_PIN > -1
413
           bool y_max_endstop=(READ(Y_MAX_PIN) != Y_ENDSTOPS_INVERTING);
413
           bool y_max_endstop=(READ(Y_MAX_PIN) != Y_ENDSTOPS_INVERTING);
414
           if(y_max_endstop && old_y_max_endstop && (current_block->steps_y > 0)){
414
           if(y_max_endstop && old_y_max_endstop && (current_block->steps_y > 0)){
415
             endstops_trigsteps[Y_AXIS] = count_position[Y_AXIS];
415
             endstops_trigsteps[Y_AXIS] = count_position[Y_AXIS];
452
       count_direction[Z_AXIS]=-1;
452
       count_direction[Z_AXIS]=-1;
453
       CHECK_ENDSTOPS
453
       CHECK_ENDSTOPS
454
       {
454
       {
455
-        #if Z_MIN_PIN > -1
455
+        #if defined(Z_MIN_PIN) && Z_MIN_PIN > -1
456
           bool z_min_endstop=(READ(Z_MIN_PIN) != Z_ENDSTOPS_INVERTING);
456
           bool z_min_endstop=(READ(Z_MIN_PIN) != Z_ENDSTOPS_INVERTING);
457
           if(z_min_endstop && old_z_min_endstop && (current_block->steps_z > 0)) {
457
           if(z_min_endstop && old_z_min_endstop && (current_block->steps_z > 0)) {
458
             endstops_trigsteps[Z_AXIS] = count_position[Z_AXIS];
458
             endstops_trigsteps[Z_AXIS] = count_position[Z_AXIS];
473
       count_direction[Z_AXIS]=1;
473
       count_direction[Z_AXIS]=1;
474
       CHECK_ENDSTOPS
474
       CHECK_ENDSTOPS
475
       {
475
       {
476
-        #if Z_MAX_PIN > -1
476
+        #if defined(Z_MAX_PIN) && Z_MAX_PIN > -1
477
           bool z_max_endstop=(READ(Z_MAX_PIN) != Z_ENDSTOPS_INVERTING);
477
           bool z_max_endstop=(READ(Z_MAX_PIN) != Z_ENDSTOPS_INVERTING);
478
           if(z_max_endstop && old_z_max_endstop && (current_block->steps_z > 0)) {
478
           if(z_max_endstop && old_z_max_endstop && (current_block->steps_z > 0)) {
479
             endstops_trigsteps[Z_AXIS] = count_position[Z_AXIS];
479
             endstops_trigsteps[Z_AXIS] = count_position[Z_AXIS];
743
   microstep_init(); //Initialize Microstepping Pins
743
   microstep_init(); //Initialize Microstepping Pins
744
   
744
   
745
   //Initialize Dir Pins
745
   //Initialize Dir Pins
746
-  #if X_DIR_PIN > -1
746
+  #if defined(X_DIR_PIN) && X_DIR_PIN > -1
747
     SET_OUTPUT(X_DIR_PIN);
747
     SET_OUTPUT(X_DIR_PIN);
748
   #endif
748
   #endif
749
-  #if Y_DIR_PIN > -1 
749
+  #if defined(Y_DIR_PIN) && Y_DIR_PIN > -1 
750
     SET_OUTPUT(Y_DIR_PIN);
750
     SET_OUTPUT(Y_DIR_PIN);
751
   #endif
751
   #endif
752
-  #if Z_DIR_PIN > -1 
752
+  #if defined(Z_DIR_PIN) && Z_DIR_PIN > -1 
753
     SET_OUTPUT(Z_DIR_PIN);
753
     SET_OUTPUT(Z_DIR_PIN);
754
 
754
 
755
-    #if defined(Z_DUAL_STEPPER_DRIVERS) && (Z2_DIR_PIN > -1)
755
+    #if defined(Z_DUAL_STEPPER_DRIVERS) && defined(Z2_DIR_PIN) && (Z2_DIR_PIN > -1)
756
       SET_OUTPUT(Z2_DIR_PIN);
756
       SET_OUTPUT(Z2_DIR_PIN);
757
     #endif
757
     #endif
758
   #endif
758
   #endif
759
-  #if E0_DIR_PIN > -1 
759
+  #if defined(E0_DIR_PIN) && E0_DIR_PIN > -1 
760
     SET_OUTPUT(E0_DIR_PIN);
760
     SET_OUTPUT(E0_DIR_PIN);
761
   #endif
761
   #endif
762
   #if defined(E1_DIR_PIN) && (E1_DIR_PIN > -1)
762
   #if defined(E1_DIR_PIN) && (E1_DIR_PIN > -1)
768
 
768
 
769
   //Initialize Enable Pins - steppers default to disabled.
769
   //Initialize Enable Pins - steppers default to disabled.
770
 
770
 
771
-  #if (X_ENABLE_PIN > -1)
771
+  #if defined(X_ENABLE_PIN) && X_ENABLE_PIN > -1
772
     SET_OUTPUT(X_ENABLE_PIN);
772
     SET_OUTPUT(X_ENABLE_PIN);
773
     if(!X_ENABLE_ON) WRITE(X_ENABLE_PIN,HIGH);
773
     if(!X_ENABLE_ON) WRITE(X_ENABLE_PIN,HIGH);
774
   #endif
774
   #endif
775
-  #if (Y_ENABLE_PIN > -1)
775
+  #if defined(Y_ENABLE_PIN) && Y_ENABLE_PIN > -1
776
     SET_OUTPUT(Y_ENABLE_PIN);
776
     SET_OUTPUT(Y_ENABLE_PIN);
777
     if(!Y_ENABLE_ON) WRITE(Y_ENABLE_PIN,HIGH);
777
     if(!Y_ENABLE_ON) WRITE(Y_ENABLE_PIN,HIGH);
778
   #endif
778
   #endif
779
-  #if (Z_ENABLE_PIN > -1)
779
+  #if defined(Z_ENABLE_PIN) && Z_ENABLE_PIN > -1
780
     SET_OUTPUT(Z_ENABLE_PIN);
780
     SET_OUTPUT(Z_ENABLE_PIN);
781
     if(!Z_ENABLE_ON) WRITE(Z_ENABLE_PIN,HIGH);
781
     if(!Z_ENABLE_ON) WRITE(Z_ENABLE_PIN,HIGH);
782
     
782
     
783
-    #if defined(Z_DUAL_STEPPER_DRIVERS) && (Z2_ENABLE_PIN > -1)
783
+    #if defined(Z_DUAL_STEPPER_DRIVERS) && defined(Z2_ENABLE_PIN) && (Z2_ENABLE_PIN > -1)
784
       SET_OUTPUT(Z2_ENABLE_PIN);
784
       SET_OUTPUT(Z2_ENABLE_PIN);
785
       if(!Z_ENABLE_ON) WRITE(Z2_ENABLE_PIN,HIGH);
785
       if(!Z_ENABLE_ON) WRITE(Z2_ENABLE_PIN,HIGH);
786
     #endif
786
     #endif
787
   #endif
787
   #endif
788
-  #if (E0_ENABLE_PIN > -1)
788
+  #if defined(E0_ENABLE_PIN) && (E0_ENABLE_PIN > -1)
789
     SET_OUTPUT(E0_ENABLE_PIN);
789
     SET_OUTPUT(E0_ENABLE_PIN);
790
     if(!E_ENABLE_ON) WRITE(E0_ENABLE_PIN,HIGH);
790
     if(!E_ENABLE_ON) WRITE(E0_ENABLE_PIN,HIGH);
791
   #endif
791
   #endif
800
 
800
 
801
   //endstops and pullups
801
   //endstops and pullups
802
   
802
   
803
-  #if X_MIN_PIN > -1
803
+  #if defined(X_MIN_PIN) && X_MIN_PIN > -1
804
     SET_INPUT(X_MIN_PIN); 
804
     SET_INPUT(X_MIN_PIN); 
805
     #ifdef ENDSTOPPULLUP_XMIN
805
     #ifdef ENDSTOPPULLUP_XMIN
806
       WRITE(X_MIN_PIN,HIGH);
806
       WRITE(X_MIN_PIN,HIGH);
807
     #endif
807
     #endif
808
   #endif
808
   #endif
809
       
809
       
810
-  #if Y_MIN_PIN > -1
810
+  #if defined(Y_MIN_PIN) && Y_MIN_PIN > -1
811
     SET_INPUT(Y_MIN_PIN); 
811
     SET_INPUT(Y_MIN_PIN); 
812
     #ifdef ENDSTOPPULLUP_YMIN
812
     #ifdef ENDSTOPPULLUP_YMIN
813
       WRITE(Y_MIN_PIN,HIGH);
813
       WRITE(Y_MIN_PIN,HIGH);
814
     #endif
814
     #endif
815
   #endif
815
   #endif
816
   
816
   
817
-  #if Z_MIN_PIN > -1
817
+  #if defined(Z_MIN_PIN) && Z_MIN_PIN > -1
818
     SET_INPUT(Z_MIN_PIN); 
818
     SET_INPUT(Z_MIN_PIN); 
819
     #ifdef ENDSTOPPULLUP_ZMIN
819
     #ifdef ENDSTOPPULLUP_ZMIN
820
       WRITE(Z_MIN_PIN,HIGH);
820
       WRITE(Z_MIN_PIN,HIGH);
821
     #endif
821
     #endif
822
   #endif
822
   #endif
823
       
823
       
824
-  #if X_MAX_PIN > -1
824
+  #if defined(X_MAX_PIN) && X_MAX_PIN > -1
825
     SET_INPUT(X_MAX_PIN); 
825
     SET_INPUT(X_MAX_PIN); 
826
     #ifdef ENDSTOPPULLUP_XMAX
826
     #ifdef ENDSTOPPULLUP_XMAX
827
       WRITE(X_MAX_PIN,HIGH);
827
       WRITE(X_MAX_PIN,HIGH);
828
     #endif
828
     #endif
829
   #endif
829
   #endif
830
       
830
       
831
-  #if Y_MAX_PIN > -1
831
+  #if defined(Y_MAX_PIN) && Y_MAX_PIN > -1
832
     SET_INPUT(Y_MAX_PIN); 
832
     SET_INPUT(Y_MAX_PIN); 
833
     #ifdef ENDSTOPPULLUP_YMAX
833
     #ifdef ENDSTOPPULLUP_YMAX
834
       WRITE(Y_MAX_PIN,HIGH);
834
       WRITE(Y_MAX_PIN,HIGH);
835
     #endif
835
     #endif
836
   #endif
836
   #endif
837
   
837
   
838
-  #if Z_MAX_PIN > -1
838
+  #if defined(Z_MAX_PIN) && Z_MAX_PIN > -1
839
     SET_INPUT(Z_MAX_PIN); 
839
     SET_INPUT(Z_MAX_PIN); 
840
     #ifdef ENDSTOPPULLUP_ZMAX
840
     #ifdef ENDSTOPPULLUP_ZMAX
841
       WRITE(Z_MAX_PIN,HIGH);
841
       WRITE(Z_MAX_PIN,HIGH);
844
  
844
  
845
 
845
 
846
   //Initialize Step Pins
846
   //Initialize Step Pins
847
-  #if (X_STEP_PIN > -1) 
847
+  #if defined(X_STEP_PIN) && (X_STEP_PIN > -1) 
848
     SET_OUTPUT(X_STEP_PIN);
848
     SET_OUTPUT(X_STEP_PIN);
849
     WRITE(X_STEP_PIN,INVERT_X_STEP_PIN);
849
     WRITE(X_STEP_PIN,INVERT_X_STEP_PIN);
850
     disable_x();
850
     disable_x();
851
   #endif  
851
   #endif  
852
-  #if (Y_STEP_PIN > -1) 
852
+  #if defined(Y_STEP_PIN) && (Y_STEP_PIN > -1) 
853
     SET_OUTPUT(Y_STEP_PIN);
853
     SET_OUTPUT(Y_STEP_PIN);
854
     WRITE(Y_STEP_PIN,INVERT_Y_STEP_PIN);
854
     WRITE(Y_STEP_PIN,INVERT_Y_STEP_PIN);
855
     disable_y();
855
     disable_y();
856
   #endif  
856
   #endif  
857
-  #if (Z_STEP_PIN > -1) 
857
+  #if defined(Z_STEP_PIN) && (Z_STEP_PIN > -1) 
858
     SET_OUTPUT(Z_STEP_PIN);
858
     SET_OUTPUT(Z_STEP_PIN);
859
     WRITE(Z_STEP_PIN,INVERT_Z_STEP_PIN);
859
     WRITE(Z_STEP_PIN,INVERT_Z_STEP_PIN);
860
-    #if defined(Z_DUAL_STEPPER_DRIVERS) && (Z2_STEP_PIN > -1)
860
+    #if defined(Z_DUAL_STEPPER_DRIVERS) && defined(Z2_STEP_PIN) && (Z2_STEP_PIN > -1)
861
       SET_OUTPUT(Z2_STEP_PIN);
861
       SET_OUTPUT(Z2_STEP_PIN);
862
       WRITE(Z2_STEP_PIN,INVERT_Z_STEP_PIN);
862
       WRITE(Z2_STEP_PIN,INVERT_Z_STEP_PIN);
863
     #endif
863
     #endif
864
     disable_z();
864
     disable_z();
865
   #endif  
865
   #endif  
866
-  #if (E0_STEP_PIN > -1) 
866
+  #if defined(E0_STEP_PIN) && (E0_STEP_PIN > -1) 
867
     SET_OUTPUT(E0_STEP_PIN);
867
     SET_OUTPUT(E0_STEP_PIN);
868
     WRITE(E0_STEP_PIN,INVERT_E_STEP_PIN);
868
     WRITE(E0_STEP_PIN,INVERT_E_STEP_PIN);
869
     disable_e0();
869
     disable_e0();
974
 
974
 
975
 void digitalPotWrite(int address, int value) // From Arduino DigitalPotControl example
975
 void digitalPotWrite(int address, int value) // From Arduino DigitalPotControl example
976
 {
976
 {
977
-  #if DIGIPOTSS_PIN > -1
977
+  #if defined(DIGIPOTSS_PIN) && DIGIPOTSS_PIN > -1
978
     digitalWrite(DIGIPOTSS_PIN,LOW); // take the SS pin low to select the chip
978
     digitalWrite(DIGIPOTSS_PIN,LOW); // take the SS pin low to select the chip
979
     SPI.transfer(address); //  send in the address and value via SPI:
979
     SPI.transfer(address); //  send in the address and value via SPI:
980
     SPI.transfer(value);
980
     SPI.transfer(value);
985
 
985
 
986
 void digipot_init() //Initialize Digipot Motor Current
986
 void digipot_init() //Initialize Digipot Motor Current
987
 {
987
 {
988
-  #if DIGIPOTSS_PIN > -1
988
+  #if defined(DIGIPOTSS_PIN) && DIGIPOTSS_PIN > -1
989
     const uint8_t digipot_motor_current[] = DIGIPOT_MOTOR_CURRENT;
989
     const uint8_t digipot_motor_current[] = DIGIPOT_MOTOR_CURRENT;
990
     
990
     
991
     SPI.begin(); 
991
     SPI.begin(); 
998
 
998
 
999
 void digipot_current(uint8_t driver, int current)
999
 void digipot_current(uint8_t driver, int current)
1000
 {
1000
 {
1001
-  #if DIGIPOTSS_PIN > -1
1001
+  #if defined(DIGIPOTSS_PIN) && DIGIPOTSS_PIN > -1
1002
     const uint8_t digipot_ch[] = DIGIPOT_CHANNELS;
1002
     const uint8_t digipot_ch[] = DIGIPOT_CHANNELS;
1003
     digitalPotWrite(digipot_ch[driver], current);
1003
     digitalPotWrite(digipot_ch[driver], current);
1004
   #endif
1004
   #endif
1006
 
1006
 
1007
 void microstep_init()
1007
 void microstep_init()
1008
 {
1008
 {
1009
-  #if X_MS1_PIN > -1
1009
+  #if defined(X_MS1_PIN) && X_MS1_PIN > -1
1010
   const uint8_t microstep_modes[] = MICROSTEP_MODES;
1010
   const uint8_t microstep_modes[] = MICROSTEP_MODES;
1011
   pinMode(X_MS2_PIN,OUTPUT);
1011
   pinMode(X_MS2_PIN,OUTPUT);
1012
   pinMode(Y_MS2_PIN,OUTPUT);
1012
   pinMode(Y_MS2_PIN,OUTPUT);

+ 43
- 37
Marlin/temperature.cpp View File

99
 #ifdef FAN_SOFT_PWM
99
 #ifdef FAN_SOFT_PWM
100
   static unsigned char soft_pwm_fan;
100
   static unsigned char soft_pwm_fan;
101
 #endif
101
 #endif
102
-#if EXTRUDER_0_AUTO_FAN_PIN > 0 || EXTRUDER_1_AUTO_FAN_PIN > 0 || EXTRUDER_2_AUTO_FAN_PIN > 0
102
+#if (defined(EXTRUDER_0_AUTO_FAN_PIN) && EXTRUDER_0_AUTO_FAN_PIN > -1) || \
103
+    (defined(EXTRUDER_1_AUTO_FAN_PIN) && EXTRUDER_1_AUTO_FAN_PIN > -1) || \
104
+    (defined(EXTRUDER_2_AUTO_FAN_PIN) && EXTRUDER_2_AUTO_FAN_PIN > -1)
103
   static unsigned long extruder_autofan_last_check;
105
   static unsigned long extruder_autofan_last_check;
104
 #endif  
106
 #endif  
105
   
107
   
307
   return soft_pwm[heater];
309
   return soft_pwm[heater];
308
 }
310
 }
309
 
311
 
310
-#if EXTRUDER_0_AUTO_FAN_PIN > 0 || EXTRUDER_1_AUTO_FAN_PIN > 0 || EXTRUDER_2_AUTO_FAN_PIN > 0
312
+#if (defined(EXTRUDER_0_AUTO_FAN_PIN) && EXTRUDER_0_AUTO_FAN_PIN > -1) || \
313
+    (defined(EXTRUDER_1_AUTO_FAN_PIN) && EXTRUDER_1_AUTO_FAN_PIN > -1) || \
314
+    (defined(EXTRUDER_2_AUTO_FAN_PIN) && EXTRUDER_2_AUTO_FAN_PIN > -1)
311
 
315
 
312
-  #if FAN_PIN > 0
316
+  #if defined(FAN_PIN) && FAN_PIN > -1
313
     #if EXTRUDER_0_AUTO_FAN_PIN == FAN_PIN 
317
     #if EXTRUDER_0_AUTO_FAN_PIN == FAN_PIN 
314
        #error "You cannot set EXTRUDER_0_AUTO_FAN_PIN equal to FAN_PIN"
318
        #error "You cannot set EXTRUDER_0_AUTO_FAN_PIN equal to FAN_PIN"
315
     #endif
319
     #endif
335
   uint8_t fanState = 0;
339
   uint8_t fanState = 0;
336
 
340
 
337
   // which fan pins need to be turned on?      
341
   // which fan pins need to be turned on?      
338
-  #if EXTRUDER_0_AUTO_FAN_PIN > 0
342
+  #if defined(EXTRUDER_0_AUTO_FAN_PIN) && EXTRUDER_0_AUTO_FAN_PIN > -1
339
     if (current_temperature[0] > EXTRUDER_AUTO_FAN_TEMPERATURE) 
343
     if (current_temperature[0] > EXTRUDER_AUTO_FAN_TEMPERATURE) 
340
       fanState |= 1;
344
       fanState |= 1;
341
   #endif
345
   #endif
342
-  #if EXTRUDER_1_AUTO_FAN_PIN > 0
346
+  #if defined(EXTRUDER_1_AUTO_FAN_PIN) && EXTRUDER_1_AUTO_FAN_PIN > -1
343
     if (current_temperature[1] > EXTRUDER_AUTO_FAN_TEMPERATURE) 
347
     if (current_temperature[1] > EXTRUDER_AUTO_FAN_TEMPERATURE) 
344
     {
348
     {
345
       if (EXTRUDER_1_AUTO_FAN_PIN == EXTRUDER_0_AUTO_FAN_PIN) 
349
       if (EXTRUDER_1_AUTO_FAN_PIN == EXTRUDER_0_AUTO_FAN_PIN) 
348
         fanState |= 2;
352
         fanState |= 2;
349
     }
353
     }
350
   #endif
354
   #endif
351
-  #if EXTRUDER_2_AUTO_FAN_PIN > 0
355
+  #if defined(EXTRUDER_2_AUTO_FAN_PIN) && EXTRUDER_2_AUTO_FAN_PIN > -1
352
     if (current_temperature[2] > EXTRUDER_AUTO_FAN_TEMPERATURE) 
356
     if (current_temperature[2] > EXTRUDER_AUTO_FAN_TEMPERATURE) 
353
     {
357
     {
354
       if (EXTRUDER_2_AUTO_FAN_PIN == EXTRUDER_0_AUTO_FAN_PIN) 
358
       if (EXTRUDER_2_AUTO_FAN_PIN == EXTRUDER_0_AUTO_FAN_PIN) 
361
   #endif
365
   #endif
362
   
366
   
363
   // update extruder auto fan states
367
   // update extruder auto fan states
364
-  #if EXTRUDER_0_AUTO_FAN_PIN > 0
368
+  #if defined(EXTRUDER_0_AUTO_FAN_PIN) && EXTRUDER_0_AUTO_FAN_PIN > -1
365
     setExtruderAutoFanState(EXTRUDER_0_AUTO_FAN_PIN, (fanState & 1) != 0);
369
     setExtruderAutoFanState(EXTRUDER_0_AUTO_FAN_PIN, (fanState & 1) != 0);
366
   #endif 
370
   #endif 
367
-  #if EXTRUDER_1_AUTO_FAN_PIN > 0
371
+  #if defined(EXTRUDER_1_AUTO_FAN_PIN) && EXTRUDER_1_AUTO_FAN_PIN > -1
368
     if (EXTRUDER_1_AUTO_FAN_PIN != EXTRUDER_0_AUTO_FAN_PIN) 
372
     if (EXTRUDER_1_AUTO_FAN_PIN != EXTRUDER_0_AUTO_FAN_PIN) 
369
       setExtruderAutoFanState(EXTRUDER_1_AUTO_FAN_PIN, (fanState & 2) != 0);
373
       setExtruderAutoFanState(EXTRUDER_1_AUTO_FAN_PIN, (fanState & 2) != 0);
370
   #endif 
374
   #endif 
371
-  #if EXTRUDER_2_AUTO_FAN_PIN > 0
375
+  #if defined(EXTRUDER_2_AUTO_FAN_PIN) && EXTRUDER_2_AUTO_FAN_PIN > -1
372
     if (EXTRUDER_2_AUTO_FAN_PIN != EXTRUDER_0_AUTO_FAN_PIN 
376
     if (EXTRUDER_2_AUTO_FAN_PIN != EXTRUDER_0_AUTO_FAN_PIN 
373
         && EXTRUDER_2_AUTO_FAN_PIN != EXTRUDER_1_AUTO_FAN_PIN)
377
         && EXTRUDER_2_AUTO_FAN_PIN != EXTRUDER_1_AUTO_FAN_PIN)
374
       setExtruderAutoFanState(EXTRUDER_2_AUTO_FAN_PIN, (fanState & 4) != 0);
378
       setExtruderAutoFanState(EXTRUDER_2_AUTO_FAN_PIN, (fanState & 4) != 0);
470
 
474
 
471
   } // End extruder for loop
475
   } // End extruder for loop
472
 
476
 
473
-  #if EXTRUDER_0_AUTO_FAN_PIN > 0 || EXTRUDER_1_AUTO_FAN_PIN > 0 || EXTRUDER_2_AUTO_FAN_PIN > 0
477
+  #if (defined(EXTRUDER_0_AUTO_FAN_PIN) && EXTRUDER_0_AUTO_FAN_PIN > -1) || \
478
+      (defined(EXTRUDER_1_AUTO_FAN_PIN) && EXTRUDER_1_AUTO_FAN_PIN > -1) || \
479
+      (defined(EXTRUDER_2_AUTO_FAN_PIN) && EXTRUDER_2_AUTO_FAN_PIN > -1)
474
   if(millis() - extruder_autofan_last_check > 2500)  // only need to check fan state very infrequently
480
   if(millis() - extruder_autofan_last_check > 2500)  // only need to check fan state very infrequently
475
   {
481
   {
476
     checkExtruderAutoFans();
482
     checkExtruderAutoFans();
669
 #endif //PIDTEMPBED
675
 #endif //PIDTEMPBED
670
   }
676
   }
671
 
677
 
672
-  #if (HEATER_0_PIN > -1) 
678
+  #if defined(HEATER_0_PIN) && (HEATER_0_PIN > -1) 
673
     SET_OUTPUT(HEATER_0_PIN);
679
     SET_OUTPUT(HEATER_0_PIN);
674
   #endif  
680
   #endif  
675
-  #if (HEATER_1_PIN > -1) 
681
+  #if defined(HEATER_1_PIN) && (HEATER_1_PIN > -1) 
676
     SET_OUTPUT(HEATER_1_PIN);
682
     SET_OUTPUT(HEATER_1_PIN);
677
   #endif  
683
   #endif  
678
-  #if (HEATER_2_PIN > -1) 
684
+  #if defined(HEATER_2_PIN) && (HEATER_2_PIN > -1) 
679
     SET_OUTPUT(HEATER_2_PIN);
685
     SET_OUTPUT(HEATER_2_PIN);
680
   #endif  
686
   #endif  
681
-  #if (HEATER_BED_PIN > -1) 
687
+  #if defined(HEATER_BED_PIN) && (HEATER_BED_PIN > -1) 
682
     SET_OUTPUT(HEATER_BED_PIN);
688
     SET_OUTPUT(HEATER_BED_PIN);
683
   #endif  
689
   #endif  
684
-  #if (FAN_PIN > -1) 
690
+  #if defined(FAN_PIN) && (FAN_PIN > -1) 
685
     SET_OUTPUT(FAN_PIN);
691
     SET_OUTPUT(FAN_PIN);
686
     #ifdef FAST_PWM_FAN
692
     #ifdef FAST_PWM_FAN
687
     setPwmFrequency(FAN_PIN, 1); // No prescaling. Pwm frequency = F_CPU/256/8
693
     setPwmFrequency(FAN_PIN, 1); // No prescaling. Pwm frequency = F_CPU/256/8
713
   #ifdef DIDR2
719
   #ifdef DIDR2
714
     DIDR2 = 0;
720
     DIDR2 = 0;
715
   #endif
721
   #endif
716
-  #if (TEMP_0_PIN > -1)
722
+  #if defined(TEMP_0_PIN) && (TEMP_0_PIN > -1)
717
     #if TEMP_0_PIN < 8
723
     #if TEMP_0_PIN < 8
718
        DIDR0 |= 1 << TEMP_0_PIN; 
724
        DIDR0 |= 1 << TEMP_0_PIN; 
719
     #else
725
     #else
720
        DIDR2 |= 1<<(TEMP_0_PIN - 8); 
726
        DIDR2 |= 1<<(TEMP_0_PIN - 8); 
721
     #endif
727
     #endif
722
   #endif
728
   #endif
723
-  #if (TEMP_1_PIN > -1)
729
+  #if defined(TEMP_1_PIN) && (TEMP_1_PIN > -1)
724
     #if TEMP_1_PIN < 8
730
     #if TEMP_1_PIN < 8
725
        DIDR0 |= 1<<TEMP_1_PIN; 
731
        DIDR0 |= 1<<TEMP_1_PIN; 
726
     #else
732
     #else
727
        DIDR2 |= 1<<(TEMP_1_PIN - 8); 
733
        DIDR2 |= 1<<(TEMP_1_PIN - 8); 
728
     #endif
734
     #endif
729
   #endif
735
   #endif
730
-  #if (TEMP_2_PIN > -1)
736
+  #if defined(TEMP_2_PIN) && (TEMP_2_PIN > -1)
731
     #if TEMP_2_PIN < 8
737
     #if TEMP_2_PIN < 8
732
        DIDR0 |= 1 << TEMP_2_PIN; 
738
        DIDR0 |= 1 << TEMP_2_PIN; 
733
     #else
739
     #else
734
        DIDR2 |= 1<<(TEMP_2_PIN - 8); 
740
        DIDR2 |= 1<<(TEMP_2_PIN - 8); 
735
     #endif
741
     #endif
736
   #endif
742
   #endif
737
-  #if (TEMP_BED_PIN > -1)
743
+  #if defined(TEMP_BED_PIN) && (TEMP_BED_PIN > -1)
738
     #if TEMP_BED_PIN < 8
744
     #if TEMP_BED_PIN < 8
739
        DIDR0 |= 1<<TEMP_BED_PIN; 
745
        DIDR0 |= 1<<TEMP_BED_PIN; 
740
     #else
746
     #else
855
   for(int i=0;i<EXTRUDERS;i++)
861
   for(int i=0;i<EXTRUDERS;i++)
856
     setTargetHotend(0,i);
862
     setTargetHotend(0,i);
857
   setTargetBed(0);
863
   setTargetBed(0);
858
-  #if TEMP_0_PIN > -1
864
+  #if defined(TEMP_0_PIN) && TEMP_0_PIN > -1
859
   target_temperature[0]=0;
865
   target_temperature[0]=0;
860
   soft_pwm[0]=0;
866
   soft_pwm[0]=0;
861
-   #if HEATER_0_PIN > -1  
867
+   #if defined(HEATER_0_PIN) && HEATER_0_PIN > -1  
862
      WRITE(HEATER_0_PIN,LOW);
868
      WRITE(HEATER_0_PIN,LOW);
863
    #endif
869
    #endif
864
   #endif
870
   #endif
865
      
871
      
866
-  #if TEMP_1_PIN > -1
872
+  #if defined(TEMP_1_PIN) && TEMP_1_PIN > -1
867
     target_temperature[1]=0;
873
     target_temperature[1]=0;
868
     soft_pwm[1]=0;
874
     soft_pwm[1]=0;
869
-    #if HEATER_1_PIN > -1 
875
+    #if defined(HEATER_1_PIN) && HEATER_1_PIN > -1 
870
       WRITE(HEATER_1_PIN,LOW);
876
       WRITE(HEATER_1_PIN,LOW);
871
     #endif
877
     #endif
872
   #endif
878
   #endif
873
       
879
       
874
-  #if TEMP_2_PIN > -1
880
+  #if defined(TEMP_2_PIN) && TEMP_2_PIN > -1
875
     target_temperature[2]=0;
881
     target_temperature[2]=0;
876
     soft_pwm[2]=0;
882
     soft_pwm[2]=0;
877
-    #if HEATER_2_PIN > -1  
883
+    #if defined(HEATER_2_PIN) && HEATER_2_PIN > -1  
878
       WRITE(HEATER_2_PIN,LOW);
884
       WRITE(HEATER_2_PIN,LOW);
879
     #endif
885
     #endif
880
   #endif 
886
   #endif 
881
 
887
 
882
-  #if TEMP_BED_PIN > -1
888
+  #if defined(TEMP_BED_PIN) && TEMP_BED_PIN > -1
883
     target_temperature_bed=0;
889
     target_temperature_bed=0;
884
     soft_pwm_bed=0;
890
     soft_pwm_bed=0;
885
-    #if HEATER_BED_PIN > -1  
891
+    #if defined(HEATER_BED_PIN) && HEATER_BED_PIN > -1  
886
       WRITE(HEATER_BED_PIN,LOW);
892
       WRITE(HEATER_BED_PIN,LOW);
887
     #endif
893
     #endif
888
   #endif 
894
   #endif 
1018
     soft_pwm_2 = soft_pwm[2];
1024
     soft_pwm_2 = soft_pwm[2];
1019
     if(soft_pwm_2 > 0) WRITE(HEATER_2_PIN,1);
1025
     if(soft_pwm_2 > 0) WRITE(HEATER_2_PIN,1);
1020
     #endif
1026
     #endif
1021
-    #if HEATER_BED_PIN > -1
1027
+    #if defined(HEATER_BED_PIN) && HEATER_BED_PIN > -1
1022
     soft_pwm_b = soft_pwm_bed;
1028
     soft_pwm_b = soft_pwm_bed;
1023
     if(soft_pwm_b > 0) WRITE(HEATER_BED_PIN,1);
1029
     if(soft_pwm_b > 0) WRITE(HEATER_BED_PIN,1);
1024
     #endif
1030
     #endif
1034
   #if EXTRUDERS > 2
1040
   #if EXTRUDERS > 2
1035
   if(soft_pwm_2 <= pwm_count) WRITE(HEATER_2_PIN,0);
1041
   if(soft_pwm_2 <= pwm_count) WRITE(HEATER_2_PIN,0);
1036
   #endif
1042
   #endif
1037
-  #if HEATER_BED_PIN > -1
1043
+  #if defined(HEATER_BED_PIN) && HEATER_BED_PIN > -1
1038
   if(soft_pwm_b <= pwm_count) WRITE(HEATER_BED_PIN,0);
1044
   if(soft_pwm_b <= pwm_count) WRITE(HEATER_BED_PIN,0);
1039
   #endif
1045
   #endif
1040
   #ifdef FAN_SOFT_PWM
1046
   #ifdef FAN_SOFT_PWM
1046
   
1052
   
1047
   switch(temp_state) {
1053
   switch(temp_state) {
1048
     case 0: // Prepare TEMP_0
1054
     case 0: // Prepare TEMP_0
1049
-      #if (TEMP_0_PIN > -1)
1055
+      #if defined(TEMP_0_PIN) && (TEMP_0_PIN > -1)
1050
         #if TEMP_0_PIN > 7
1056
         #if TEMP_0_PIN > 7
1051
           ADCSRB = 1<<MUX5;
1057
           ADCSRB = 1<<MUX5;
1052
         #else
1058
         #else
1059
       temp_state = 1;
1065
       temp_state = 1;
1060
       break;
1066
       break;
1061
     case 1: // Measure TEMP_0
1067
     case 1: // Measure TEMP_0
1062
-      #if (TEMP_0_PIN > -1)
1068
+      #if defined(TEMP_0_PIN) && (TEMP_0_PIN > -1)
1063
         raw_temp_0_value += ADC;
1069
         raw_temp_0_value += ADC;
1064
       #endif
1070
       #endif
1065
       #ifdef HEATER_0_USES_MAX6675 // TODO remove the blocking
1071
       #ifdef HEATER_0_USES_MAX6675 // TODO remove the blocking
1068
       temp_state = 2;
1074
       temp_state = 2;
1069
       break;
1075
       break;
1070
     case 2: // Prepare TEMP_BED
1076
     case 2: // Prepare TEMP_BED
1071
-      #if (TEMP_BED_PIN > -1)
1077
+      #if defined(TEMP_BED_PIN) && (TEMP_BED_PIN > -1)
1072
         #if TEMP_BED_PIN > 7
1078
         #if TEMP_BED_PIN > 7
1073
           ADCSRB = 1<<MUX5;
1079
           ADCSRB = 1<<MUX5;
1074
         #else
1080
         #else
1081
       temp_state = 3;
1087
       temp_state = 3;
1082
       break;
1088
       break;
1083
     case 3: // Measure TEMP_BED
1089
     case 3: // Measure TEMP_BED
1084
-      #if (TEMP_BED_PIN > -1)
1090
+      #if defined(TEMP_BED_PIN) && (TEMP_BED_PIN > -1)
1085
         raw_temp_bed_value += ADC;
1091
         raw_temp_bed_value += ADC;
1086
       #endif
1092
       #endif
1087
       temp_state = 4;
1093
       temp_state = 4;
1088
       break;
1094
       break;
1089
     case 4: // Prepare TEMP_1
1095
     case 4: // Prepare TEMP_1
1090
-      #if (TEMP_1_PIN > -1)
1096
+      #if defined(TEMP_1_PIN) && (TEMP_1_PIN > -1)
1091
         #if TEMP_1_PIN > 7
1097
         #if TEMP_1_PIN > 7
1092
           ADCSRB = 1<<MUX5;
1098
           ADCSRB = 1<<MUX5;
1093
         #else
1099
         #else
1100
       temp_state = 5;
1106
       temp_state = 5;
1101
       break;
1107
       break;
1102
     case 5: // Measure TEMP_1
1108
     case 5: // Measure TEMP_1
1103
-      #if (TEMP_1_PIN > -1)
1109
+      #if defined(TEMP_1_PIN) && (TEMP_1_PIN > -1)
1104
         raw_temp_1_value += ADC;
1110
         raw_temp_1_value += ADC;
1105
       #endif
1111
       #endif
1106
       temp_state = 6;
1112
       temp_state = 6;
1107
       break;
1113
       break;
1108
     case 6: // Prepare TEMP_2
1114
     case 6: // Prepare TEMP_2
1109
-      #if (TEMP_2_PIN > -1)
1115
+      #if defined(TEMP_2_PIN) && (TEMP_2_PIN > -1)
1110
         #if TEMP_2_PIN > 7
1116
         #if TEMP_2_PIN > 7
1111
           ADCSRB = 1<<MUX5;
1117
           ADCSRB = 1<<MUX5;
1112
         #else
1118
         #else
1119
       temp_state = 7;
1125
       temp_state = 7;
1120
       break;
1126
       break;
1121
     case 7: // Measure TEMP_2
1127
     case 7: // Measure TEMP_2
1122
-      #if (TEMP_2_PIN > -1)
1128
+      #if defined(TEMP_2_PIN) && (TEMP_2_PIN > -1)
1123
         raw_temp_2_value += ADC;
1129
         raw_temp_2_value += ADC;
1124
       #endif
1130
       #endif
1125
       temp_state = 0;
1131
       temp_state = 0;

Loading…
Cancel
Save