Quad Z stepper support (#16277)

This commit is contained in:
InsanityAutomation 2020-01-20 00:35:07 -05:00 committed by Scott Lahteine
parent f36f084465
commit 0fcf2b1110
52 changed files with 1198 additions and 415 deletions

View file

@ -670,6 +670,7 @@
//#define Y2_DRIVER_TYPE A4988 //#define Y2_DRIVER_TYPE A4988
//#define Z2_DRIVER_TYPE A4988 //#define Z2_DRIVER_TYPE A4988
//#define Z3_DRIVER_TYPE A4988 //#define Z3_DRIVER_TYPE A4988
//#define Z4_DRIVER_TYPE A4988
//#define E0_DRIVER_TYPE A4988 //#define E0_DRIVER_TYPE A4988
//#define E1_DRIVER_TYPE A4988 //#define E1_DRIVER_TYPE A4988
//#define E2_DRIVER_TYPE A4988 //#define E2_DRIVER_TYPE A4988

View file

@ -479,7 +479,7 @@
//#define X_DUAL_ENDSTOPS //#define X_DUAL_ENDSTOPS
#if ENABLED(X_DUAL_ENDSTOPS) #if ENABLED(X_DUAL_ENDSTOPS)
#define X2_USE_ENDSTOP _XMAX_ #define X2_USE_ENDSTOP _XMAX_
#define X_DUAL_ENDSTOPS_ADJUSTMENT 0 #define X2_ENDSTOP_ADJUSTMENT 0
#endif #endif
#endif #endif
@ -489,27 +489,28 @@
//#define Y_DUAL_ENDSTOPS //#define Y_DUAL_ENDSTOPS
#if ENABLED(Y_DUAL_ENDSTOPS) #if ENABLED(Y_DUAL_ENDSTOPS)
#define Y2_USE_ENDSTOP _YMAX_ #define Y2_USE_ENDSTOP _YMAX_
#define Y_DUAL_ENDSTOPS_ADJUSTMENT 0 #define Y2_ENDSTOP_ADJUSTMENT 0
#endif #endif
#endif #endif
//#define Z_DUAL_STEPPER_DRIVERS //
#if ENABLED(Z_DUAL_STEPPER_DRIVERS) // For Z set the number of stepper drivers
//#define Z_DUAL_ENDSTOPS //
#if ENABLED(Z_DUAL_ENDSTOPS) #define NUM_Z_STEPPER_DRIVERS 1 // (1-4) Z options change based on how many
#define Z2_USE_ENDSTOP _XMAX_
#define Z_DUAL_ENDSTOPS_ADJUSTMENT 0
#endif
#endif
//#define Z_TRIPLE_STEPPER_DRIVERS #if NUM_Z_STEPPER_DRIVERS > 1
#if ENABLED(Z_TRIPLE_STEPPER_DRIVERS) //#define Z_MULTI_ENDSTOPS
//#define Z_TRIPLE_ENDSTOPS #if ENABLED(Z_MULTI_ENDSTOPS)
#if ENABLED(Z_TRIPLE_ENDSTOPS)
#define Z2_USE_ENDSTOP _XMAX_ #define Z2_USE_ENDSTOP _XMAX_
#define Z2_ENDSTOP_ADJUSTMENT 0
#if NUM_Z_STEPPER_DRIVERS >= 3
#define Z3_USE_ENDSTOP _YMAX_ #define Z3_USE_ENDSTOP _YMAX_
#define Z_TRIPLE_ENDSTOPS_ADJUSTMENT2 0 #define Z3_ENDSTOP_ADJUSTMENT 0
#define Z_TRIPLE_ENDSTOPS_ADJUSTMENT3 0 #endif
#if NUM_Z_STEPPER_DRIVERS >= 4
#define Z4_USE_ENDSTOP _ZMAX_
#define Z4_ENDSTOP_ADJUSTMENT 0
#endif
#endif #endif
#endif #endif
@ -1898,6 +1899,12 @@
#define Z3_MICROSTEPS 16 #define Z3_MICROSTEPS 16
#endif #endif
#if AXIS_DRIVER_TYPE_Z4(TMC26X)
#define Z4_MAX_CURRENT 1000
#define Z4_SENSE_RESISTOR 91
#define Z4_MICROSTEPS 16
#endif
#if AXIS_DRIVER_TYPE_E0(TMC26X) #if AXIS_DRIVER_TYPE_E0(TMC26X)
#define E0_MAX_CURRENT 1000 #define E0_MAX_CURRENT 1000
#define E0_SENSE_RESISTOR 91 #define E0_SENSE_RESISTOR 91
@ -2015,6 +2022,14 @@
#define Z3_CHAIN_POS -1 #define Z3_CHAIN_POS -1
#endif #endif
#if AXIS_IS_TMC(Z4)
#define Z4_CURRENT 800
#define Z4_CURRENT_HOME Z4_CURRENT
#define Z4_MICROSTEPS 16
#define Z4_RSENSE 0.11
#define Z4_CHAIN_POS -1
#endif
#if AXIS_IS_TMC(E0) #if AXIS_IS_TMC(E0)
#define E0_CURRENT 800 #define E0_CURRENT 800
#define E0_MICROSTEPS 16 #define E0_MICROSTEPS 16
@ -2104,6 +2119,7 @@
#define Y2_SLAVE_ADDRESS 0 #define Y2_SLAVE_ADDRESS 0
#define Z2_SLAVE_ADDRESS 0 #define Z2_SLAVE_ADDRESS 0
#define Z3_SLAVE_ADDRESS 0 #define Z3_SLAVE_ADDRESS 0
#define Z4_SLAVE_ADDRESS 0
#define E0_SLAVE_ADDRESS 0 #define E0_SLAVE_ADDRESS 0
#define E1_SLAVE_ADDRESS 0 #define E1_SLAVE_ADDRESS 0
#define E2_SLAVE_ADDRESS 0 #define E2_SLAVE_ADDRESS 0
@ -2179,6 +2195,7 @@
#define Z_HYBRID_THRESHOLD 3 #define Z_HYBRID_THRESHOLD 3
#define Z2_HYBRID_THRESHOLD 3 #define Z2_HYBRID_THRESHOLD 3
#define Z3_HYBRID_THRESHOLD 3 #define Z3_HYBRID_THRESHOLD 3
#define Z4_HYBRID_THRESHOLD 3
#define E0_HYBRID_THRESHOLD 30 #define E0_HYBRID_THRESHOLD 30
#define E1_HYBRID_THRESHOLD 30 #define E1_HYBRID_THRESHOLD 30
#define E2_HYBRID_THRESHOLD 30 #define E2_HYBRID_THRESHOLD 30
@ -2344,6 +2361,15 @@
#define Z3_SLEW_RATE 1 #define Z3_SLEW_RATE 1
#endif #endif
#if AXIS_IS_L64XX(Z4)
#define Z4_MICROSTEPS 128
#define Z4_OVERCURRENT 2000
#define Z4_STALLCURRENT 1500
#define Z4_MAX_VOLTAGE 127
#define Z4_CHAIN_POS -1
#define Z4_SLEW_RATE 1
#endif
#if AXIS_IS_L64XX(E0) #if AXIS_IS_L64XX(E0)
#define E0_MICROSTEPS 128 #define E0_MICROSTEPS 128
#define E0_OVERCURRENT 2000 #define E0_OVERCURRENT 2000
@ -2407,7 +2433,7 @@
* I not present or I0 or I1 - X, Y, Z or E0 * I not present or I0 or I1 - X, Y, Z or E0
* I2 - X2, Y2, Z2 or E1 * I2 - X2, Y2, Z2 or E1
* I3 - Z3 or E3 * I3 - Z3 or E3
* I4 - E4 * I4 - Z4 or E4
* I5 - E5 * I5 - E5
* M916 - Increase drive level until get thermal warning * M916 - Increase drive level until get thermal warning
* M917 - Find minimum current thresholds * M917 - Find minimum current thresholds

View file

@ -232,6 +232,22 @@ void setup_endstop_interrupts() {
pciSetup(Z3_MIN_PIN); pciSetup(Z3_MIN_PIN);
#endif #endif
#endif #endif
#if HAS_Z4_MAX
#if (digitalPinToInterrupt(Z4_MAX_PIN) != NOT_AN_INTERRUPT)
_ATTACH(Z4_MAX_PIN);
#else
static_assert(digitalPinHasPCICR(Z4_MAX_PIN), "Z4_MAX_PIN is not interrupt-capable");
pciSetup(Z4_MAX_PIN);
#endif
#endif
#if HAS_Z4_MIN
#if (digitalPinToInterrupt(Z4_MIN_PIN) != NOT_AN_INTERRUPT)
_ATTACH(Z4_MIN_PIN);
#else
static_assert(digitalPinHasPCICR(Z4_MIN_PIN), "Z4_MIN_PIN is not interrupt-capable");
pciSetup(Z4_MIN_PIN);
#endif
#endif
#if HAS_Z_MIN_PROBE_PIN #if HAS_Z_MIN_PROBE_PIN
#if (digitalPinToInterrupt(Z_MIN_PROBE_PIN) != NOT_AN_INTERRUPT) #if (digitalPinToInterrupt(Z_MIN_PROBE_PIN) != NOT_AN_INTERRUPT)
_ATTACH(Z_MIN_PROBE_PIN); _ATTACH(Z_MIN_PROBE_PIN);

View file

@ -77,6 +77,12 @@ void setup_endstop_interrupts() {
#if HAS_Z3_MIN #if HAS_Z3_MIN
_ATTACH(Z3_MIN_PIN); _ATTACH(Z3_MIN_PIN);
#endif #endif
#if HAS_Z4_MAX
_ATTACH(Z4_MAX_PIN);
#endif
#if HAS_Z4_MIN
_ATTACH(Z4_MIN_PIN);
#endif
#if HAS_Z_MIN_PROBE_PIN #if HAS_Z_MIN_PROBE_PIN
_ATTACH(Z_MIN_PROBE_PIN); _ATTACH(Z_MIN_PROBE_PIN);
#endif #endif

View file

@ -72,6 +72,12 @@ void setup_endstop_interrupts() {
#if HAS_Z3_MIN #if HAS_Z3_MIN
_ATTACH(Z3_MIN_PIN); _ATTACH(Z3_MIN_PIN);
#endif #endif
#if HAS_Z4_MAX
_ATTACH(Z4_MAX_PIN);
#endif
#if HAS_Z4_MIN
_ATTACH(Z4_MIN_PIN);
#endif
#if HAS_Z_MIN_PROBE_PIN #if HAS_Z_MIN_PROBE_PIN
_ATTACH(Z_MIN_PROBE_PIN); _ATTACH(Z_MIN_PROBE_PIN);
#endif #endif

View file

@ -93,7 +93,7 @@ void setup_endstop_interrupts() {
_ATTACH(Z2_MIN_PIN); _ATTACH(Z2_MIN_PIN);
#endif #endif
#if HAS_Z3_MAX #if HAS_Z3_MAX
#if !LPC1768_PIN_INTERRUPT_M(Z3_MIN_PIN) #if !LPC1768_PIN_INTERRUPT_M(Z3_MAX_PIN)
#error "Z3_MIN_PIN is not INTERRUPT-capable." #error "Z3_MIN_PIN is not INTERRUPT-capable."
#endif #endif
_ATTACH(Z3_MAX_PIN); _ATTACH(Z3_MAX_PIN);
@ -104,6 +104,18 @@ void setup_endstop_interrupts() {
#endif #endif
_ATTACH(Z3_MIN_PIN); _ATTACH(Z3_MIN_PIN);
#endif #endif
#if HAS_Z4_MAX
#if !LPC1768_PIN_INTERRUPT_M(Z4_MAX_PIN)
#error "Z4_MIN_PIN is not INTERRUPT-capable."
#endif
_ATTACH(Z4_MAX_PIN);
#endif
#if HAS_Z4_MIN
#if !LPC1768_PIN_INTERRUPT_M(Z4_MIN_PIN)
#error "Z4_MIN_PIN is not INTERRUPT-capable."
#endif
_ATTACH(Z4_MIN_PIN);
#endif
#if HAS_Z_MIN_PROBE_PIN #if HAS_Z_MIN_PROBE_PIN
#if !LPC1768_PIN_INTERRUPT_M(Z_MIN_PROBE_PIN) #if !LPC1768_PIN_INTERRUPT_M(Z_MIN_PROBE_PIN)
#error "Z_MIN_PROBE_PIN is not INTERRUPT-capable." #error "Z_MIN_PROBE_PIN is not INTERRUPT-capable."

View file

@ -98,6 +98,16 @@
#else #else
#define MATCH_Z3_MIN_EILINE(P) false #define MATCH_Z3_MIN_EILINE(P) false
#endif #endif
#if HAS_Z4_MAX
#define MATCH_Z4_MAX_EILINE(P) MATCH_EILINE(P, Z4_MAX_PIN)
#else
#define MATCH_Z4_MAX_EILINE(P) false
#endif
#if HAS_Z4_MIN
#define MATCH_Z4_MIN_EILINE(P) MATCH_EILINE(P, Z4_MIN_PIN)
#else
#define MATCH_Z4_MIN_EILINE(P) false
#endif
#if HAS_Z_MIN_PROBE_PIN #if HAS_Z_MIN_PROBE_PIN
#define MATCH_Z_MIN_PROBE_EILINE(P) MATCH_EILINE(P, Z_MIN_PROBE_PIN) #define MATCH_Z_MIN_PROBE_EILINE(P) MATCH_EILINE(P, Z_MIN_PROBE_PIN)
#else #else
@ -109,6 +119,7 @@
&& !MATCH_Z_MAX_EILINE(P) && !MATCH_Z_MIN_EILINE(P) \ && !MATCH_Z_MAX_EILINE(P) && !MATCH_Z_MIN_EILINE(P) \
&& !MATCH_Z2_MAX_EILINE(P) && !MATCH_Z2_MIN_EILINE(P) \ && !MATCH_Z2_MAX_EILINE(P) && !MATCH_Z2_MIN_EILINE(P) \
&& !MATCH_Z3_MAX_EILINE(P) && !MATCH_Z3_MIN_EILINE(P) \ && !MATCH_Z3_MAX_EILINE(P) && !MATCH_Z3_MIN_EILINE(P) \
&& !MATCH_Z4_MAX_EILINE(P) && !MATCH_Z4_MIN_EILINE(P) \
&& !MATCH_Z_MIN_PROBE_EILINE(P)) && !MATCH_Z_MIN_PROBE_EILINE(P))
// One ISR for all EXT-Interrupts // One ISR for all EXT-Interrupts
@ -117,67 +128,79 @@ void endstop_ISR() { endstops.update(); }
void setup_endstop_interrupts() { void setup_endstop_interrupts() {
#if HAS_X_MAX #if HAS_X_MAX
#if !AVAILABLE_EILINE(X_MAX_PIN) #if !AVAILABLE_EILINE(X_MAX_PIN)
static_assert(false, "X_MAX_PIN has no EXTINT line available."); #error "X_MAX_PIN has no EXTINT line available."
#endif #endif
attachInterrupt(X_MAX_PIN, endstop_ISR, CHANGE); attachInterrupt(X_MAX_PIN, endstop_ISR, CHANGE);
#endif #endif
#if HAS_X_MIN #if HAS_X_MIN
#if !AVAILABLE_EILINE(X_MIN_PIN) #if !AVAILABLE_EILINE(X_MIN_PIN)
static_assert(false, "X_MIN_PIN has no EXTINT line available."); #error "X_MIN_PIN has no EXTINT line available."
#endif #endif
attachInterrupt(X_MIN_PIN, endstop_ISR, CHANGE); attachInterrupt(X_MIN_PIN, endstop_ISR, CHANGE);
#endif #endif
#if HAS_Y_MAX #if HAS_Y_MAX
#if !AVAILABLE_EILINE(Y_MAX_PIN) #if !AVAILABLE_EILINE(Y_MAX_PIN)
static_assert(false, "Y_MAX_PIN has no EXTINT line available."); #error "Y_MAX_PIN has no EXTINT line available."
#endif #endif
attachInterrupt(Y_MAX_PIN, endstop_ISR, CHANGE); attachInterrupt(Y_MAX_PIN, endstop_ISR, CHANGE);
#endif #endif
#if HAS_Y_MIN #if HAS_Y_MIN
#if !AVAILABLE_EILINE(Y_MIN_PIN) #if !AVAILABLE_EILINE(Y_MIN_PIN)
static_assert(false, "Y_MIN_PIN has no EXTINT line available."); #error "Y_MIN_PIN has no EXTINT line available."
#endif #endif
attachInterrupt(Y_MIN_PIN, endstop_ISR, CHANGE); attachInterrupt(Y_MIN_PIN, endstop_ISR, CHANGE);
#endif #endif
#if HAS_Z_MAX #if HAS_Z_MAX
#if !AVAILABLE_EILINE(Z_MAX_PIN) #if !AVAILABLE_EILINE(Z_MAX_PIN)
static_assert(false, "Z_MAX_PIN has no EXTINT line available."); #error "Z_MAX_PIN has no EXTINT line available."
#endif #endif
attachInterrupt(Z_MAX_PIN, endstop_ISR, CHANGE); attachInterrupt(Z_MAX_PIN, endstop_ISR, CHANGE);
#endif #endif
#if HAS_Z_MIN #if HAS_Z_MIN
#if !AVAILABLE_EILINE(Z_MIN_PIN) #if !AVAILABLE_EILINE(Z_MIN_PIN)
static_assert(false, "Z_MIN_PIN has no EXTINT line available."); #error "Z_MIN_PIN has no EXTINT line available."
#endif #endif
attachInterrupt(Z_MIN_PIN, endstop_ISR, CHANGE); attachInterrupt(Z_MIN_PIN, endstop_ISR, CHANGE);
#endif #endif
#if HAS_Z2_MAX #if HAS_Z2_MAX
#if !AVAILABLE_EILINE(Z2_MAX_PIN) #if !AVAILABLE_EILINE(Z2_MAX_PIN)
static_assert(false, "Z2_MAX_PIN has no EXTINT line available."); #error "Z2_MAX_PIN has no EXTINT line available."
#endif #endif
attachInterrupt(Z2_MAX_PIN, endstop_ISR, CHANGE); attachInterrupt(Z2_MAX_PIN, endstop_ISR, CHANGE);
#endif #endif
#if HAS_Z2_MIN #if HAS_Z2_MIN
#if !AVAILABLE_EILINE(Z2_MIN_PIN) #if !AVAILABLE_EILINE(Z2_MIN_PIN)
static_assert(false, "Z2_MIN_PIN has no EXTINT line available."); #error "Z2_MIN_PIN has no EXTINT line available."
#endif #endif
attachInterrupt(Z2_MIN_PIN, endstop_ISR, CHANGE); attachInterrupt(Z2_MIN_PIN, endstop_ISR, CHANGE);
#endif #endif
#if HAS_Z3_MAX #if HAS_Z3_MAX
#if !AVAILABLE_EILINE(Z3_MAX_PIN) #if !AVAILABLE_EILINE(Z3_MAX_PIN)
static_assert(false, "Z3_MAX_PIN has no EXTINT line available."); #error "Z3_MAX_PIN has no EXTINT line available."
#endif #endif
attachInterrupt(Z3_MAX_PIN, endstop_ISR, CHANGE); attachInterrupt(Z3_MAX_PIN, endstop_ISR, CHANGE);
#endif #endif
#if HAS_Z3_MIN #if HAS_Z3_MIN
#if !AVAILABLE_EILINE(Z3_MIN_PIN) #if !AVAILABLE_EILINE(Z3_MIN_PIN)
static_assert(false, "Z3_MIN_PIN has no EXTINT line available."); #error "Z3_MIN_PIN has no EXTINT line available."
#endif #endif
attachInterrupt(Z3_MIN_PIN, endstop_ISR, CHANGE); attachInterrupt(Z3_MIN_PIN, endstop_ISR, CHANGE);
#endif #endif
#if HAS_Z4_MAX
#if !AVAILABLE_EILINE(Z4_MAX_PIN)
#error "Z4_MAX_PIN has no EXTINT line available."
#endif
attachInterrupt(Z4_MAX_PIN, endstop_ISR, CHANGE);
#endif
#if HAS_Z4_MIN
#if !AVAILABLE_EILINE(Z4_MIN_PIN)
#error "Z4_MIN_PIN has no EXTINT line available."
#endif
attachInterrupt(Z4_MIN_PIN, endstop_ISR, CHANGE);
#endif
#if HAS_Z_MIN_PROBE_PIN #if HAS_Z_MIN_PROBE_PIN
#if !AVAILABLE_EILINE(Z_MIN_PROBE_PIN) #if !AVAILABLE_EILINE(Z_MIN_PROBE_PIN)
static_assert(false, "Z_MIN_PROBE_PIN has no EXTINT line available."); #error "Z_MIN_PROBE_PIN has no EXTINT line available."
#endif #endif
attachInterrupt(Z_MIN_PROBE_PIN, endstop_ISR, CHANGE); attachInterrupt(Z_MIN_PROBE_PIN, endstop_ISR, CHANGE);
#endif #endif

View file

@ -58,6 +58,12 @@ void setup_endstop_interrupts() {
#if HAS_Z3_MIN #if HAS_Z3_MIN
attachInterrupt(Z3_MIN_PIN, endstop_ISR, CHANGE); attachInterrupt(Z3_MIN_PIN, endstop_ISR, CHANGE);
#endif #endif
#if HAS_Z4_MAX
attachInterrupt(Z4_MAX_PIN, endstop_ISR, CHANGE);
#endif
#if HAS_Z4_MIN
attachInterrupt(Z4_MIN_PIN, endstop_ISR, CHANGE);
#endif
#if HAS_Z_MIN_PROBE_PIN #if HAS_Z_MIN_PROBE_PIN
attachInterrupt(Z_MIN_PROBE_PIN, endstop_ISR, CHANGE); attachInterrupt(Z_MIN_PROBE_PIN, endstop_ISR, CHANGE);
#endif #endif

View file

@ -82,6 +82,12 @@ void setup_endstop_interrupts() {
#endif #endif
#if HAS_Z3_MIN #if HAS_Z3_MIN
attachInterrupt(Z3_MIN_PIN, endstop_ISR, CHANGE); attachInterrupt(Z3_MIN_PIN, endstop_ISR, CHANGE);
#endif
#if HAS_Z4_MAX
attachInterrupt(Z4_MAX_PIN, endstop_ISR, CHANGE);
#endif
#if HAS_Z4_MIN
attachInterrupt(Z4_MIN_PIN, endstop_ISR, CHANGE);
#endif #endif
#if HAS_Z_MIN_PROBE_PIN #if HAS_Z_MIN_PROBE_PIN
attachInterrupt(Z_MIN_PROBE_PIN, endstop_ISR, CHANGE); attachInterrupt(Z_MIN_PROBE_PIN, endstop_ISR, CHANGE);

View file

@ -58,6 +58,12 @@ void setup_endstop_interrupts() {
#if HAS_Z3_MIN #if HAS_Z3_MIN
attachInterrupt(Z3_MIN_PIN, endstop_ISR, CHANGE); attachInterrupt(Z3_MIN_PIN, endstop_ISR, CHANGE);
#endif #endif
#if HAS_Z4_MAX
attachInterrupt(Z4_MAX_PIN, endstop_ISR, CHANGE);
#endif
#if HAS_Z4_MIN
attachInterrupt(Z4_MIN_PIN, endstop_ISR, CHANGE);
#endif
#if HAS_Z_MIN_PROBE_PIN #if HAS_Z_MIN_PROBE_PIN
attachInterrupt(Z_MIN_PROBE_PIN, endstop_ISR, CHANGE); attachInterrupt(Z_MIN_PROBE_PIN, endstop_ISR, CHANGE);
#endif #endif

View file

@ -76,6 +76,12 @@ void setup_endstop_interrupts() {
#if HAS_Z3_MIN #if HAS_Z3_MIN
_ATTACH(Z3_MIN_PIN); _ATTACH(Z3_MIN_PIN);
#endif #endif
#if HAS_Z4_MAX
_ATTACH(Z4_MAX_PIN);
#endif
#if HAS_Z4_MIN
_ATTACH(Z4_MIN_PIN);
#endif
#if HAS_Z_MIN_PROBE_PIN #if HAS_Z_MIN_PROBE_PIN
_ATTACH(Z_MIN_PROBE_PIN); _ATTACH(Z_MIN_PROBE_PIN);
#endif #endif

View file

@ -63,8 +63,9 @@
#define AXIS_DRIVER_TYPE_X2(T) false #define AXIS_DRIVER_TYPE_X2(T) false
#endif #endif
#define AXIS_DRIVER_TYPE_Y2(T) (ENABLED(Y_DUAL_STEPPER_DRIVERS) && _AXIS_DRIVER_TYPE(Y2,T)) #define AXIS_DRIVER_TYPE_Y2(T) (ENABLED(Y_DUAL_STEPPER_DRIVERS) && _AXIS_DRIVER_TYPE(Y2,T))
#define AXIS_DRIVER_TYPE_Z2(T) (Z_MULTI_STEPPER_DRIVERS && _AXIS_DRIVER_TYPE(Z2,T)) #define AXIS_DRIVER_TYPE_Z2(T) (NUM_Z_STEPPER_DRIVERS >= 2 && _AXIS_DRIVER_TYPE(Z2,T))
#define AXIS_DRIVER_TYPE_Z3(T) (ENABLED(Z_TRIPLE_STEPPER_DRIVERS) && _AXIS_DRIVER_TYPE(Z3,T)) #define AXIS_DRIVER_TYPE_Z3(T) (NUM_Z_STEPPER_DRIVERS >= 3 && _AXIS_DRIVER_TYPE(Z3,T))
#define AXIS_DRIVER_TYPE_Z4(T) (NUM_Z_STEPPER_DRIVERS >= 4 && _AXIS_DRIVER_TYPE(Z4,T))
#define AXIS_DRIVER_TYPE_E0(T) (E_STEPPERS > 0 && _AXIS_DRIVER_TYPE(E0,T)) #define AXIS_DRIVER_TYPE_E0(T) (E_STEPPERS > 0 && _AXIS_DRIVER_TYPE(E0,T))
#define AXIS_DRIVER_TYPE_E1(T) (E_STEPPERS > 1 && _AXIS_DRIVER_TYPE(E1,T)) #define AXIS_DRIVER_TYPE_E1(T) (E_STEPPERS > 1 && _AXIS_DRIVER_TYPE(E1,T))
#define AXIS_DRIVER_TYPE_E2(T) (E_STEPPERS > 2 && _AXIS_DRIVER_TYPE(E2,T)) #define AXIS_DRIVER_TYPE_E2(T) (E_STEPPERS > 2 && _AXIS_DRIVER_TYPE(E2,T))
@ -80,7 +81,8 @@
#define HAS_DRIVER(T) ( AXIS_DRIVER_TYPE_X(T) || AXIS_DRIVER_TYPE_X2(T) \ #define HAS_DRIVER(T) ( AXIS_DRIVER_TYPE_X(T) || AXIS_DRIVER_TYPE_X2(T) \
|| AXIS_DRIVER_TYPE_Y(T) || AXIS_DRIVER_TYPE_Y2(T) \ || AXIS_DRIVER_TYPE_Y(T) || AXIS_DRIVER_TYPE_Y2(T) \
|| AXIS_DRIVER_TYPE_Z(T) || AXIS_DRIVER_TYPE_Z2(T) || AXIS_DRIVER_TYPE_Z3(T) \ || AXIS_DRIVER_TYPE_Z(T) || AXIS_DRIVER_TYPE_Z2(T) \
|| AXIS_DRIVER_TYPE_Z3(T) || AXIS_DRIVER_TYPE_Z4(T) \
|| HAS_E_DRIVER(T) ) || HAS_E_DRIVER(T) )
// Test for supported TMC drivers that require advanced configuration // Test for supported TMC drivers that require advanced configuration

View file

@ -195,6 +195,8 @@
#define MSG_Z2_MAX "z2_max" #define MSG_Z2_MAX "z2_max"
#define MSG_Z3_MIN "z3_min" #define MSG_Z3_MIN "z3_min"
#define MSG_Z3_MAX "z3_max" #define MSG_Z3_MAX "z3_max"
#define MSG_Z4_MIN "z4_min"
#define MSG_Z4_MAX "z4_max"
#define MSG_Z_PROBE "z_probe" #define MSG_Z_PROBE "z_probe"
#define MSG_FILAMENT_RUNOUT_SENSOR "filament" #define MSG_FILAMENT_RUNOUT_SENSOR "filament"
#define MSG_PROBE_OFFSET "Probe Offset" #define MSG_PROBE_OFFSET "Probe Offset"
@ -333,6 +335,7 @@
#define MSG_Y2 "Y2" #define MSG_Y2 "Y2"
#define MSG_Z2 "Z2" #define MSG_Z2 "Z2"
#define MSG_Z3 "Z3" #define MSG_Z3 "Z3"
#define MSG_Z4 "Z4"
#define LCD_STR_A MSG_A #define LCD_STR_A MSG_A
#define LCD_STR_B MSG_B #define LCD_STR_B MSG_B

View file

@ -55,6 +55,9 @@ void controllerfan_update() {
#if HAS_Z3_ENABLE #if HAS_Z3_ENABLE
|| Z3_ENABLE_READ() == bool(Z_ENABLE_ON) || Z3_ENABLE_READ() == bool(Z_ENABLE_ON)
#endif #endif
#if HAS_Z4_ENABLE
|| Z4_ENABLE_READ() == bool(Z_ENABLE_ON)
#endif
#if E_STEPPERS #if E_STEPPERS
#define _OR_ENABLED_E(N) || E##N##_ENABLE_READ() == bool(E_ENABLE_ON) #define _OR_ENABLED_E(N) || E##N##_ENABLE_READ() == bool(E_ENABLE_ON)
REPEAT(E_STEPPERS, _OR_ENABLED_E) REPEAT(E_STEPPERS, _OR_ENABLED_E)

View file

@ -387,7 +387,7 @@
} }
#endif #endif
#if AXIS_IS_TMC(Z) || AXIS_IS_TMC(Z2) || AXIS_IS_TMC(Z3) #if AXIS_IS_TMC(Z) || AXIS_IS_TMC(Z2) || AXIS_IS_TMC(Z3) || AXIS_IS_TMC(Z4)
{ {
bool result = false; bool result = false;
#if AXIS_IS_TMC(Z) #if AXIS_IS_TMC(Z)
@ -399,6 +399,9 @@
#if AXIS_IS_TMC(Z3) #if AXIS_IS_TMC(Z3)
if (monitor_tmc_driver(stepperZ3, need_update_error_counters, need_debug_reporting)) result = true; if (monitor_tmc_driver(stepperZ3, need_update_error_counters, need_debug_reporting)) result = true;
#endif #endif
#if AXIS_IS_TMC(Z4)
if (monitor_tmc_driver(stepperZ4, need_update_error_counters, need_debug_reporting)) result = true;
#endif
if (result) { if (result) {
#if AXIS_IS_TMC(Z) #if AXIS_IS_TMC(Z)
step_current_down(stepperZ); step_current_down(stepperZ);
@ -409,6 +412,9 @@
#if AXIS_IS_TMC(Z3) #if AXIS_IS_TMC(Z3)
step_current_down(stepperZ3); step_current_down(stepperZ3);
#endif #endif
#if AXIS_IS_TMC(Z4)
step_current_down(stepperZ4);
#endif
} }
} }
#endif #endif
@ -750,6 +756,9 @@
#if AXIS_IS_TMC(Z3) #if AXIS_IS_TMC(Z3)
tmc_status(stepperZ3, i); tmc_status(stepperZ3, i);
#endif #endif
#if AXIS_IS_TMC(Z4)
tmc_status(stepperZ4, i);
#endif
} }
if (print_e) { if (print_e) {
@ -805,6 +814,9 @@
#if AXIS_IS_TMC(Z3) #if AXIS_IS_TMC(Z3)
tmc_parse_drv_status(stepperZ3, i); tmc_parse_drv_status(stepperZ3, i);
#endif #endif
#if AXIS_IS_TMC(Z4)
tmc_parse_drv_status(stepperZ4, i);
#endif
} }
if (print_e) { if (print_e) {
@ -980,6 +992,9 @@
#if AXIS_IS_TMC(Z3) #if AXIS_IS_TMC(Z3)
tmc_get_registers(stepperZ3, i); tmc_get_registers(stepperZ3, i);
#endif #endif
#if AXIS_IS_TMC(Z4)
tmc_get_registers(stepperZ4, i);
#endif
} }
if (print_e) { if (print_e) {
@ -1086,6 +1101,9 @@
#if AXIS_HAS_SPI(Z3) #if AXIS_HAS_SPI(Z3)
SET_CS_PIN(Z3); SET_CS_PIN(Z3);
#endif #endif
#if AXIS_HAS_SPI(Z4)
SET_CS_PIN(Z4);
#endif
#if AXIS_HAS_SPI(E0) #if AXIS_HAS_SPI(E0)
SET_CS_PIN(E0); SET_CS_PIN(E0);
#endif #endif
@ -1160,6 +1178,9 @@ void test_tmc_connection(const bool test_x, const bool test_y, const bool test_z
#if AXIS_IS_TMC(Z3) #if AXIS_IS_TMC(Z3)
axis_connection += test_connection(stepperZ3); axis_connection += test_connection(stepperZ3);
#endif #endif
#if AXIS_IS_TMC(Z4)
axis_connection += test_connection(stepperZ4);
#endif
} }
if (test_e) { if (test_e) {

View file

@ -350,7 +350,7 @@ void test_tmc_connection(const bool test_x, const bool test_y, const bool test_z
#if USE_SENSORLESS #if USE_SENSORLESS
// Track enabled status of stealthChop and only re-enable where applicable // Track enabled status of stealthChop and only re-enable where applicable
struct sensorless_t { bool x, y, z, x2, y2, z2, z3; }; struct sensorless_t { bool x, y, z, x2, y2, z2, z3, z4; };
#if ENABLED(IMPROVE_HOMING_RELIABILITY) #if ENABLED(IMPROVE_HOMING_RELIABILITY)
extern millis_t sg_guard_period; extern millis_t sg_guard_period;

View file

@ -52,20 +52,22 @@ constexpr xy_pos_t test_z_stepper_align_xy[] = Z_STEPPER_ALIGN_XY;
#if ENABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) #if ENABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS)
static_assert(COUNT(test_z_stepper_align_xy) >= Z_STEPPER_COUNT, static_assert(COUNT(test_z_stepper_align_xy) >= NUM_Z_STEPPER_DRIVERS,
"Z_STEPPER_ALIGN_XY requires at least three {X,Y} entries (Z, Z2, Z3, ...)." "Z_STEPPER_ALIGN_XY requires at least three {X,Y} entries (Z, Z2, Z3, ...)."
); );
constexpr float test_z_stepper_align_stepper_xy[][XY] = Z_STEPPER_ALIGN_STEPPER_XY; constexpr float test_z_stepper_align_stepper_xy[][XY] = Z_STEPPER_ALIGN_STEPPER_XY;
static_assert( static_assert(
COUNT(test_z_stepper_align_stepper_xy) == Z_STEPPER_COUNT, COUNT(test_z_stepper_align_stepper_xy) == NUM_Z_STEPPER_DRIVERS,
"Z_STEPPER_ALIGN_STEPPER_XY requires three {X,Y} entries (one per Z stepper)." "Z_STEPPER_ALIGN_STEPPER_XY requires three {X,Y} entries (one per Z stepper)."
); );
#else #else
static_assert(COUNT(test_z_stepper_align_xy) == Z_STEPPER_COUNT, static_assert(COUNT(test_z_stepper_align_xy) == NUM_Z_STEPPER_DRIVERS,
#if ENABLED(Z_TRIPLE_STEPPER_DRIVERS) #if NUM_Z_STEPPER_DRIVERS == 4
"Z_STEPPER_ALIGN_XY requires four {X,Y} entries (Z, Z2, Z3, and Z4)."
#elif NUM_Z_STEPPER_DRIVERS == 3
"Z_STEPPER_ALIGN_XY requires three {X,Y} entries (Z, Z2, and Z3)." "Z_STEPPER_ALIGN_XY requires three {X,Y} entries (Z, Z2, and Z3)."
#else #else
"Z_STEPPER_ALIGN_XY requires two {X,Y} entries (Z and Z2)." "Z_STEPPER_ALIGN_XY requires two {X,Y} entries (Z and Z2)."
@ -85,10 +87,13 @@ static_assert(LTEST(0) && RTEST(0), "The 1st Z_STEPPER_ALIGN_XY X is unreachable
static_assert(FTEST(0) && BTEST(0), "The 1st Z_STEPPER_ALIGN_XY Y is unreachable with the default probe Y offset."); static_assert(FTEST(0) && BTEST(0), "The 1st Z_STEPPER_ALIGN_XY Y is unreachable with the default probe Y offset.");
static_assert(LTEST(1) && RTEST(1), "The 2nd Z_STEPPER_ALIGN_XY X is unreachable with the default probe X offset."); static_assert(LTEST(1) && RTEST(1), "The 2nd Z_STEPPER_ALIGN_XY X is unreachable with the default probe X offset.");
static_assert(FTEST(1) && BTEST(1), "The 2nd Z_STEPPER_ALIGN_XY Y is unreachable with the default probe Y offset."); static_assert(FTEST(1) && BTEST(1), "The 2nd Z_STEPPER_ALIGN_XY Y is unreachable with the default probe Y offset.");
#if NUM_Z_STEPPER_DRIVERS >= 3
#if ENABLED(Z_TRIPLE_STEPPER_DRIVERS)
static_assert(LTEST(2) && RTEST(2), "The 3rd Z_STEPPER_ALIGN_XY X is unreachable with the default probe X offset."); static_assert(LTEST(2) && RTEST(2), "The 3rd Z_STEPPER_ALIGN_XY X is unreachable with the default probe X offset.");
static_assert(FTEST(2) && BTEST(2), "The 3rd Z_STEPPER_ALIGN_XY Y is unreachable with the default probe Y offset."); static_assert(FTEST(2) && BTEST(2), "The 3rd Z_STEPPER_ALIGN_XY Y is unreachable with the default probe Y offset.");
#if NUM_Z_STEPPER_DRIVERS >= 4
static_assert(LTEST(3) && RTEST(3), "The 4th Z_STEPPER_ALIGN_XY X is unreachable with the default probe X offset.");
static_assert(FTEST(3) && BTEST(3), "The 4th Z_STEPPER_ALIGN_XY Y is unreachable with the default probe Y offset.");
#endif
#endif #endif
// //
@ -105,8 +110,11 @@ static xy_pos_t z_stepper_align_pos[] = Z_STEPPER_ALIGN_XY;
inline void set_all_z_lock(const bool lock) { inline void set_all_z_lock(const bool lock) {
stepper.set_z_lock(lock); stepper.set_z_lock(lock);
stepper.set_z2_lock(lock); stepper.set_z2_lock(lock);
#if ENABLED(Z_TRIPLE_STEPPER_DRIVERS) #if NUM_Z_STEPPER_DRIVERS >= 3
stepper.set_z3_lock(lock); stepper.set_z3_lock(lock);
#if NUM_Z_STEPPER_DRIVERS >= 4
stepper.set_z4_lock(lock);
#endif
#endif #endif
} }
@ -125,6 +133,11 @@ void GcodeSuite::G34() {
do { // break out on error do { // break out on error
#if NUM_Z_STEPPER_DRIVERS == 4
SERIAL_ECHOLNPGM("Quad Z Stepper Leveling not Yet Supported");
break;
#endif
const int8_t z_auto_align_iterations = parser.intval('I', Z_STEPPER_ALIGN_ITERATIONS); const int8_t z_auto_align_iterations = parser.intval('I', Z_STEPPER_ALIGN_ITERATIONS);
if (!WITHIN(z_auto_align_iterations, 1, 30)) { if (!WITHIN(z_auto_align_iterations, 1, 30)) {
SERIAL_ECHOLNPGM("?(I)teration out of bounds (1-30)."); SERIAL_ECHOLNPGM("?(I)teration out of bounds (1-30).");
@ -187,7 +200,7 @@ void GcodeSuite::G34() {
// Compute a worst-case clearance height to probe from. After the first // Compute a worst-case clearance height to probe from. After the first
// iteration this will be re-calculated based on the actual bed position // iteration this will be re-calculated based on the actual bed position
float z_probe = Z_BASIC_CLEARANCE + (G34_MAX_GRADE) * 0.01f * ( float z_probe = Z_BASIC_CLEARANCE + (G34_MAX_GRADE) * 0.01f * (
#if ENABLED(Z_TRIPLE_STEPPER_DRIVERS) #if NUM_Z_STEPPER_DRIVERS == 3
SQRT(_MAX(HYPOT2(z_stepper_align_pos[0].x - z_stepper_align_pos[0].y, z_stepper_align_pos[1].x - z_stepper_align_pos[1].y), SQRT(_MAX(HYPOT2(z_stepper_align_pos[0].x - z_stepper_align_pos[0].y, z_stepper_align_pos[1].x - z_stepper_align_pos[1].y),
HYPOT2(z_stepper_align_pos[1].x - z_stepper_align_pos[1].y, z_stepper_align_pos[2].x - z_stepper_align_pos[2].y), HYPOT2(z_stepper_align_pos[1].x - z_stepper_align_pos[1].y, z_stepper_align_pos[2].x - z_stepper_align_pos[2].y),
HYPOT2(z_stepper_align_pos[2].x - z_stepper_align_pos[2].y, z_stepper_align_pos[0].x - z_stepper_align_pos[0].y))) HYPOT2(z_stepper_align_pos[2].x - z_stepper_align_pos[2].y, z_stepper_align_pos[0].x - z_stepper_align_pos[0].y)))
@ -202,7 +215,7 @@ void GcodeSuite::G34() {
// Move the Z coordinate realm towards the positive - dirty trick // Move the Z coordinate realm towards the positive - dirty trick
current_position.z -= z_probe * 0.5f; current_position.z -= z_probe * 0.5f;
float last_z_align_move[Z_STEPPER_COUNT] = ARRAY_N(Z_STEPPER_COUNT, 10000.0f, 10000.0f, 10000.0f), float last_z_align_move[NUM_Z_STEPPER_DRIVERS] = ARRAY_N(NUM_Z_STEPPER_DRIVERS, 10000.0f, 10000.0f, 10000.0f),
z_measured[G34_PROBE_COUNT] = { 0 }, z_measured[G34_PROBE_COUNT] = { 0 },
z_maxdiff = 0.0f, z_maxdiff = 0.0f,
amplification = z_auto_align_amplification; amplification = z_auto_align_amplification;
@ -273,7 +286,7 @@ void GcodeSuite::G34() {
finish_incremental_LSF(&lfd); finish_incremental_LSF(&lfd);
z_measured_min = 100000.0f; z_measured_min = 100000.0f;
for (uint8_t i = 0; i < Z_STEPPER_COUNT; ++i) { for (uint8_t i = 0; i < NUM_Z_STEPPER_DRIVERS; ++i) {
z_measured[i] = -(lfd.A * z_stepper_align_stepper_pos[i].x + lfd.B * z_stepper_align_stepper_pos[i].y); z_measured[i] = -(lfd.A * z_stepper_align_stepper_pos[i].x + lfd.B * z_stepper_align_stepper_pos[i].y);
z_measured_min = _MIN(z_measured_min, z_measured[i]); z_measured_min = _MIN(z_measured_min, z_measured[i]);
} }
@ -283,7 +296,7 @@ void GcodeSuite::G34() {
SERIAL_ECHOLNPAIR("\n" SERIAL_ECHOLNPAIR("\n"
"DIFFERENCE Z1-Z2=", ABS(z_measured[0] - z_measured[1]) "DIFFERENCE Z1-Z2=", ABS(z_measured[0] - z_measured[1])
#if ENABLED(Z_TRIPLE_STEPPER_DRIVERS) #if NUM_Z_STEPPER_DRIVERS == 3
, " Z2-Z3=", ABS(z_measured[1] - z_measured[2]) , " Z2-Z3=", ABS(z_measured[1] - z_measured[2])
, " Z3-Z1=", ABS(z_measured[2] - z_measured[0]) , " Z3-Z1=", ABS(z_measured[2] - z_measured[0])
#endif #endif
@ -294,7 +307,7 @@ void GcodeSuite::G34() {
bool success_break = true; bool success_break = true;
// Correct the individual stepper offsets // Correct the individual stepper offsets
for (uint8_t zstepper = 0; zstepper < Z_STEPPER_COUNT; ++zstepper) { for (uint8_t zstepper = 0; zstepper < NUM_Z_STEPPER_DRIVERS; ++zstepper) {
// Calculate current stepper move // Calculate current stepper move
const float z_align_move = z_measured[zstepper] - z_measured_min, const float z_align_move = z_measured[zstepper] - z_measured_min,
z_align_abs = ABS(z_align_move); z_align_abs = ABS(z_align_move);
@ -324,7 +337,7 @@ void GcodeSuite::G34() {
switch (zstepper) { switch (zstepper) {
case 0: stepper.set_z_lock(false); break; case 0: stepper.set_z_lock(false); break;
case 1: stepper.set_z2_lock(false); break; case 1: stepper.set_z2_lock(false); break;
#if ENABLED(Z_TRIPLE_STEPPER_DRIVERS) #if NUM_Z_STEPPER_DRIVERS == 3
case 2: stepper.set_z3_lock(false); break; case 2: stepper.set_z3_lock(false); break;
#endif #endif
} }
@ -397,7 +410,7 @@ void GcodeSuite::M422() {
for (uint8_t i = 0; i < G34_PROBE_COUNT; ++i) for (uint8_t i = 0; i < G34_PROBE_COUNT; ++i)
SERIAL_ECHOLNPAIR_P(PSTR("M422 S"), i + 1, SP_X_STR, z_stepper_align_pos[i].x, SP_Y_STR, z_stepper_align_pos[i].y); SERIAL_ECHOLNPAIR_P(PSTR("M422 S"), i + 1, SP_X_STR, z_stepper_align_pos[i].x, SP_Y_STR, z_stepper_align_pos[i].y);
#if ENABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) #if ENABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS)
for (uint8_t i = 0; i < Z_STEPPER_COUNT; ++i) for (uint8_t i = 0; i < NUM_Z_STEPPER_DRIVERS; ++i)
SERIAL_ECHOLNPAIR_P(PSTR("M422 W"), i + 1, SP_X_STR, z_stepper_align_stepper_pos[i].x, SP_Y_STR, z_stepper_align_stepper_pos[i].y); SERIAL_ECHOLNPAIR_P(PSTR("M422 W"), i + 1, SP_X_STR, z_stepper_align_stepper_pos[i].x, SP_Y_STR, z_stepper_align_stepper_pos[i].y);
#endif #endif
return; return;
@ -446,7 +459,7 @@ void GcodeSuite::M422() {
else { else {
#if ENABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) #if ENABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS)
position_index = parser.intval('W') - 1; position_index = parser.intval('W') - 1;
if (!WITHIN(position_index, 0, Z_STEPPER_COUNT - 1)) { if (!WITHIN(position_index, 0, NUM_Z_STEPPER_DRIVERS - 1)) {
SERIAL_ECHOLNPGM("?(W) Z-Stepper index invalid."); SERIAL_ECHOLNPGM("?(W) Z-Stepper index invalid.");
return; return;
} }

View file

@ -57,10 +57,11 @@
* M666: Set Dual Endstops offsets for X, Y, and/or Z. * M666: Set Dual Endstops offsets for X, Y, and/or Z.
* With no parameters report current offsets. * With no parameters report current offsets.
* *
* For Triple Z Endstops: * For Triple / Quad Z Endstops:
* Set Z2 Only: M666 S2 Z<offset> * Set Z2 Only: M666 S2 Z<offset>
* Set Z3 Only: M666 S3 Z<offset> * Set Z3 Only: M666 S3 Z<offset>
* Set Both: M666 Z<offset> * Set Z4 Only: M666 S4 Z<offset>
* Set All: M666 Z<offset>
*/ */
void GcodeSuite::M666() { void GcodeSuite::M666() {
#if ENABLED(X_DUAL_ENDSTOPS) #if ENABLED(X_DUAL_ENDSTOPS)
@ -69,15 +70,20 @@
#if ENABLED(Y_DUAL_ENDSTOPS) #if ENABLED(Y_DUAL_ENDSTOPS)
if (parser.seenval('Y')) endstops.y2_endstop_adj = parser.value_linear_units(); if (parser.seenval('Y')) endstops.y2_endstop_adj = parser.value_linear_units();
#endif #endif
#if ENABLED(Z_TRIPLE_ENDSTOPS) #if ENABLED(Z_MULTI_ENDSTOPS)
if (parser.seenval('Z')) { if (parser.seenval('Z')) {
#if NUM_Z_STEPPER_DRIVERS >= 3
const float z_adj = parser.value_linear_units(); const float z_adj = parser.value_linear_units();
const int ind = parser.intval('S'); const int ind = parser.intval('S');
if (!ind || ind == 2) endstops.z2_endstop_adj = z_adj; if (!ind || ind == 2) endstops.z2_endstop_adj = z_adj;
if (!ind || ind == 3) endstops.z3_endstop_adj = z_adj; if (!ind || ind == 3) endstops.z3_endstop_adj = z_adj;
#if NUM_Z_STEPPER_DRIVERS >= 4
if (!ind || ind == 4) endstops.z4_endstop_adj = z_adj;
#endif
#else
endstops.z2_endstop_adj = parser.value_linear_units();
#endif
} }
#elif Z_MULTI_ENDSTOPS
if (parser.seen('Z')) endstops.z2_endstop_adj = parser.value_linear_units();
#endif #endif
if (!parser.seen("XYZ")) { if (!parser.seen("XYZ")) {
SERIAL_ECHOPGM("Dual Endstop Adjustment (mm): "); SERIAL_ECHOPGM("Dual Endstop Adjustment (mm): ");
@ -87,11 +93,14 @@
#if ENABLED(Y_DUAL_ENDSTOPS) #if ENABLED(Y_DUAL_ENDSTOPS)
SERIAL_ECHOPAIR(" Y2:", endstops.y2_endstop_adj); SERIAL_ECHOPAIR(" Y2:", endstops.y2_endstop_adj);
#endif #endif
#if Z_MULTI_ENDSTOPS #if ENABLED(Z_MULTI_ENDSTOPS)
SERIAL_ECHOPAIR(" Z2:", endstops.z2_endstop_adj); SERIAL_ECHOPAIR(" Z2:", endstops.z2_endstop_adj);
#endif #if NUM_Z_STEPPER_DRIVERS >= 3
#if ENABLED(Z_TRIPLE_ENDSTOPS)
SERIAL_ECHOPAIR(" Z3:", endstops.z3_endstop_adj); SERIAL_ECHOPAIR(" Z3:", endstops.z3_endstop_adj);
#if NUM_Z_STEPPER_DRIVERS >= 4
SERIAL_ECHOPAIR(" Z4:", endstops.z4_endstop_adj);
#endif
#endif
#endif #endif
SERIAL_EOL(); SERIAL_EOL();
} }

View file

@ -115,6 +115,9 @@ void GcodeSuite::M122() {
#if AXIS_IS_L64XX(Z3) #if AXIS_IS_L64XX(Z3)
L6470_say_status(Z3); L6470_say_status(Z3);
#endif #endif
#if AXIS_IS_L64XX(Z4)
L6470_say_status(Z4);
#endif
#if AXIS_IS_L64XX(E0) #if AXIS_IS_L64XX(E0)
L6470_say_status(E0); L6470_say_status(E0);
#endif #endif

View file

@ -44,7 +44,7 @@
* 1 - monitor only X, Y, Z or E1 * 1 - monitor only X, Y, Z or E1
* 2 - monitor only X2, Y2, Z2 or E2 * 2 - monitor only X2, Y2, Z2 or E2
* 3 - monitor only Z3 or E3 * 3 - monitor only Z3 or E3
* 4 - monitor only E4 * 4 - monitor only Z4 or E4
* 5 - monitor only E5 * 5 - monitor only E5
* Xxxx, Yxxx, Zxxx, Exxx - axis to change (optional) * Xxxx, Yxxx, Zxxx, Exxx - axis to change (optional)
* L6474 - current in mA (4A max) * L6474 - current in mA (4A max)
@ -274,6 +274,9 @@ void GcodeSuite::M906() {
#if AXIS_IS_L64XX(Z3) #if AXIS_IS_L64XX(Z3)
if (index == 2) L6470_SET_KVAL_HOLD(Z3); if (index == 2) L6470_SET_KVAL_HOLD(Z3);
#endif #endif
#if AXIS_DRIVER_TYPE_Z4(L6470)
if (index == 3) L6470_SET_KVAL_HOLD(Z4);
#endif
break; break;
case E_AXIS: { case E_AXIS: {
const int8_t target_extruder = get_target_extruder_from_command(); const int8_t target_extruder = get_target_extruder_from_command();
@ -328,6 +331,9 @@ void GcodeSuite::M906() {
#if AXIS_IS_L64XX(Z3) #if AXIS_IS_L64XX(Z3)
L64XX_REPORT_CURRENT(Z3); L64XX_REPORT_CURRENT(Z3);
#endif #endif
#if AXIS_IS_L64XX(Z4)
L64XX_REPORT_CURRENT(Z4);
#endif
#if AXIS_IS_L64XX(E0) #if AXIS_IS_L64XX(E0)
L64XX_REPORT_CURRENT(E0); L64XX_REPORT_CURRENT(E0);
#endif #endif

View file

@ -46,6 +46,7 @@
* 1 - monitor only X, Y, Z, E1 * 1 - monitor only X, Y, Z, E1
* 2 - monitor only X2, Y2, Z2, E2 * 2 - monitor only X2, Y2, Z2, E2
* 3 - monitor only Z3, E3 * 3 - monitor only Z3, E3
* 4 - monitor only Z4, E4
* *
* Xxxx, Yxxx, Zxxx, Exxx - axis to be monitored with displacement * Xxxx, Yxxx, Zxxx, Exxx - axis to be monitored with displacement
* xxx (1-255) is distance moved on either side of current position * xxx (1-255) is distance moved on either side of current position

View file

@ -46,7 +46,8 @@ static void set_stealth_status(const bool enable, const int8_t target_extruder)
#if AXIS_HAS_STEALTHCHOP(X) || AXIS_HAS_STEALTHCHOP(X2) \ #if AXIS_HAS_STEALTHCHOP(X) || AXIS_HAS_STEALTHCHOP(X2) \
|| AXIS_HAS_STEALTHCHOP(Y) || AXIS_HAS_STEALTHCHOP(Y2) \ || AXIS_HAS_STEALTHCHOP(Y) || AXIS_HAS_STEALTHCHOP(Y2) \
|| AXIS_HAS_STEALTHCHOP(Z) || AXIS_HAS_STEALTHCHOP(Z2) || AXIS_HAS_STEALTHCHOP(Z3) || AXIS_HAS_STEALTHCHOP(Z) || AXIS_HAS_STEALTHCHOP(Z2) \
|| AXIS_HAS_STEALTHCHOP(Z3) || AXIS_HAS_STEALTHCHOP(Z4)
const uint8_t index = parser.byteval('I'); const uint8_t index = parser.byteval('I');
#endif #endif
@ -78,6 +79,9 @@ static void set_stealth_status(const bool enable, const int8_t target_extruder)
#if AXIS_HAS_STEALTHCHOP(Z3) #if AXIS_HAS_STEALTHCHOP(Z3)
if (index == 2) TMC_SET_STEALTH(Z3); if (index == 2) TMC_SET_STEALTH(Z3);
#endif #endif
#if AXIS_HAS_STEALTHCHOP(Z4)
if (index == 3) TMC_SET_STEALTH(Z4);
#endif
break; break;
case E_AXIS: { case E_AXIS: {
if (target_extruder < 0) return; if (target_extruder < 0) return;
@ -130,6 +134,9 @@ static void say_stealth_status() {
#if AXIS_HAS_STEALTHCHOP(Z3) #if AXIS_HAS_STEALTHCHOP(Z3)
TMC_SAY_STEALTH_STATUS(Z3); TMC_SAY_STEALTH_STATUS(Z3);
#endif #endif
#if AXIS_HAS_STEALTHCHOP(Z4)
TMC_SAY_STEALTH_STATUS(Z4);
#endif
#if AXIS_HAS_STEALTHCHOP(E0) #if AXIS_HAS_STEALTHCHOP(E0)
TMC_SAY_STEALTH_STATUS(E0); TMC_SAY_STEALTH_STATUS(E0);
#endif #endif

View file

@ -37,7 +37,7 @@
* Z[current] - Set mA current for Z driver(s) * Z[current] - Set mA current for Z driver(s)
* E[current] - Set mA current for E driver(s) * E[current] - Set mA current for E driver(s)
* *
* I[index] - Axis sub-index (Omit or 0 for X, Y, Z; 1 for X2, Y2, Z2; 2 for Z3.) * I[index] - Axis sub-index (Omit or 0 for X, Y, Z; 1 for X2, Y2, Z2; 2 for Z3; 3 for Z4.)
* T[index] - Extruder index (Zero-based. Omit for E0 only.) * T[index] - Extruder index (Zero-based. Omit for E0 only.)
* *
* With no parameters report driver currents. * With no parameters report driver currents.
@ -48,7 +48,7 @@ void GcodeSuite::M906() {
bool report = true; bool report = true;
#if AXIS_IS_TMC(X) || AXIS_IS_TMC(X2) || AXIS_IS_TMC(Y) || AXIS_IS_TMC(Y2) || AXIS_IS_TMC(Z) || AXIS_IS_TMC(Z2) || AXIS_IS_TMC(Z3) #if AXIS_IS_TMC(X) || AXIS_IS_TMC(X2) || AXIS_IS_TMC(Y) || AXIS_IS_TMC(Y2) || AXIS_IS_TMC(Z) || AXIS_IS_TMC(Z2) || AXIS_IS_TMC(Z3) || AXIS_IS_TMC(Z4)
const uint8_t index = parser.byteval('I'); const uint8_t index = parser.byteval('I');
#endif #endif
@ -81,6 +81,9 @@ void GcodeSuite::M906() {
#if AXIS_IS_TMC(Z3) #if AXIS_IS_TMC(Z3)
if (index == 2) TMC_SET_CURRENT(Z3); if (index == 2) TMC_SET_CURRENT(Z3);
#endif #endif
#if AXIS_IS_TMC(Z4)
if (index == 3) TMC_SET_CURRENT(Z4);
#endif
break; break;
case E_AXIS: { case E_AXIS: {
const int8_t target_extruder = get_target_extruder_from_command(); const int8_t target_extruder = get_target_extruder_from_command();
@ -131,6 +134,9 @@ void GcodeSuite::M906() {
#if AXIS_IS_TMC(Z3) #if AXIS_IS_TMC(Z3)
TMC_SAY_CURRENT(Z3); TMC_SAY_CURRENT(Z3);
#endif #endif
#if AXIS_IS_TMC(Z4)
TMC_SAY_CURRENT(Z4);
#endif
#if AXIS_IS_TMC(E0) #if AXIS_IS_TMC(E0)
TMC_SAY_CURRENT(E0); TMC_SAY_CURRENT(E0);
#endif #endif

View file

@ -37,7 +37,7 @@
#define M91x_SOME_X (M91x_USE(X) || M91x_USE(X2)) #define M91x_SOME_X (M91x_USE(X) || M91x_USE(X2))
#define M91x_SOME_Y (M91x_USE(Y) || M91x_USE(Y2)) #define M91x_SOME_Y (M91x_USE(Y) || M91x_USE(Y2))
#define M91x_SOME_Z (M91x_USE(Z) || M91x_USE(Z2) || M91x_USE(Z3)) #define M91x_SOME_Z (M91x_USE(Z) || M91x_USE(Z2) || M91x_USE(Z3) || M91x_USE(Z4))
#define M91x_SOME_E (M91x_USE_E(0) || M91x_USE_E(1) || M91x_USE_E(2) || M91x_USE_E(3) || M91x_USE_E(4) || M91x_USE_E(5)) #define M91x_SOME_E (M91x_USE_E(0) || M91x_USE_E(1) || M91x_USE_E(2) || M91x_USE_E(3) || M91x_USE_E(4) || M91x_USE_E(5))
#if !M91x_SOME_X && !M91x_SOME_Y && !M91x_SOME_Z && !M91x_SOME_E #if !M91x_SOME_X && !M91x_SOME_Y && !M91x_SOME_Z && !M91x_SOME_E
@ -70,6 +70,9 @@
#if M91x_USE(Z3) #if M91x_USE(Z3)
tmc_report_otpw(stepperZ3); tmc_report_otpw(stepperZ3);
#endif #endif
#if M91x_USE(Z4)
tmc_report_otpw(stepperZ4);
#endif
#if M91x_USE_E(0) #if M91x_USE_E(0)
tmc_report_otpw(stepperE0); tmc_report_otpw(stepperE0);
#endif #endif
@ -92,7 +95,7 @@
/** /**
* M912: Clear TMC stepper driver overtemperature pre-warn flag held by the library * M912: Clear TMC stepper driver overtemperature pre-warn flag held by the library
* Specify one or more axes with X, Y, Z, X1, Y1, Z1, X2, Y2, Z2, Z3 and E[index]. * Specify one or more axes with X, Y, Z, X1, Y1, Z1, X2, Y2, Z2, Z3, Z4 and E[index].
* If no axes are given, clear all. * If no axes are given, clear all.
* *
* Examples: * Examples:
@ -160,6 +163,9 @@
#if M91x_USE(Z3) #if M91x_USE(Z3)
if (hasNone || zval == 3 || (hasZ && zval < 0)) tmc_clear_otpw(stepperZ3); if (hasNone || zval == 3 || (hasZ && zval < 0)) tmc_clear_otpw(stepperZ3);
#endif #endif
#if M91x_USE(Z4)
if (hasNone || zval == 4 || (hasZ && zval < 0)) tmc_clear_otpw(stepperZ4);
#endif
#endif #endif
#if M91x_SOME_E #if M91x_SOME_E
@ -198,7 +204,7 @@
#define TMC_SET_PWMTHRS_E(E) stepperE##E.set_pwm_thrs(value) #define TMC_SET_PWMTHRS_E(E) stepperE##E.set_pwm_thrs(value)
bool report = true; bool report = true;
#if AXIS_IS_TMC(X) || AXIS_IS_TMC(X2) || AXIS_IS_TMC(Y) || AXIS_IS_TMC(Y2) || AXIS_IS_TMC(Z) || AXIS_IS_TMC(Z2) || AXIS_IS_TMC(Z3) #if AXIS_IS_TMC(X) || AXIS_IS_TMC(X2) || AXIS_IS_TMC(Y) || AXIS_IS_TMC(Y2) || AXIS_IS_TMC(Z) || AXIS_IS_TMC(Z2) || AXIS_IS_TMC(Z3) || AXIS_IS_TMC(Z4)
const uint8_t index = parser.byteval('I'); const uint8_t index = parser.byteval('I');
#endif #endif
LOOP_XYZE(i) if (int32_t value = parser.longval(axis_codes[i])) { LOOP_XYZE(i) if (int32_t value = parser.longval(axis_codes[i])) {
@ -230,6 +236,9 @@
#if AXIS_HAS_STEALTHCHOP(Z3) #if AXIS_HAS_STEALTHCHOP(Z3)
if (index == 0 || index == 3) TMC_SET_PWMTHRS(Z,Z3); if (index == 0 || index == 3) TMC_SET_PWMTHRS(Z,Z3);
#endif #endif
#if AXIS_HAS_STEALTHCHOP(Z4)
if (index == 0 || index == 4) TMC_SET_PWMTHRS(Z,Z4);
#endif
break; break;
case E_AXIS: { case E_AXIS: {
#if E_STEPPERS #if E_STEPPERS
@ -282,6 +291,9 @@
#if AXIS_HAS_STEALTHCHOP(Z3) #if AXIS_HAS_STEALTHCHOP(Z3)
TMC_SAY_PWMTHRS(Z,Z3); TMC_SAY_PWMTHRS(Z,Z3);
#endif #endif
#if AXIS_HAS_STEALTHCHOP(Z4)
TMC_SAY_PWMTHRS(Z,Z4);
#endif
#if E_STEPPERS && AXIS_HAS_STEALTHCHOP(E0) #if E_STEPPERS && AXIS_HAS_STEALTHCHOP(E0)
TMC_SAY_PWMTHRS_E(0); TMC_SAY_PWMTHRS_E(0);
#endif #endif
@ -347,6 +359,9 @@
#if AXIS_HAS_STALLGUARD(Z3) #if AXIS_HAS_STALLGUARD(Z3)
if (index == 0 || index == 3) stepperZ3.homing_threshold(value); if (index == 0 || index == 3) stepperZ3.homing_threshold(value);
#endif #endif
#if AXIS_HAS_STALLGUARD(Z4)
if (index == 0 || index == 4) stepperZ4.homing_threshold(value);
#endif
break; break;
#endif #endif
} }
@ -379,6 +394,9 @@
#if AXIS_HAS_STALLGUARD(Z3) #if AXIS_HAS_STALLGUARD(Z3)
tmc_print_sgt(stepperZ3); tmc_print_sgt(stepperZ3);
#endif #endif
#if AXIS_HAS_STALLGUARD(Z4)
tmc_print_sgt(stepperZ4);
#endif
#endif #endif
} }
} }

View file

@ -566,8 +566,8 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) {
case 665: M665(); break; // M665: Set delta configurations case 665: M665(); break; // M665: Set delta configurations
#endif #endif
#if ANY(DELTA, X_DUAL_ENDSTOPS, Y_DUAL_ENDSTOPS, Z_DUAL_ENDSTOPS) #if ENABLED(DELTA) || HAS_EXTRA_ENDSTOPS
case 666: M666(); break; // M666: Set delta or dual endstop adjustment case 666: M666(); break; // M666: Set delta or multiple endstop adjustment
#endif #endif
#if ENABLED(FWRETRACT) #if ENABLED(FWRETRACT)

View file

@ -121,6 +121,9 @@
#if AXIS_IS_L64XX(Z3) #if AXIS_IS_L64XX(Z3)
REPORT_ABSOLUTE_POS(Z3); REPORT_ABSOLUTE_POS(Z3);
#endif #endif
#if AXIS_IS_L64XX(Z4)
REPORT_ABSOLUTE_POS(Z4);
#endif
#if AXIS_IS_L64XX(E0) #if AXIS_IS_L64XX(E0)
REPORT_ABSOLUTE_POS(E0); REPORT_ABSOLUTE_POS(E0);
#endif #endif

View file

@ -526,6 +526,7 @@
#define GRID_MAX_POINTS ((GRID_MAX_POINTS_X) * (GRID_MAX_POINTS_Y)) #define GRID_MAX_POINTS ((GRID_MAX_POINTS_X) * (GRID_MAX_POINTS_Y))
#endif #endif
#define HAS_EXTRA_ENDSTOPS ANY(X_DUAL_ENDSTOPS, Y_DUAL_ENDSTOPS, Z_MULTI_ENDSTOPS)
#define HAS_SOFTWARE_ENDSTOPS EITHER(MIN_SOFTWARE_ENDSTOPS, MAX_SOFTWARE_ENDSTOPS) #define HAS_SOFTWARE_ENDSTOPS EITHER(MIN_SOFTWARE_ENDSTOPS, MAX_SOFTWARE_ENDSTOPS)
#define HAS_RESUME_CONTINUE ANY(EXTENSIBLE_UI, NEWPANEL, EMERGENCY_PARSER) #define HAS_RESUME_CONTINUE ANY(EXTENSIBLE_UI, NEWPANEL, EMERGENCY_PARSER)
#define HAS_COLOR_LEDS ANY(BLINKM, RGB_LED, RGBW_LED, PCA9632, PCA9533, NEOPIXEL_LED) #define HAS_COLOR_LEDS ANY(BLINKM, RGB_LED, RGBW_LED, PCA9632, PCA9533, NEOPIXEL_LED)
@ -535,10 +536,6 @@
#define HAS_SERVICE_INTERVALS (ENABLED(PRINTCOUNTER) && (SERVICE_INTERVAL_1 > 0 || SERVICE_INTERVAL_2 > 0 || SERVICE_INTERVAL_3 > 0)) #define HAS_SERVICE_INTERVALS (ENABLED(PRINTCOUNTER) && (SERVICE_INTERVAL_1 > 0 || SERVICE_INTERVAL_2 > 0 || SERVICE_INTERVAL_3 > 0))
#define HAS_FILAMENT_SENSOR ENABLED(FILAMENT_RUNOUT_SENSOR) #define HAS_FILAMENT_SENSOR ENABLED(FILAMENT_RUNOUT_SENSOR)
#define Z_MULTI_STEPPER_DRIVERS EITHER(Z_DUAL_STEPPER_DRIVERS, Z_TRIPLE_STEPPER_DRIVERS)
#define Z_MULTI_ENDSTOPS EITHER(Z_DUAL_ENDSTOPS, Z_TRIPLE_ENDSTOPS)
#define HAS_EXTRA_ENDSTOPS (EITHER(X_DUAL_ENDSTOPS, Y_DUAL_ENDSTOPS) || Z_MULTI_ENDSTOPS)
#define HAS_GAMES ANY(MARLIN_BRICKOUT, MARLIN_INVADERS, MARLIN_SNAKE, MARLIN_MAZE) #define HAS_GAMES ANY(MARLIN_BRICKOUT, MARLIN_INVADERS, MARLIN_SNAKE, MARLIN_MAZE)
#define HAS_GAME_MENU (1 < ENABLED(MARLIN_BRICKOUT) + ENABLED(MARLIN_INVADERS) + ENABLED(MARLIN_SNAKE) + ENABLED(MARLIN_MAZE)) #define HAS_GAME_MENU (1 < ENABLED(MARLIN_BRICKOUT) + ENABLED(MARLIN_INVADERS) + ENABLED(MARLIN_SNAKE) + ENABLED(MARLIN_MAZE))

View file

@ -54,6 +54,11 @@
#undef SHOW_TEMP_ADC_VALUES #undef SHOW_TEMP_ADC_VALUES
#endif #endif
// Multiple Z steppers
#ifndef NUM_Z_STEPPER_DRIVERS
#define NUM_Z_STEPPER_DRIVERS 1
#endif
#define HAS_CUTTER EITHER(SPINDLE_FEATURE, LASER_FEATURE) #define HAS_CUTTER EITHER(SPINDLE_FEATURE, LASER_FEATURE)
#if !defined(__AVR__) || !defined(USBCON) #if !defined(__AVR__) || !defined(USBCON)

View file

@ -687,9 +687,6 @@
#endif #endif
#endif #endif
// Is an endstop plug used for the X2 endstop?
#define IS_X2_ENDSTOP(A,M) (ENABLED(X_DUAL_ENDSTOPS) && X2_USE_ENDSTOP == _##A##M##_)
/** /**
* Y_DUAL_ENDSTOPS endstop reassignment * Y_DUAL_ENDSTOPS endstop reassignment
*/ */
@ -743,13 +740,11 @@
#endif #endif
#endif #endif
// Is an endstop plug used for the Y2 endstop or the bed probe?
#define IS_Y2_ENDSTOP(A,M) (ENABLED(Y_DUAL_ENDSTOPS) && Y2_USE_ENDSTOP == _##A##M##_)
/** /**
* Z_DUAL_ENDSTOPS endstop reassignment * Z_MULTI_ENDSTOPS endstop reassignment
*/ */
#if Z_MULTI_ENDSTOPS #if ENABLED(Z_MULTI_ENDSTOPS)
#if Z_HOME_DIR > 0 #if Z_HOME_DIR > 0
#if Z2_USE_ENDSTOP == _XMIN_ #if Z2_USE_ENDSTOP == _XMIN_
#define Z2_MAX_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING #define Z2_MAX_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING
@ -797,9 +792,8 @@
#endif #endif
#define Z2_MAX_ENDSTOP_INVERTING false #define Z2_MAX_ENDSTOP_INVERTING false
#endif #endif
#endif
#if ENABLED(Z_TRIPLE_ENDSTOPS) #if NUM_Z_STEPPER_DRIVERS >= 3
#if Z_HOME_DIR > 0 #if Z_HOME_DIR > 0
#if Z3_USE_ENDSTOP == _XMIN_ #if Z3_USE_ENDSTOP == _XMIN_
#define Z3_MAX_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING #define Z3_MAX_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING
@ -849,15 +843,57 @@
#endif #endif
#endif #endif
// Is an endstop plug used for the Z2 endstop or the bed probe? #if NUM_Z_STEPPER_DRIVERS >= 4
#define IS_Z2_OR_PROBE(A,M) ( \ #if Z_HOME_DIR > 0
(Z_MULTI_ENDSTOPS && Z2_USE_ENDSTOP == _##A##M##_) \ #if Z4_USE_ENDSTOP == _XMIN_
|| (HAS_CUSTOM_PROBE_PIN && Z_MIN_PROBE_PIN == A##_##M##_PIN ) ) #define Z4_MAX_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING
#define Z4_MAX_PIN X_MIN_PIN
#elif Z4_USE_ENDSTOP == _XMAX_
#define Z4_MAX_ENDSTOP_INVERTING X_MAX_ENDSTOP_INVERTING
#define Z4_MAX_PIN X_MAX_PIN
#elif Z4_USE_ENDSTOP == _YMIN_
#define Z4_MAX_ENDSTOP_INVERTING Y_MIN_ENDSTOP_INVERTING
#define Z4_MAX_PIN Y_MIN_PIN
#elif Z4_USE_ENDSTOP == _YMAX_
#define Z4_MAX_ENDSTOP_INVERTING Y_MAX_ENDSTOP_INVERTING
#define Z4_MAX_PIN Y_MAX_PIN
#elif Z4_USE_ENDSTOP == _ZMIN_
#define Z4_MAX_ENDSTOP_INVERTING Z_MIN_ENDSTOP_INVERTING
#define Z4_MAX_PIN Z_MIN_PIN
#elif Z4_USE_ENDSTOP == _ZMAX_
#define Z4_MAX_ENDSTOP_INVERTING Z_MAX_ENDSTOP_INVERTING
#define Z4_MAX_PIN Z_MAX_PIN
#else
#define Z4_MAX_ENDSTOP_INVERTING false
#endif
#define Z4_MIN_ENDSTOP_INVERTING false
#else
#if Z4_USE_ENDSTOP == _XMIN_
#define Z4_MIN_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING
#define Z4_MIN_PIN X_MIN_PIN
#elif Z4_USE_ENDSTOP == _XMAX_
#define Z4_MIN_ENDSTOP_INVERTING X_MAX_ENDSTOP_INVERTING
#define Z4_MIN_PIN X_MAX_PIN
#elif Z4_USE_ENDSTOP == _YMIN_
#define Z4_MIN_ENDSTOP_INVERTING Y_MIN_ENDSTOP_INVERTING
#define Z4_MIN_PIN Y_MIN_PIN
#elif Z4_USE_ENDSTOP == _YMAX_
#define Z4_MIN_ENDSTOP_INVERTING Y_MAX_ENDSTOP_INVERTING
#define Z4_MIN_PIN Y_MAX_PIN
#elif Z4_USE_ENDSTOP == _ZMIN_
#define Z4_MIN_ENDSTOP_INVERTING Z_MIN_ENDSTOP_INVERTING
#define Z4_MIN_PIN Z_MIN_PIN
#elif Z4_USE_ENDSTOP == _ZMAX_
#define Z4_MIN_ENDSTOP_INVERTING Z_MAX_ENDSTOP_INVERTING
#define Z4_MIN_PIN Z_MAX_PIN
#else
#define Z4_MIN_ENDSTOP_INVERTING false
#endif
#define Z4_MAX_ENDSTOP_INVERTING false
#endif
#endif
// Is an endstop plug used for the Z3 endstop or the bed probe? #endif // Z_MULTI_ENDSTOPS
#define IS_Z3_OR_PROBE(A,M) ( \
(ENABLED(Z_TRIPLE_ENDSTOPS) && Z3_USE_ENDSTOP == _##A##M##_) \
|| (HAS_CUSTOM_PROBE_PIN && Z_MIN_PROBE_PIN == A##_##M##_PIN ) )
/** /**
* Set ENDSTOPPULLUPS for active endstop switches * Set ENDSTOPPULLUPS for active endstop switches
@ -947,6 +983,11 @@
#define HAS_Z3_STEP (PIN_EXISTS(Z3_STEP)) #define HAS_Z3_STEP (PIN_EXISTS(Z3_STEP))
#define HAS_Z3_MICROSTEPS (PIN_EXISTS(Z3_MS1)) #define HAS_Z3_MICROSTEPS (PIN_EXISTS(Z3_MS1))
#define HAS_Z4_ENABLE (PIN_EXISTS(Z4_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(Z4)))
#define HAS_Z4_DIR (PIN_EXISTS(Z4_DIR))
#define HAS_Z4_STEP (PIN_EXISTS(Z4_STEP))
#define HAS_Z4_MICROSTEPS (PIN_EXISTS(Z4_MS1))
// Extruder steppers and solenoids // Extruder steppers and solenoids
#define HAS_E0_ENABLE (PIN_EXISTS(E0_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E0))) #define HAS_E0_ENABLE (PIN_EXISTS(E0_ENABLE) || (ENABLED(SOFTWARE_DRIVER_ENABLE) && AXIS_IS_TMC(E0)))
#define HAS_E0_DIR (PIN_EXISTS(E0_DIR)) #define HAS_E0_DIR (PIN_EXISTS(E0_DIR))
@ -999,6 +1040,7 @@
#define Z_SENSORLESS (AXIS_HAS_STALLGUARD(Z) && defined(Z_STALL_SENSITIVITY)) #define Z_SENSORLESS (AXIS_HAS_STALLGUARD(Z) && defined(Z_STALL_SENSITIVITY))
#define Z2_SENSORLESS (AXIS_HAS_STALLGUARD(Z2) && defined(Z2_STALL_SENSITIVITY)) #define Z2_SENSORLESS (AXIS_HAS_STALLGUARD(Z2) && defined(Z2_STALL_SENSITIVITY))
#define Z3_SENSORLESS (AXIS_HAS_STALLGUARD(Z3) && defined(Z3_STALL_SENSITIVITY)) #define Z3_SENSORLESS (AXIS_HAS_STALLGUARD(Z3) && defined(Z3_STALL_SENSITIVITY))
#define Z4_SENSORLESS (AXIS_HAS_STALLGUARD(Z4) && defined(Z4_STALL_SENSITIVITY))
#if ENABLED(SPI_ENDSTOPS) #if ENABLED(SPI_ENDSTOPS)
#define X_SPI_SENSORLESS X_SENSORLESS #define X_SPI_SENSORLESS X_SENSORLESS
#define Y_SPI_SENSORLESS Y_SENSORLESS #define Y_SPI_SENSORLESS Y_SENSORLESS
@ -1011,8 +1053,19 @@
&& E0_ENABLE_PIN != Y_ENABLE_PIN && E1_ENABLE_PIN != Y_ENABLE_PIN ) \ && E0_ENABLE_PIN != Y_ENABLE_PIN && E1_ENABLE_PIN != Y_ENABLE_PIN ) \
) )
//
// Endstops and bed probe // Endstops and bed probe
#define _HAS_STOP(A,M) (PIN_EXISTS(A##_##M) && !IS_X2_ENDSTOP(A,M) && !IS_Y2_ENDSTOP(A,M) && !IS_Z2_OR_PROBE(A,M)) //
// Is an endstop plug used for extra Z endstops or the probe?
#define IS_PROBE_PIN(A,M) (HAS_CUSTOM_PROBE_PIN && Z_MIN_PROBE_PIN == P)
#define IS_X2_ENDSTOP(A,M) (ENABLED(X_DUAL_ENDSTOPS) && X2_USE_ENDSTOP == _##A##M##_)
#define IS_Y2_ENDSTOP(A,M) (ENABLED(Y_DUAL_ENDSTOPS) && Y2_USE_ENDSTOP == _##A##M##_)
#define IS_Z2_ENDSTOP(A,M) (ENABLED(Z_MULTI_ENDSTOPS) && Z2_USE_ENDSTOP == _##A##M##_)
#define IS_Z3_ENDSTOP(A,M) (ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 3 && Z3_USE_ENDSTOP == _##A##M##_)
#define IS_Z4_ENDSTOP(A,M) (ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 4 && Z4_USE_ENDSTOP == _##A##M##_)
#define _HAS_STOP(A,M) (PIN_EXISTS(A##_##M) && !IS_PROBE_PIN(A,M) && !IS_X2_ENDSTOP(A,M) && !IS_Y2_ENDSTOP(A,M) && !IS_Z2_ENDSTOP(A,M) && !IS_Z3_ENDSTOP(A,M) && !IS_Z4_ENDSTOP(A,M))
#define HAS_X_MIN _HAS_STOP(X,MIN) #define HAS_X_MIN _HAS_STOP(X,MIN)
#define HAS_X_MAX _HAS_STOP(X,MAX) #define HAS_X_MAX _HAS_STOP(X,MAX)
#define HAS_Y_MIN _HAS_STOP(Y,MIN) #define HAS_Y_MIN _HAS_STOP(Y,MIN)
@ -1027,6 +1080,8 @@
#define HAS_Z2_MAX (PIN_EXISTS(Z2_MAX)) #define HAS_Z2_MAX (PIN_EXISTS(Z2_MAX))
#define HAS_Z3_MIN (PIN_EXISTS(Z3_MIN)) #define HAS_Z3_MIN (PIN_EXISTS(Z3_MIN))
#define HAS_Z3_MAX (PIN_EXISTS(Z3_MAX)) #define HAS_Z3_MAX (PIN_EXISTS(Z3_MAX))
#define HAS_Z4_MIN (PIN_EXISTS(Z4_MIN))
#define HAS_Z4_MAX (PIN_EXISTS(Z4_MAX))
#define HAS_Z_MIN_PROBE_PIN (HAS_CUSTOM_PROBE_PIN && PIN_EXISTS(Z_MIN_PROBE)) #define HAS_Z_MIN_PROBE_PIN (HAS_CUSTOM_PROBE_PIN && PIN_EXISTS(Z_MIN_PROBE))
#define HAS_CALIBRATION_PIN (PIN_EXISTS(CALIBRATION)) #define HAS_CALIBRATION_PIN (PIN_EXISTS(CALIBRATION))
@ -1147,7 +1202,7 @@
#define HAS_DIGIPOTSS (PIN_EXISTS(DIGIPOTSS)) #define HAS_DIGIPOTSS (PIN_EXISTS(DIGIPOTSS))
#define HAS_MOTOR_CURRENT_PWM ANY_PIN(MOTOR_CURRENT_PWM_X, MOTOR_CURRENT_PWM_Y, MOTOR_CURRENT_PWM_XY, MOTOR_CURRENT_PWM_Z, MOTOR_CURRENT_PWM_E) #define HAS_MOTOR_CURRENT_PWM ANY_PIN(MOTOR_CURRENT_PWM_X, MOTOR_CURRENT_PWM_Y, MOTOR_CURRENT_PWM_XY, MOTOR_CURRENT_PWM_Z, MOTOR_CURRENT_PWM_E)
#define HAS_SOME_Z_MICROSTEPS (HAS_Z_MICROSTEPS || HAS_Z2_MICROSTEPS || HAS_Z3_MICROSTEPS) #define HAS_SOME_Z_MICROSTEPS (HAS_Z_MICROSTEPS || HAS_Z2_MICROSTEPS || HAS_Z3_MICROSTEPS || HAS_Z4_MICROSTEPS)
#define HAS_SOME_E_MICROSTEPS (HAS_E0_MICROSTEPS || HAS_E1_MICROSTEPS || HAS_E2_MICROSTEPS || HAS_E3_MICROSTEPS || HAS_E4_MICROSTEPS || HAS_E5_MICROSTEPS) #define HAS_SOME_E_MICROSTEPS (HAS_E0_MICROSTEPS || HAS_E1_MICROSTEPS || HAS_E2_MICROSTEPS || HAS_E3_MICROSTEPS || HAS_E4_MICROSTEPS || HAS_E5_MICROSTEPS)
#define HAS_MICROSTEPS (HAS_X_MICROSTEPS || HAS_X2_MICROSTEPS || HAS_Y_MICROSTEPS || HAS_Y2_MICROSTEPS || HAS_SOME_Z_MICROSTEPS || HAS_SOME_E_MICROSTEPS) #define HAS_MICROSTEPS (HAS_X_MICROSTEPS || HAS_X2_MICROSTEPS || HAS_Y_MICROSTEPS || HAS_Y2_MICROSTEPS || HAS_SOME_Z_MICROSTEPS || HAS_SOME_E_MICROSTEPS)
@ -1753,14 +1808,6 @@
// If platform requires early initialization of watchdog to properly boot // If platform requires early initialization of watchdog to properly boot
#define EARLY_WATCHDOG (ENABLED(USE_WATCHDOG) && defined(ARDUINO_ARCH_SAM)) #define EARLY_WATCHDOG (ENABLED(USE_WATCHDOG) && defined(ARDUINO_ARCH_SAM))
#if ENABLED(Z_TRIPLE_STEPPER_DRIVERS)
#define Z_STEPPER_COUNT 3
#elif ENABLED(Z_DUAL_STEPPER_DRIVERS)
#define Z_STEPPER_COUNT 2
#else
#define Z_STEPPER_COUNT 1
#endif
#if HAS_SPI_LCD #if HAS_SPI_LCD
// Get LCD character width/height, which may be overridden by pins, configs, etc. // Get LCD character width/height, which may be overridden by pins, configs, etc.
#ifndef LCD_WIDTH #ifndef LCD_WIDTH

View file

@ -426,6 +426,28 @@
#error "HOME_USING_SPREADCYCLE is now obsolete. Please remove it from Configuration_adv.h." #error "HOME_USING_SPREADCYCLE is now obsolete. Please remove it from Configuration_adv.h."
#elif defined(DGUS_LCD) #elif defined(DGUS_LCD)
#error "DGUS_LCD is now DGUS_LCD_UI_(ORIGIN|FYSETC|HIPRECY). Please update your configuration." #error "DGUS_LCD is now DGUS_LCD_UI_(ORIGIN|FYSETC|HIPRECY). Please update your configuration."
#elif defined(X_DUAL_ENDSTOPS_ADJUSTMENT)
#error "X_DUAL_ENDSTOPS_ADJUSTMENT is now X2_ENDSTOP_ADJUSTMENT. Please update Configuration_adv.h."
#elif defined(Y_DUAL_ENDSTOPS_ADJUSTMENT)
#error "Y_DUAL_ENDSTOPS_ADJUSTMENT is now Y2_ENDSTOP_ADJUSTMENT. Please update Configuration_adv.h."
#elif defined(Z_DUAL_ENDSTOPS_ADJUSTMENT)
#error "Z_DUAL_ENDSTOPS_ADJUSTMENT is now Z2_ENDSTOP_ADJUSTMENT. Please update Configuration_adv.h."
#elif defined(Z_TRIPLE_ENDSTOPS_ADJUSTMENT2) || defined(Z_TRIPLE_ENDSTOPS_ADJUSTMENT3)
#error "Z_TRIPLE_ENDSTOPS_ADJUSTMENT[23] is now Z[23]_ENDSTOP_ADJUSTMENT. Please update Configuration_adv.h."
#elif defined(Z_QUAD_ENDSTOPS_ADJUSTMENT2) || defined(Z_QUAD_ENDSTOPS_ADJUSTMENT3) || defined(Z_QUAD_ENDSTOPS_ADJUSTMENT4)
#error "Z_QUAD_ENDSTOPS_ADJUSTMENT[234] is now Z[234]_ENDSTOP_ADJUSTMENT. Please update Configuration_adv.h."
#elif defined(Z_DUAL_STEPPER_DRIVERS)
#error "Z_DUAL_STEPPER_DRIVERS is now NUM_Z_STEPPER_DRIVERS with a value of 2. Please update Configuration_adv.h."
#elif defined(Z_TRIPLE_STEPPER_DRIVERS)
#error "Z_TRIPLE_STEPPER_DRIVERS is now NUM_Z_STEPPER_DRIVERS with a value of 3. Please update Configuration_adv.h."
#elif defined(Z_QUAD_STEPPER_DRIVERS)
#error "Z_QUAD_STEPPER_DRIVERS is now NUM_Z_STEPPER_DRIVERS with a value of 4. Please update Configuration_adv.h."
#elif defined(Z_DUAL_ENDSTOPS)
#error "Z_DUAL_ENDSTOPS is now Z_MULTI_ENDSTOPS. Please update Configuration_adv.h."
#elif defined(Z_TRIPLE_ENDSTOPS)
#error "Z_TRIPLE_ENDSTOPS is now Z_MULTI_ENDSTOPS. Please update Configuration_adv.h."
#elif defined(Z_QUAD_ENDSTOPS)
#error "Z_QUAD_ENDSTOPS is now Z_MULTI_ENDSTOPS. Please update Configuration_adv.h."
#endif #endif
/** /**
@ -473,22 +495,27 @@
#endif #endif
/** /**
* Dual / Triple Stepper Drivers * Multiple Stepper Drivers Per Axis
*/ */
#if BOTH(X_DUAL_STEPPER_DRIVERS, DUAL_X_CARRIAGE) #define GOOD_AXIS_PINS(A) (HAS_##A##_ENABLE && HAS_##A##_STEP && HAS_##A##_DIR)
#if ENABLED(X_DUAL_STEPPER_DRIVERS)
#if ENABLED(DUAL_X_CARRIAGE)
#error "DUAL_X_CARRIAGE is not compatible with X_DUAL_STEPPER_DRIVERS." #error "DUAL_X_CARRIAGE is not compatible with X_DUAL_STEPPER_DRIVERS."
#elif ENABLED(X_DUAL_STEPPER_DRIVERS) && !(HAS_X2_ENABLE && HAS_X2_STEP && HAS_X2_DIR) #elif !GOOD_AXIS_PINS(X)
#error "X_DUAL_STEPPER_DRIVERS requires X2 pins (and an extra E plug)." #error "X_DUAL_STEPPER_DRIVERS requires X2 pins to be defined."
#elif ENABLED(Y_DUAL_STEPPER_DRIVERS) && !(HAS_Y2_ENABLE && HAS_Y2_STEP && HAS_Y2_DIR)
#error "Y_DUAL_STEPPER_DRIVERS requires Y2 pins (and an extra E plug)."
#elif ENABLED(Z_DUAL_STEPPER_DRIVERS)
#if ENABLED(Z_TRIPLE_STEPPER_DRIVERS)
#error "Please select either Z_TRIPLE_STEPPER_DRIVERS or Z_DUAL_STEPPER_DRIVERS, not both."
#elif !(HAS_Z2_ENABLE && HAS_Z2_STEP && HAS_Z2_DIR)
#error "Z_DUAL_STEPPER_DRIVERS requires Z2 pins (and an extra E plug)."
#endif #endif
#elif ENABLED(Z_TRIPLE_STEPPER_DRIVERS) && !(HAS_Z2_ENABLE && HAS_Z2_STEP && HAS_Z2_DIR && HAS_Z3_ENABLE && HAS_Z3_STEP && HAS_Z3_DIR) #endif
#error "Z_TRIPLE_STEPPER_DRIVERS requires Z3 pins (and two extra E plugs)."
#if ENABLED(Y_DUAL_STEPPER_DRIVERS) && !GOOD_AXIS_PINS(Y)
#error "Y_DUAL_STEPPER_DRIVERS requires Y2 pins to be defined."
#elif !WITHIN(NUM_Z_STEPPER_DRIVERS, 1, 4)
#error "NUM_Z_STEPPER_DRIVERS must be an integer from 1 to 4."
#elif NUM_Z_STEPPER_DRIVERS == 2 && !GOOD_AXIS_PINS(Z2)
#error "If NUM_Z_STEPPER_DRIVERS is 2, you must define stepper pins for Z2."
#elif NUM_Z_STEPPER_DRIVERS == 3 && !(GOOD_AXIS_PINS(Z2) && GOOD_AXIS_PINS(Z3))
#error "If NUM_Z_STEPPER_DRIVERS is 3, you must define stepper pins for Z2 and Z3."
#elif NUM_Z_STEPPER_DRIVERS == 4 && !(GOOD_AXIS_PINS(Z2) && GOOD_AXIS_PINS(Z3) && GOOD_AXIS_PINS(Z4))
#error "If NUM_Z_STEPPER_DRIVERS is 4, you must define stepper pins for Z2, Z3, and Z4."
#endif #endif
/** /**
@ -1393,7 +1420,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
#error "DUAL_X_CARRIAGE requires 2 (or more) extruders." #error "DUAL_X_CARRIAGE requires 2 (or more) extruders."
#elif CORE_IS_XY || CORE_IS_XZ #elif CORE_IS_XY || CORE_IS_XZ
#error "DUAL_X_CARRIAGE cannot be used with COREXY, COREYX, COREXZ, or COREZX." #error "DUAL_X_CARRIAGE cannot be used with COREXY, COREYX, COREXZ, or COREZX."
#elif !(HAS_X2_ENABLE && HAS_X2_STEP && HAS_X2_DIR) #elif !GOOD_AXIS_PINS(X2)
#error "DUAL_X_CARRIAGE requires X2 stepper pins to be defined." #error "DUAL_X_CARRIAGE requires X2 stepper pins to be defined."
#elif !HAS_X_MAX #elif !HAS_X_MAX
#error "DUAL_X_CARRIAGE requires USE_XMAX_PLUG and an X Max Endstop." #error "DUAL_X_CARRIAGE requires USE_XMAX_PLUG and an X Max Endstop."
@ -1404,6 +1431,8 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
#endif #endif
#endif #endif
#undef GOOD_AXIS_PINS
/** /**
* Make sure auto fan pins don't conflict with the fan pin * Make sure auto fan pins don't conflict with the fan pin
*/ */
@ -1695,7 +1724,7 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
#error "Enable USE_ZMAX_PLUG when homing Z to MAX." #error "Enable USE_ZMAX_PLUG when homing Z to MAX."
#endif #endif
// Dual endstops requirements // Dual/multiple endstops requirements
#if ENABLED(X_DUAL_ENDSTOPS) #if ENABLED(X_DUAL_ENDSTOPS)
#if !X2_USE_ENDSTOP #if !X2_USE_ENDSTOP
#error "You must set X2_USE_ENDSTOP with X_DUAL_ENDSTOPS." #error "You must set X2_USE_ENDSTOP with X_DUAL_ENDSTOPS."
@ -1738,9 +1767,10 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
#error "Y_DUAL_ENDSTOPS is not compatible with DELTA." #error "Y_DUAL_ENDSTOPS is not compatible with DELTA."
#endif #endif
#endif #endif
#if ENABLED(Z_DUAL_ENDSTOPS)
#if ENABLED(Z_MULTI_ENDSTOPS)
#if !Z2_USE_ENDSTOP #if !Z2_USE_ENDSTOP
#error "You must set Z2_USE_ENDSTOP with Z_DUAL_ENDSTOPS." #error "You must set Z2_USE_ENDSTOP with Z_MULTI_ENDSTOPS when NUM_Z_STEPPER_DRIVERS >= 2."
#elif Z2_USE_ENDSTOP == _XMIN_ && DISABLED(USE_XMIN_PLUG) #elif Z2_USE_ENDSTOP == _XMIN_ && DISABLED(USE_XMIN_PLUG)
#error "USE_XMIN_PLUG is required when Z2_USE_ENDSTOP is _XMIN_." #error "USE_XMIN_PLUG is required when Z2_USE_ENDSTOP is _XMIN_."
#elif Z2_USE_ENDSTOP == _XMAX_ && DISABLED(USE_XMAX_PLUG) #elif Z2_USE_ENDSTOP == _XMAX_ && DISABLED(USE_XMAX_PLUG)
@ -1756,31 +1786,11 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
#elif !HAS_Z2_MIN && !HAS_Z2_MAX #elif !HAS_Z2_MIN && !HAS_Z2_MAX
#error "Z2_USE_ENDSTOP has been assigned to a nonexistent endstop!" #error "Z2_USE_ENDSTOP has been assigned to a nonexistent endstop!"
#elif ENABLED(DELTA) #elif ENABLED(DELTA)
#error "Z_DUAL_ENDSTOPS is not compatible with DELTA." #error "Z_MULTI_ENDSTOPS is not compatible with DELTA."
#endif
#endif
#if ENABLED(Z_TRIPLE_ENDSTOPS)
#if !Z2_USE_ENDSTOP
#error "You must set Z2_USE_ENDSTOP with Z_TRIPLE_ENDSTOPS."
#elif Z2_USE_ENDSTOP == _XMIN_ && DISABLED(USE_XMIN_PLUG)
#error "USE_XMIN_PLUG is required when Z2_USE_ENDSTOP is _XMIN_."
#elif Z2_USE_ENDSTOP == _XMAX_ && DISABLED(USE_XMAX_PLUG)
#error "USE_XMAX_PLUG is required when Z2_USE_ENDSTOP is _XMAX_."
#elif Z2_USE_ENDSTOP == _YMIN_ && DISABLED(USE_YMIN_PLUG)
#error "USE_YMIN_PLUG is required when Z2_USE_ENDSTOP is _YMIN_."
#elif Z2_USE_ENDSTOP == _YMAX_ && DISABLED(USE_YMAX_PLUG)
#error "USE_YMAX_PLUG is required when Z2_USE_ENDSTOP is _YMAX_."
#elif Z2_USE_ENDSTOP == _ZMIN_ && DISABLED(USE_ZMIN_PLUG)
#error "USE_ZMIN_PLUG is required when Z2_USE_ENDSTOP is _ZMIN_."
#elif Z2_USE_ENDSTOP == _ZMAX_ && DISABLED(USE_ZMAX_PLUG)
#error "USE_ZMAX_PLUG is required when Z2_USE_ENDSTOP is _ZMAX_."
#elif !HAS_Z2_MIN && !HAS_Z2_MAX
#error "Z2_USE_ENDSTOP has been assigned to a nonexistent endstop!"
#elif ENABLED(DELTA)
#error "Z_TRIPLE_ENDSTOPS is not compatible with DELTA."
#endif #endif
#if NUM_Z_STEPPER_DRIVERS >= 3
#if !Z3_USE_ENDSTOP #if !Z3_USE_ENDSTOP
#error "You must set Z3_USE_ENDSTOP with Z_TRIPLE_ENDSTOPS." #error "You must set Z3_USE_ENDSTOP with Z_MULTI_ENDSTOPS when NUM_Z_STEPPER_DRIVERS >= 3."
#elif Z3_USE_ENDSTOP == _XMIN_ && DISABLED(USE_XMIN_PLUG) #elif Z3_USE_ENDSTOP == _XMIN_ && DISABLED(USE_XMIN_PLUG)
#error "USE_XMIN_PLUG is required when Z3_USE_ENDSTOP is _XMIN_." #error "USE_XMIN_PLUG is required when Z3_USE_ENDSTOP is _XMIN_."
#elif Z3_USE_ENDSTOP == _XMAX_ && DISABLED(USE_XMAX_PLUG) #elif Z3_USE_ENDSTOP == _XMAX_ && DISABLED(USE_XMAX_PLUG)
@ -1795,8 +1805,26 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
#error "USE_ZMAX_PLUG is required when Z3_USE_ENDSTOP is _ZMAX_." #error "USE_ZMAX_PLUG is required when Z3_USE_ENDSTOP is _ZMAX_."
#elif !HAS_Z3_MIN && !HAS_Z3_MAX #elif !HAS_Z3_MIN && !HAS_Z3_MAX
#error "Z3_USE_ENDSTOP has been assigned to a nonexistent endstop!" #error "Z3_USE_ENDSTOP has been assigned to a nonexistent endstop!"
#elif ENABLED(DELTA) #endif
#error "Z_TRIPLE_ENDSTOPS is not compatible with DELTA." #endif
#if NUM_Z_STEPPER_DRIVERS >= 4
#if !Z4_USE_ENDSTOP
#error "You must set Z4_USE_ENDSTOP with Z_MULTI_ENDSTOPS when NUM_Z_STEPPER_DRIVERS >= 4."
#elif Z4_USE_ENDSTOP == _XMIN_ && DISABLED(USE_XMIN_PLUG)
#error "USE_XMIN_PLUG is required when Z4_USE_ENDSTOP is _XMIN_."
#elif Z4_USE_ENDSTOP == _XMAX_ && DISABLED(USE_XMAX_PLUG)
#error "USE_XMAX_PLUG is required when Z4_USE_ENDSTOP is _XMAX_."
#elif Z4_USE_ENDSTOP == _YMIN_ && DISABLED(USE_YMIN_PLUG)
#error "USE_YMIN_PLUG is required when Z4_USE_ENDSTOP is _YMIN_."
#elif Z4_USE_ENDSTOP == _YMAX_ && DISABLED(USE_YMAX_PLUG)
#error "USE_YMAX_PLUG is required when Z4_USE_ENDSTOP is _YMAX_."
#elif Z4_USE_ENDSTOP == _ZMIN_ && DISABLED(USE_ZMIN_PLUG)
#error "USE_ZMIN_PLUG is required when Z4_USE_ENDSTOP is _ZMIN_."
#elif Z4_USE_ENDSTOP == _ZMAX_ && DISABLED(USE_ZMAX_PLUG)
#error "USE_ZMAX_PLUG is required when Z4_USE_ENDSTOP is _ZMAX_."
#elif !HAS_Z4_MIN && !HAS_Z4_MAX
#error "Z4_USE_ENDSTOP has been assigned to a nonexistent endstop!"
#endif
#endif #endif
#endif #endif
@ -2321,12 +2349,12 @@ static_assert( _ARR_TEST(3,0) && _ARR_TEST(3,1) && _ARR_TEST(3,2)
#endif #endif
#if ENABLED(Z_STEPPER_AUTO_ALIGN) #if ENABLED(Z_STEPPER_AUTO_ALIGN)
#if !Z_MULTI_STEPPER_DRIVERS #if NUM_Z_STEPPER_DRIVERS <= 1
#error "Z_STEPPER_AUTO_ALIGN requires Z_DUAL_STEPPER_DRIVERS or Z_TRIPLE_STEPPER_DRIVERS." #error "Z_STEPPER_AUTO_ALIGN requires NUM_Z_STEPPER_DRIVERS greater than 1."
#elif !HAS_BED_PROBE #elif !HAS_BED_PROBE
#error "Z_STEPPER_AUTO_ALIGN requires a Z-bed probe." #error "Z_STEPPER_AUTO_ALIGN requires a Z-bed probe."
#elif ENABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) && DISABLED(Z_TRIPLE_STEPPER_DRIVERS) #elif ENABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) && NUM_Z_STEPPER_DRIVERS != 3
#error "Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS requires Z_TRIPLE_STEPPER_DRIVERS." #error "Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS requires NUM_Z_STEPPER_DRIVERS to be 3."
#endif #endif
#endif #endif

View file

@ -58,6 +58,9 @@ void menu_tmc_current() {
#if AXIS_IS_TMC(Z3) #if AXIS_IS_TMC(Z3)
TMC_EDIT_STORED_I_RMS(Z3, MSG_Z3); TMC_EDIT_STORED_I_RMS(Z3, MSG_Z3);
#endif #endif
#if AXIS_IS_TMC(Z4)
TMC_EDIT_STORED_I_RMS(Z4, MSG_Z4);
#endif
#if AXIS_IS_TMC(E0) #if AXIS_IS_TMC(E0)
TMC_EDIT_STORED_I_RMS(E0, LCD_STR_E0); TMC_EDIT_STORED_I_RMS(E0, LCD_STR_E0);
#endif #endif
@ -107,6 +110,9 @@ void menu_tmc_current() {
#if AXIS_HAS_STEALTHCHOP(Z3) #if AXIS_HAS_STEALTHCHOP(Z3)
TMC_EDIT_STORED_HYBRID_THRS(Z3, MSG_Z3); TMC_EDIT_STORED_HYBRID_THRS(Z3, MSG_Z3);
#endif #endif
#if AXIS_HAS_STEALTHCHOP(Z4)
TMC_EDIT_STORED_HYBRID_THRS(Z4, MSG_Z4);
#endif
#if AXIS_HAS_STEALTHCHOP(E0) #if AXIS_HAS_STEALTHCHOP(E0)
TMC_EDIT_STORED_HYBRID_THRS(E0, LCD_STR_E0); TMC_EDIT_STORED_HYBRID_THRS(E0, LCD_STR_E0);
#endif #endif
@ -183,6 +189,9 @@ void menu_tmc_current() {
#if AXIS_HAS_STEALTHCHOP(Z3) #if AXIS_HAS_STEALTHCHOP(Z3)
TMC_EDIT_STEP_MODE(Z3, MSG_Z3); TMC_EDIT_STEP_MODE(Z3, MSG_Z3);
#endif #endif
#if AXIS_HAS_STEALTHCHOP(Z4)
TMC_EDIT_STEP_MODE(Z4, MSG_Z4);
#endif
#if AXIS_HAS_STEALTHCHOP(E0) #if AXIS_HAS_STEALTHCHOP(E0)
TMC_EDIT_STEP_MODE(E0, LCD_STR_E0); TMC_EDIT_STEP_MODE(E0, LCD_STR_E0);
#endif #endif

View file

@ -39,7 +39,7 @@ L64XX_Marlin L64xxManager;
void echo_yes_no(const bool yes) { serialprintPGM(yes ? PSTR(" YES") : PSTR(" NO ")); } void echo_yes_no(const bool yes) { serialprintPGM(yes ? PSTR(" YES") : PSTR(" NO ")); }
char L64XX_Marlin::index_to_axis[MAX_L64XX][3] = { "X ", "Y ", "Z ", "X2", "Y2", "Z2", "Z3", "E0", "E1", "E2", "E3", "E4", "E5" }; char L64XX_Marlin::index_to_axis[MAX_L64XX][3] = { "X ", "Y ", "Z ", "X2", "Y2", "Z2", "Z3", "Z4", "E0", "E1", "E2", "E3", "E4", "E5" };
#define DEBUG_OUT ENABLED(L6470_CHITCHAT) #define DEBUG_OUT ENABLED(L6470_CHITCHAT)
#include "../../core/debug_out.h" #include "../../core/debug_out.h"
@ -61,12 +61,14 @@ uint8_t L64XX_Marlin::index_to_dir[MAX_L64XX] = { (INVERT_X_DIR),
#endif #endif
(INVERT_Z_DIR), // 5 Z2 (INVERT_Z_DIR), // 5 Z2
(INVERT_Z_DIR), // 6 Z3 (INVERT_Z_DIR), // 6 Z3
(INVERT_E0_DIR), // 7 E0 (INVERT_Z_DIR), // 7 Z4
(INVERT_E1_DIR), // 8 E1
(INVERT_E2_DIR), // 9 E2 (INVERT_E0_DIR), // 8 E0
(INVERT_E3_DIR), // 10 E3 (INVERT_E1_DIR), // 9 E1
(INVERT_E4_DIR), // 11 E4 (INVERT_E2_DIR), // 10 E2
(INVERT_E5_DIR), // 12 E5 (INVERT_E3_DIR), // 11 E3
(INVERT_E4_DIR), // 12 E4
(INVERT_E5_DIR), // 13 E5
}; };
volatile uint8_t L64XX_Marlin::spi_abort = false; volatile uint8_t L64XX_Marlin::spi_abort = false;
@ -101,6 +103,9 @@ void L6470_populate_chain_array() {
#if AXIS_IS_L64XX(Z3) #if AXIS_IS_L64XX(Z3)
_L6470_INIT_SPI(Z3); _L6470_INIT_SPI(Z3);
#endif #endif
#if AXIS_IS_L64XX(Z4)
_L6470_INIT_SPI(Z4);
#endif
#if AXIS_IS_L64XX(E0) #if AXIS_IS_L64XX(E0)
_L6470_INIT_SPI(E0); _L6470_INIT_SPI(E0);
#endif #endif
@ -211,6 +216,9 @@ uint16_t L64XX_Marlin::get_status(const L64XX_axis_t axis) {
#if AXIS_IS_L64XX(Z3) #if AXIS_IS_L64XX(Z3)
case Z3: return STATUS_L6470(Z3); case Z3: return STATUS_L6470(Z3);
#endif #endif
#if AXIS_IS_L64XX(Z4)
case Z4: return STATUS_L6470(Z4);
#endif
#if AXIS_IS_L64XX(E0) #if AXIS_IS_L64XX(E0)
case E0: return STATUS_L6470(E0); case E0: return STATUS_L6470(E0);
#endif #endif
@ -261,6 +269,9 @@ uint32_t L64XX_Marlin::get_param(const L64XX_axis_t axis, const uint8_t param) {
#if AXIS_IS_L64XX(Z3) #if AXIS_IS_L64XX(Z3)
case Z3: return GET_L6470_PARAM(Z3); case Z3: return GET_L6470_PARAM(Z3);
#endif #endif
#if AXIS_IS_L64XX(Z4)
case Z4: return GET_L6470_PARAM(Z4);
#endif
#if AXIS_IS_L64XX(E0) #if AXIS_IS_L64XX(E0)
case E0: return GET_L6470_PARAM(E0); case E0: return GET_L6470_PARAM(E0);
#endif #endif
@ -311,6 +322,9 @@ void L64XX_Marlin::set_param(const L64XX_axis_t axis, const uint8_t param, const
#if AXIS_IS_L64XX(Z3) #if AXIS_IS_L64XX(Z3)
case Z3: SET_L6470_PARAM(Z3); break; case Z3: SET_L6470_PARAM(Z3); break;
#endif #endif
#if AXIS_IS_L64XX(Z4)
case Z4: SET_L6470_PARAM(Z4); break;
#endif
#if AXIS_IS_L64XX(E0) #if AXIS_IS_L64XX(E0)
case E0: SET_L6470_PARAM(E0); break; case E0: SET_L6470_PARAM(E0); break;
#endif #endif
@ -684,6 +698,9 @@ void L64XX_Marlin::say_axis(const L64XX_axis_t axis, const uint8_t label/*=true*
#if AXIS_IS_L64XX(Z3) #if AXIS_IS_L64XX(Z3)
{ 6, 0, 0, 0, 0, 0, 0 }, { 6, 0, 0, 0, 0, 0, 0 },
#endif #endif
#if AXIS_IS_L64XX(Z4)
{ 6, 0, 0, 0, 0, 0, 0 },
#endif
#if AXIS_IS_L64XX(E0) #if AXIS_IS_L64XX(E0)
{ 7, 0, 0, 0, 0, 0, 0 }, { 7, 0, 0, 0, 0, 0, 0 },
#endif #endif
@ -858,6 +875,9 @@ void L64XX_Marlin::say_axis(const L64XX_axis_t axis, const uint8_t label/*=true*
#if AXIS_IS_L64XX(Z3) #if AXIS_IS_L64XX(Z3)
monitor_update(Z3); monitor_update(Z3);
#endif #endif
#if AXIS_IS_L64XX(Z4)
monitor_update(Z4);
#endif
#if AXIS_IS_L64XX(E0) #if AXIS_IS_L64XX(E0)
monitor_update(E0); monitor_update(E0);
#endif #endif

View file

@ -35,7 +35,7 @@
#define dSPIN_STEP_CLOCK_REV dSPIN_STEP_CLOCK+1 #define dSPIN_STEP_CLOCK_REV dSPIN_STEP_CLOCK+1
#define HAS_L64XX_EXTRUDER (AXIS_IS_L64XX(E0) || AXIS_IS_L64XX(E1) || AXIS_IS_L64XX(E2) || AXIS_IS_L64XX(E3) || AXIS_IS_L64XX(E4) || AXIS_IS_L64XX(E5)) #define HAS_L64XX_EXTRUDER (AXIS_IS_L64XX(E0) || AXIS_IS_L64XX(E1) || AXIS_IS_L64XX(E2) || AXIS_IS_L64XX(E3) || AXIS_IS_L64XX(E4) || AXIS_IS_L64XX(E5))
enum L64XX_axis_t : uint8_t { X, Y, Z, X2, Y2, Z2, Z3, E0, E1, E2, E3, E4, E5, MAX_L64XX }; enum L64XX_axis_t : uint8_t { X, Y, Z, X2, Y2, Z2, Z3, Z4, E0, E1, E2, E3, E4, E5, MAX_L64XX };
class L64XX_Marlin : public L64XXHelper { class L64XX_Marlin : public L64XXHelper {
public: public:

View file

@ -37,7 +37,7 @@
*/ */
// Change EEPROM version if the structure changes // Change EEPROM version if the structure changes
#define EEPROM_VERSION "V74" #define EEPROM_VERSION "V75"
#define EEPROM_OFFSET 100 #define EEPROM_OFFSET 100
// Check the integrity of data offsets. // Check the integrity of data offsets.
@ -120,10 +120,10 @@
#pragma pack(push, 1) // No padding between variables #pragma pack(push, 1) // No padding between variables
typedef struct { uint16_t X, Y, Z, X2, Y2, Z2, Z3, E0, E1, E2, E3, E4, E5; } tmc_stepper_current_t; typedef struct { uint16_t X, Y, Z, X2, Y2, Z2, Z3, Z4, E0, E1, E2, E3, E4, E5; } tmc_stepper_current_t;
typedef struct { uint32_t X, Y, Z, X2, Y2, Z2, Z3, E0, E1, E2, E3, E4, E5; } tmc_hybrid_threshold_t; typedef struct { uint32_t X, Y, Z, X2, Y2, Z2, Z3, Z4, E0, E1, E2, E3, E4, E5; } tmc_hybrid_threshold_t;
typedef struct { int16_t X, Y, Z, X2; } tmc_sgt_t; typedef struct { int16_t X, Y, Z, X2; } tmc_sgt_t;
typedef struct { bool X, Y, Z, X2, Y2, Z2, Z3, E0, E1, E2, E3, E4, E5; } tmc_stealth_enabled_t; typedef struct { bool X, Y, Z, X2, Y2, Z2, Z3, Z4, E0, E1, E2, E3, E4, E5; } tmc_stealth_enabled_t;
// Limit an index to an array size // Limit an index to an array size
#define ALIM(I,ARR) _MIN(I, COUNT(ARR) - 1) #define ALIM(I,ARR) _MIN(I, COUNT(ARR) - 1)
@ -243,11 +243,12 @@ typedef struct SettingsDataStruct {
delta_diagonal_rod, // M665 L delta_diagonal_rod, // M665 L
delta_segments_per_second; // M665 S delta_segments_per_second; // M665 S
abc_float_t delta_tower_angle_trim; // M665 XYZ abc_float_t delta_tower_angle_trim; // M665 XYZ
#elif EITHER(X_DUAL_ENDSTOPS, Y_DUAL_ENDSTOPS) || Z_MULTI_ENDSTOPS #elif HAS_EXTRA_ENDSTOPS
float x2_endstop_adj, // M666 X float x2_endstop_adj, // M666 X
y2_endstop_adj, // M666 Y y2_endstop_adj, // M666 Y
z2_endstop_adj, // M666 Z (S2) z2_endstop_adj, // M666 (S2) Z
z3_endstop_adj; // M666 Z (S3) z3_endstop_adj, // M666 (S3) Z
z4_endstop_adj; // M666 (S4) Z
#endif #endif
// //
@ -300,10 +301,10 @@ typedef struct SettingsDataStruct {
// //
// HAS_TRINAMIC // HAS_TRINAMIC
// //
tmc_stepper_current_t tmc_stepper_current; // M906 X Y Z X2 Y2 Z2 Z3 E0 E1 E2 E3 E4 E5 tmc_stepper_current_t tmc_stepper_current; // M906 X Y Z X2 Y2 Z2 Z3 Z4 E0 E1 E2 E3 E4 E5
tmc_hybrid_threshold_t tmc_hybrid_threshold; // M913 X Y Z X2 Y2 Z2 Z3 E0 E1 E2 E3 E4 E5 tmc_hybrid_threshold_t tmc_hybrid_threshold; // M913 X Y Z X2 Y2 Z2 Z3 Z4 E0 E1 E2 E3 E4 E5
tmc_sgt_t tmc_sgt; // M914 X Y Z X2 tmc_sgt_t tmc_sgt; // M914 X Y Z X2
tmc_stealth_enabled_t tmc_stealth_enabled; // M569 X Y Z X2 Y2 Z2 Z3 E0 E1 E2 E3 E4 E5 tmc_stealth_enabled_t tmc_stealth_enabled; // M569 X Y Z X2 Y2 Z2 Z3 Z4 E0 E1 E2 E3 E4 E5
// //
// LIN_ADVANCE // LIN_ADVANCE
@ -756,7 +757,7 @@ void MarlinSettings::postprocess() {
EEPROM_WRITE(delta_segments_per_second); // 1 float EEPROM_WRITE(delta_segments_per_second); // 1 float
EEPROM_WRITE(delta_tower_angle_trim); // 3 floats EEPROM_WRITE(delta_tower_angle_trim); // 3 floats
#elif EITHER(X_DUAL_ENDSTOPS, Y_DUAL_ENDSTOPS) || Z_MULTI_ENDSTOPS #elif HAS_EXTRA_ENDSTOPS
_FIELD_TEST(x2_endstop_adj); _FIELD_TEST(x2_endstop_adj);
@ -774,18 +775,24 @@ void MarlinSettings::postprocess() {
EEPROM_WRITE(dummy); EEPROM_WRITE(dummy);
#endif #endif
#if Z_MULTI_ENDSTOPS #if ENABLED(Z_MULTI_ENDSTOPS)
EEPROM_WRITE(endstops.z2_endstop_adj); // 1 float EEPROM_WRITE(endstops.z2_endstop_adj); // 1 float
#else #else
EEPROM_WRITE(dummy); EEPROM_WRITE(dummy);
#endif #endif
#if ENABLED(Z_TRIPLE_ENDSTOPS) #if ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 3
EEPROM_WRITE(endstops.z3_endstop_adj); // 1 float EEPROM_WRITE(endstops.z3_endstop_adj); // 1 float
#else #else
EEPROM_WRITE(dummy); EEPROM_WRITE(dummy);
#endif #endif
#if ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 4
EEPROM_WRITE(endstops.z4_endstop_adj); // 1 float
#else
EEPROM_WRITE(dummy);
#endif
#endif #endif
} }
@ -974,6 +981,9 @@ void MarlinSettings::postprocess() {
#if AXIS_IS_TMC(Z3) #if AXIS_IS_TMC(Z3)
tmc_stepper_current.Z3 = stepperZ3.getMilliamps(); tmc_stepper_current.Z3 = stepperZ3.getMilliamps();
#endif #endif
#if AXIS_IS_TMC(Z4)
tmc_stepper_current.Z4 = stepperZ4.getMilliamps();
#endif
#if MAX_EXTRUDERS #if MAX_EXTRUDERS
#if AXIS_IS_TMC(E0) #if AXIS_IS_TMC(E0)
tmc_stepper_current.E0 = stepperE0.getMilliamps(); tmc_stepper_current.E0 = stepperE0.getMilliamps();
@ -1037,6 +1047,9 @@ void MarlinSettings::postprocess() {
#if AXIS_HAS_STEALTHCHOP(Z3) #if AXIS_HAS_STEALTHCHOP(Z3)
tmc_hybrid_threshold.Z3 = stepperZ3.get_pwm_thrs(); tmc_hybrid_threshold.Z3 = stepperZ3.get_pwm_thrs();
#endif #endif
#if AXIS_HAS_STEALTHCHOP(Z4)
tmc_hybrid_threshold.Z4 = stepperZ4.get_pwm_thrs();
#endif
#if MAX_EXTRUDERS #if MAX_EXTRUDERS
#if AXIS_HAS_STEALTHCHOP(E0) #if AXIS_HAS_STEALTHCHOP(E0)
tmc_hybrid_threshold.E0 = stepperE0.get_pwm_thrs(); tmc_hybrid_threshold.E0 = stepperE0.get_pwm_thrs();
@ -1070,7 +1083,7 @@ void MarlinSettings::postprocess() {
#else #else
const tmc_hybrid_threshold_t tmc_hybrid_threshold = { const tmc_hybrid_threshold_t tmc_hybrid_threshold = {
.X = 100, .Y = 100, .Z = 3, .X = 100, .Y = 100, .Z = 3,
.X2 = 100, .Y2 = 100, .Z2 = 3, .Z3 = 3, .X2 = 100, .Y2 = 100, .Z2 = 3, .Z3 = 3, .Z4 = 3,
.E0 = 30, .E1 = 30, .E2 = 30, .E0 = 30, .E1 = 30, .E2 = 30,
.E3 = 30, .E4 = 30, .E5 = 30 .E3 = 30, .E4 = 30, .E5 = 30
}; };
@ -1130,6 +1143,9 @@ void MarlinSettings::postprocess() {
#if AXIS_HAS_STEALTHCHOP(Z3) #if AXIS_HAS_STEALTHCHOP(Z3)
tmc_stealth_enabled.Z3 = stepperZ3.get_stealthChop_status(); tmc_stealth_enabled.Z3 = stepperZ3.get_stealthChop_status();
#endif #endif
#if AXIS_HAS_STEALTHCHOP(Z4)
tmc_stealth_enabled.Z4 = stepperZ4.get_stealthChop_status();
#endif
#if MAX_EXTRUDERS #if MAX_EXTRUDERS
#if AXIS_HAS_STEALTHCHOP(E0) #if AXIS_HAS_STEALTHCHOP(E0)
tmc_stealth_enabled.E0 = stepperE0.get_stealthChop_status(); tmc_stealth_enabled.E0 = stepperE0.get_stealthChop_status();
@ -1585,7 +1601,7 @@ void MarlinSettings::postprocess() {
EEPROM_READ(delta_segments_per_second); // 1 float EEPROM_READ(delta_segments_per_second); // 1 float
EEPROM_READ(delta_tower_angle_trim); // 3 floats EEPROM_READ(delta_tower_angle_trim); // 3 floats
#elif EITHER(X_DUAL_ENDSTOPS, Y_DUAL_ENDSTOPS) || Z_MULTI_ENDSTOPS #elif HAS_EXTRA_ENDSTOPS
_FIELD_TEST(x2_endstop_adj); _FIELD_TEST(x2_endstop_adj);
@ -1599,16 +1615,21 @@ void MarlinSettings::postprocess() {
#else #else
EEPROM_READ(dummy); EEPROM_READ(dummy);
#endif #endif
#if Z_MULTI_ENDSTOPS #if ENABLED(Z_MULTI_ENDSTOPS)
EEPROM_READ(endstops.z2_endstop_adj); // 1 float EEPROM_READ(endstops.z2_endstop_adj); // 1 float
#else #else
EEPROM_READ(dummy); EEPROM_READ(dummy);
#endif #endif
#if ENABLED(Z_TRIPLE_ENDSTOPS) #if ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 3
EEPROM_READ(endstops.z3_endstop_adj); // 1 float EEPROM_READ(endstops.z3_endstop_adj); // 1 float
#else #else
EEPROM_READ(dummy); EEPROM_READ(dummy);
#endif #endif
#if ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 4
EEPROM_READ(endstops.z4_endstop_adj); // 1 float
#else
EEPROM_READ(dummy);
#endif
#endif #endif
} }
@ -1800,6 +1821,9 @@ void MarlinSettings::postprocess() {
#if AXIS_IS_TMC(Z3) #if AXIS_IS_TMC(Z3)
SET_CURR(Z3); SET_CURR(Z3);
#endif #endif
#if AXIS_IS_TMC(Z4)
SET_CURR(Z4);
#endif
#if AXIS_IS_TMC(E0) #if AXIS_IS_TMC(E0)
SET_CURR(E0); SET_CURR(E0);
#endif #endif
@ -1851,6 +1875,9 @@ void MarlinSettings::postprocess() {
#if AXIS_HAS_STEALTHCHOP(Z3) #if AXIS_HAS_STEALTHCHOP(Z3)
stepperZ3.set_pwm_thrs(tmc_hybrid_threshold.Z3); stepperZ3.set_pwm_thrs(tmc_hybrid_threshold.Z3);
#endif #endif
#if AXIS_HAS_STEALTHCHOP(Z4)
stepperZ4.set_pwm_thrs(tmc_hybrid_threshold.Z4);
#endif
#if AXIS_HAS_STEALTHCHOP(E0) #if AXIS_HAS_STEALTHCHOP(E0)
stepperE0.set_pwm_thrs(tmc_hybrid_threshold.E0); stepperE0.set_pwm_thrs(tmc_hybrid_threshold.E0);
#endif #endif
@ -1877,7 +1904,7 @@ void MarlinSettings::postprocess() {
// TMC StallGuard threshold. // TMC StallGuard threshold.
// X and X2 use the same value // X and X2 use the same value
// Y and Y2 use the same value // Y and Y2 use the same value
// Z, Z2 and Z3 use the same value // Z, Z2, Z3 and Z4 use the same value
// //
{ {
tmc_sgt_t tmc_sgt; tmc_sgt_t tmc_sgt;
@ -1914,6 +1941,9 @@ void MarlinSettings::postprocess() {
#if AXIS_HAS_STALLGUARD(Z3) #if AXIS_HAS_STALLGUARD(Z3)
stepperZ3.homing_threshold(tmc_sgt.Z); stepperZ3.homing_threshold(tmc_sgt.Z);
#endif #endif
#if AXIS_HAS_STALLGUARD(Z4)
stepperZ4.homing_threshold(tmc_sgt.Z);
#endif
#endif #endif
} }
#endif #endif
@ -1951,6 +1981,9 @@ void MarlinSettings::postprocess() {
#if AXIS_HAS_STEALTHCHOP(Z3) #if AXIS_HAS_STEALTHCHOP(Z3)
SET_STEPPING_MODE(Z3); SET_STEPPING_MODE(Z3);
#endif #endif
#if AXIS_HAS_STEALTHCHOP(Z4)
SET_STEPPING_MODE(Z4);
#endif
#if AXIS_HAS_STEALTHCHOP(E0) #if AXIS_HAS_STEALTHCHOP(E0)
SET_STEPPING_MODE(E0); SET_STEPPING_MODE(E0);
#endif #endif
@ -2433,51 +2466,39 @@ void MarlinSettings::reset() {
delta_segments_per_second = DELTA_SEGMENTS_PER_SECOND; delta_segments_per_second = DELTA_SEGMENTS_PER_SECOND;
delta_tower_angle_trim = dta; delta_tower_angle_trim = dta;
#elif EITHER(X_DUAL_ENDSTOPS, Y_DUAL_ENDSTOPS) || Z_MULTI_ENDSTOPS #endif
#if ENABLED(X_DUAL_ENDSTOPS) #if ENABLED(X_DUAL_ENDSTOPS)
endstops.x2_endstop_adj = ( #ifndef X2_ENDSTOP_ADJUSTMENT
#ifdef X_DUAL_ENDSTOPS_ADJUSTMENT #define X2_ENDSTOP_ADJUSTMENT 0
X_DUAL_ENDSTOPS_ADJUSTMENT
#else
0
#endif #endif
); endstops.x2_endstop_adj = X2_ENDSTOP_ADJUSTMENT;
#endif
#if ENABLED(Y_DUAL_ENDSTOPS)
endstops.y2_endstop_adj = (
#ifdef Y_DUAL_ENDSTOPS_ADJUSTMENT
Y_DUAL_ENDSTOPS_ADJUSTMENT
#else
0
#endif
);
#endif
#if ENABLED(Z_DUAL_ENDSTOPS)
endstops.z2_endstop_adj = (
#ifdef Z_DUAL_ENDSTOPS_ADJUSTMENT
Z_DUAL_ENDSTOPS_ADJUSTMENT
#else
0
#endif
);
#elif ENABLED(Z_TRIPLE_ENDSTOPS)
endstops.z2_endstop_adj = (
#ifdef Z_TRIPLE_ENDSTOPS_ADJUSTMENT2
Z_TRIPLE_ENDSTOPS_ADJUSTMENT2
#else
0
#endif
);
endstops.z3_endstop_adj = (
#ifdef Z_TRIPLE_ENDSTOPS_ADJUSTMENT3
Z_TRIPLE_ENDSTOPS_ADJUSTMENT3
#else
0
#endif
);
#endif #endif
#if ENABLED(Y_DUAL_ENDSTOPS)
#ifndef Y2_ENDSTOP_ADJUSTMENT
#define Y2_ENDSTOP_ADJUSTMENT 0
#endif
endstops.y2_endstop_adj = Y2_ENDSTOP_ADJUSTMENT;
#endif
#if ENABLED(Z_MULTI_ENDSTOPS)
#ifndef Z2_ENDSTOP_ADJUSTMENT
#define Z2_ENDSTOP_ADJUSTMENT 0
#endif
endstops.z2_endstop_adj = Z2_ENDSTOP_ADJUSTMENT;
#if NUM_Z_STEPPER_DRIVERS >= 3
#ifndef Z3_ENDSTOP_ADJUSTMENT
#define Z3_ENDSTOP_ADJUSTMENT 0
#endif
endstops.z3_endstop_adj = Z3_ENDSTOP_ADJUSTMENT;
#endif
#if NUM_Z_STEPPER_DRIVERS >= 4
#ifndef Z4_ENDSTOP_ADJUSTMENT
#define Z4_ENDSTOP_ADJUSTMENT 0
#endif
endstops.z4_endstop_adj = Z4_ENDSTOP_ADJUSTMENT;
#endif
#endif #endif
// //
@ -3016,25 +3037,30 @@ void MarlinSettings::reset() {
, SP_Z_STR, LINEAR_UNIT(delta_tower_angle_trim.c) , SP_Z_STR, LINEAR_UNIT(delta_tower_angle_trim.c)
); );
#elif EITHER(X_DUAL_ENDSTOPS, Y_DUAL_ENDSTOPS) || Z_MULTI_ENDSTOPS #elif HAS_EXTRA_ENDSTOPS
CONFIG_ECHO_HEADING("Endstop adjustment:"); CONFIG_ECHO_HEADING("Endstop adjustment:");
CONFIG_ECHO_START(); CONFIG_ECHO_START();
SERIAL_ECHOPGM(" M666"); SERIAL_ECHOPGM(" M666");
#if ENABLED(X_DUAL_ENDSTOPS) #if ENABLED(X_DUAL_ENDSTOPS)
SERIAL_ECHOPAIR_P(SP_X_STR, LINEAR_UNIT(endstops.x2_endstop_adj)); SERIAL_ECHOLNPAIR_P(SP_X_STR, LINEAR_UNIT(endstops.x2_endstop_adj));
#endif #endif
#if ENABLED(Y_DUAL_ENDSTOPS) #if ENABLED(Y_DUAL_ENDSTOPS)
SERIAL_ECHOPAIR_P(SP_Y_STR, LINEAR_UNIT(endstops.y2_endstop_adj)); SERIAL_ECHOLNPAIR_P(SP_Y_STR, LINEAR_UNIT(endstops.y2_endstop_adj));
#endif #endif
#if ENABLED(Z_TRIPLE_ENDSTOPS) #if ENABLED(Z_MULTI_ENDSTOPS)
SERIAL_ECHOLNPAIR("S1 Z", LINEAR_UNIT(endstops.z2_endstop_adj)); #if NUM_Z_STEPPER_DRIVERS >= 3
SERIAL_ECHOPAIR(" S2 Z", LINEAR_UNIT(endstops.z3_endstop_adj));
CONFIG_ECHO_START(); CONFIG_ECHO_START();
SERIAL_ECHOPAIR(" M666 S2 Z", LINEAR_UNIT(endstops.z3_endstop_adj)); SERIAL_ECHOPAIR(" M666 S3 Z", LINEAR_UNIT(endstops.z3_endstop_adj));
#elif ENABLED(Z_DUAL_ENDSTOPS) #if NUM_Z_STEPPER_DRIVERS >= 4
SERIAL_ECHOPAIR_P(SP_Z_STR, LINEAR_UNIT(endstops.z2_endstop_adj)); CONFIG_ECHO_START();
SERIAL_ECHOPAIR(" M666 S4 Z", LINEAR_UNIT(endstops.z4_endstop_adj));
#endif
#else
SERIAL_ECHOLNPAIR_P(SP_Z_STR, LINEAR_UNIT(endstops.z2_endstop_adj));
#endif
#endif #endif
SERIAL_EOL();
#endif // [XYZ]_DUAL_ENDSTOPS #endif // [XYZ]_DUAL_ENDSTOPS
@ -3218,6 +3244,11 @@ void MarlinSettings::reset() {
SERIAL_ECHOLNPAIR(" I2 Z", stepperZ3.getMilliamps()); SERIAL_ECHOLNPAIR(" I2 Z", stepperZ3.getMilliamps());
#endif #endif
#if AXIS_IS_TMC(Z4)
say_M906(forReplay);
SERIAL_ECHOLNPAIR(" I3 Z", stepperZ4.getMilliamps());
#endif
#if AXIS_IS_TMC(E0) #if AXIS_IS_TMC(E0)
say_M906(forReplay); say_M906(forReplay);
SERIAL_ECHOLNPAIR(" T0 E", stepperE0.getMilliamps()); SERIAL_ECHOLNPAIR(" T0 E", stepperE0.getMilliamps());
@ -3287,6 +3318,11 @@ void MarlinSettings::reset() {
SERIAL_ECHOLNPAIR(" I2 Z", stepperZ3.get_pwm_thrs()); SERIAL_ECHOLNPAIR(" I2 Z", stepperZ3.get_pwm_thrs());
#endif #endif
#if AXIS_HAS_STEALTHCHOP(Z4)
say_M913(forReplay);
SERIAL_ECHOLNPAIR(" I3 Z", stepperZ4.get_pwm_thrs());
#endif
#if AXIS_HAS_STEALTHCHOP(E0) #if AXIS_HAS_STEALTHCHOP(E0)
say_M913(forReplay); say_M913(forReplay);
SERIAL_ECHOLNPAIR(" T0 E", stepperE0.get_pwm_thrs()); SERIAL_ECHOLNPAIR(" T0 E", stepperE0.get_pwm_thrs());
@ -3356,6 +3392,12 @@ void MarlinSettings::reset() {
SERIAL_ECHOLNPAIR(" I2 Z", stepperZ3.homing_threshold()); SERIAL_ECHOLNPAIR(" I2 Z", stepperZ3.homing_threshold());
#endif #endif
#if Z4_SENSORLESS
CONFIG_ECHO_START();
say_M914();
SERIAL_ECHOLNPAIR(" I3 Z", stepperZ4.homing_threshold());
#endif
#endif // USE_SENSORLESS #endif // USE_SENSORLESS
/** /**
@ -3415,6 +3457,10 @@ void MarlinSettings::reset() {
if (stepperZ3.get_stealthChop_status()) { say_M569(forReplay, PSTR("I2 Z"), true); } if (stepperZ3.get_stealthChop_status()) { say_M569(forReplay, PSTR("I2 Z"), true); }
#endif #endif
#if AXIS_HAS_STEALTHCHOP(Z4)
if (stepperZ4.get_stealthChop_status()) { say_M569(forReplay, PSTR("I3 Z"), true); }
#endif
#if AXIS_HAS_STEALTHCHOP(E0) #if AXIS_HAS_STEALTHCHOP(E0)
if (stepperE0.get_stealthChop_status()) { say_M569(forReplay, PSTR("T0 E"), true); } if (stepperE0.get_stealthChop_status()) { say_M569(forReplay, PSTR("T0 E"), true); }
#endif #endif

View file

@ -73,11 +73,14 @@ Endstops::esbits_t Endstops::live_state = 0;
#if ENABLED(Y_DUAL_ENDSTOPS) #if ENABLED(Y_DUAL_ENDSTOPS)
float Endstops::y2_endstop_adj; float Endstops::y2_endstop_adj;
#endif #endif
#if Z_MULTI_ENDSTOPS #if ENABLED(Z_MULTI_ENDSTOPS)
float Endstops::z2_endstop_adj; float Endstops::z2_endstop_adj;
#endif #if NUM_Z_STEPPER_DRIVERS >= 3
#if ENABLED(Z_TRIPLE_ENDSTOPS)
float Endstops::z3_endstop_adj; float Endstops::z3_endstop_adj;
#if NUM_Z_STEPPER_DRIVERS >= 4
float Endstops::z4_endstop_adj;
#endif
#endif
#endif #endif
#if ENABLED(SPI_ENDSTOPS) #if ENABLED(SPI_ENDSTOPS)
@ -163,6 +166,16 @@ void Endstops::init() {
#endif #endif
#endif #endif
#if HAS_Z4_MIN
#if ENABLED(ENDSTOPPULLUP_ZMIN)
SET_INPUT_PULLUP(Z4_MIN_PIN);
#elif ENABLED(ENDSTOPPULLDOWN_ZMIN)
SET_INPUT_PULLDOWN(Z4_MIN_PIN);
#else
SET_INPUT(Z4_MIN_PIN);
#endif
#endif
#if HAS_X_MAX #if HAS_X_MAX
#if ENABLED(ENDSTOPPULLUP_XMAX) #if ENABLED(ENDSTOPPULLUP_XMAX)
SET_INPUT_PULLUP(X_MAX_PIN); SET_INPUT_PULLUP(X_MAX_PIN);
@ -233,6 +246,16 @@ void Endstops::init() {
#endif #endif
#endif #endif
#if HAS_Z4_MAX
#if ENABLED(ENDSTOPPULLUP_ZMAX)
SET_INPUT_PULLUP(Z4_MAX_PIN);
#elif ENABLED(ENDSTOPPULLDOWN_ZMAX)
SET_INPUT_PULLDOWN(Z4_MAX_PIN);
#else
SET_INPUT(Z4_MAX_PIN);
#endif
#endif
#if HAS_CALIBRATION_PIN #if HAS_CALIBRATION_PIN
#if ENABLED(CALIBRATION_PIN_PULLUP) #if ENABLED(CALIBRATION_PIN_PULLUP)
SET_INPUT_PULLUP(CALIBRATION_PIN); SET_INPUT_PULLUP(CALIBRATION_PIN);
@ -435,6 +458,9 @@ void _O2 Endstops::report_states() {
#if HAS_Z3_MIN #if HAS_Z3_MIN
ES_REPORT(Z3_MIN); ES_REPORT(Z3_MIN);
#endif #endif
#if HAS_Z4_MIN
ES_REPORT(Z4_MIN);
#endif
#if HAS_Z_MAX #if HAS_Z_MAX
ES_REPORT(Z_MAX); ES_REPORT(Z_MAX);
#endif #endif
@ -444,6 +470,9 @@ void _O2 Endstops::report_states() {
#if HAS_Z3_MAX #if HAS_Z3_MAX
ES_REPORT(Z3_MAX); ES_REPORT(Z3_MAX);
#endif #endif
#if HAS_Z4_MAX
ES_REPORT(Z4_MAX);
#endif
#if HAS_CUSTOM_PROBE_PIN #if HAS_CUSTOM_PROBE_PIN
print_es_state(READ(Z_MIN_PROBE_PIN) != Z_MIN_PROBE_ENDSTOP_INVERTING, PSTR(MSG_Z_PROBE)); print_es_state(READ(Z_MIN_PROBE_PIN) != Z_MIN_PROBE_ENDSTOP_INVERTING, PSTR(MSG_Z_PROBE));
#endif #endif
@ -584,19 +613,26 @@ void Endstops::update() {
#if HAS_Z_MIN && !Z_SPI_SENSORLESS #if HAS_Z_MIN && !Z_SPI_SENSORLESS
UPDATE_ENDSTOP_BIT(Z, MIN); UPDATE_ENDSTOP_BIT(Z, MIN);
#if Z_MULTI_ENDSTOPS #if ENABLED(Z_MULTI_ENDSTOPS)
#if HAS_Z2_MIN #if HAS_Z2_MIN
UPDATE_ENDSTOP_BIT(Z2, MIN); UPDATE_ENDSTOP_BIT(Z2, MIN);
#else #else
COPY_LIVE_STATE(Z_MIN, Z2_MIN); COPY_LIVE_STATE(Z_MIN, Z2_MIN);
#endif #endif
#if ENABLED(Z_TRIPLE_ENDSTOPS) #if NUM_Z_STEPPER_DRIVERS >= 3
#if HAS_Z3_MIN #if HAS_Z3_MIN
UPDATE_ENDSTOP_BIT(Z3, MIN); UPDATE_ENDSTOP_BIT(Z3, MIN);
#else #else
COPY_LIVE_STATE(Z_MIN, Z3_MIN); COPY_LIVE_STATE(Z_MIN, Z3_MIN);
#endif #endif
#endif #endif
#if NUM_Z_STEPPER_DRIVERS >= 4
#if HAS_Z4_MIN
UPDATE_ENDSTOP_BIT(Z4, MIN);
#else
COPY_LIVE_STATE(Z_MIN, Z4_MIN);
#endif
#endif
#endif #endif
#endif #endif
@ -607,20 +643,27 @@ void Endstops::update() {
#if HAS_Z_MAX && !Z_SPI_SENSORLESS #if HAS_Z_MAX && !Z_SPI_SENSORLESS
// Check both Z dual endstops // Check both Z dual endstops
#if Z_MULTI_ENDSTOPS #if ENABLED(Z_MULTI_ENDSTOPS)
UPDATE_ENDSTOP_BIT(Z, MAX); UPDATE_ENDSTOP_BIT(Z, MAX);
#if HAS_Z2_MAX #if HAS_Z2_MAX
UPDATE_ENDSTOP_BIT(Z2, MAX); UPDATE_ENDSTOP_BIT(Z2, MAX);
#else #else
COPY_LIVE_STATE(Z_MAX, Z2_MAX); COPY_LIVE_STATE(Z_MAX, Z2_MAX);
#endif #endif
#if ENABLED(Z_TRIPLE_ENDSTOPS) #if NUM_Z_STEPPER_DRIVERS >= 3
#if HAS_Z3_MAX #if HAS_Z3_MAX
UPDATE_ENDSTOP_BIT(Z3, MAX); UPDATE_ENDSTOP_BIT(Z3, MAX);
#else #else
COPY_LIVE_STATE(Z_MAX, Z3_MAX); COPY_LIVE_STATE(Z_MAX, Z3_MAX);
#endif #endif
#endif #endif
#if NUM_Z_STEPPER_DRIVERS >= 4
#if HAS_Z4_MAX
UPDATE_ENDSTOP_BIT(Z4, MAX);
#else
COPY_LIVE_STATE(Z_MAX, Z4_MAX);
#endif
#endif
#elif !HAS_CUSTOM_PROBE_PIN || Z_MAX_PIN != Z_MIN_PROBE_PIN #elif !HAS_CUSTOM_PROBE_PIN || Z_MAX_PIN != Z_MIN_PROBE_PIN
// If this pin isn't the bed probe it's the Z endstop // If this pin isn't the bed probe it's the Z endstop
UPDATE_ENDSTOP_BIT(Z, MAX); UPDATE_ENDSTOP_BIT(Z, MAX);
@ -686,6 +729,16 @@ void Endstops::update() {
} \ } \
}while(0) }while(0)
#define PROCESS_QUAD_ENDSTOP(AXIS1, AXIS2, AXIS3, AXIS4, MINMAX) do { \
const byte quad_hit = TEST_ENDSTOP(_ENDSTOP(AXIS1, MINMAX)) | (TEST_ENDSTOP(_ENDSTOP(AXIS2, MINMAX)) << 1) | (TEST_ENDSTOP(_ENDSTOP(AXIS3, MINMAX)) << 2) | (TEST_ENDSTOP(_ENDSTOP(AXIS4, MINMAX)) << 3); \
if (quad_hit) { \
_ENDSTOP_HIT(AXIS1, MINMAX); \
/* if not performing home or if both endstops were trigged during homing... */ \
if (!stepper.separate_multi_axis || quad_hit == 0b1111) \
planner.endstop_triggered(_AXIS(AXIS1)); \
} \
}while(0)
#if ENABLED(G38_PROBE_TARGET) && PIN_EXISTS(Z_MIN_PROBE) && !(CORE_IS_XY || CORE_IS_XZ) #if ENABLED(G38_PROBE_TARGET) && PIN_EXISTS(Z_MIN_PROBE) && !(CORE_IS_XY || CORE_IS_XZ)
#if ENABLED(G38_PROBE_AWAY) #if ENABLED(G38_PROBE_AWAY)
#define _G38_OPEN_STATE (G38_move >= 4) #define _G38_OPEN_STATE (G38_move >= 4)
@ -747,10 +800,14 @@ void Endstops::update() {
if (stepper.axis_is_moving(Z_AXIS)) { if (stepper.axis_is_moving(Z_AXIS)) {
if (stepper.motor_direction(Z_AXIS_HEAD)) { // Z -direction. Gantry down, bed up. if (stepper.motor_direction(Z_AXIS_HEAD)) { // Z -direction. Gantry down, bed up.
#if HAS_Z_MIN || (Z_SPI_SENSORLESS && Z_HOME_DIR < 0) #if HAS_Z_MIN || (Z_SPI_SENSORLESS && Z_HOME_DIR < 0)
#if ENABLED(Z_TRIPLE_ENDSTOPS) #if ENABLED(Z_MULTI_ENDSTOPS)
#if NUM_Z_STEPPER_DRIVERS == 4
PROCESS_QUAD_ENDSTOP(Z, Z2, Z3, Z4, MIN);
#elif NUM_Z_STEPPER_DRIVERS == 3
PROCESS_TRIPLE_ENDSTOP(Z, Z2, Z3, MIN); PROCESS_TRIPLE_ENDSTOP(Z, Z2, Z3, MIN);
#elif ENABLED(Z_DUAL_ENDSTOPS) #else
PROCESS_DUAL_ENDSTOP(Z, Z2, MIN); PROCESS_DUAL_ENDSTOP(Z, Z2, MIN);
#endif
#else #else
#if ENABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN) #if ENABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN)
if (z_probe_enabled) PROCESS_ENDSTOP(Z, MIN); if (z_probe_enabled) PROCESS_ENDSTOP(Z, MIN);
@ -769,10 +826,14 @@ void Endstops::update() {
} }
else { // Z +direction. Gantry up, bed down. else { // Z +direction. Gantry up, bed down.
#if HAS_Z_MAX || (Z_SPI_SENSORLESS && Z_HOME_DIR > 0) #if HAS_Z_MAX || (Z_SPI_SENSORLESS && Z_HOME_DIR > 0)
#if ENABLED(Z_TRIPLE_ENDSTOPS) #if ENABLED(Z_MULTI_ENDSTOPS)
#if NUM_Z_STEPPER_DRIVERS == 4
PROCESS_QUAD_ENDSTOP(Z, Z2, Z3, Z4, MAX);
#elif NUM_Z_STEPPER_DRIVERS == 3
PROCESS_TRIPLE_ENDSTOP(Z, Z2, Z3, MAX); PROCESS_TRIPLE_ENDSTOP(Z, Z2, Z3, MAX);
#elif ENABLED(Z_DUAL_ENDSTOPS) #else
PROCESS_DUAL_ENDSTOP(Z, Z2, MAX); PROCESS_DUAL_ENDSTOP(Z, Z2, MAX);
#endif
#elif !HAS_CUSTOM_PROBE_PIN || Z_MAX_PIN != Z_MIN_PROBE_PIN #elif !HAS_CUSTOM_PROBE_PIN || Z_MAX_PIN != Z_MIN_PROBE_PIN
// If this pin is not hijacked for the bed probe // If this pin is not hijacked for the bed probe
// then it belongs to the Z endstop // then it belongs to the Z endstop
@ -892,6 +953,12 @@ void Endstops::update() {
#if HAS_Z3_MAX #if HAS_Z3_MAX
ES_GET_STATE(Z3_MAX); ES_GET_STATE(Z3_MAX);
#endif #endif
#if HAS_Z4_MIN
ES_GET_STATE(Z4_MIN);
#endif
#if HAS_Z4_MAX
ES_GET_STATE(Z4_MAX);
#endif
uint16_t endstop_change = live_state_local ^ old_live_state_local; uint16_t endstop_change = live_state_local ^ old_live_state_local;
#define ES_REPORT_CHANGE(S) if (TEST(endstop_change, S)) SERIAL_ECHOPAIR(" " STRINGIFY(S) ":", TEST(live_state_local, S)) #define ES_REPORT_CHANGE(S) if (TEST(endstop_change, S)) SERIAL_ECHOPAIR(" " STRINGIFY(S) ":", TEST(live_state_local, S))
@ -942,6 +1009,12 @@ void Endstops::update() {
#if HAS_Z3_MAX #if HAS_Z3_MAX
ES_REPORT_CHANGE(Z3_MAX); ES_REPORT_CHANGE(Z3_MAX);
#endif #endif
#if HAS_Z4_MIN
ES_REPORT_CHANGE(Z4_MIN);
#endif
#if HAS_Z4_MAX
ES_REPORT_CHANGE(Z4_MAX);
#endif
SERIAL_ECHOLNPGM("\n"); SERIAL_ECHOLNPGM("\n");
analogWrite(pin_t(LED_PIN), local_LED_status); analogWrite(pin_t(LED_PIN), local_LED_status);
local_LED_status ^= 255; local_LED_status ^= 255;

View file

@ -34,7 +34,8 @@ enum EndstopEnum : char {
X2_MIN, X2_MAX, X2_MIN, X2_MAX,
Y2_MIN, Y2_MAX, Y2_MIN, Y2_MAX,
Z2_MIN, Z2_MAX, Z2_MIN, Z2_MAX,
Z3_MIN, Z3_MAX Z3_MIN, Z3_MAX,
Z4_MIN, Z4_MAX
}; };
class Endstops { class Endstops {
@ -47,12 +48,15 @@ class Endstops {
#if ENABLED(Y_DUAL_ENDSTOPS) #if ENABLED(Y_DUAL_ENDSTOPS)
static float y2_endstop_adj; static float y2_endstop_adj;
#endif #endif
#if Z_MULTI_ENDSTOPS #if ENABLED(Z_MULTI_ENDSTOPS)
static float z2_endstop_adj; static float z2_endstop_adj;
#endif #endif
#if ENABLED(Z_TRIPLE_ENDSTOPS) #if ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 3
static float z3_endstop_adj; static float z3_endstop_adj;
#endif #endif
#if ENABLED(Z_MULTI_ENDSTOPS) && NUM_Z_STEPPER_DRIVERS >= 4
static float z4_endstop_adj;
#endif
#else #else
typedef uint8_t esbits_t; typedef uint8_t esbits_t;
#endif #endif

View file

@ -1156,6 +1156,9 @@ feedRate_t get_homing_bump_feedrate(const AxisEnum axis) {
#if AXIS_HAS_STALLGUARD(Z3) #if AXIS_HAS_STALLGUARD(Z3)
stealth_states.z3 = tmc_enable_stallguard(stepperZ3); stealth_states.z3 = tmc_enable_stallguard(stepperZ3);
#endif #endif
#if AXIS_HAS_STALLGUARD(Z4)
stealth_states.z4 = tmc_enable_stallguard(stepperZ4);
#endif
#if CORE_IS_XZ && X_SENSORLESS #if CORE_IS_XZ && X_SENSORLESS
stealth_states.x = tmc_enable_stallguard(stepperX); stealth_states.x = tmc_enable_stallguard(stepperX);
#elif CORE_IS_YZ && Y_SENSORLESS #elif CORE_IS_YZ && Y_SENSORLESS
@ -1225,6 +1228,9 @@ feedRate_t get_homing_bump_feedrate(const AxisEnum axis) {
#if AXIS_HAS_STALLGUARD(Z3) #if AXIS_HAS_STALLGUARD(Z3)
tmc_disable_stallguard(stepperZ3, enable_stealth.z3); tmc_disable_stallguard(stepperZ3, enable_stealth.z3);
#endif #endif
#if AXIS_HAS_STALLGUARD(Z4)
tmc_disable_stallguard(stepperZ4, enable_stealth.z4);
#endif
#if CORE_IS_XZ && X_SENSORLESS #if CORE_IS_XZ && X_SENSORLESS
tmc_disable_stallguard(stepperX, enable_stealth.x); tmc_disable_stallguard(stepperX, enable_stealth.x);
#elif CORE_IS_YZ && Y_SENSORLESS #elif CORE_IS_YZ && Y_SENSORLESS
@ -1509,7 +1515,7 @@ void homeaxis(const AxisEnum axis) {
#if ENABLED(Y_DUAL_ENDSTOPS) #if ENABLED(Y_DUAL_ENDSTOPS)
case Y_AXIS: case Y_AXIS:
#endif #endif
#if Z_MULTI_ENDSTOPS #if ENABLED(Z_MULTI_ENDSTOPS)
case Z_AXIS: case Z_AXIS:
#endif #endif
stepper.set_separate_multi_axis(true); stepper.set_separate_multi_axis(true);
@ -1593,8 +1599,12 @@ void homeaxis(const AxisEnum axis) {
} }
} }
#endif #endif
#if ENABLED(Z_DUAL_ENDSTOPS)
#if ENABLED(Z_MULTI_ENDSTOPS)
if (axis == Z_AXIS) { if (axis == Z_AXIS) {
#if NUM_Z_STEPPER_DRIVERS == 2
const float adj = ABS(endstops.z2_endstop_adj); const float adj = ABS(endstops.z2_endstop_adj);
if (adj) { if (adj) {
if (pos_dir ? (endstops.z2_endstop_adj > 0) : (endstops.z2_endstop_adj < 0)) stepper.set_z_lock(true); else stepper.set_z2_lock(true); if (pos_dir ? (endstops.z2_endstop_adj > 0) : (endstops.z2_endstop_adj < 0)) stepper.set_z_lock(true); else stepper.set_z2_lock(true);
@ -1602,18 +1612,30 @@ void homeaxis(const AxisEnum axis) {
stepper.set_z_lock(false); stepper.set_z_lock(false);
stepper.set_z2_lock(false); stepper.set_z2_lock(false);
} }
}
#endif
#if ENABLED(Z_TRIPLE_ENDSTOPS)
if (axis == Z_AXIS) {
// we push the function pointers for the stepper lock function into an array
void (*lock[3]) (bool)= {&stepper.set_z_lock, &stepper.set_z2_lock, &stepper.set_z3_lock};
float adj[3] = {0, endstops.z2_endstop_adj, endstops.z3_endstop_adj};
void (*tempLock) (bool); #else
// Handy arrays of stepper lock function pointers
typedef void (*adjustFunc_t)(const bool);
adjustFunc_t lock[] = {
stepper.set_z_lock, stepper.set_z2_lock, stepper.set_z3_lock
#if NUM_Z_STEPPER_DRIVERS >= 4
, stepper.set_z4_lock
#endif
};
float adj[] = {
0, endstops.z2_endstop_adj, endstops.z3_endstop_adj
#if NUM_Z_STEPPER_DRIVERS >= 4
, endstops.z4_endstop_adj
#endif
};
adjustFunc_t tempLock;
float tempAdj; float tempAdj;
// manual bubble sort by adjust value // Manual bubble sort by adjust value
if (adj[1] < adj[0]) { if (adj[1] < adj[0]) {
tempLock = lock[0], tempAdj = adj[0]; tempLock = lock[0], tempAdj = adj[0];
lock[0] = lock[1], adj[0] = adj[1]; lock[0] = lock[1], adj[0] = adj[1];
@ -1624,6 +1646,18 @@ void homeaxis(const AxisEnum axis) {
lock[1] = lock[2], adj[1] = adj[2]; lock[1] = lock[2], adj[1] = adj[2];
lock[2] = tempLock, adj[2] = tempAdj; lock[2] = tempLock, adj[2] = tempAdj;
} }
#if NUM_Z_STEPPER_DRIVERS >= 4
if (adj[3] < adj[2]) {
tempLock = lock[2], tempAdj = adj[2];
lock[2] = lock[3], adj[2] = adj[3];
lock[3] = tempLock, adj[3] = tempAdj;
}
if (adj[2] < adj[1]) {
tempLock = lock[1], tempAdj = adj[1];
lock[1] = lock[2], adj[1] = adj[2];
lock[2] = tempLock, adj[2] = tempAdj;
}
#endif
if (adj[1] < adj[0]) { if (adj[1] < adj[0]) {
tempLock = lock[0], tempAdj = adj[0]; tempLock = lock[0], tempAdj = adj[0];
lock[0] = lock[1], adj[0] = adj[1]; lock[0] = lock[1], adj[0] = adj[1];
@ -1637,8 +1671,17 @@ void homeaxis(const AxisEnum axis) {
// lock the second stepper for the final correction // lock the second stepper for the final correction
(*lock[1])(true); (*lock[1])(true);
do_homing_move(axis, adj[2] - adj[1]); do_homing_move(axis, adj[2] - adj[1]);
#if NUM_Z_STEPPER_DRIVERS >= 4
// lock the third stepper for the final correction
(*lock[2])(true);
do_homing_move(axis, adj[3] - adj[2]);
#endif
} }
else { else {
#if NUM_Z_STEPPER_DRIVERS >= 4
(*lock[3])(true);
do_homing_move(axis, adj[2] - adj[3]);
#endif
(*lock[2])(true); (*lock[2])(true);
do_homing_move(axis, adj[1] - adj[2]); do_homing_move(axis, adj[1] - adj[2]);
(*lock[1])(true); (*lock[1])(true);
@ -1648,22 +1691,27 @@ void homeaxis(const AxisEnum axis) {
stepper.set_z_lock(false); stepper.set_z_lock(false);
stepper.set_z2_lock(false); stepper.set_z2_lock(false);
stepper.set_z3_lock(false); stepper.set_z3_lock(false);
#if NUM_Z_STEPPER_DRIVERS >= 4
stepper.set_z4_lock(false);
#endif
#endif
} }
#endif #endif
// Reset flags for X, Y, Z motor locking // Reset flags for X, Y, Z motor locking
switch (axis) { switch (axis) {
default: break;
#if ENABLED(X_DUAL_ENDSTOPS) #if ENABLED(X_DUAL_ENDSTOPS)
case X_AXIS: case X_AXIS:
#endif #endif
#if ENABLED(Y_DUAL_ENDSTOPS) #if ENABLED(Y_DUAL_ENDSTOPS)
case Y_AXIS: case Y_AXIS:
#endif #endif
#if Z_MULTI_ENDSTOPS #if ENABLED(Z_MULTI_ENDSTOPS)
case Z_AXIS: case Z_AXIS:
#endif #endif
stepper.set_separate_multi_axis(false); stepper.set_separate_multi_axis(false);
default: break;
} }
#endif #endif

View file

@ -156,11 +156,16 @@ bool Stepper::abort_current_block;
#if ENABLED(Y_DUAL_ENDSTOPS) #if ENABLED(Y_DUAL_ENDSTOPS)
bool Stepper::locked_Y_motor = false, Stepper::locked_Y2_motor = false; bool Stepper::locked_Y_motor = false, Stepper::locked_Y2_motor = false;
#endif #endif
#if Z_MULTI_ENDSTOPS || ENABLED(Z_STEPPER_AUTO_ALIGN)
bool Stepper::locked_Z_motor = false, Stepper::locked_Z2_motor = false; #if EITHER(Z_MULTI_ENDSTOPS, Z_STEPPER_AUTO_ALIGN)
bool Stepper::locked_Z_motor = false, Stepper::locked_Z2_motor = false
#if NUM_Z_STEPPER_DRIVERS >= 3
, Stepper::locked_Z3_motor = false
#if NUM_Z_STEPPER_DRIVERS >= 4
, Stepper::locked_Z4_motor = false
#endif #endif
#if ENABLED(Z_TRIPLE_ENDSTOPS) || BOTH(Z_STEPPER_AUTO_ALIGN, Z_TRIPLE_STEPPER_DRIVERS) #endif
bool Stepper::locked_Z3_motor = false; ;
#endif #endif
uint32_t Stepper::acceleration_time, Stepper::deceleration_time; uint32_t Stepper::acceleration_time, Stepper::deceleration_time;
@ -281,6 +286,42 @@ xyze_int8_t Stepper::count_direction{0};
A##3_STEP_WRITE(V); \ A##3_STEP_WRITE(V); \
} }
#define QUAD_ENDSTOP_APPLY_STEP(A,V) \
if (separate_multi_axis) { \
if (A##_HOME_DIR < 0) { \
if (!(TEST(endstops.state(), A##_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##_motor) A##_STEP_WRITE(V); \
if (!(TEST(endstops.state(), A##2_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##2_motor) A##2_STEP_WRITE(V); \
if (!(TEST(endstops.state(), A##3_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##3_motor) A##3_STEP_WRITE(V); \
if (!(TEST(endstops.state(), A##4_MIN) && count_direction[_AXIS(A)] < 0) && !locked_##A##4_motor) A##4_STEP_WRITE(V); \
} \
else { \
if (!(TEST(endstops.state(), A##_MAX) && count_direction[_AXIS(A)] > 0) && !locked_##A##_motor) A##_STEP_WRITE(V); \
if (!(TEST(endstops.state(), A##2_MAX) && count_direction[_AXIS(A)] > 0) && !locked_##A##2_motor) A##2_STEP_WRITE(V); \
if (!(TEST(endstops.state(), A##3_MAX) && count_direction[_AXIS(A)] > 0) && !locked_##A##3_motor) A##3_STEP_WRITE(V); \
if (!(TEST(endstops.state(), A##4_MAX) && count_direction[_AXIS(A)] > 0) && !locked_##A##4_motor) A##4_STEP_WRITE(V); \
} \
} \
else { \
A##_STEP_WRITE(V); \
A##2_STEP_WRITE(V); \
A##3_STEP_WRITE(V); \
A##4_STEP_WRITE(V); \
}
#define QUAD_SEPARATE_APPLY_STEP(A,V) \
if (separate_multi_axis) { \
if (!locked_##A##_motor) A##_STEP_WRITE(V); \
if (!locked_##A##2_motor) A##2_STEP_WRITE(V); \
if (!locked_##A##3_motor) A##3_STEP_WRITE(V); \
if (!locked_##A##4_motor) A##4_STEP_WRITE(V); \
} \
else { \
A##_STEP_WRITE(V); \
A##2_STEP_WRITE(V); \
A##3_STEP_WRITE(V); \
A##4_STEP_WRITE(V); \
}
#if ENABLED(X_DUAL_STEPPER_DRIVERS) #if ENABLED(X_DUAL_STEPPER_DRIVERS)
#define X_APPLY_DIR(v,Q) do{ X_DIR_WRITE(v); X2_DIR_WRITE((v) != INVERT_X2_VS_X_DIR); }while(0) #define X_APPLY_DIR(v,Q) do{ X_DIR_WRITE(v); X2_DIR_WRITE((v) != INVERT_X2_VS_X_DIR); }while(0)
#if ENABLED(X_DUAL_ENDSTOPS) #if ENABLED(X_DUAL_ENDSTOPS)
@ -314,18 +355,27 @@ xyze_int8_t Stepper::count_direction{0};
#define Y_APPLY_STEP(v,Q) Y_STEP_WRITE(v) #define Y_APPLY_STEP(v,Q) Y_STEP_WRITE(v)
#endif #endif
#if ENABLED(Z_TRIPLE_STEPPER_DRIVERS) #if NUM_Z_STEPPER_DRIVERS == 4
#define Z_APPLY_DIR(v,Q) do{ Z_DIR_WRITE(v); Z2_DIR_WRITE(v); Z3_DIR_WRITE(v); Z4_DIR_WRITE(v); }while(0)
#if ENABLED(Z_MULTI_ENDSTOPS)
#define Z_APPLY_STEP(v,Q) QUAD_ENDSTOP_APPLY_STEP(Z,v)
#elif ENABLED(Z_STEPPER_AUTO_ALIGN)
#define Z_APPLY_STEP(v,Q) QUAD_SEPARATE_APPLY_STEP(Z,v)
#else
#define Z_APPLY_STEP(v,Q) do{ Z_STEP_WRITE(v); Z2_STEP_WRITE(v); Z3_STEP_WRITE(v); Z4_STEP_WRITE(v); }while(0)
#endif
#elif NUM_Z_STEPPER_DRIVERS == 3
#define Z_APPLY_DIR(v,Q) do{ Z_DIR_WRITE(v); Z2_DIR_WRITE(v); Z3_DIR_WRITE(v); }while(0) #define Z_APPLY_DIR(v,Q) do{ Z_DIR_WRITE(v); Z2_DIR_WRITE(v); Z3_DIR_WRITE(v); }while(0)
#if ENABLED(Z_TRIPLE_ENDSTOPS) #if ENABLED(Z_MULTI_ENDSTOPS)
#define Z_APPLY_STEP(v,Q) TRIPLE_ENDSTOP_APPLY_STEP(Z,v) #define Z_APPLY_STEP(v,Q) TRIPLE_ENDSTOP_APPLY_STEP(Z,v)
#elif ENABLED(Z_STEPPER_AUTO_ALIGN) #elif ENABLED(Z_STEPPER_AUTO_ALIGN)
#define Z_APPLY_STEP(v,Q) TRIPLE_SEPARATE_APPLY_STEP(Z,v) #define Z_APPLY_STEP(v,Q) TRIPLE_SEPARATE_APPLY_STEP(Z,v)
#else #else
#define Z_APPLY_STEP(v,Q) do{ Z_STEP_WRITE(v); Z2_STEP_WRITE(v); Z3_STEP_WRITE(v); }while(0) #define Z_APPLY_STEP(v,Q) do{ Z_STEP_WRITE(v); Z2_STEP_WRITE(v); Z3_STEP_WRITE(v); }while(0)
#endif #endif
#elif ENABLED(Z_DUAL_STEPPER_DRIVERS) #elif NUM_Z_STEPPER_DRIVERS == 2
#define Z_APPLY_DIR(v,Q) do{ Z_DIR_WRITE(v); Z2_DIR_WRITE(v); }while(0) #define Z_APPLY_DIR(v,Q) do{ Z_DIR_WRITE(v); Z2_DIR_WRITE(v); }while(0)
#if ENABLED(Z_DUAL_ENDSTOPS) #if ENABLED(Z_MULTI_ENDSTOPS)
#define Z_APPLY_STEP(v,Q) DUAL_ENDSTOP_APPLY_STEP(Z,v) #define Z_APPLY_STEP(v,Q) DUAL_ENDSTOP_APPLY_STEP(Z,v)
#elif ENABLED(Z_STEPPER_AUTO_ALIGN) #elif ENABLED(Z_STEPPER_AUTO_ALIGN)
#define Z_APPLY_STEP(v,Q) DUAL_SEPARATE_APPLY_STEP(Z,v) #define Z_APPLY_STEP(v,Q) DUAL_SEPARATE_APPLY_STEP(Z,v)
@ -2062,12 +2112,15 @@ void Stepper::init() {
#endif #endif
#if HAS_Z_DIR #if HAS_Z_DIR
Z_DIR_INIT(); Z_DIR_INIT();
#if Z_MULTI_STEPPER_DRIVERS && HAS_Z2_DIR #if NUM_Z_STEPPER_DRIVERS >= 2 && HAS_Z2_DIR
Z2_DIR_INIT(); Z2_DIR_INIT();
#endif #endif
#if ENABLED(Z_TRIPLE_STEPPER_DRIVERS) && HAS_Z3_DIR #if NUM_Z_STEPPER_DRIVERS >= 3 && HAS_Z3_DIR
Z3_DIR_INIT(); Z3_DIR_INIT();
#endif #endif
#if NUM_Z_STEPPER_DRIVERS >= 4 && HAS_Z4_DIR
Z4_DIR_INIT();
#endif
#endif #endif
#if HAS_E0_DIR #if HAS_E0_DIR
E0_DIR_INIT(); E0_DIR_INIT();
@ -2108,14 +2161,18 @@ void Stepper::init() {
#if HAS_Z_ENABLE #if HAS_Z_ENABLE
Z_ENABLE_INIT(); Z_ENABLE_INIT();
if (!Z_ENABLE_ON) Z_ENABLE_WRITE(HIGH); if (!Z_ENABLE_ON) Z_ENABLE_WRITE(HIGH);
#if Z_MULTI_STEPPER_DRIVERS && HAS_Z2_ENABLE #if NUM_Z_STEPPER_DRIVERS >= 2 && HAS_Z2_ENABLE
Z2_ENABLE_INIT(); Z2_ENABLE_INIT();
if (!Z_ENABLE_ON) Z2_ENABLE_WRITE(HIGH); if (!Z_ENABLE_ON) Z2_ENABLE_WRITE(HIGH);
#endif #endif
#if ENABLED(Z_TRIPLE_STEPPER_DRIVERS) && HAS_Z3_ENABLE #if NUM_Z_STEPPER_DRIVERS >= 3 && HAS_Z3_ENABLE
Z3_ENABLE_INIT(); Z3_ENABLE_INIT();
if (!Z_ENABLE_ON) Z3_ENABLE_WRITE(HIGH); if (!Z_ENABLE_ON) Z3_ENABLE_WRITE(HIGH);
#endif #endif
#if NUM_Z_STEPPER_DRIVERS >= 4 && HAS_Z4_ENABLE
Z4_ENABLE_INIT();
if (!Z_ENABLE_ON) Z4_ENABLE_WRITE(HIGH);
#endif
#endif #endif
#if HAS_E0_ENABLE #if HAS_E0_ENABLE
E0_ENABLE_INIT(); E0_ENABLE_INIT();
@ -2171,14 +2228,18 @@ void Stepper::init() {
#endif #endif
#if HAS_Z_STEP #if HAS_Z_STEP
#if Z_MULTI_STEPPER_DRIVERS #if NUM_Z_STEPPER_DRIVERS >= 2
Z2_STEP_INIT(); Z2_STEP_INIT();
Z2_STEP_WRITE(INVERT_Z_STEP_PIN); Z2_STEP_WRITE(INVERT_Z_STEP_PIN);
#endif #endif
#if ENABLED(Z_TRIPLE_STEPPER_DRIVERS) #if NUM_Z_STEPPER_DRIVERS >= 3
Z3_STEP_INIT(); Z3_STEP_INIT();
Z3_STEP_WRITE(INVERT_Z_STEP_PIN); Z3_STEP_WRITE(INVERT_Z_STEP_PIN);
#endif #endif
#if NUM_Z_STEPPER_DRIVERS >= 4
Z4_STEP_INIT();
Z4_STEP_WRITE(INVERT_Z_STEP_PIN);
#endif
AXIS_INIT(Z, Z); AXIS_INIT(Z, Z);
#endif #endif
@ -2692,6 +2753,13 @@ void Stepper::report_positions() {
SET_OUTPUT(Z3_MS3_PIN); SET_OUTPUT(Z3_MS3_PIN);
#endif #endif
#endif #endif
#if HAS_Z4_MICROSTEPS
SET_OUTPUT(Z4_MS1_PIN);
SET_OUTPUT(Z4_MS2_PIN);
#if PIN_EXISTS(Z4_MS3)
SET_OUTPUT(Z4_MS3_PIN);
#endif
#endif
#if HAS_E0_MICROSTEPS #if HAS_E0_MICROSTEPS
SET_OUTPUT(E0_MS1_PIN); SET_OUTPUT(E0_MS1_PIN);
SET_OUTPUT(E0_MS2_PIN); SET_OUTPUT(E0_MS2_PIN);
@ -2762,7 +2830,7 @@ void Stepper::report_positions() {
#endif #endif
break; break;
#endif #endif
#if HAS_Z_MICROSTEPS || HAS_Z2_MICROSTEPS || HAS_Z3_MICROSTEPS #if HAS_SOME_Z_MICROSTEPS
case 2: case 2:
#if HAS_Z_MICROSTEPS #if HAS_Z_MICROSTEPS
WRITE(Z_MS1_PIN, ms1); WRITE(Z_MS1_PIN, ms1);
@ -2773,6 +2841,9 @@ void Stepper::report_positions() {
#if HAS_Z3_MICROSTEPS #if HAS_Z3_MICROSTEPS
WRITE(Z3_MS1_PIN, ms1); WRITE(Z3_MS1_PIN, ms1);
#endif #endif
#if HAS_Z4_MICROSTEPS
WRITE(Z4_MS1_PIN, ms1);
#endif
break; break;
#endif #endif
#if HAS_E0_MICROSTEPS #if HAS_E0_MICROSTEPS
@ -2815,7 +2886,7 @@ void Stepper::report_positions() {
#endif #endif
break; break;
#endif #endif
#if HAS_Z_MICROSTEPS || HAS_Z2_MICROSTEPS || HAS_Z3_MICROSTEPS #if HAS_SOME_Z_MICROSTEPS
case 2: case 2:
#if HAS_Z_MICROSTEPS #if HAS_Z_MICROSTEPS
WRITE(Z_MS2_PIN, ms2); WRITE(Z_MS2_PIN, ms2);
@ -2826,6 +2897,9 @@ void Stepper::report_positions() {
#if HAS_Z3_MICROSTEPS #if HAS_Z3_MICROSTEPS
WRITE(Z3_MS2_PIN, ms2); WRITE(Z3_MS2_PIN, ms2);
#endif #endif
#if HAS_Z4_MICROSTEPS
WRITE(Z4_MS2_PIN, ms2);
#endif
break; break;
#endif #endif
#if HAS_E0_MICROSTEPS #if HAS_E0_MICROSTEPS
@ -2868,7 +2942,7 @@ void Stepper::report_positions() {
#endif #endif
break; break;
#endif #endif
#if HAS_Z_MICROSTEPS || HAS_Z2_MICROSTEPS || HAS_Z3_MICROSTEPS #if HAS_SOME_Z_MICROSTEPS
case 2: case 2:
#if HAS_Z_MICROSTEPS && PIN_EXISTS(Z_MS3) #if HAS_Z_MICROSTEPS && PIN_EXISTS(Z_MS3)
WRITE(Z_MS3_PIN, ms3); WRITE(Z_MS3_PIN, ms3);
@ -2879,6 +2953,9 @@ void Stepper::report_positions() {
#if HAS_Z3_MICROSTEPS && PIN_EXISTS(Z3_MS3) #if HAS_Z3_MICROSTEPS && PIN_EXISTS(Z3_MS3)
WRITE(Z3_MS3_PIN, ms3); WRITE(Z3_MS3_PIN, ms3);
#endif #endif
#if HAS_Z4_MICROSTEPS && PIN_EXISTS(Z4_MS3)
WRITE(Z4_MS3_PIN, ms3);
#endif
break; break;
#endif #endif
#if HAS_E0_MICROSTEPS && PIN_EXISTS(E0_MS3) #if HAS_E0_MICROSTEPS && PIN_EXISTS(E0_MS3)

View file

@ -274,11 +274,15 @@ class Stepper {
#if ENABLED(Y_DUAL_ENDSTOPS) #if ENABLED(Y_DUAL_ENDSTOPS)
static bool locked_Y_motor, locked_Y2_motor; static bool locked_Y_motor, locked_Y2_motor;
#endif #endif
#if Z_MULTI_ENDSTOPS || ENABLED(Z_STEPPER_AUTO_ALIGN) #if EITHER(Z_MULTI_ENDSTOPS, Z_STEPPER_AUTO_ALIGN)
static bool locked_Z_motor, locked_Z2_motor; static bool locked_Z_motor, locked_Z2_motor
#if NUM_Z_STEPPER_DRIVERS >= 3
, locked_Z3_motor
#if NUM_Z_STEPPER_DRIVERS >= 4
, locked_Z4_motor
#endif #endif
#if ENABLED(Z_TRIPLE_ENDSTOPS) || BOTH(Z_STEPPER_AUTO_ALIGN, Z_TRIPLE_STEPPER_DRIVERS) #endif
static bool locked_Z3_motor; ;
#endif #endif
static uint32_t acceleration_time, deceleration_time; // time measured in Stepper Timer ticks static uint32_t acceleration_time, deceleration_time; // time measured in Stepper Timer ticks
@ -430,12 +434,15 @@ class Stepper {
FORCE_INLINE static void set_y_lock(const bool state) { locked_Y_motor = state; } FORCE_INLINE static void set_y_lock(const bool state) { locked_Y_motor = state; }
FORCE_INLINE static void set_y2_lock(const bool state) { locked_Y2_motor = state; } FORCE_INLINE static void set_y2_lock(const bool state) { locked_Y2_motor = state; }
#endif #endif
#if Z_MULTI_ENDSTOPS || (ENABLED(Z_STEPPER_AUTO_ALIGN) && Z_MULTI_STEPPER_DRIVERS) #if EITHER(Z_MULTI_ENDSTOPS, Z_STEPPER_AUTO_ALIGN)
FORCE_INLINE static void set_z_lock(const bool state) { locked_Z_motor = state; } FORCE_INLINE static void set_z_lock(const bool state) { locked_Z_motor = state; }
FORCE_INLINE static void set_z2_lock(const bool state) { locked_Z2_motor = state; } FORCE_INLINE static void set_z2_lock(const bool state) { locked_Z2_motor = state; }
#endif #if NUM_Z_STEPPER_DRIVERS >= 3
#if ENABLED(Z_TRIPLE_ENDSTOPS) || BOTH(Z_STEPPER_AUTO_ALIGN, Z_TRIPLE_STEPPER_DRIVERS)
FORCE_INLINE static void set_z3_lock(const bool state) { locked_Z3_motor = state; } FORCE_INLINE static void set_z3_lock(const bool state) { locked_Z3_motor = state; }
#if NUM_Z_STEPPER_DRIVERS >= 4
FORCE_INLINE static void set_z4_lock(const bool state) { locked_Z4_motor = state; }
#endif
#endif
#endif #endif
#if ENABLED(BABYSTEPPING) #if ENABLED(BABYSTEPPING)

View file

@ -52,6 +52,9 @@
#if AXIS_IS_L64XX(Z3) #if AXIS_IS_L64XX(Z3)
L64XX_CLASS(Z3) stepperZ3(L6470_CHAIN_SS_PIN); L64XX_CLASS(Z3) stepperZ3(L6470_CHAIN_SS_PIN);
#endif #endif
#if AXIS_IS_L64XX(Z4)
L64XX_CLASS(Z4) stepperZ4(L6470_CHAIN_SS_PIN);
#endif
#if AXIS_IS_L64XX(E0) #if AXIS_IS_L64XX(E0)
L64XX_CLASS(E0) stepperE0(L6470_CHAIN_SS_PIN); L64XX_CLASS(E0) stepperE0(L6470_CHAIN_SS_PIN);
#endif #endif

View file

@ -160,6 +160,23 @@
#endif #endif
#endif #endif
// Z4 Stepper
#if HAS_Z4_ENABLE && AXIS_IS_L64XX(Z4)
extern L64XX_CLASS(Z4) stepperZ4;
#define Z4_ENABLE_INIT() NOOP
#define Z4_ENABLE_WRITE(STATE) (STATE ? NOOP : stepperZ4.free())
#define Z4_ENABLE_READ() (stepperZ4.getStatus() & STATUS_HIZ)
#if AXIS_DRIVER_TYPE_Z4(L6474)
#define Z4_DIR_INIT() SET_OUTPUT(Z4_DIR_PIN)
#define Z4_DIR_WRITE(STATE) L6474_DIR_WRITE(Z4, STATE)
#define Z4_DIR_READ() READ(Z4_DIR_PIN)
#else
#define Z4_DIR_INIT() NOOP
#define Z4_DIR_WRITE(STATE) L64XX_DIR_WRITE(Z4, STATE)
#define Z4_DIR_READ() (stepper##Z4.getStatus() & STATUS_DIR);
#endif
#endif
// E0 Stepper // E0 Stepper
#if AXIS_IS_L64XX(E0) #if AXIS_IS_L64XX(E0)
extern L64XX_CLASS(E0) stepperE0; extern L64XX_CLASS(E0) stepperE0;

View file

@ -57,6 +57,9 @@
#if AXIS_DRIVER_TYPE_Z3(TMC26X) #if AXIS_DRIVER_TYPE_Z3(TMC26X)
_TMC26X_DEFINE(Z3); _TMC26X_DEFINE(Z3);
#endif #endif
#if AXIS_DRIVER_TYPE_Z4(TMC26X)
_TMC26X_DEFINE(Z4);
#endif
#if AXIS_DRIVER_TYPE_E0(TMC26X) #if AXIS_DRIVER_TYPE_E0(TMC26X)
_TMC26X_DEFINE(E0); _TMC26X_DEFINE(E0);
#endif #endif
@ -103,6 +106,9 @@ void tmc26x_init_to_defaults() {
#if AXIS_DRIVER_TYPE_Z3(TMC26X) #if AXIS_DRIVER_TYPE_Z3(TMC26X)
_TMC26X_INIT(Z3); _TMC26X_INIT(Z3);
#endif #endif
#if AXIS_DRIVER_TYPE_Z4(TMC26X)
_TMC26X_INIT(Z4);
#endif
#if AXIS_DRIVER_TYPE_E0(TMC26X) #if AXIS_DRIVER_TYPE_E0(TMC26X)
_TMC26X_INIT(E0); _TMC26X_INIT(E0);
#endif #endif

View file

@ -95,6 +95,14 @@ void tmc26x_init_to_defaults();
#define Z3_ENABLE_READ() stepperZ3.isEnabled() #define Z3_ENABLE_READ() stepperZ3.isEnabled()
#endif #endif
// Z4 Stepper
#if HAS_Z4_ENABLE && AXIS_DRIVER_TYPE_Z4(TMC26X)
extern TMC26XStepper stepperZ4;
#define Z4_ENABLE_INIT() NOOP
#define Z4_ENABLE_WRITE(STATE) stepperZ4.setEnabled(STATE)
#define Z4_ENABLE_READ() stepperZ4.isEnabled()
#endif
// E0 Stepper // E0 Stepper
#if AXIS_DRIVER_TYPE_E0(TMC26X) #if AXIS_DRIVER_TYPE_E0(TMC26X)
extern TMC26XStepper stepperE0; extern TMC26XStepper stepperE0;

View file

@ -180,6 +180,27 @@ void reset_stepper_drivers(); // Called by settings.load / settings.reset
#define Z3_DIR_WRITE(STATE) NOOP #define Z3_DIR_WRITE(STATE) NOOP
#endif #endif
// Z4 Stepper
#if HAS_Z4_ENABLE
#ifndef Z4_ENABLE_INIT
#define Z4_ENABLE_INIT() SET_OUTPUT(Z4_ENABLE_PIN)
#define Z4_ENABLE_WRITE(STATE) WRITE(Z4_ENABLE_PIN,STATE)
#define Z4_ENABLE_READ() READ(Z4_ENABLE_PIN)
#endif
#ifndef Z4_DIR_INIT
#define Z4_DIR_INIT() SET_OUTPUT(Z4_DIR_PIN)
#define Z4_DIR_WRITE(STATE) WRITE(Z4_DIR_PIN,STATE)
#define Z4_DIR_READ() READ(Z4_DIR_PIN)
#endif
#define Z4_STEP_INIT SET_OUTPUT(Z4_STEP_PIN)
#ifndef Z4_STEP_WRITE
#define Z4_STEP_WRITE(STATE) WRITE(Z4_STEP_PIN,STATE)
#endif
#define Z4_STEP_READ READ(Z4_STEP_PIN)
#else
#define Z4_DIR_WRITE(STATE) NOOP
#endif
// E0 Stepper // E0 Stepper
#ifndef E0_ENABLE_INIT #ifndef E0_ENABLE_INIT
#define E0_ENABLE_INIT() SET_OUTPUT(E0_ENABLE_PIN) #define E0_ENABLE_INIT() SET_OUTPUT(E0_ENABLE_PIN)
@ -491,8 +512,20 @@ void reset_stepper_drivers(); // Called by settings.load / settings.reset
#define Z3_disable() NOOP #define Z3_disable() NOOP
#endif #endif
#define enable_Z() do{ Z_enable(); Z2_enable(); Z3_enable(); }while(0) #if AXIS_DRIVER_TYPE_Z4(L6470)
#define disable_Z() do{ Z_disable(); Z2_disable(); Z3_disable(); CBI(axis_known_position, Z_AXIS); }while(0) extern L6470 stepperZ4;
#define Z4_enable() NOOP
#define Z4_disable() stepperZ4.free()
#elif HAS_Z4_ENABLE
#define Z4_enable() Z4_ENABLE_WRITE( Z_ENABLE_ON)
#define Z4_disable() Z4_ENABLE_WRITE(!Z_ENABLE_ON)
#else
#define Z4_enable() NOOP
#define Z4_disable() NOOP
#endif
#define enable_Z() do{ Z_enable(); Z2_enable(); Z3_enable(); Z4_enable(); }while(0)
#define disable_Z() do{ Z_disable(); Z2_disable(); Z3_disable(); Z4_disable(); CBI(axis_known_position, Z_AXIS); }while(0)
// //
// Extruder Stepper enable / disable // Extruder Stepper enable / disable

View file

@ -88,6 +88,9 @@ enum StealthIndex : uint8_t { STEALTH_AXIS_XY, STEALTH_AXIS_Z, STEALTH_AXIS_E };
#if AXIS_HAS_SPI(Z3) #if AXIS_HAS_SPI(Z3)
TMC_SPI_DEFINE(Z3, Z); TMC_SPI_DEFINE(Z3, Z);
#endif #endif
#if AXIS_HAS_SPI(Z4)
TMC_SPI_DEFINE(Z4, Z);
#endif
#if AXIS_HAS_SPI(E0) #if AXIS_HAS_SPI(E0)
TMC_SPI_DEFINE_E(0); TMC_SPI_DEFINE_E(0);
#endif #endif
@ -249,6 +252,13 @@ enum StealthIndex : uint8_t { STEALTH_AXIS_XY, STEALTH_AXIS_Z, STEALTH_AXIS_E };
TMC_UART_DEFINE(SW, Z3, Z); TMC_UART_DEFINE(SW, Z3, Z);
#endif #endif
#endif #endif
#if AXIS_HAS_UART(Z4)
#ifdef Z4_HARDWARE_SERIAL
TMC_UART_DEFINE(HW, Z4, Z);
#else
TMC_UART_DEFINE(SW, Z4, Z);
#endif
#endif
#if AXIS_HAS_UART(E0) #if AXIS_HAS_UART(E0)
#ifdef E0_HARDWARE_SERIAL #ifdef E0_HARDWARE_SERIAL
TMC_UART_DEFINE_E(HW, 0); TMC_UART_DEFINE_E(HW, 0);
@ -342,6 +352,13 @@ enum StealthIndex : uint8_t { STEALTH_AXIS_XY, STEALTH_AXIS_Z, STEALTH_AXIS_E };
stepperZ3.beginSerial(TMC_BAUD_RATE); stepperZ3.beginSerial(TMC_BAUD_RATE);
#endif #endif
#endif #endif
#if AXIS_HAS_UART(Z4)
#ifdef Z4_HARDWARE_SERIAL
Z4_HARDWARE_SERIAL.begin(TMC_BAUD_RATE);
#else
stepperZ4.beginSerial(TMC_BAUD_RATE);
#endif
#endif
#if AXIS_HAS_UART(E0) #if AXIS_HAS_UART(E0)
#ifdef E0_HARDWARE_SERIAL #ifdef E0_HARDWARE_SERIAL
E0_HARDWARE_SERIAL.begin(TMC_BAUD_RATE); E0_HARDWARE_SERIAL.begin(TMC_BAUD_RATE);
@ -616,6 +633,9 @@ void restore_trinamic_drivers() {
#if AXIS_IS_TMC(Z3) #if AXIS_IS_TMC(Z3)
stepperZ3.push(); stepperZ3.push();
#endif #endif
#if AXIS_IS_TMC(Z4)
stepperZ4.push();
#endif
#if AXIS_IS_TMC(E0) #if AXIS_IS_TMC(E0)
stepperE0.push(); stepperE0.push();
#endif #endif
@ -678,6 +698,9 @@ void reset_trinamic_drivers() {
#if AXIS_IS_TMC(Z3) #if AXIS_IS_TMC(Z3)
_TMC_INIT(Z3, STEALTH_AXIS_Z); _TMC_INIT(Z3, STEALTH_AXIS_Z);
#endif #endif
#if AXIS_IS_TMC(Z4)
_TMC_INIT(Z4, STEALTH_AXIS_Z);
#endif
#if AXIS_IS_TMC(E0) #if AXIS_IS_TMC(E0)
_TMC_INIT(E0, STEALTH_AXIS_E); _TMC_INIT(E0, STEALTH_AXIS_E);
#endif #endif
@ -727,6 +750,9 @@ void reset_trinamic_drivers() {
#if AXIS_HAS_STALLGUARD(Z3) #if AXIS_HAS_STALLGUARD(Z3)
stepperZ3.homing_threshold(Z_STALL_SENSITIVITY); stepperZ3.homing_threshold(Z_STALL_SENSITIVITY);
#endif #endif
#if AXIS_HAS_STALLGUARD(Z4)
stepperZ4.homing_threshold(Z_STALL_SENSITIVITY);
#endif
#endif #endif
#endif #endif

View file

@ -50,6 +50,7 @@
#define TMC_Y2_LABEL 'Y', '2' #define TMC_Y2_LABEL 'Y', '2'
#define TMC_Z2_LABEL 'Z', '2' #define TMC_Z2_LABEL 'Z', '2'
#define TMC_Z3_LABEL 'Z', '3' #define TMC_Z3_LABEL 'Z', '3'
#define TMC_Z4_LABEL 'Z', '4'
#define TMC_E0_LABEL 'E', '0' #define TMC_E0_LABEL 'E', '0'
#define TMC_E1_LABEL 'E', '1' #define TMC_E1_LABEL 'E', '1'
@ -175,6 +176,19 @@ void reset_trinamic_drivers();
#endif #endif
#endif #endif
// Z4 Stepper
#if HAS_Z4_ENABLE && AXIS_IS_TMC(Z4)
extern TMC_CLASS(Z4, Z) stepperZ4;
#if ENABLED(SOFTWARE_DRIVER_ENABLE)
#define Z4_ENABLE_INIT() NOOP
#define Z4_ENABLE_WRITE(STATE) stepperZ4.toff((STATE)==Z_ENABLE_ON ? chopper_timing.toff : 0)
#define Z4_ENABLE_READ() stepperZ4.isEnabled()
#endif
#if AXIS_HAS_SQUARE_WAVE(Z4)
#define Z4_STEP_WRITE(STATE) do{ if(STATE) TOGGLE(Z4_STEP_PIN); }while(0)
#endif
#endif
// E0 Stepper // E0 Stepper
#if AXIS_IS_TMC(E0) #if AXIS_IS_TMC(E0)
extern TMC_CLASS_E(0) stepperE0; extern TMC_CLASS_E(0) stepperE0;

View file

@ -1153,7 +1153,7 @@
#endif #endif
// The Z2 axis, if any, should be the next open extruder port // The Z2 axis, if any, should be the next open extruder port
#if Z_MULTI_STEPPER_DRIVERS #if NUM_Z_STEPPER_DRIVERS >= 2
#ifndef Z2_STEP_PIN #ifndef Z2_STEP_PIN
#define Z2_STEP_PIN _EPIN(Z2_E_INDEX, STEP) #define Z2_STEP_PIN _EPIN(Z2_E_INDEX, STEP)
#define Z2_DIR_PIN _EPIN(Z2_E_INDEX, DIR) #define Z2_DIR_PIN _EPIN(Z2_E_INDEX, DIR)
@ -1200,7 +1200,7 @@
#define Z2_MS3_PIN -1 #define Z2_MS3_PIN -1
#endif #endif
#if ENABLED(Z_TRIPLE_STEPPER_DRIVERS) #if NUM_Z_STEPPER_DRIVERS >= 3
#ifndef Z3_STEP_PIN #ifndef Z3_STEP_PIN
#define Z3_STEP_PIN _EPIN(Z3_E_INDEX, STEP) #define Z3_STEP_PIN _EPIN(Z3_E_INDEX, STEP)
#define Z3_DIR_PIN _EPIN(Z3_E_INDEX, DIR) #define Z3_DIR_PIN _EPIN(Z3_E_INDEX, DIR)
@ -1231,6 +1231,7 @@
#define Z3_SERIAL_RX_PIN _EPIN(Z3_E_INDEX, SERIAL_RX) #define Z3_SERIAL_RX_PIN _EPIN(Z3_E_INDEX, SERIAL_RX)
#endif #endif
#endif #endif
#define Z4_E_INDEX INCREMENT(Z3_E_INDEX)
#endif #endif
#ifndef Z3_CS_PIN #ifndef Z3_CS_PIN
@ -1246,6 +1247,52 @@
#define Z3_MS3_PIN -1 #define Z3_MS3_PIN -1
#endif #endif
#if NUM_Z_STEPPER_DRIVERS >= 4
#ifndef Z4_STEP_PIN
#define Z4_STEP_PIN _EPIN(Z4_E_INDEX, STEP)
#define Z4_DIR_PIN _EPIN(Z4_E_INDEX, DIR)
#define Z4_ENABLE_PIN _EPIN(Z4_E_INDEX, ENABLE)
#if Z4_E_INDEX >= MAX_EXTRUDERS || !PIN_EXISTS(Z4_STEP)
#error "No E stepper plug left for Z4!"
#endif
#endif
#if AXIS_HAS_SPI(Z4)
#ifndef Z4_CS_PIN
#define Z4_CS_PIN _EPIN(Z4_E_INDEX, CS)
#endif
#endif
#ifndef Z4_MS1_PIN
#define Z4_MS1_PIN _EPIN(Z4_E_INDEX, MS1)
#endif
#ifndef Z4_MS2_PIN
#define Z4_MS2_PIN _EPIN(Z4_E_INDEX, MS2)
#endif
#ifndef Z4_MS3_PIN
#define Z4_MS3_PIN _EPIN(Z4_E_INDEX, MS3)
#endif
#if AXIS_HAS_UART(Z4)
#ifndef Z4_SERIAL_TX_PIN
#define Z4_SERIAL_TX_PIN _EPIN(Z4_E_INDEX, SERIAL_TX)
#endif
#ifndef Z4_SERIAL_RX_PIN
#define Z4_SERIAL_RX_PIN _EPIN(Z4_E_INDEX, SERIAL_RX)
#endif
#endif
#endif
#ifndef Z4_CS_PIN
#define Z4_CS_PIN -1
#endif
#ifndef Z4_MS1_PIN
#define Z4_MS1_PIN -1
#endif
#ifndef Z4_MS2_PIN
#define Z4_MS2_PIN -1
#endif
#ifndef Z4_MS3_PIN
#define Z4_MS3_PIN -1
#endif
#if HAS_GRAPHICAL_LCD #if HAS_GRAPHICAL_LCD
#if !defined(ST7920_DELAY_1) && defined(BOARD_ST7920_DELAY_1) #if !defined(ST7920_DELAY_1) && defined(BOARD_ST7920_DELAY_1)
#define ST7920_DELAY_1 BOARD_ST7920_DELAY_1 #define ST7920_DELAY_1 BOARD_ST7920_DELAY_1

View file

@ -90,6 +90,15 @@
#if !PIN_EXISTS(Z3_MS3) #if !PIN_EXISTS(Z3_MS3)
#undef Z3_MS3_PIN #undef Z3_MS3_PIN
#endif #endif
#if !PIN_EXISTS(Z4_MS1)
#undef Z4_MS1_PIN
#endif
#if !PIN_EXISTS(Z4_MS2)
#undef Z4_MS2_PIN
#endif
#if !PIN_EXISTS(Z4_MS3)
#undef Z4_MS3_PIN
#endif
#if !PIN_EXISTS(E0_MS1) #if !PIN_EXISTS(E0_MS1)
#undef E0_MS1_PIN #undef E0_MS1_PIN
#endif #endif
@ -1335,6 +1344,27 @@
#if PIN_EXISTS(Z3_STEP) #if PIN_EXISTS(Z3_STEP)
REPORT_NAME_DIGITAL(__LINE__, Z3_STEP_PIN) REPORT_NAME_DIGITAL(__LINE__, Z3_STEP_PIN)
#endif #endif
#if PIN_EXISTS(Z4_CS)
REPORT_NAME_DIGITAL(__LINE__, Z4_CS_PIN)
#endif
#if PIN_EXISTS(Z4_DIR)
REPORT_NAME_DIGITAL(__LINE__, Z4_DIR_PIN)
#endif
#if PIN_EXISTS(Z4_ENABLE)
REPORT_NAME_DIGITAL(__LINE__, Z4_ENABLE_PIN)
#endif
#if PIN_EXISTS(Z4_MS1)
REPORT_NAME_DIGITAL(__LINE__, Z4_MS1_PIN)
#endif
#if PIN_EXISTS(Z4_MS2)
REPORT_NAME_DIGITAL(__LINE__, Z4_MS2_PIN)
#endif
#if PIN_EXISTS(Z4_MS3)
REPORT_NAME_DIGITAL(__LINE__, Z4_MS3_PIN)
#endif
#if PIN_EXISTS(Z4_STEP)
REPORT_NAME_DIGITAL(__LINE__, Z4_STEP_PIN)
#endif
#if PIN_EXISTS(ZRIB_V20_D6) #if PIN_EXISTS(ZRIB_V20_D6)
REPORT_NAME_DIGITAL(__LINE__, ZRIB_V20_D6_PIN) REPORT_NAME_DIGITAL(__LINE__, ZRIB_V20_D6_PIN)
#endif #endif
@ -1383,6 +1413,12 @@
#if PIN_EXISTS(Z3_SERIAL_RX) #if PIN_EXISTS(Z3_SERIAL_RX)
REPORT_NAME_DIGITAL(__LINE__, Z3_SERIAL_RX_PIN) REPORT_NAME_DIGITAL(__LINE__, Z3_SERIAL_RX_PIN)
#endif #endif
#if PIN_EXISTS(Z4_SERIAL_TX)
REPORT_NAME_DIGITAL(__LINE__, Z4_SERIAL_TX_PIN)
#endif
#if PIN_EXISTS(Z4_SERIAL_RX)
REPORT_NAME_DIGITAL(__LINE__, Z4_SERIAL_RX_PIN)
#endif
#if PIN_EXISTS(E0_SERIAL_TX) #if PIN_EXISTS(E0_SERIAL_TX)
REPORT_NAME_DIGITAL(__LINE__, E0_SERIAL_TX_PIN) REPORT_NAME_DIGITAL(__LINE__, E0_SERIAL_TX_PIN)
#endif #endif

View file

@ -31,13 +31,9 @@
#if HOTENDS > 2 || E_STEPPERS > 2 #if HOTENDS > 2 || E_STEPPERS > 2
#error "RL200v1 supports up to 2 hotends / E-steppers. Comment out this line to continue." #error "RL200v1 supports up to 2 hotends / E-steppers. Comment out this line to continue."
#endif #elif NUM_Z_STEPPER_DRIVERS != 2
#error "RL200 uses dual Z stepper motors. Set NUM_Z_STEPPER_DRIVERS to 2 or comment out this line to continue."
#if DISABLED(Z_DUAL_STEPPER_DRIVERS) #elif !(AXIS_DRIVER_TYPE_X(DRV8825) && AXIS_DRIVER_TYPE_Y(DRV8825) && AXIS_DRIVER_TYPE_Z(DRV8825) && AXIS_DRIVER_TYPE_Z2(DRV8825) && AXIS_DRIVER_TYPE_E0(DRV8825))
#error "RL200 uses dual Z stepper motors. Update Configuration_adv.h or comment out this line to continue."
#endif
#if !(AXIS_DRIVER_TYPE_X(DRV8825) && AXIS_DRIVER_TYPE_Y(DRV8825) && AXIS_DRIVER_TYPE_Z(DRV8825) && AXIS_DRIVER_TYPE_Z2(DRV8825) && AXIS_DRIVER_TYPE_E0(DRV8825))
#error "You must set ([XYZ]|Z2|E0)_DRIVER_TYPE to DRV8825 in Configuration.h for RL200." #error "You must set ([XYZ]|Z2|E0)_DRIVER_TYPE to DRV8825 in Configuration.h for RL200."
#endif #endif

View file

@ -423,7 +423,7 @@
#define _Y2_PINS #define _Y2_PINS
#endif #endif
#if Z_MULTI_STEPPER_DRIVERS #if NUM_Z_STEPPER_DRIVERS >= 2
#if PIN_EXISTS(Z2_CS) && AXIS_HAS_SPI(Z2) #if PIN_EXISTS(Z2_CS) && AXIS_HAS_SPI(Z2)
#define _Z2_CS Z2_CS_PIN, #define _Z2_CS Z2_CS_PIN,
#else #else
@ -449,7 +449,7 @@
#define _Z2_PINS #define _Z2_PINS
#endif #endif
#if ENABLED(Z_TRIPLE_STEPPER_DRIVERS) #if NUM_Z_STEPPER_DRIVERS >= 3
#if PIN_EXISTS(Z3_CS) && AXIS_HAS_SPI(Z3) #if PIN_EXISTS(Z3_CS) && AXIS_HAS_SPI(Z3)
#define _Z3_CS Z3_CS_PIN, #define _Z3_CS Z3_CS_PIN,
#else #else
@ -475,6 +475,32 @@
#define _Z3_PINS #define _Z3_PINS
#endif #endif
#if NUM_Z_STEPPER_DRIVERS >= 4
#if PIN_EXISTS(Z4_CS) && AXIS_HAS_SPI(Z4)
#define _Z4_CS Z4_CS_PIN,
#else
#define _Z4_CS
#endif
#if PIN_EXISTS(Z4_MS1)
#define _Z4_MS1 Z4_MS1_PIN,
#else
#define _Z4_MS1
#endif
#if PIN_EXISTS(Z4_MS2)
#define _Z4_MS2 Z4_MS2_PIN,
#else
#define _Z4_MS2
#endif
#if PIN_EXISTS(Z4_MS3)
#define _Z4_MS3 Z4_MS3_PIN,
#else
#define _Z4_MS3
#endif
#define _Z4_PINS Z4_STEP_PIN, Z4_DIR_PIN, Z4_ENABLE_PIN, _Z4_CS _Z4_MS1 _Z4_MS2 _Z4_MS3
#else
#define _Z4_PINS
#endif
// //
// Generate the final Sensitive Pins array, // Generate the final Sensitive Pins array,
// keeping the array as small as possible. // keeping the array as small as possible.
@ -524,9 +550,9 @@
#endif #endif
#define SENSITIVE_PINS { \ #define SENSITIVE_PINS { \
_X_PINS _Y_PINS _Z_PINS _X2_PINS _Y2_PINS _Z2_PINS _Z3_PINS _Z_PROBE \ _X_PINS _Y_PINS _Z_PINS _X2_PINS _Y2_PINS _Z2_PINS _Z3_PINS _Z4_PINS \
_E0_PINS _E1_PINS _E2_PINS _E3_PINS _E4_PINS _E5_PINS _BED_PINS \ _Z_PROBE _E0_PINS _E1_PINS _E2_PINS _E3_PINS _E4_PINS _E5_PINS \
_H0_PINS _H1_PINS _H2_PINS _H3_PINS _H4_PINS _H5_PINS \ _BED_PINS _H0_PINS _H1_PINS _H2_PINS _H3_PINS _H4_PINS _H5_PINS \
_PS_ON _HEATER_BED _FAN0 _FAN1 _FAN2 _FANC \ _PS_ON _HEATER_BED _FAN0 _FAN1 _FAN2 _FANC \
HAL_SENSITIVE_PINS \ HAL_SENSITIVE_PINS \
} }

View file

@ -37,16 +37,16 @@ exec_test $1 $2 "RAMPS4DUE_EFB with ABL (Bilinear), EXTENSIBLE_UI, S-Curve, many
restore_configs restore_configs
opt_set MOTHERBOARD BOARD_RADDS opt_set MOTHERBOARD BOARD_RADDS
opt_enable USE_XMAX_PLUG USE_YMAX_PLUG ENDSTOPPULLUPS BLTOUCH AUTO_BED_LEVELING_BILINEAR \ opt_enable USE_XMAX_PLUG USE_YMAX_PLUG ENDSTOPPULLUPS BLTOUCH AUTO_BED_LEVELING_BILINEAR \
Z_TRIPLE_STEPPER_DRIVERS Z_TRIPLE_ENDSTOPS Z_STEPPER_AUTO_ALIGN \ Z_MULTI_ENDSTOPS Z_STEPPER_AUTO_ALIGN Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS
Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS
#TOUCH_UI_FTDI_EVE LCD_ALEPHOBJECTS_CLCD_UI OTHER_PIN_LAYOUT #TOUCH_UI_FTDI_EVE LCD_ALEPHOBJECTS_CLCD_UI OTHER_PIN_LAYOUT
opt_set NUM_Z_STEPPER_DRIVERS 3
opt_add Z2_MAX_ENDSTOP_INVERTING false opt_add Z2_MAX_ENDSTOP_INVERTING false
opt_add Z3_MAX_ENDSTOP_INVERTING false opt_add Z3_MAX_ENDSTOP_INVERTING false
pins_set ramps/RAMPS X_MAX_PIN -1
pins_set ramps/RAMPS Y_MAX_PIN -1
opt_add Z2_MAX_PIN 2 opt_add Z2_MAX_PIN 2
opt_add Z3_MAX_PIN 3 opt_add Z3_MAX_PIN 3
exec_test $1 $2 "RADDS with ABL (Bilinear), Z_TRIPLE_STEPPER_DRIVERS and Z_STEPPER_AUTO_ALIGN" pins_set ramps/RAMPS X_MAX_PIN -1
pins_set ramps/RAMPS Y_MAX_PIN -1
exec_test $1 $2 "RADDS with ABL (Bilinear), Triple Z Axis, Z_STEPPER_AUTO_ALIGN"
# #
# Test SWITCHING_EXTRUDER # Test SWITCHING_EXTRUDER

View file

@ -100,15 +100,16 @@ opt_enable COREXZ
exec_test $1 $2 "COREXZ" exec_test $1 $2 "COREXZ"
# #
# Enable Z_DUAL_STEPPER_DRIVERS, Z_DUAL_ENDSTOPS # Enable Dual Z with Dual Z endstops
# #
restore_configs restore_configs
opt_set MOTHERBOARD BOARD_TEENSY35_36 opt_set MOTHERBOARD BOARD_TEENSY35_36
opt_enable Z_DUAL_STEPPER_DRIVERS Z_DUAL_ENDSTOPS opt_enable Z_MULTI_ENDSTOPS
opt_set NUM_Z_STEPPER_DRIVERS 2
pins_set ramps/RAMPS X_MAX_PIN -1 pins_set ramps/RAMPS X_MAX_PIN -1
opt_add Z2_MAX_PIN 2 opt_add Z2_MAX_PIN 2
opt_enable USE_XMAX_PLUG opt_enable USE_XMAX_PLUG
exec_test $1 $2 "Z_DUAL_STEPPER_DRIVERS, Z_DUAL_ENDSTOPS" exec_test $1 $2 "Dual Z with Dual Z endstops"
# Clean up # Clean up
restore_configs restore_configs