Protected pin err for M226
This commit is contained in:
parent
4b90cd8ead
commit
968a5d2e63
@ -264,6 +264,11 @@ bool pin_is_protected(const pin_t pin) {
|
||||
return false;
|
||||
}
|
||||
|
||||
void protected_pin_err() {
|
||||
SERIAL_ERROR_START();
|
||||
SERIAL_ERRORLNPGM(MSG_ERR_PROTECTED_PIN);
|
||||
}
|
||||
|
||||
void quickstop_stepper() {
|
||||
planner.quick_stop();
|
||||
planner.synchronize();
|
||||
|
@ -219,6 +219,7 @@ extern millis_t max_inactive_time, stepper_inactive_time;
|
||||
#endif
|
||||
|
||||
bool pin_is_protected(const pin_t pin);
|
||||
void protected_pin_err();
|
||||
|
||||
#if HAS_SUICIDE
|
||||
inline void suicide() { OUT_WRITE(SUICIDE_PIN, LOW); }
|
||||
|
@ -35,7 +35,7 @@
|
||||
#endif
|
||||
|
||||
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),
|
||||
start = PARSED_PIN_INDEX('S', 0),
|
||||
end = PARSED_PIN_INDEX('E', NUM_DIGITAL_PINS - 1),
|
||||
@ -43,14 +43,14 @@ inline void toggle_pins() {
|
||||
|
||||
for (uint8_t i = start; i <= end; i++) {
|
||||
pin_t pin = GET_PIN_MAP_PIN(i);
|
||||
//report_pin_state_extended(pin, I_flag, false);
|
||||
//report_pin_state_extended(pin, ignore_protection, false);
|
||||
if (!VALID_PIN(pin)) continue;
|
||||
if (!I_flag && pin_is_protected(pin)) {
|
||||
report_pin_state_extended(pin, I_flag, true, "Untouched ");
|
||||
if (!ignore_protection && pin_is_protected(pin)) {
|
||||
report_pin_state_extended(pin, ignore_protection, true, "Untouched ");
|
||||
SERIAL_EOL();
|
||||
}
|
||||
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 (pin == TEENSY_E2) {
|
||||
SET_OUTPUT(TEENSY_E2);
|
||||
@ -275,7 +275,7 @@ void GcodeSuite::M43() {
|
||||
for (uint8_t i = first_pin; i <= last_pin; i++) {
|
||||
pin_t pin = GET_PIN_MAP_PIN(i);
|
||||
if (!VALID_PIN(pin)) continue;
|
||||
if (pin_is_protected(pin) && !ignore_protection) continue;
|
||||
if (!ignore_protection && pin_is_protected(pin)) continue;
|
||||
pinMode(pin, INPUT_PULLUP);
|
||||
delay(1);
|
||||
/*
|
||||
@ -295,7 +295,7 @@ void GcodeSuite::M43() {
|
||||
for (uint8_t i = first_pin; i <= last_pin; i++) {
|
||||
pin_t pin = GET_PIN_MAP_PIN(i);
|
||||
if (!VALID_PIN(pin)) continue;
|
||||
if (pin_is_protected(pin) && !ignore_protection) continue;
|
||||
if (!ignore_protection && pin_is_protected(pin)) continue;
|
||||
const byte val =
|
||||
/*
|
||||
IS_ANALOG(pin)
|
||||
|
@ -33,27 +33,20 @@ void GcodeSuite::M226() {
|
||||
pin_state = parser.intval('S', -1); // required pin state - default is inverted
|
||||
const pin_t pin = GET_PIN_MAP_PIN(pin_number);
|
||||
|
||||
if (WITHIN(pin_state, -1, 1) && pin > -1 && !pin_is_protected(pin)) {
|
||||
|
||||
int target = LOW;
|
||||
|
||||
planner.synchronize();
|
||||
|
||||
pinMode(pin, INPUT);
|
||||
switch (pin_state) {
|
||||
case 1:
|
||||
target = HIGH;
|
||||
break;
|
||||
case 0:
|
||||
target = LOW;
|
||||
break;
|
||||
case -1:
|
||||
target = !digitalRead(pin);
|
||||
break;
|
||||
if (WITHIN(pin_state, -1, 1) && pin > -1) {
|
||||
if (pin_is_protected(pin))
|
||||
protected_pin_err();
|
||||
else {
|
||||
int target = LOW;
|
||||
planner.synchronize();
|
||||
pinMode(pin, INPUT);
|
||||
switch (pin_state) {
|
||||
case 1: target = HIGH; break;
|
||||
case 0: target = LOW; break;
|
||||
case -1: target = !digitalRead(pin); break;
|
||||
}
|
||||
while (digitalRead(pin) != target) idle();
|
||||
}
|
||||
|
||||
while (digitalRead(pin) != target) idle();
|
||||
|
||||
} // pin_state -1 0 1 && pin > -1
|
||||
} // parser.seen('P')
|
||||
}
|
||||
|
@ -41,11 +41,8 @@ void GcodeSuite::M42() {
|
||||
if (pin_index < 0) return;
|
||||
|
||||
const pin_t pin = GET_PIN_MAP_PIN(pin_index);
|
||||
if (pin_is_protected(pin)) {
|
||||
SERIAL_ERROR_START();
|
||||
SERIAL_ERRORLNPGM(MSG_ERR_PROTECTED_PIN);
|
||||
return;
|
||||
}
|
||||
|
||||
if (pin_is_protected(pin_number)) return protected_pin_err();
|
||||
|
||||
pinMode(pin, OUTPUT);
|
||||
digitalWrite(pin, pin_status);
|
||||
|
Loading…
Reference in New Issue
Block a user