Browse Source

Fix the sensitive pin definitions, there where analogue numbers in the digital pin list. Also made M42 without a P function on the LED_PIN (which was otherwise a useless pin definition)

daid303 12 years ago
parent
commit
5ff5cee8ce
5 changed files with 26 additions and 26 deletions
  1. 1
    1
      Marlin/Configuration.h
  2. 12
    14
      Marlin/Marlin_main.cpp
  3. 2
    0
      Marlin/language.h
  4. 2
    2
      Marlin/pins.h
  5. 9
    9
      Marlin/temperature.cpp

+ 1
- 1
Marlin/Configuration.h View File

@@ -43,7 +43,7 @@
43 43
 // 70 = Megatronics
44 44
 // 90 = Alpha OMCA board
45 45
 // 91 = Final OMCA board
46
-// Rambo = 301
46
+// 301 = Rambo
47 47
 
48 48
 #ifndef MOTHERBOARD
49 49
 #define MOTHERBOARD 7

+ 12
- 14
Marlin/Marlin_main.cpp View File

@@ -956,25 +956,23 @@ void process_commands()
956 956
       if (code_seen('S'))
957 957
       {
958 958
         int pin_status = code_value();
959
+        int pin_number = LED_PIN;
959 960
         if (code_seen('P') && pin_status >= 0 && pin_status <= 255)
961
+          pin_number = code_value();
962
+        for(int8_t i = 0; i < (int8_t)sizeof(sensitive_pins); i++)
960 963
         {
961
-          int pin_number = code_value();
962
-          for(int8_t i = 0; i < (int8_t)sizeof(sensitive_pins); i++)
964
+          if (sensitive_pins[i] == pin_number)
963 965
           {
964
-            if (sensitive_pins[i] == pin_number)
965
-            {
966
-              pin_number = -1;
967
-              break;
968
-            }
969
-          }
970
-          
971
-          if (pin_number > -1)
972
-          {              
973
-            pinMode(pin_number, OUTPUT);
974
-            digitalWrite(pin_number, pin_status);
975
-            analogWrite(pin_number, pin_status);
966
+            pin_number = -1;
967
+            break;
976 968
           }
977 969
         }
970
+        if (pin_number > -1)
971
+        {
972
+          pinMode(pin_number, OUTPUT);
973
+          digitalWrite(pin_number, pin_status);
974
+          analogWrite(pin_number, pin_status);
975
+        }
978 976
       }
979 977
      break;
980 978
     case 104: // M104

+ 2
- 0
Marlin/language.h View File

@@ -16,7 +16,9 @@
16 16
 // 7  Italian
17 17
 // 8  Portuguese
18 18
 
19
+#ifndef LANGUAGE_CHOICE
19 20
 #define LANGUAGE_CHOICE 1  // Pick your language from the list above
21
+#endif
20 22
 
21 23
 #define PROTOCOL_VERSION "1.0"
22 24
 

+ 2
- 2
Marlin/pins.h View File

@@ -1505,8 +1505,8 @@
1505 1505
 #define Z_MAX_PIN          -1
1506 1506
 #endif
1507 1507
 
1508
-#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, \
1508
+#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, PS_ON_PIN, \
1509 1509
                         HEATER_BED_PIN, FAN_PIN,                  \
1510 1510
                         _E0_PINS _E1_PINS _E2_PINS             \
1511
-                        TEMP_0_PIN, TEMP_1_PIN, TEMP_2_PIN, TEMP_BED_PIN }
1511
+                        analogInputToDigitalPin(TEMP_0_PIN), analogInputToDigitalPin(TEMP_1_PIN), analogInputToDigitalPin(TEMP_2_PIN), analogInputToDigitalPin(TEMP_BED_PIN) }
1512 1512
 #endif

+ 9
- 9
Marlin/temperature.cpp View File

@@ -117,7 +117,7 @@ static int maxttemp[EXTRUDERS] = ARRAY_BY_EXTRUDERS( 16383, 16383, 16383 );
117 117
 static int bed_maxttemp_raw = HEATER_BED_RAW_HI_TEMP;
118 118
 #endif
119 119
 static void *heater_ttbl_map[EXTRUDERS] = ARRAY_BY_EXTRUDERS( (void *)HEATER_0_TEMPTABLE, (void *)HEATER_1_TEMPTABLE, (void *)HEATER_2_TEMPTABLE );
120
-static int heater_ttbllen_map[EXTRUDERS] = ARRAY_BY_EXTRUDERS( HEATER_0_TEMPTABLE_LEN, HEATER_1_TEMPTABLE_LEN, HEATER_2_TEMPTABLE_LEN );
120
+static uint8_t heater_ttbllen_map[EXTRUDERS] = ARRAY_BY_EXTRUDERS( HEATER_0_TEMPTABLE_LEN, HEATER_1_TEMPTABLE_LEN, HEATER_2_TEMPTABLE_LEN );
121 121
 
122 122
 static float analog2temp(int raw, uint8_t e);
123 123
 static float analog2tempBed(int raw);
@@ -493,7 +493,7 @@ static float analog2temp(int raw, uint8_t e) {
493 493
   if(heater_ttbl_map[e] != NULL)
494 494
   {
495 495
     float celsius = 0;
496
-    byte i;
496
+    uint8_t i;
497 497
     short (*tt)[][2] = (short (*)[][2])(heater_ttbl_map[e]);
498 498
 
499 499
     for (i=1; i<heater_ttbllen_map[e]; i++)
@@ -523,20 +523,20 @@ static float analog2tempBed(int raw) {
523 523
     float celsius = 0;
524 524
     byte i;
525 525
 
526
-    for (i=1; i<bedtemptable_len; i++)
526
+    for (i=1; i<BEDTEMPTABLE_LEN; i++)
527 527
     {
528
-      if (PGM_RD_W(bedtemptable[i][0]) > raw)
528
+      if (PGM_RD_W(BEDTEMPTABLE[i][0]) > raw)
529 529
       {
530
-        celsius  = PGM_RD_W(bedtemptable[i-1][1]) + 
531
-          (raw - PGM_RD_W(bedtemptable[i-1][0])) * 
532
-          (float)(PGM_RD_W(bedtemptable[i][1]) - PGM_RD_W(bedtemptable[i-1][1])) /
533
-          (float)(PGM_RD_W(bedtemptable[i][0]) - PGM_RD_W(bedtemptable[i-1][0]));
530
+        celsius  = PGM_RD_W(BEDTEMPTABLE[i-1][1]) + 
531
+          (raw - PGM_RD_W(BEDTEMPTABLE[i-1][0])) * 
532
+          (float)(PGM_RD_W(BEDTEMPTABLE[i][1]) - PGM_RD_W(BEDTEMPTABLE[i-1][1])) /
533
+          (float)(PGM_RD_W(BEDTEMPTABLE[i][0]) - PGM_RD_W(BEDTEMPTABLE[i-1][0]));
534 534
         break;
535 535
       }
536 536
     }
537 537
 
538 538
     // Overflow: Set to last value in the table
539
-    if (i == bedtemptable_len) celsius = PGM_RD_W(bedtemptable[i-1][1]);
539
+    if (i == BEDTEMPTABLE_LEN) celsius = PGM_RD_W(BEDTEMPTABLE[i-1][1]);
540 540
 
541 541
     return celsius;
542 542
   #elif defined BED_USES_AD595

Loading…
Cancel
Save