Parcourir la source

Added M42, M80 and M81

Erik van der Zalm il y a 13 ans
Parent
révision
d7c4f0780b
2 fichiers modifiés avec 41 ajouts et 1 suppressions
  1. 37
    1
      Marlin/Marlin.pde
  2. 4
    0
      Marlin/pins.h

+ 37
- 1
Marlin/Marlin.pde Voir le fichier

@@ -69,7 +69,6 @@ char version_string[] = "1.0.0 Alpha 1";
69 69
 // M114 - Display current position
70 70
 
71 71
 //Custom M Codes
72
-// M80  - Turn on Power Supply
73 72
 // M20  - List SD card
74 73
 // M21  - Init SD card
75 74
 // M22  - Release SD card
@@ -80,6 +79,8 @@ char version_string[] = "1.0.0 Alpha 1";
80 79
 // M27  - Report SD print status
81 80
 // M28  - Start SD write (M28 filename.g)
82 81
 // M29  - Stop SD write
82
+// M42  - Change pin status via gcode
83
+// M80  - Turn on Power Supply
83 84
 // M81  - Turn off Power Supply
84 85
 // M82  - Set E codes absolute (default)
85 86
 // M83  - Set E codes relative while in Absolute Coordinates (G90) mode
@@ -142,6 +143,8 @@ extern float HeaterPower;
142 143
 
143 144
 #include "EEPROM.h"
144 145
 
146
+const int sensitive_pins[] = SENSITIVE_PINS; // Sensitive pin list for M42
147
+
145 148
 float tt = 0, bt = 0;
146 149
 #ifdef WATCHPERIOD
147 150
 int watch_raw = -1000;
@@ -772,6 +775,31 @@ inline void process_commands()
772 775
 		}
773 776
 				break;
774 777
 #endif //SDSUPPORT
778
+      case 42: //M42 -Change pin status via gcode
779
+        if (code_seen('S'))
780
+        {
781
+          int pin_status = code_value();
782
+          if (code_seen('P') && pin_status >= 0 && pin_status <= 255)
783
+          {
784
+            int pin_number = code_value();
785
+            for(int i = 0; i < sizeof(sensitive_pins); i++)
786
+            {
787
+              if (sensitive_pins[i] == pin_number)
788
+              {
789
+                pin_number = -1;
790
+                break;
791
+              }
792
+            }
793
+            
794
+            if (pin_number > -1)
795
+            {              
796
+              pinMode(pin_number, OUTPUT);
797
+              digitalWrite(pin_number, pin_status);
798
+              analogWrite(pin_number, pin_status);
799
+            }
800
+          }
801
+        }
802
+        break;
775 803
       case 104: // M104
776 804
                 if (code_seen('S')) target_raw[0] = temp2analog(code_value());
777 805
 #ifdef PIDTEMP
@@ -908,6 +936,14 @@ inline void process_commands()
908 936
         analogWrite(FAN_PIN, 0);
909 937
         break;
910 938
 #endif
939
+#if (PS_ON_PIN > -1)
940
+      case 80: // M80 - ATX Power On
941
+        SET_OUTPUT(PS_ON_PIN); //GND
942
+        break;
943
+      case 81: // M81 - ATX Power Off
944
+        SET_INPUT(PS_ON_PIN); //Floating
945
+        break;
946
+#endif
911 947
     case 82:
912 948
       axis_relative_modes[3] = false;
913 949
       break;

+ 4
- 0
Marlin/pins.h Voir le fichier

@@ -563,4 +563,8 @@
563 563
 #ifndef KNOWN_BOARD
564 564
 #error Unknown MOTHERBOARD value in configuration.h
565 565
 #endif
566
+
567
+//List of pins which to ignore when asked to change by gcode, 0 and 1 are RX and TX, do not mess with those!
568
+#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}
569
+
566 570
 #endif

Chargement…
Annuler
Enregistrer