Ensure pins set to INPUT after attachInterrupt (#10928)
This commit is contained in:
parent
d8b983f624
commit
a426986df8
|
@ -56,40 +56,40 @@ void endstop_ISR(void) { endstops.check_possible_change(); }
|
|||
|
||||
void setup_endstop_interrupts(void) {
|
||||
#if HAS_X_MAX
|
||||
SET_INPUT(X_MAX_PIN);
|
||||
attachInterrupt(X_MAX_PIN, endstop_ISR, CHANGE); // assign it
|
||||
SET_INPUT(X_MAX_PIN);
|
||||
#endif
|
||||
#if HAS_X_MIN
|
||||
SET_INPUT(X_MIN_PIN);
|
||||
attachInterrupt(X_MIN_PIN, endstop_ISR, CHANGE);
|
||||
SET_INPUT(X_MIN_PIN);
|
||||
#endif
|
||||
#if HAS_Y_MAX
|
||||
SET_INPUT(Y_MAX_PIN);
|
||||
attachInterrupt(Y_MAX_PIN, endstop_ISR, CHANGE);
|
||||
SET_INPUT(Y_MAX_PIN);
|
||||
#endif
|
||||
#if HAS_Y_MIN
|
||||
SET_INPUT(Y_MIN_PIN);
|
||||
attachInterrupt(Y_MIN_PIN, endstop_ISR, CHANGE);
|
||||
SET_INPUT(Y_MIN_PIN);
|
||||
#endif
|
||||
#if HAS_Z_MAX
|
||||
SET_INPUT(Z_MAX_PIN);
|
||||
attachInterrupt(Z_MAX_PIN, endstop_ISR, CHANGE);
|
||||
SET_INPUT(Z_MAX_PIN);
|
||||
#endif
|
||||
#if HAS_Z_MIN
|
||||
SET_INPUT(Z_MIN_PIN);
|
||||
attachInterrupt(Z_MIN_PIN, endstop_ISR, CHANGE);
|
||||
SET_INPUT(Z_MIN_PIN);
|
||||
#endif
|
||||
#if HAS_Z2_MAX
|
||||
SET_INPUT(Z2_MAX_PIN);
|
||||
attachInterrupt(Z2_MAX_PIN, endstop_ISR, CHANGE);
|
||||
SET_INPUT(Z2_MAX_PIN);
|
||||
#endif
|
||||
#if HAS_Z2_MIN
|
||||
SET_INPUT(Z2_MIN_PIN);
|
||||
attachInterrupt(Z2_MIN_PIN, endstop_ISR, CHANGE);
|
||||
SET_INPUT(Z2_MIN_PIN);
|
||||
#endif
|
||||
#if HAS_Z_MIN_PROBE_PIN
|
||||
SET_INPUT(Z_MIN_PROBE_PIN);
|
||||
attachInterrupt(Z_MIN_PROBE_PIN, endstop_ISR, CHANGE);
|
||||
SET_INPUT(Z_MIN_PROBE_PIN);
|
||||
#endif
|
||||
}
|
||||
|
||||
|
|
|
@ -31,40 +31,40 @@ void endstop_ISR(void) { endstops.check_possible_change(); }
|
|||
|
||||
void setup_endstop_interrupts(void) {
|
||||
#if HAS_X_MAX
|
||||
pinMode(X_MAX_PIN, INPUT);
|
||||
attachInterrupt(X_MAX_PIN, endstop_ISR, CHANGE); // assign it
|
||||
attachInterrupt(X_MAX_PIN, endstop_ISR, CHANGE);
|
||||
SET_INPUT(X_MAX_PIN);
|
||||
#endif
|
||||
#if HAS_X_MIN
|
||||
pinMode(X_MIN_PIN, INPUT);
|
||||
attachInterrupt(X_MIN_PIN, endstop_ISR, CHANGE);
|
||||
SET_INPUT(X_MIN_PIN);
|
||||
#endif
|
||||
#if HAS_Y_MAX
|
||||
pinMode(Y_MAX_PIN, INPUT);
|
||||
attachInterrupt(Y_MAX_PIN, endstop_ISR, CHANGE);
|
||||
SET_INPUT(Y_MAX_PIN);
|
||||
#endif
|
||||
#if HAS_Y_MIN
|
||||
pinMode(Y_MIN_PIN, INPUT);
|
||||
attachInterrupt(Y_MIN_PIN, endstop_ISR, CHANGE);
|
||||
SET_INPUT(Y_MIN_PIN);
|
||||
#endif
|
||||
#if HAS_Z_MAX
|
||||
pinMode(Z_MAX_PIN, INPUT);
|
||||
attachInterrupt(Z_MAX_PIN, endstop_ISR, CHANGE);
|
||||
SET_INPUT(Z_MAX_PIN);
|
||||
#endif
|
||||
#if HAS_Z_MIN
|
||||
pinMode(Z_MIN_PIN, INPUT);
|
||||
attachInterrupt(Z_MIN_PIN, endstop_ISR, CHANGE);
|
||||
SET_INPUT(Z_MIN_PIN);
|
||||
#endif
|
||||
#if HAS_Z2_MAX
|
||||
pinMode(Z2_MAX_PIN, INPUT);
|
||||
attachInterrupt(Z2_MAX_PIN, endstop_ISR, CHANGE);
|
||||
SET_INPUT(Z2_MAX_PIN);
|
||||
#endif
|
||||
#if HAS_Z2_MIN
|
||||
pinMode(Z2_MIN_PIN, INPUT);
|
||||
attachInterrupt(Z2_MIN_PIN, endstop_ISR, CHANGE);
|
||||
SET_INPUT(Z2_MIN_PIN);
|
||||
#endif
|
||||
#if HAS_Z_MIN_PROBE_PIN
|
||||
pinMode(Z_MIN_PROBE_PIN, INPUT);
|
||||
attachInterrupt(Z_MIN_PROBE_PIN, endstop_ISR, CHANGE);
|
||||
SET_INPUT(Z_MIN_PROBE_PIN);
|
||||
#endif
|
||||
}
|
||||
|
||||
|
|
|
@ -33,40 +33,40 @@ void endstop_ISR(void) { endstops.check_possible_change(); }
|
|||
|
||||
void setup_endstop_interrupts(void) {
|
||||
#if HAS_X_MAX
|
||||
pinMode(X_MAX_PIN, INPUT);
|
||||
attachInterrupt(X_MAX_PIN, endstop_ISR, CHANGE); // assign it
|
||||
attachInterrupt(X_MAX_PIN, endstop_ISR, CHANGE);
|
||||
SET_INPUT(X_MAX_PIN);
|
||||
#endif
|
||||
#if HAS_X_MIN
|
||||
pinMode(X_MIN_PIN, INPUT);
|
||||
attachInterrupt(X_MIN_PIN, endstop_ISR, CHANGE);
|
||||
SET_INPUT(X_MIN_PIN);
|
||||
#endif
|
||||
#if HAS_Y_MAX
|
||||
pinMode(Y_MAX_PIN, INPUT);
|
||||
attachInterrupt(Y_MAX_PIN, endstop_ISR, CHANGE);
|
||||
SET_INPUT(Y_MAX_PIN);
|
||||
#endif
|
||||
#if HAS_Y_MIN
|
||||
pinMode(Y_MIN_PIN, INPUT);
|
||||
attachInterrupt(Y_MIN_PIN, endstop_ISR, CHANGE);
|
||||
SET_INPUT(Y_MIN_PIN);
|
||||
#endif
|
||||
#if HAS_Z_MAX
|
||||
pinMode(Z_MAX_PIN, INPUT);
|
||||
attachInterrupt(Z_MAX_PIN, endstop_ISR, CHANGE);
|
||||
SET_INPUT(Z_MAX_PIN);
|
||||
#endif
|
||||
#if HAS_Z_MIN
|
||||
pinMode(Z_MIN_PIN, INPUT);
|
||||
attachInterrupt(Z_MIN_PIN, endstop_ISR, CHANGE);
|
||||
SET_INPUT(Z_MIN_PIN);
|
||||
#endif
|
||||
#if HAS_Z2_MAX
|
||||
pinMode(Z2_MAX_PIN, INPUT);
|
||||
attachInterrupt(Z2_MAX_PIN, endstop_ISR, CHANGE);
|
||||
SET_INPUT(Z2_MAX_PIN);
|
||||
#endif
|
||||
#if HAS_Z2_MIN
|
||||
pinMode(Z2_MIN_PIN, INPUT);
|
||||
attachInterrupt(Z2_MIN_PIN, endstop_ISR, CHANGE);
|
||||
SET_INPUT(Z2_MIN_PIN);
|
||||
#endif
|
||||
#if HAS_Z_MIN_PROBE_PIN
|
||||
pinMode(Z_MIN_PROBE_PIN, INPUT);
|
||||
attachInterrupt(Z_MIN_PROBE_PIN, endstop_ISR, CHANGE);
|
||||
SET_INPUT(Z_MIN_PROBE_PIN);
|
||||
#endif
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in a new issue