|
@@ -414,8 +414,6 @@ const char axis_codes[NUM_AXIS] = {'X', 'Y', 'Z', 'E'};
|
414
|
414
|
|
415
|
415
|
static int serial_count = 0;
|
416
|
416
|
|
417
|
|
-const int sensitive_pins[] = SENSITIVE_PINS; ///< Sensitive pin list for M42
|
418
|
|
-
|
419
|
417
|
// Inactivity shutdown
|
420
|
418
|
millis_t previous_cmd_ms = 0;
|
421
|
419
|
static millis_t max_inactive_time = 0;
|
|
@@ -4610,6 +4608,16 @@ inline void gcode_M31() {
|
4610
|
4608
|
#endif // SDSUPPORT
|
4611
|
4609
|
|
4612
|
4610
|
/**
|
|
4611
|
+ * Sensitive pin test for M42, M226
|
|
4612
|
+ */
|
|
4613
|
+static bool pin_is_protected(uint8_t pin) {
|
|
4614
|
+ static const int sensitive_pins[] = SENSITIVE_PINS;
|
|
4615
|
+ for (uint8_t i = 0; i < COUNT(sensitive_pins); i++)
|
|
4616
|
+ if (sensitive_pins[i] == pin) return true;
|
|
4617
|
+ return false;
|
|
4618
|
+}
|
|
4619
|
+
|
|
4620
|
+/**
|
4613
|
4621
|
* M42: Change pin status via GCode
|
4614
|
4622
|
*
|
4615
|
4623
|
* P<pin> Pin number (LED if omitted)
|
|
@@ -4624,12 +4632,11 @@ inline void gcode_M42() {
|
4624
|
4632
|
int pin_number = code_seen('P') ? code_value_int() : LED_PIN;
|
4625
|
4633
|
if (pin_number < 0) return;
|
4626
|
4634
|
|
4627
|
|
- for (uint8_t i = 0; i < COUNT(sensitive_pins); i++)
|
4628
|
|
- if (pin_number == sensitive_pins[i]) {
|
4629
|
|
- SERIAL_ERROR_START;
|
4630
|
|
- SERIAL_ERRORLNPGM(MSG_ERR_PROTECTED_PIN);
|
4631
|
|
- return;
|
4632
|
|
- }
|
|
4635
|
+ if (pin_is_protected(pin_number)) {
|
|
4636
|
+ SERIAL_ERROR_START;
|
|
4637
|
+ SERIAL_ERRORLNPGM(MSG_ERR_PROTECTED_PIN);
|
|
4638
|
+ return;
|
|
4639
|
+ }
|
4633
|
4640
|
|
4634
|
4641
|
pinMode(pin_number, OUTPUT);
|
4635
|
4642
|
digitalWrite(pin_number, pin_status);
|
|
@@ -6050,43 +6057,31 @@ inline void gcode_M221() {
|
6050
|
6057
|
*/
|
6051
|
6058
|
inline void gcode_M226() {
|
6052
|
6059
|
if (code_seen('P')) {
|
6053
|
|
- int pin_number = code_value_int();
|
6054
|
|
- int pin_state = code_seen('S') ? code_value_int() : -1; // required pin state - default is inverted
|
|
6060
|
+ int pin_number = code_value_int(),
|
|
6061
|
+ pin_state = code_seen('S') ? code_value_int() : -1; // required pin state - default is inverted
|
6055
|
6062
|
|
6056
|
|
- if (pin_state >= -1 && pin_state <= 1) {
|
6057
|
|
-
|
6058
|
|
- for (uint8_t i = 0; i < COUNT(sensitive_pins); i++) {
|
6059
|
|
- if (sensitive_pins[i] == pin_number) {
|
6060
|
|
- pin_number = -1;
|
6061
|
|
- break;
|
6062
|
|
- }
|
6063
|
|
- }
|
|
6063
|
+ if (pin_state >= -1 && pin_state <= 1 && pin_number > -1 && !pin_is_protected(pin_number)) {
|
6064
|
6064
|
|
6065
|
|
- if (pin_number > -1) {
|
6066
|
|
- int target = LOW;
|
|
6065
|
+ int target = LOW;
|
6067
|
6066
|
|
6068
|
|
- stepper.synchronize();
|
6069
|
|
-
|
6070
|
|
- pinMode(pin_number, INPUT);
|
6071
|
|
-
|
6072
|
|
- switch (pin_state) {
|
6073
|
|
- case 1:
|
6074
|
|
- target = HIGH;
|
6075
|
|
- break;
|
6076
|
|
-
|
6077
|
|
- case 0:
|
6078
|
|
- target = LOW;
|
6079
|
|
- break;
|
|
6067
|
+ stepper.synchronize();
|
6080
|
6068
|
|
6081
|
|
- case -1:
|
6082
|
|
- target = !digitalRead(pin_number);
|
6083
|
|
- break;
|
6084
|
|
- }
|
|
6069
|
+ pinMode(pin_number, INPUT);
|
|
6070
|
+ switch (pin_state) {
|
|
6071
|
+ case 1:
|
|
6072
|
+ target = HIGH;
|
|
6073
|
+ break;
|
|
6074
|
+ case 0:
|
|
6075
|
+ target = LOW;
|
|
6076
|
+ break;
|
|
6077
|
+ case -1:
|
|
6078
|
+ target = !digitalRead(pin_number);
|
|
6079
|
+ break;
|
|
6080
|
+ }
|
6085
|
6081
|
|
6086
|
|
- while (digitalRead(pin_number) != target) idle();
|
|
6082
|
+ while (digitalRead(pin_number) != target) idle();
|
6087
|
6083
|
|
6088
|
|
- } // pin_number > -1
|
6089
|
|
- } // pin_state -1 0 1
|
|
6084
|
+ } // pin_state -1 0 1 && pin_number > -1
|
6090
|
6085
|
} // code_seen('P')
|
6091
|
6086
|
}
|
6092
|
6087
|
|