|
|
@ -51,39 +51,39 @@ |
|
|
|
|
|
|
|
void setup_endstop_interrupts(void) { |
|
|
|
#if HAS_X_MAX |
|
|
|
pinMode(X_MAX_PIN, INPUT); |
|
|
|
SET_INPUT(X_MAX_PIN); |
|
|
|
attachInterrupt(X_MAX_PIN, endstop_ISR, CHANGE); // assign it
|
|
|
|
#endif |
|
|
|
#if HAS_X_MIN |
|
|
|
pinMode(X_MIN_PIN, INPUT); |
|
|
|
SET_INPUT(X_MIN_PIN); |
|
|
|
attachInterrupt(X_MIN_PIN, endstop_ISR, CHANGE); |
|
|
|
#endif |
|
|
|
#if HAS_Y_MAX |
|
|
|
pinMode(Y_MAX_PIN, INPUT); |
|
|
|
SET_INPUT(Y_MAX_PIN); |
|
|
|
attachInterrupt(Y_MAX_PIN, endstop_ISR, CHANGE); |
|
|
|
#endif |
|
|
|
#if HAS_Y_MIN |
|
|
|
pinMode(Y_MIN_PIN, INPUT); |
|
|
|
SET_INPUT(Y_MIN_PIN); |
|
|
|
attachInterrupt(Y_MIN_PIN, endstop_ISR, CHANGE); |
|
|
|
#endif |
|
|
|
#if HAS_Z_MAX |
|
|
|
pinMode(Z_MAX_PIN, INPUT); |
|
|
|
SET_INPUT(Z_MAX_PIN); |
|
|
|
attachInterrupt(Z_MAX_PIN, endstop_ISR, CHANGE); |
|
|
|
#endif |
|
|
|
#if HAS_Z_MIN |
|
|
|
pinMode(Z_MIN_PIN, INPUT); |
|
|
|
SET_INPUT(Z_MIN_PIN); |
|
|
|
attachInterrupt(Z_MIN_PIN, endstop_ISR, CHANGE); |
|
|
|
#endif |
|
|
|
#if HAS_Z2_MAX |
|
|
|
pinMode(Z2_MAX_PIN, INPUT); |
|
|
|
SET_INPUT(Z2_MAX_PIN); |
|
|
|
attachInterrupt(Z2_MAX_PIN, endstop_ISR, CHANGE); |
|
|
|
#endif |
|
|
|
#if HAS_Z2_MIN |
|
|
|
pinMode(Z2_MIN_PIN, INPUT); |
|
|
|
SET_INPUT(Z2_MIN_PIN); |
|
|
|
attachInterrupt(Z2_MIN_PIN, endstop_ISR, CHANGE); |
|
|
|
#endif |
|
|
|
#if HAS_Z_MIN_PROBE_PIN |
|
|
|
pinMode(Z_MIN_PROBE_PIN, INPUT); |
|
|
|
SET_INPUT(Z_MIN_PROBE_PIN); |
|
|
|
attachInterrupt(Z_MIN_PROBE_PIN, endstop_ISR, CHANGE); |
|
|
|
#endif |
|
|
|
} |
|
|
|