Protected pin err for M226
This commit is contained in:
@@ -7242,6 +7242,11 @@ static bool pin_is_protected(const pin_t pin) {
|
|||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
inline void protected_pin_err() {
|
||||||
|
SERIAL_ERROR_START();
|
||||||
|
SERIAL_ERRORLNPGM(MSG_ERR_PROTECTED_PIN);
|
||||||
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* M42: Change pin status via GCode
|
* M42: Change pin status via GCode
|
||||||
*
|
*
|
||||||
@@ -7255,11 +7260,7 @@ inline void gcode_M42() {
|
|||||||
const pin_t pin_number = parser.byteval('P', LED_PIN);
|
const pin_t pin_number = parser.byteval('P', LED_PIN);
|
||||||
if (pin_number < 0) return;
|
if (pin_number < 0) return;
|
||||||
|
|
||||||
if (pin_is_protected(pin_number)) {
|
if (pin_is_protected(pin_number)) return protected_pin_err();
|
||||||
SERIAL_ERROR_START();
|
|
||||||
SERIAL_ERRORLNPGM(MSG_ERR_PROTECTED_PIN);
|
|
||||||
return;
|
|
||||||
}
|
|
||||||
|
|
||||||
pinMode(pin_number, OUTPUT);
|
pinMode(pin_number, OUTPUT);
|
||||||
digitalWrite(pin_number, pin_status);
|
digitalWrite(pin_number, pin_status);
|
||||||
@@ -7285,21 +7286,21 @@ inline void gcode_M42() {
|
|||||||
#include "pinsDebug.h"
|
#include "pinsDebug.h"
|
||||||
|
|
||||||
inline void toggle_pins() {
|
inline void toggle_pins() {
|
||||||
const bool I_flag = parser.boolval('I');
|
const bool ignore_protection = parser.boolval('I');
|
||||||
const int repeat = parser.intval('R', 1),
|
const int repeat = parser.intval('R', 1),
|
||||||
start = parser.intval('S'),
|
start = parser.intval('S'),
|
||||||
end = parser.intval('L', NUM_DIGITAL_PINS - 1),
|
end = parser.intval('L', NUM_DIGITAL_PINS - 1),
|
||||||
wait = parser.intval('W', 500);
|
wait = parser.intval('W', 500);
|
||||||
|
|
||||||
for (uint8_t pin = start; pin <= end; pin++) {
|
for (uint8_t pin = start; pin <= end; pin++) {
|
||||||
//report_pin_state_extended(pin, I_flag, false);
|
//report_pin_state_extended(pin, ignore_protection, false);
|
||||||
|
|
||||||
if (!I_flag && pin_is_protected(pin)) {
|
if (!ignore_protection && pin_is_protected(pin)) {
|
||||||
report_pin_state_extended(pin, I_flag, true, "Untouched ");
|
report_pin_state_extended(pin, ignore_protection, true, "Untouched ");
|
||||||
SERIAL_EOL();
|
SERIAL_EOL();
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
report_pin_state_extended(pin, I_flag, true, "Pulsing ");
|
report_pin_state_extended(pin, ignore_protection, true, "Pulsing ");
|
||||||
#if AVR_AT90USB1286_FAMILY // Teensy IDEs don't know about these pins so must use FASTIO
|
#if AVR_AT90USB1286_FAMILY // Teensy IDEs don't know about these pins so must use FASTIO
|
||||||
if (pin == TEENSY_E2) {
|
if (pin == TEENSY_E2) {
|
||||||
SET_OUTPUT(TEENSY_E2);
|
SET_OUTPUT(TEENSY_E2);
|
||||||
@@ -7518,7 +7519,7 @@ inline void gcode_M42() {
|
|||||||
SERIAL_PROTOCOLLNPGM("Watching pins");
|
SERIAL_PROTOCOLLNPGM("Watching pins");
|
||||||
byte pin_state[last_pin - first_pin + 1];
|
byte pin_state[last_pin - first_pin + 1];
|
||||||
for (pin_t pin = first_pin; pin <= last_pin; pin++) {
|
for (pin_t pin = first_pin; pin <= last_pin; pin++) {
|
||||||
if (pin_is_protected(pin) && !ignore_protection) continue;
|
if (!ignore_protection && pin_is_protected(pin)) continue;
|
||||||
pinMode(pin, INPUT_PULLUP);
|
pinMode(pin, INPUT_PULLUP);
|
||||||
delay(1);
|
delay(1);
|
||||||
/*
|
/*
|
||||||
@@ -7536,7 +7537,7 @@ inline void gcode_M42() {
|
|||||||
|
|
||||||
for (;;) {
|
for (;;) {
|
||||||
for (pin_t pin = first_pin; pin <= last_pin; pin++) {
|
for (pin_t pin = first_pin; pin <= last_pin; pin++) {
|
||||||
if (pin_is_protected(pin) && !ignore_protection) continue;
|
if (!ignore_protection && pin_is_protected(pin)) continue;
|
||||||
const byte val =
|
const byte val =
|
||||||
/*
|
/*
|
||||||
IS_ANALOG(pin)
|
IS_ANALOG(pin)
|
||||||
@@ -9462,30 +9463,21 @@ inline void gcode_M221() {
|
|||||||
*/
|
*/
|
||||||
inline void gcode_M226() {
|
inline void gcode_M226() {
|
||||||
if (parser.seen('P')) {
|
if (parser.seen('P')) {
|
||||||
const int pin = parser.value_int(),
|
const int pin = parser.value_int(), pin_state = parser.intval('S', -1);
|
||||||
pin_state = parser.intval('S', -1); // required pin state - default is inverted
|
if (WITHIN(pin_state, -1, 1) && pin > -1) {
|
||||||
|
if (pin_is_protected(pin))
|
||||||
if (WITHIN(pin_state, -1, 1) && pin > -1 && !pin_is_protected(pin)) {
|
protected_pin_err();
|
||||||
|
else {
|
||||||
int target = LOW;
|
int target = LOW;
|
||||||
|
planner.synchronize();
|
||||||
planner.synchronize();
|
pinMode(pin, INPUT);
|
||||||
|
switch (pin_state) {
|
||||||
pinMode(pin, INPUT);
|
case 1: target = HIGH; break;
|
||||||
switch (pin_state) {
|
case 0: target = LOW; break;
|
||||||
case 1:
|
case -1: target = !digitalRead(pin); break;
|
||||||
target = HIGH;
|
}
|
||||||
break;
|
while (digitalRead(pin) != target) idle();
|
||||||
case 0:
|
|
||||||
target = LOW;
|
|
||||||
break;
|
|
||||||
case -1:
|
|
||||||
target = !digitalRead(pin);
|
|
||||||
break;
|
|
||||||
}
|
}
|
||||||
|
|
||||||
while (digitalRead(pin) != target) idle();
|
|
||||||
|
|
||||||
} // pin_state -1 0 1 && pin > -1
|
} // pin_state -1 0 1 && pin > -1
|
||||||
} // parser.seen('P')
|
} // parser.seen('P')
|
||||||
}
|
}
|
||||||
|
Reference in New Issue
Block a user