Browse Source

Add support for Triple-Z steppers/endstops

pull/1/head
Holger Müller 6 years ago
committed by Scott Lahteine
parent
commit
1a6f2b29b8
  1. 1
      Marlin/Configuration.h
  2. 23
      Marlin/Configuration_adv.h
  3. 1
      Marlin/src/HAL/HAL_AVR/SanityCheck.h
  4. 20
      Marlin/src/HAL/HAL_AVR/endstop_interrupts.h
  5. 6
      Marlin/src/HAL/HAL_DUE/endstop_interrupts.h
  6. 6
      Marlin/src/HAL/HAL_ESP32/endstop_interrupts.h
  7. 6
      Marlin/src/HAL/HAL_LPC1768/endstop_interrupts.h
  8. 6
      Marlin/src/HAL/HAL_STM32F1/endstop_interrupts.h
  9. 6
      Marlin/src/HAL/HAL_STM32F4/endstop_interrupts.h
  10. 6
      Marlin/src/HAL/HAL_STM32F7/endstop_interrupts.h
  11. 20
      Marlin/src/HAL/HAL_TEENSY35_36/endstop_interrupts.h
  12. 5
      Marlin/src/Marlin.h
  13. 1
      Marlin/src/config/default/Configuration.h
  14. 23
      Marlin/src/config/default/Configuration_adv.h
  15. 5
      Marlin/src/core/drivers.h
  16. 2
      Marlin/src/core/language.h
  17. 3
      Marlin/src/feature/controllerfan.cpp
  18. 78
      Marlin/src/feature/tmc_util.cpp
  19. 29
      Marlin/src/feature/tmc_util.h
  20. 34
      Marlin/src/gcode/calibrate/M666.cpp
  21. 6
      Marlin/src/gcode/feature/trinamic/M906.cpp
  22. 63
      Marlin/src/gcode/feature/trinamic/M911-M915.cpp
  23. 3
      Marlin/src/inc/Conditionals_LCD.h
  24. 65
      Marlin/src/inc/Conditionals_post.h
  25. 82
      Marlin/src/inc/SanityCheck.h
  26. 126
      Marlin/src/module/configuration_store.cpp
  27. 87
      Marlin/src/module/endstops.cpp
  28. 17
      Marlin/src/module/endstops.h
  29. 76
      Marlin/src/module/motion.cpp
  30. 86
      Marlin/src/module/stepper.cpp
  31. 18
      Marlin/src/module/stepper.h
  32. 41
      Marlin/src/module/stepper_indirection.cpp
  33. 35
      Marlin/src/module/stepper_indirection.h
  34. 29
      Marlin/src/pins/pins.h
  35. 27
      Marlin/src/pins/pinsDebug_list.h
  36. 12
      buildroot/share/tests/DUE_tests
  37. 2
      buildroot/share/tests/teensy35_tests

1
Marlin/Configuration.h

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

23
Marlin/Configuration_adv.h

@ -338,6 +338,17 @@
#endif
#endif
//#define Z_TRIPLE_STEPPER_DRIVERS
#if ENABLED(Z_TRIPLE_STEPPER_DRIVERS)
//#define Z_TRIPLE_ENDSTOPS
#if ENABLED(Z_TRIPLE_ENDSTOPS)
#define Z2_USE_ENDSTOP _XMAX_
#define Z3_USE_ENDSTOP _YMAX_
#define Z_TRIPLE2_ENDSTOPS_ADJUSTMENT 0
#define Z_TRIPLE3_ENDSTOPS_ADJUSTMENT 0
#endif
#endif
/**
* Dual X Carriage
*
@ -1087,6 +1098,10 @@
#define Z2_SENSE_RESISTOR 91
#define Z2_MICROSTEPS 16
#define Z3_MAX_CURRENT 1000
#define Z3_SENSE_RESISTOR 91
#define Z3_MICROSTEPS 16
#define E0_MAX_CURRENT 1000
#define E0_SENSE_RESISTOR 91
#define E0_MICROSTEPS 16
@ -1153,6 +1168,9 @@
#define Z2_CURRENT 800
#define Z2_MICROSTEPS 16
#define Z3_CURRENT 800
#define Z3_MICROSTEPS 16
#define E0_CURRENT 800
#define E0_MICROSTEPS 16
@ -1217,6 +1235,7 @@
#define Y2_HYBRID_THRESHOLD 100
#define Z_HYBRID_THRESHOLD 3
#define Z2_HYBRID_THRESHOLD 3
#define Z3_HYBRID_THRESHOLD 3
#define E0_HYBRID_THRESHOLD 30
#define E1_HYBRID_THRESHOLD 30
#define E2_HYBRID_THRESHOLD 30
@ -1315,6 +1334,10 @@
#define Z2_OVERCURRENT 2000
#define Z2_STALLCURRENT 1500
#define Z3_MICROSTEPS 16
#define Z3_OVERCURRENT 2000
#define Z3_STALLCURRENT 1500
#define E0_MICROSTEPS 16
#define E0_OVERCURRENT 2000
#define E0_STALLCURRENT 1500

1
Marlin/src/HAL/HAL_AVR/SanityCheck.h

@ -106,6 +106,7 @@
|| defined(Y2_HARDWARE_SERIAL) \
|| defined(Z_HARDWARE_SERIAL ) \
|| defined(Z2_HARDWARE_SERIAL) \
|| defined(Z3_HARDWARE_SERIAL) \
|| defined(E0_HARDWARE_SERIAL) \
|| defined(E1_HARDWARE_SERIAL) \
|| defined(E2_HARDWARE_SERIAL) \

20
Marlin/src/HAL/HAL_AVR/endstop_interrupts.h

@ -225,6 +225,26 @@ void setup_endstop_interrupts( void ) {
#endif
#endif
#if HAS_Z3_MAX
#if (digitalPinToInterrupt(Z3_MAX_PIN) != NOT_AN_INTERRUPT)
attachInterrupt(digitalPinToInterrupt(Z3_MAX_PIN), endstop_ISR, CHANGE);
#else
// Not all used endstop/probe -pins can raise interrupts. Please deactivate ENDSTOP_INTERRUPTS or change the pin configuration!
static_assert(digitalPinToPCICR(Z3_MAX_PIN) != NULL, "Z3_MAX_PIN is not interrupt-capable");
pciSetup(Z3_MAX_PIN);
#endif
#endif
#if HAS_Z3_MIN
#if (digitalPinToInterrupt(Z3_MIN_PIN) != NOT_AN_INTERRUPT)
attachInterrupt(digitalPinToInterrupt(Z3_MIN_PIN), endstop_ISR, CHANGE);
#else
// Not all used endstop/probe -pins can raise interrupts. Please deactivate ENDSTOP_INTERRUPTS or change the pin configuration!
static_assert(digitalPinToPCICR(Z3_MIN_PIN) != NULL, "Z3_MIN_PIN is not interrupt-capable");
pciSetup(Z3_MIN_PIN);
#endif
#endif
#if HAS_Z_MIN_PROBE_PIN
#if (digitalPinToInterrupt(Z_MIN_PROBE_PIN) != NOT_AN_INTERRUPT)
attachInterrupt(digitalPinToInterrupt(Z_MIN_PROBE_PIN), endstop_ISR, CHANGE);

6
Marlin/src/HAL/HAL_DUE/endstop_interrupts.h

@ -72,6 +72,12 @@ void setup_endstop_interrupts(void) {
#if HAS_Z2_MIN
attachInterrupt(digitalPinToInterrupt(Z2_MIN_PIN), endstop_ISR, CHANGE);
#endif
#if HAS_Z3_MAX
attachInterrupt(digitalPinToInterrupt(Z3_MAX_PIN), endstop_ISR, CHANGE);
#endif
#if HAS_Z3_MIN
attachInterrupt(digitalPinToInterrupt(Z3_MIN_PIN), endstop_ISR, CHANGE);
#endif
#if HAS_Z_MIN_PROBE_PIN
attachInterrupt(digitalPinToInterrupt(Z_MIN_PROBE_PIN), endstop_ISR, CHANGE);
#endif

6
Marlin/src/HAL/HAL_ESP32/endstop_interrupts.h

@ -67,6 +67,12 @@ void setup_endstop_interrupts(void) {
#if HAS_Z2_MIN
attachInterrupt(digitalPinToInterrupt(Z2_MIN_PIN), endstop_ISR, CHANGE);
#endif
#if HAS_Z3_MAX
attachInterrupt(digitalPinToInterrupt(Z3_MAX_PIN), endstop_ISR, CHANGE);
#endif
#if HAS_Z3_MIN
attachInterrupt(digitalPinToInterrupt(Z3_MIN_PIN), endstop_ISR, CHANGE);
#endif
#if HAS_Z_MIN_PROBE_PIN
attachInterrupt(digitalPinToInterrupt(Z_MIN_PROBE_PIN), endstop_ISR, CHANGE);
#endif

6
Marlin/src/HAL/HAL_LPC1768/endstop_interrupts.h

@ -91,6 +91,12 @@ void setup_endstop_interrupts(void) {
#endif
attachInterrupt(digitalPinToInterrupt(Z2_MIN_PIN), endstop_ISR, CHANGE);
#endif
#if HAS_Z3_MAX
attachInterrupt(digitalPinToInterrupt(Z3_MAX_PIN), endstop_ISR, CHANGE);
#endif
#if HAS_Z3_MIN
attachInterrupt(digitalPinToInterrupt(Z3_MIN_PIN), endstop_ISR, CHANGE);
#endif
#if HAS_Z_MIN_PROBE_PIN
#if !LPC1768_PIN_INTERRUPT_M(Z_MIN_PROBE_PIN)
#error "Z_MIN_PROBE_PIN is not an INTERRUPT capable pin."

6
Marlin/src/HAL/HAL_STM32F1/endstop_interrupts.h

@ -79,6 +79,12 @@ void setup_endstop_interrupts(void) {
#if HAS_Z2_MIN
attachInterrupt(Z2_MIN_PIN, endstop_ISR, CHANGE);
#endif
#if HAS_Z3_MAX
attachInterrupt(Z3_MAX_PIN, endstop_ISR, CHANGE);
#endif
#if HAS_Z3_MIN
attachInterrupt(Z3_MIN_PIN, endstop_ISR, CHANGE);
#endif
#if HAS_Z_MIN_PROBE_PIN
attachInterrupt(Z_MIN_PROBE_PIN, endstop_ISR, CHANGE);
#endif

6
Marlin/src/HAL/HAL_STM32F4/endstop_interrupts.h

@ -54,6 +54,12 @@ void setup_endstop_interrupts(void) {
#if HAS_Z2_MIN
attachInterrupt(Z2_MIN_PIN, endstop_ISR, CHANGE);
#endif
#if HAS_Z3_MAX
attachInterrupt(Z3_MAX_PIN, endstop_ISR, CHANGE);
#endif
#if HAS_Z3_MIN
attachInterrupt(Z3_MIN_PIN, endstop_ISR, CHANGE);
#endif
#if HAS_Z_MIN_PROBE_PIN
attachInterrupt(Z_MIN_PROBE_PIN, endstop_ISR, CHANGE);
#endif

6
Marlin/src/HAL/HAL_STM32F7/endstop_interrupts.h

@ -56,6 +56,12 @@ void setup_endstop_interrupts(void) {
#if HAS_Z2_MIN
attachInterrupt(Z2_MIN_PIN, endstop_ISR, CHANGE);
#endif
#if HAS_Z3_MAX
attachInterrupt(Z3_MAX_PIN, endstop_ISR, CHANGE);
#endif
#if HAS_Z3_MIN
attachInterrupt(Z3_MIN_PIN, endstop_ISR, CHANGE);
#endif
#if HAS_Z_MIN_PROBE_PIN
attachInterrupt(Z_MIN_PROBE_PIN, endstop_ISR, CHANGE);
#endif

20
Marlin/src/HAL/HAL_TEENSY35_36/endstop_interrupts.h

@ -43,44 +43,40 @@
void endstop_ISR(void) { endstops.update(); }
/**
* Endstop interrupts for Due based targets.
* On Due, all pins support external interrupt capability.
* Endstop interrupts for Due based targets.
* On Due, all pins support external interrupt capability.
*/
void setup_endstop_interrupts( void ) {
#if HAS_X_MAX
attachInterrupt(digitalPinToInterrupt(X_MAX_PIN), endstop_ISR, CHANGE); // assign it
#endif
#if HAS_X_MIN
attachInterrupt(digitalPinToInterrupt(X_MIN_PIN), endstop_ISR, CHANGE);
#endif
#if HAS_Y_MAX
attachInterrupt(digitalPinToInterrupt(Y_MAX_PIN), endstop_ISR, CHANGE);
#endif
#if HAS_Y_MIN
attachInterrupt(digitalPinToInterrupt(Y_MIN_PIN), endstop_ISR, CHANGE);
#endif
#if HAS_Z_MAX
attachInterrupt(digitalPinToInterrupt(Z_MAX_PIN), endstop_ISR, CHANGE);
#endif
#if HAS_Z_MIN
attachInterrupt(digitalPinToInterrupt(Z_MIN_PIN), endstop_ISR, CHANGE);
#endif
#if HAS_Z2_MAX
attachInterrupt(digitalPinToInterrupt(Z2_MAX_PIN), endstop_ISR, CHANGE);
#endif
#if HAS_Z2_MIN
attachInterrupt(digitalPinToInterrupt(Z2_MIN_PIN), endstop_ISR, CHANGE);
#endif
#if HAS_Z3_MAX
attachInterrupt(digitalPinToInterrupt(Z3_MAX_PIN), endstop_ISR, CHANGE);
#endif
#if HAS_Z3_MIN
attachInterrupt(digitalPinToInterrupt(Z3_MIN_PIN), endstop_ISR, CHANGE);
#endif
#if HAS_Z_MIN_PROBE_PIN
attachInterrupt(digitalPinToInterrupt(Z_MIN_PROBE_PIN), endstop_ISR, CHANGE);
#endif

5
Marlin/src/Marlin.h

@ -64,7 +64,10 @@ void manage_inactivity(const bool ignore_stepper_queue=false);
#define disable_Y() NOOP
#endif
#if HAS_Z2_ENABLE
#if HAS_Z3_ENABLE
#define enable_Z() do{ Z_ENABLE_WRITE( Z_ENABLE_ON); Z2_ENABLE_WRITE(Z_ENABLE_ON); Z3_ENABLE_WRITE(Z_ENABLE_ON); }while(0)
#define disable_Z() do{ Z_ENABLE_WRITE(!Z_ENABLE_ON); Z2_ENABLE_WRITE(!Z_ENABLE_ON); Z3_ENABLE_WRITE(!Z_ENABLE_ON); CBI(axis_known_position, Z_AXIS); }while(0)
#elif HAS_Z2_ENABLE
#define enable_Z() do{ Z_ENABLE_WRITE( Z_ENABLE_ON); Z2_ENABLE_WRITE(Z_ENABLE_ON); }while(0)
#define disable_Z() do{ Z_ENABLE_WRITE(!Z_ENABLE_ON); Z2_ENABLE_WRITE(!Z_ENABLE_ON); CBI(axis_known_position, Z_AXIS); }while(0)
#elif HAS_Z_ENABLE

1
Marlin/src/config/default/Configuration.h

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

23
Marlin/src/config/default/Configuration_adv.h

@ -338,6 +338,17 @@
#endif
#endif
//#define Z_TRIPLE_STEPPER_DRIVERS
#if ENABLED(Z_TRIPLE_STEPPER_DRIVERS)
//#define Z_TRIPLE_ENDSTOPS
#if ENABLED(Z_TRIPLE_ENDSTOPS)
#define Z2_USE_ENDSTOP _XMAX_
#define Z3_USE_ENDSTOP _YMAX_
#define Z_TRIPLE_ENDSTOPS_ADJUSTMENT2 0
#define Z_TRIPLE_ENDSTOPS_ADJUSTMENT3 0
#endif
#endif
/**
* Dual X Carriage
*
@ -1087,6 +1098,10 @@
#define Z2_SENSE_RESISTOR 91
#define Z2_MICROSTEPS 16
#define Z3_MAX_CURRENT 1000
#define Z3_SENSE_RESISTOR 91
#define Z3_MICROSTEPS 16
#define E0_MAX_CURRENT 1000
#define E0_SENSE_RESISTOR 91
#define E0_MICROSTEPS 16
@ -1153,6 +1168,9 @@
#define Z2_CURRENT 800
#define Z2_MICROSTEPS 16
#define Z3_CURRENT 800
#define Z3_MICROSTEPS 16
#define E0_CURRENT 800
#define E0_MICROSTEPS 16
@ -1217,6 +1235,7 @@
#define Y2_HYBRID_THRESHOLD 100
#define Z_HYBRID_THRESHOLD 3
#define Z2_HYBRID_THRESHOLD 3
#define Z3_HYBRID_THRESHOLD 3
#define E0_HYBRID_THRESHOLD 30
#define E1_HYBRID_THRESHOLD 30
#define E2_HYBRID_THRESHOLD 30
@ -1315,6 +1334,10 @@
#define Z2_OVERCURRENT 2000
#define Z2_STALLCURRENT 1500
#define Z3_MICROSTEPS 16
#define Z3_OVERCURRENT 2000
#define Z3_STALLCURRENT 1500
#define E0_MICROSTEPS 16
#define E0_OVERCURRENT 2000
#define E0_STALLCURRENT 1500

5
Marlin/src/core/drivers.h

@ -47,7 +47,8 @@
#define AXIS_DRIVER_TYPE_Z(T) _AXIS_DRIVER_TYPE(Z,T)
#define AXIS_DRIVER_TYPE_X2(T) (ENABLED(X_DUAL_STEPPER_DRIVERS) || ENABLED(DUAL_X_CARRIAGE)) && _AXIS_DRIVER_TYPE(X2,T)
#define AXIS_DRIVER_TYPE_Y2(T) (ENABLED(Y_DUAL_STEPPER_DRIVERS) && _AXIS_DRIVER_TYPE(Y2,T))
#define AXIS_DRIVER_TYPE_Z2(T) (ENABLED(Z_DUAL_STEPPER_DRIVERS) && _AXIS_DRIVER_TYPE(Z2,T))
#define AXIS_DRIVER_TYPE_Z2(T) (Z_MULTI_STEPPER_DRIVERS && _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_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_E2(T) (E_STEPPERS > 2 && _AXIS_DRIVER_TYPE(E2,T))
@ -58,7 +59,7 @@
#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_Z(T) || AXIS_DRIVER_TYPE_Z2(T) || \
AXIS_DRIVER_TYPE_Z(T) || AXIS_DRIVER_TYPE_Z2(T) || AXIS_DRIVER_TYPE_Z3(T) || \
AXIS_DRIVER_TYPE_E0(T) || AXIS_DRIVER_TYPE_E1(T) || \
AXIS_DRIVER_TYPE_E2(T) || AXIS_DRIVER_TYPE_E3(T) || \
AXIS_DRIVER_TYPE_E4(T) )

2
Marlin/src/core/language.h

@ -151,6 +151,8 @@
#define MSG_Z_MAX "z_max: "
#define MSG_Z2_MIN "z2_min: "
#define MSG_Z2_MAX "z2_max: "
#define MSG_Z3_MIN "z3_min: "
#define MSG_Z3_MAX "z3_max: "
#define MSG_Z_PROBE "z_probe: "
#define MSG_PROBE_Z_OFFSET "Probe Z Offset"
#define MSG_SKEW_MIN "min_skew_factor: "

3
Marlin/src/feature/controllerfan.cpp

@ -50,6 +50,9 @@ void controllerfan_update() {
#if HAS_Z2_ENABLE
|| Z2_ENABLE_READ == Z_ENABLE_ON
#endif
#if HAS_Z3_ENABLE
|| Z3_ENABLE_READ == Z_ENABLE_ON
#endif
|| E0_ENABLE_READ == E_ENABLE_ON
#if E_STEPPERS > 1
|| E1_ENABLE_READ == E_ENABLE_ON

78
Marlin/src/feature/tmc_util.cpp

@ -189,6 +189,10 @@ bool report_tmc_status = false;
static uint8_t z2_otpw_cnt = 0;
monitor_tmc_driver(stepperZ2, TMC_Z, z2_otpw_cnt);
#endif
#if HAS_HW_COMMS(Z3)
static uint8_t z3_otpw_cnt = 0;
monitor_tmc_driver(stepperZ3, TMC_Z, z3_otpw_cnt);
#endif
#if HAS_HW_COMMS(E0)
static uint8_t e0_otpw_cnt = 0;
monitor_tmc_driver(stepperE0, TMC_E0, e0_otpw_cnt);
@ -217,12 +221,65 @@ bool report_tmc_status = false;
#endif // MONITOR_DRIVER_STATUS
void _tmc_say_axis(const TMC_AxisEnum axis) {
static const char ext_X[] PROGMEM = "X", ext_Y[] PROGMEM = "Y", ext_Z[] PROGMEM = "Z",
ext_X2[] PROGMEM = "X2", ext_Y2[] PROGMEM = "Y2", ext_Z2[] PROGMEM = "Z2",
ext_E0[] PROGMEM = "E0", ext_E1[] PROGMEM = "E1",
ext_E2[] PROGMEM = "E2", ext_E3[] PROGMEM = "E3",
ext_E4[] PROGMEM = "E4";
static const char* const tmc_axes[] PROGMEM = { ext_X, ext_Y, ext_Z, ext_X2, ext_Y2, ext_Z2, ext_E0, ext_E1, ext_E2, ext_E3, ext_E4 };
static const char ext_X[] PROGMEM = "X", ext_Y[] PROGMEM = "Y", ext_Z[] PROGMEM = "Z",
#if ENABLED(DUAL_X_CARRIAGE) || ENABLED(X_DUAL_STEPPER_DRIVERS)
, ext_X2[] PROGMEM = "X2"
#endif
#if ENABLED(Y_DUAL_STEPPER_DRIVERS)
, ext_Y2[] PROGMEM = "Y2"
#endif
#if Z_MULTI_STEPPER_DRIVERS
, ext_Z2[] PROGMEM = "Z2"
#if ENABLED(Z_TRIPLE_STEPPER_DRIVERS)
, ext_Z3[] PROGMEM = "Z3"
#endif
#endif
#if E_STEPPERS
, ext_E0[] PROGMEM = "E0"
#if E_STEPPERS > 1
, ext_E1[] PROGMEM = "E1"
#if E_STEPPERS > 2
, ext_E2[] PROGMEM = "E2"
#if E_STEPPERS > 3
, ext_E3[] PROGMEM = "E3"
#if E_STEPPERS > 4
, ext_E4[] PROGMEM = "E4"
#endif
#endif
#endif
#endif
#endif
static const char* const tmc_axes[] PROGMEM = {
ext_X, ext_Y, ext_Z
#if ENABLED(DUAL_X_CARRIAGE) || ENABLED(X_DUAL_STEPPER_DRIVERS)
, ext_X2
#endif
#if ENABLED(Y_DUAL_STEPPER_DRIVERS)
, ext_Y2
#endif
#if Z_MULTI_STEPPER_DRIVERS
, ext_Z2
#if ENABLED(Z_TRIPLE_STEPPER_DRIVERS)
, ext_Z3
#endif
#endif
#if E_STEPPERS
, ext_E0
#if E_STEPPERS > 1
, ext_E1
#if E_STEPPERS > 2
, ext_E2
#if E_STEPPERS > 3
, ext_E3
#if E_STEPPERS > 4
, ext_E4
#endif
#endif
#endif
#endif
#endif
};
serialprintPGM((char*)pgm_read_ptr(&tmc_axes[axis]));
}
@ -440,6 +497,9 @@ void _tmc_say_sgt(const TMC_AxisEnum axis, const int8_t sgt) {
#if AXIS_IS_TMC(Z2)
tmc_status(stepperZ2, TMC_Z2, i, planner.axis_steps_per_mm[Z_AXIS]);
#endif
#if AXIS_IS_TMC(Z3)
tmc_status(stepperZ3, TMC_Z3, i, planner.axis_steps_per_mm[Z_AXIS]);
#endif
#if AXIS_IS_TMC(E0)
tmc_status(stepperE0, TMC_E0, i, planner.axis_steps_per_mm[E_AXIS]);
@ -497,6 +557,9 @@ void _tmc_say_sgt(const TMC_AxisEnum axis, const int8_t sgt) {
#if AXIS_IS_TMC(Z2)
tmc_parse_drv_status(stepperZ2, TMC_Z2, i);
#endif
#if AXIS_IS_TMC(Z3)
tmc_parse_drv_status(stepperZ3, TMC_Z3, i);
#endif
#if AXIS_IS_TMC(E0)
tmc_parse_drv_status(stepperE0, TMC_E0, i);
@ -612,6 +675,9 @@ void _tmc_say_sgt(const TMC_AxisEnum axis, const int8_t sgt) {
#if AXIS_DRIVER_TYPE(Z2, TMC2130)
SET_CS_PIN(Z2);
#endif
#if AXIS_DRIVER_TYPE(Z3, TMC2130)
SET_CS_PIN(Z3);
#endif
#if AXIS_DRIVER_TYPE(E0, TMC2130)
SET_CS_PIN(E0);
#endif

29
Marlin/src/feature/tmc_util.h

@ -35,7 +35,34 @@
extern bool report_tmc_status;
enum TMC_AxisEnum : char { TMC_X, TMC_Y, TMC_Z, TMC_X2, TMC_Y2, TMC_Z2, TMC_E0, TMC_E1, TMC_E2, TMC_E3, TMC_E4 };
enum TMC_AxisEnum : char {
TMC_X, TMC_Y, TMC_Z
#if ENABLED(DUAL_X_CARRIAGE) || ENABLED(X_DUAL_STEPPER_DRIVERS)
, TMC_X2
#endif
#if ENABLED(Y_DUAL_STEPPER_DRIVERS)
, TMC_Y2
#endif
#if ENABLED(Z_DUAL_STEPPER_DRIVERS)
, TMC_Z2
#endif
#if ENABLED(Z_TRIPLE_STEPPER_DRIVERS)
, TMC_Z3
#endif
, TMC_E0
#if E_STEPPERS > 1
, TMC_E1
#if E_STEPPERS > 2
, TMC_E2
#if E_STEPPERS > 3
, TMC_E3
#if E_STEPPERS > 4
, TMC_E4
#endif
#endif
#endif
#endif
};
constexpr uint32_t _tmc_thrs(const uint16_t msteps, const int32_t thrs, const uint32_t spmm) {
return 12650000UL * msteps / (256 * thrs * spmm);

34
Marlin/src/gcode/calibrate/M666.cpp

@ -59,44 +59,60 @@
#endif
}
#elif ENABLED(X_DUAL_ENDSTOPS) || ENABLED(Y_DUAL_ENDSTOPS) || ENABLED(Z_DUAL_ENDSTOPS)
#elif ENABLED(X_DUAL_ENDSTOPS) || ENABLED(Y_DUAL_ENDSTOPS) || Z_MULTI_ENDSTOPS
#include "../../module/endstops.h"
/**
* M666: Set Dual Endstops offsets for X, Y, and/or Z.
* With no parameters report current offsets.
*
* For Triple Z Endstops:
* Set Z2 Only: M666 S2 Z<offset>
* Set Z3 Only: M666 S3 Z<offset>
* Set Both: M666 Z<offset>
*/
void GcodeSuite::M666() {
bool report = true;
#if ENABLED(X_DUAL_ENDSTOPS)
if (parser.seen('X')) {
endstops.x_endstop_adj = parser.value_linear_units();
endstops.x2_endstop_adj = parser.value_linear_units();
report = false;
}
#endif
#if ENABLED(Y_DUAL_ENDSTOPS)
if (parser.seen('Y')) {
endstops.y_endstop_adj = parser.value_linear_units();
endstops.y2_endstop_adj = parser.value_linear_units();
report = false;
}
#endif
#if ENABLED(Z_DUAL_ENDSTOPS)
#if ENABLED(Z_TRIPLE_ENDSTOPS)
if (parser.seen('Z')) {
endstops.z_endstop_adj = parser.value_linear_units();
const int ind = parser.intval('S');
const float z_adj = parser.value_linear_units();
if (!ind || ind == 2) endstops.z2_endstop_adj = z_adj;
if (!ind || ind == 3) endstops.z3_endstop_adj = z_adj;
report = false;
}
#elif Z_MULTI_ENDSTOPS
if (parser.seen('Z')) {
endstops.z2_endstop_adj = parser.value_linear_units();
report = false;
}
#endif
if (report) {
SERIAL_ECHOPGM("Dual Endstop Adjustment (mm): ");
#if ENABLED(X_DUAL_ENDSTOPS)
SERIAL_ECHOPAIR(" X", endstops.x_endstop_adj);
SERIAL_ECHOPAIR(" X2:", endstops.x2_endstop_adj);
#endif
#if ENABLED(Y_DUAL_ENDSTOPS)
SERIAL_ECHOPAIR(" Y", endstops.y_endstop_adj);
SERIAL_ECHOPAIR(" Y2:", endstops.y2_endstop_adj);
#endif
#if Z_MULTI_ENDSTOPS
SERIAL_ECHOPAIR(" Z2:", endstops.z2_endstop_adj);
#endif
#if ENABLED(Z_DUAL_ENDSTOPS)
SERIAL_ECHOPAIR(" Z", endstops.z_endstop_adj);
#if ENABLED(Z_TRIPLE_ENDSTOPS)
SERIAL_ECHOPAIR(" Z3:", endstops.z3_endstop_adj);
#endif
SERIAL_EOL();
}

6
Marlin/src/gcode/feature/trinamic/M906.cpp

@ -64,6 +64,9 @@ void GcodeSuite::M906() {
#if AXIS_IS_TMC(Z2)
if (index == 1) TMC_SET_CURRENT(Z2);
#endif
#if AXIS_IS_TMC(Z3)
if (index == 2) TMC_SET_CURRENT(Z3);
#endif
break;
case E_AXIS: {
if (get_target_extruder_from_command()) return;
@ -107,6 +110,9 @@ void GcodeSuite::M906() {
#if AXIS_IS_TMC(Z2)
TMC_SAY_CURRENT(Z2);
#endif
#if AXIS_IS_TMC(Z3)
TMC_SAY_CURRENT(Z3);
#endif
#if AXIS_IS_TMC(E0)
TMC_SAY_CURRENT(E0);
#endif

63
Marlin/src/gcode/feature/trinamic/M911-M915.cpp

@ -56,6 +56,9 @@ void GcodeSuite::M911() {
#if M91x_USE(Z2)
tmc_report_otpw(stepperZ2, TMC_Z2);
#endif
#if M91x_USE(Z3)
tmc_report_otpw(stepperZ3, TMC_Z3);
#endif
#if M91x_USE_E(0)
tmc_report_otpw(stepperE0, TMC_E0);
#endif
@ -75,7 +78,7 @@ void GcodeSuite::M911() {
/**
* 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, and E[index].
* Specify one or more axes with X, Y, Z, X1, Y1, Z1, X2, Y2, Z2, Z3 and E[index].
* If no axes are given, clear all.
*
* Examples:
@ -93,51 +96,54 @@ void GcodeSuite::M912() {
hasNone = !hasX && !hasY && !hasZ && !hasE;
#if M91x_USE(X) || M91x_USE(X2)
const uint8_t xval = parser.byteval(axis_codes[X_AXIS], 10);
const int8_t xval = int8_t(parser.byteval(axis_codes[X_AXIS], 0xFF));
#if M91x_USE(X)
if (hasNone || xval == 1 || (hasX && xval == 10)) tmc_clear_otpw(stepperX, TMC_X);
if (hasNone || xval == 1 || (hasX && xval < 0)) tmc_clear_otpw(stepperX, TMC_X);
#endif
#if M91x_USE(X2)
if (hasNone || xval == 2 || (hasX && xval == 10)) tmc_clear_otpw(stepperX2, TMC_X2);
if (hasNone || xval == 2 || (hasX && xval < 0)) tmc_clear_otpw(stepperX2, TMC_X2);
#endif
#endif
#if M91x_USE(Y) || M91x_USE(Y2)
const uint8_t yval = parser.byteval(axis_codes[Y_AXIS], 10);
const int8_t yval = int8_t(parser.byteval(axis_codes[Y_AXIS], 0xFF));
#if M91x_USE(Y)
if (hasNone || yval == 1 || (hasY && yval == 10)) tmc_clear_otpw(stepperY, TMC_Y);
if (hasNone || yval == 1 || (hasY && yval < 0)) tmc_clear_otpw(stepperY, TMC_Y);
#endif
#if M91x_USE(Y2)
if (hasNone || yval == 2 || (hasY && yval == 10)) tmc_clear_otpw(stepperY2, TMC_Y2);
if (hasNone || yval == 2 || (hasY && yval < 0)) tmc_clear_otpw(stepperY2, TMC_Y2);
#endif
#endif
#if M91x_USE(Z) || M91x_USE(Z2)
const uint8_t zval = parser.byteval(axis_codes[Z_AXIS], 10);
#if M91x_USE(Z) || M91x_USE(Z2) || M91x_USE(Z3)
const int8_t zval = int8_t(parser.byteval(axis_codes[Z_AXIS], 0xFF));
#if M91x_USE(Z)
if (hasNone || zval == 1 || (hasZ && zval == 10)) tmc_clear_otpw(stepperZ, TMC_Z);
if (hasNone || zval == 1 || (hasZ && zval < 0)) tmc_clear_otpw(stepperZ, TMC_Z);
#endif
#if M91x_USE(Z2)
if (hasNone || zval == 2 || (hasZ && zval == 10)) tmc_clear_otpw(stepperZ2, TMC_Z2);
if (hasNone || zval == 2 || (hasZ && zval < 0)) tmc_clear_otpw(stepperZ2, TMC_Z2);
#endif
#if M91x_USE(Z3)
if (hasNone || zval == 3 || (hasZ && zval < 0)) tmc_clear_otpw(stepperZ3, TMC_Z3);
#endif
#endif
#if M91x_USE_E(0) || M91x_USE_E(1) || M91x_USE_E(2) || M91x_USE_E(3) || M91x_USE_E(4)
const uint8_t eval = parser.byteval(axis_codes[E_AXIS], 10);
const int8_t eval = int8_t(parser.byteval(axis_codes[E_AXIS], 0xFF));
#if M91x_USE_E(0)
if (hasNone || eval == 0 || (hasE && eval == 10)) tmc_clear_otpw(stepperE0, TMC_E0);
if (hasNone || eval == 0 || (hasE && eval < 0)) tmc_clear_otpw(stepperE0, TMC_E0);
#endif
#if M91x_USE_E(1)
if (hasNone || eval == 1 || (hasE && eval == 10)) tmc_clear_otpw(stepperE1, TMC_E1);
if (hasNone || eval == 1 || (hasE && eval < 0)) tmc_clear_otpw(stepperE1, TMC_E1);
#endif
#if M91x_USE_E(2)
if (hasNone || eval == 2 || (hasE && eval == 10)) tmc_clear_otpw(stepperE2, TMC_E2);
if (hasNone || eval == 2 || (hasE && eval < 0)) tmc_clear_otpw(stepperE2, TMC_E2);
#endif
#if M91x_USE_E(3)
if (hasNone || eval == 3 || (hasE && eval == 10)) tmc_clear_otpw(stepperE3, TMC_E3);
if (hasNone || eval == 3 || (hasE && eval < 0)) tmc_clear_otpw(stepperE3, TMC_E3);
#endif
#if M91x_USE_E(4)
if (hasNone || eval == 4 || (hasE && eval == 10)) tmc_clear_otpw(stepperE4, TMC_E4);
if (hasNone || eval == 4 || (hasE && eval < 0)) tmc_clear_otpw(stepperE4, TMC_E4);
#endif
#endif
}
@ -178,7 +184,10 @@ void GcodeSuite::M912() {
if (index < 2) TMC_SET_PWMTHRS(Z,Z);
#endif
#if AXIS_HAS_STEALTHCHOP(Z2)
if (!(index & 1)) TMC_SET_PWMTHRS(Z,Z2);
if (index == 0 || index == 2) TMC_SET_PWMTHRS(Z,Z2);
#endif
#if AXIS_HAS_STEALTHCHOP(Z3)
if (index == 0 || index == 3) TMC_SET_PWMTHRS(Z,Z3);
#endif
break;
case E_AXIS: {
@ -223,6 +232,9 @@ void GcodeSuite::M912() {
#if AXIS_HAS_STEALTHCHOP(Z2)
TMC_SAY_PWMTHRS(Z,Z2);
#endif
#if AXIS_HAS_STEALTHCHOP(Z3)
TMC_SAY_PWMTHRS(Z,Z3);
#endif
#if AXIS_HAS_STEALTHCHOP(E0)
TMC_SAY_PWMTHRS_E(0);
#endif
@ -282,7 +294,10 @@ void GcodeSuite::M912() {
if (index < 2) TMC_SET_SGT(Z);
#endif
#if AXIS_HAS_STALLGUARD(Z2)
if (!(index & 1)) TMC_SET_SGT(Z2);
if (index == 0 || index == 2) TMC_SET_SGT(Z2);
#endif
#if AXIS_HAS_STALLGUARD(Z3)
if (index == 0 || index == 3) TMC_SET_SGT(Z3);
#endif
break;
#endif
@ -313,6 +328,9 @@ void GcodeSuite::M912() {
#if AXIS_HAS_STALLGUARD(Z2)
TMC_SAY_SGT(Z2);
#endif
#if AXIS_HAS_STALLGUARD(Z3)
TMC_SAY_SGT(Z3);
#endif
#endif
}
}
@ -339,6 +357,10 @@ void GcodeSuite::M912() {
const uint16_t Z2_current_1 = stepperZ2.getCurrent();
stepperZ2.setCurrent(_rms, R_SENSE, HOLD_MULTIPLIER);
#endif
#if Z3_IS_TRINAMIC
const uint16_t Z3_current_1 = stepperZ3.getCurrent();
stepperZ3.setCurrent(_rms, R_SENSE, HOLD_MULTIPLIER);
#endif
SERIAL_ECHOPAIR("\nCalibration current: Z", _rms);
@ -352,6 +374,9 @@ void GcodeSuite::M912() {
#if AXIS_IS_TMC(Z2)
stepperZ2.setCurrent(Z2_current_1, R_SENSE, HOLD_MULTIPLIER);
#endif
#if AXIS_IS_TMC(Z3)
stepperZ3.setCurrent(Z3_current_1, R_SENSE, HOLD_MULTIPLIER);
#endif
do_blocking_move_to_z(Z_MAX_POS);
soft_endstops_enabled = true;

3
Marlin/src/inc/Conditionals_LCD.h

@ -546,4 +546,7 @@
#define HAS_RESUME_CONTINUE (ENABLED(NEWPANEL) || ENABLED(EMERGENCY_PARSER))
#define HAS_COLOR_LEDS (ENABLED(BLINKM) || ENABLED(RGB_LED) || ENABLED(RGBW_LED) || ENABLED(PCA9632) || ENABLED(NEOPIXEL_LED))
#define Z_MULTI_STEPPER_DRIVERS (ENABLED(Z_DUAL_STEPPER_DRIVERS) || ENABLED(Z_TRIPLE_STEPPER_DRIVERS))
#define Z_MULTI_ENDSTOPS (ENABLED(Z_DUAL_ENDSTOPS) || ENABLED(Z_TRIPLE_ENDSTOPS))
#endif // CONDITIONALS_LCD_H

65
Marlin/src/inc/Conditionals_post.h

@ -611,7 +611,7 @@
/**
* Z_DUAL_ENDSTOPS endstop reassignment
*/
#if ENABLED(Z_DUAL_ENDSTOPS)
#if Z_MULTI_ENDSTOPS
#if Z_HOME_DIR > 0
#if Z2_USE_ENDSTOP == _XMIN_
#define Z2_MAX_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING
@ -661,9 +661,64 @@
#endif
#endif
#if ENABLED(Z_TRIPLE_ENDSTOPS)
#if Z_HOME_DIR > 0
#if Z3_USE_ENDSTOP == _XMIN_
#define Z3_MAX_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING
#define Z3_MAX_PIN X_MIN_PIN
#elif Z3_USE_ENDSTOP == _XMAX_
#define Z3_MAX_ENDSTOP_INVERTING X_MAX_ENDSTOP_INVERTING
#define Z3_MAX_PIN X_MAX_PIN
#elif Z3_USE_ENDSTOP == _YMIN_
#define Z3_MAX_ENDSTOP_INVERTING Y_MIN_ENDSTOP_INVERTING
#define Z3_MAX_PIN Y_MIN_PIN
#elif Z3_USE_ENDSTOP == _YMAX_
#define Z3_MAX_ENDSTOP_INVERTING Y_MAX_ENDSTOP_INVERTING
#define Z3_MAX_PIN Y_MAX_PIN
#elif Z3_USE_ENDSTOP == _ZMIN_
#define Z3_MAX_ENDSTOP_INVERTING Z_MIN_ENDSTOP_INVERTING
#define Z3_MAX_PIN Z_MIN_PIN
#elif Z3_USE_ENDSTOP == _ZMAX_
#define Z3_MAX_ENDSTOP_INVERTING Z_MAX_ENDSTOP_INVERTING
#define Z3_MAX_PIN Z_MAX_PIN
#else
#define Z3_MAX_ENDSTOP_INVERTING false
#endif
#define Z3_MIN_ENDSTOP_INVERTING false
#else
#if Z3_USE_ENDSTOP == _XMIN_
#define Z3_MIN_ENDSTOP_INVERTING X_MIN_ENDSTOP_INVERTING
#define Z3_MIN_PIN X_MIN_PIN
#elif Z3_USE_ENDSTOP == _XMAX_
#define Z3_MIN_ENDSTOP_INVERTING X_MAX_ENDSTOP_INVERTING
#define Z3_MIN_PIN X_MAX_PIN
#elif Z3_USE_ENDSTOP == _YMIN_
#define Z3_MIN_ENDSTOP_INVERTING Y_MIN_ENDSTOP_INVERTING
#define Z3_MIN_PIN Y_MIN_PIN
#elif Z3_USE_ENDSTOP == _YMAX_
#define Z3_MIN_ENDSTOP_INVERTING Y_MAX_ENDSTOP_INVERTING
#define Z3_MIN_PIN Y_MAX_PIN
#elif Z3_USE_ENDSTOP == _ZMIN_
#define Z3_MIN_ENDSTOP_INVERTING Z_MIN_ENDSTOP_INVERTING
#define Z3_MIN_PIN Z_MIN_PIN
#elif Z3_USE_ENDSTOP == _ZMAX_
#define Z3_MIN_ENDSTOP_INVERTING Z_MAX_ENDSTOP_INVERTING
#define Z3_MIN_PIN Z_MAX_PIN
#else
#define Z3_MIN_ENDSTOP_INVERTING false
#endif
#define Z3_MAX_ENDSTOP_INVERTING false
#endif
#endif
// Is an endstop plug used for the Z2 endstop or the bed probe?
#define IS_Z2_OR_PROBE(A,M) ( \
(ENABLED(Z_DUAL_ENDSTOPS) && Z2_USE_ENDSTOP == _##A##M##_) \
(Z_MULTI_ENDSTOPS && Z2_USE_ENDSTOP == _##A##M##_) \
|| (ENABLED(Z_MIN_PROBE_ENDSTOP) && Z_MIN_PROBE_PIN == A##_##M##_PIN ) )
// Is an endstop plug used for the Z3 endstop or the bed probe?
#define IS_Z3_OR_PROBE(A,M) ( \
(ENABLED(Z_TRIPLE_ENDSTOPS) && Z3_USE_ENDSTOP == _##A##M##_) \
|| (ENABLED(Z_MIN_PROBE_ENDSTOP) && Z_MIN_PROBE_PIN == A##_##M##_PIN ) )
/**
@ -749,6 +804,10 @@
#define HAS_Z2_STEP (PIN_EXISTS(Z2_STEP))
#define HAS_Z2_MICROSTEPS (PIN_EXISTS(Z2_MS1))
#define HAS_Z3_ENABLE (PIN_EXISTS(Z3_ENABLE))
#define HAS_Z3_DIR (PIN_EXISTS(Z3_DIR))
#define HAS_Z3_STEP (PIN_EXISTS(Z3_STEP))
// Extruder steppers and solenoids
#define HAS_E0_ENABLE (PIN_EXISTS(E0_ENABLE))
#define HAS_E0_DIR (PIN_EXISTS(E0_DIR))
@ -810,6 +869,8 @@
#define HAS_Y2_MAX (PIN_EXISTS(Y2_MAX))
#define HAS_Z2_MIN (PIN_EXISTS(Z2_MIN))
#define HAS_Z2_MAX (PIN_EXISTS(Z2_MAX))
#define HAS_Z3_MIN (PIN_EXISTS(Z3_MIN))
#define HAS_Z3_MAX (PIN_EXISTS(Z3_MAX))
#define HAS_Z_MIN_PROBE_PIN (PIN_EXISTS(Z_MIN_PROBE))
// ADC Temp Sensors (Thermistor or Thermocouple with amplifier ADC interface)

82
Marlin/src/inc/SanityCheck.h

@ -272,19 +272,19 @@
#error "HAVE_TMC2130 is now [AXIS]_DRIVER_TYPE TMC2130. Please update your Configuration.h."
#elif defined(HAVE_L6470DRIVER)
#error "HAVE_L6470DRIVER is now [AXIS]_DRIVER_TYPE L6470. Please update your Configuration.h."
#elif defined(X_IS_TMC) || defined(X2_IS_TMC) || defined(Y_IS_TMC) || defined(Y2_IS_TMC) || defined(Z_IS_TMC) || defined(Z2_IS_TMC) \
#elif defined(X_IS_TMC) || defined(X2_IS_TMC) || defined(Y_IS_TMC) || defined(Y2_IS_TMC) || defined(Z_IS_TMC) || defined(Z2_IS_TMC) || defined(Z3_IS_TMC) \
|| defined(E0_IS_TMC) || defined(E1_IS_TMC) || defined(E2_IS_TMC) || defined(E3_IS_TMC) || defined(E4_IS_TMC)
#error "[AXIS]_IS_TMC is now [AXIS]_DRIVER_TYPE TMC26X. Please update your Configuration.h."
#elif defined(X_IS_TMC26X) || defined(X2_IS_TMC26X) || defined(Y_IS_TMC26X) || defined(Y2_IS_TMC26X) || defined(Z_IS_TMC26X) || defined(Z2_IS_TMC26X) \
#elif defined(X_IS_TMC26X) || defined(X2_IS_TMC26X) || defined(Y_IS_TMC26X) || defined(Y2_IS_TMC26X) || defined(Z_IS_TMC26X) || defined(Z2_IS_TMC26X) || defined(Z3_IS_TMC26X) \
|| defined(E0_IS_TMC26X) || defined(E1_IS_TMC26X) || defined(E2_IS_TMC26X) || defined(E3_IS_TMC26X) || defined(E4_IS_TMC26X)
#error "[AXIS]_IS_TMC26X is now [AXIS]_DRIVER_TYPE TMC26X. Please update your Configuration.h."
#elif defined(X_IS_TMC2130) || defined(X2_IS_TMC2130) || defined(Y_IS_TMC2130) || defined(Y2_IS_TMC2130) || defined(Z_IS_TMC2130) || defined(Z2_IS_TMC2130) \
#elif defined(X_IS_TMC2130) || defined(X2_IS_TMC2130) || defined(Y_IS_TMC2130) || defined(Y2_IS_TMC2130) || defined(Z_IS_TMC2130) || defined(Z2_IS_TMC2130) || defined(Z3_IS_TMC2130) \
|| defined(E0_IS_TMC2130) || defined(E1_IS_TMC2130) || defined(E2_IS_TMC2130) || defined(E3_IS_TMC2130) || defined(E4_IS_TMC2130)
#error "[AXIS]_IS_TMC2130 is now [AXIS]_DRIVER_TYPE TMC2130. Please update your Configuration.h."
#elif defined(X_IS_TMC2208) || defined(X2_IS_TMC2208) || defined(Y_IS_TMC2208) || defined(Y2_IS_TMC2208) || defined(Z_IS_TMC2208) || defined(Z2_IS_TMC2208) \
#elif defined(X_IS_TMC2208) || defined(X2_IS_TMC2208) || defined(Y_IS_TMC2208) || defined(Y2_IS_TMC2208) || defined(Z_IS_TMC2208) || defined(Z2_IS_TMC2208) || defined(Z3_IS_TMC2208) \
|| defined(E0_IS_TMC2208) || defined(E1_IS_TMC2208) || defined(E2_IS_TMC2208) || defined(E3_IS_TMC2208) || defined(E4_IS_TMC2208)
#error "[AXIS]_IS_TMC2208 is now [AXIS]_DRIVER_TYPE TMC2208. Please update your Configuration.h."
#elif defined(X_IS_L6470) || defined(X2_IS_L6470) || defined(Y_IS_L6470) || defined(Y2_IS_L6470) || defined(Z_IS_L6470) || defined(Z2_IS_L6470) \
#elif defined(X_IS_L6470) || defined(X2_IS_L6470) || defined(Y_IS_L6470) || defined(Y2_IS_L6470) || defined(Z_IS_L6470) || defined(Z2_IS_L6470) || defined(Z3_IS_L6470) \
|| defined(E0_IS_L6470) || defined(E1_IS_L6470) || defined(E2_IS_L6470) || defined(E3_IS_L6470) || defined(E4_IS_L6470)
#error "[AXIS]_IS_L6470 is now [AXIS]_DRIVER_TYPE L6470. Please update your Configuration.h."
#elif defined(AUTOMATIC_CURRENT_CONTROL)
@ -365,16 +365,22 @@
#endif
/**
* Dual Stepper Drivers
* Dual / Triple Stepper Drivers
*/
#if ENABLED(X_DUAL_STEPPER_DRIVERS) && ENABLED(DUAL_X_CARRIAGE)
#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 ENABLED(X_DUAL_STEPPER_DRIVERS) && !(HAS_X2_ENABLE && HAS_X2_STEP && HAS_X2_DIR)
#error "X_DUAL_STEPPER_DRIVERS requires X2 pins (and an extra E plug)."
#elif ENABLED(Y_DUAL_STEPPER_DRIVERS) && (!HAS_Y2_ENABLE || !HAS_Y2_STEP || !HAS_Y2_DIR)
#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) && (!HAS_Z2_ENABLE || !HAS_Z2_STEP || !HAS_Z2_DIR)
#error "Z_DUAL_STEPPER_DRIVERS requires Z2 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
#elif ENABLED(Z_TRIPLE_STEPPER_DRIVERS) && !(HAS_Z2_ENABLE && HAS_Z2_STEP && HAS_Z2_DIR && HAS_Z3_ENABLE && HAS_Z3_STEP && HAS_Z3_DIR)
#error "Z_TRIPLE_STEPPER_DRIVERS requires Z3 pins (and two extra E plugs)."
#endif
/**
@ -1138,7 +1144,7 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE && Y_MAX_LENGTH >= Y_BED_SIZE,
#error "DUAL_X_CARRIAGE requires 2 (or more) extruders."
#elif CORE_IS_XY || CORE_IS_XZ
#error "DUAL_X_CARRIAGE cannot be used with COREXY, COREYX, COREXZ, or COREZX."
#elif !HAS_X2_ENABLE || !HAS_X2_STEP || !HAS_X2_DIR
#elif !(HAS_X2_ENABLE && HAS_X2_STEP && HAS_X2_DIR)
#error "DUAL_X_CARRIAGE requires X2 stepper pins to be defined."
#elif !HAS_X_MAX
#error "DUAL_X_CARRIAGE requires USE_XMAX_PLUG and an X Max Endstop."
@ -1301,23 +1307,24 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE && Y_MAX_LENGTH >= Y_BED_SIZE,
*/
#if DISABLED(MK2_MULTIPLEXER) // MK2_MULTIPLEXER uses E0 stepper only
#if E_STEPPERS > 4
#if !PIN_EXISTS(E4_STEP) || !PIN_EXISTS(E4_DIR) || !PIN_EXISTS(E4_ENABLE)
#if !(PIN_EXISTS(E4_STEP) && PIN_EXISTS(E4_DIR) && PIN_EXISTS(E4_ENABLE))
#error "E4_STEP_PIN, E4_DIR_PIN, or E4_ENABLE_PIN not defined for this board."
#endif
#elif E_STEPPERS > 3
#if !PIN_EXISTS(E3_STEP) || !PIN_EXISTS(E3_DIR) || !PIN_EXISTS(E3_ENABLE)
#if !(PIN_EXISTS(E3_STEP) && PIN_EXISTS(E3_DIR) && PIN_EXISTS(E3_ENABLE))
#error "E3_STEP_PIN, E3_DIR_PIN, or E3_ENABLE_PIN not defined for this board."
#endif
#elif E_STEPPERS > 2
#if !PIN_EXISTS(E2_STEP) || !PIN_EXISTS(E2_DIR) || !PIN_EXISTS(E2_ENABLE)
#if !(PIN_EXISTS(E2_STEP) && PIN_EXISTS(E2_DIR) && PIN_EXISTS(E2_ENABLE))
#error "E2_STEP_PIN, E2_DIR_PIN, or E2_ENABLE_PIN not defined for this board."
#endif
#elif E_STEPPERS > 1
#if !PIN_EXISTS(E1_STEP) || !PIN_EXISTS(E1_DIR) || !PIN_EXISTS(E1_ENABLE)
#if !(PIN_EXISTS(E1_STEP) && PIN_EXISTS(E1_DIR) && PIN_EXISTS(E1_ENABLE))
#error "E1_STEP_PIN, E1_DIR_PIN, or E1_ENABLE_PIN not defined for this board."
#endif
#endif
#endif
/**
* Endstop Tests
*/
@ -1418,6 +1425,46 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE && Y_MAX_LENGTH >= Y_BED_SIZE,
#error "Z_DUAL_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
#if !Z3_USE_ENDSTOP
#error "You must set Z3_USE_ENDSTOP with Z_TRIPLE_ENDSTOPS."
#elif Z3_USE_ENDSTOP == _XMIN_ && DISABLED(USE_XMIN_PLUG)
#error "USE_XMIN_PLUG is required when Z3_USE_ENDSTOP is _XMIN_."
#elif Z3_USE_ENDSTOP == _XMAX_ && DISABLED(USE_XMAX_PLUG)
#error "USE_XMAX_PLUG is required when Z3_USE_ENDSTOP is _XMAX_."
#elif Z3_USE_ENDSTOP == _YMIN_ && DISABLED(USE_YMIN_PLUG)
#error "USE_YMIN_PLUG is required when Z3_USE_ENDSTOP is _YMIN_."
#elif Z3_USE_ENDSTOP == _YMAX_ && DISABLED(USE_YMAX_PLUG)
#error "USE_YMAX_PLUG is required when Z3_USE_ENDSTOP is _YMAX_."
#elif Z3_USE_ENDSTOP == _ZMIN_ && DISABLED(USE_ZMIN_PLUG)
#error "USE_ZMIN_PLUG is required when Z3_USE_ENDSTOP is _ZMIN_."
#elif Z3_USE_ENDSTOP == _ZMAX_ && DISABLED(USE_ZMAX_PLUG)
#error "USE_ZMAX_PLUG is required when Z3_USE_ENDSTOP is _ZMAX_."
#elif !HAS_Z3_MIN && !HAS_Z3_MAX
#error "Z3_USE_ENDSTOP has been assigned to a nonexistent endstop!"
#elif ENABLED(DELTA)
#error "Z_TRIPLE_ENDSTOPS is not compatible with DELTA."
#endif
#endif
/**
* emergency-command parser
@ -1566,6 +1613,8 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE && Y_MAX_LENGTH >= Y_BED_SIZE,
#error "Z_CS_PIN is required for TMC2130. Define Z_CS_PIN in Configuration_adv.h."
#elif AXIS_DRIVER_TYPE(Z2, TMC2130) && !PIN_EXISTS(Z2_CS)
#error "Z2_CS_PIN is required for TMC2130. Define Z2_CS_PIN in Configuration_adv.h."
#elif AXIS_DRIVER_TYPE(Z3, TMC2130) && !PIN_EXISTS(Z3_CS)
#error "Z3_CS_PIN is required for TMC2130. Define Z3_CS_PIN in Configuration_adv.h."
#elif AXIS_DRIVER_TYPE(E0, TMC2130) && !PIN_EXISTS(E0_CS)
#error "E0_CS_PIN is required for TMC2130. Define E0_CS_PIN in Configuration_adv.h."
#elif AXIS_DRIVER_TYPE(E1, TMC2130) && !PIN_EXISTS(E1_CS)
@ -1588,6 +1637,7 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE && Y_MAX_LENGTH >= Y_BED_SIZE,
|| defined(Y2_HARDWARE_SERIAL) \
|| defined(Z_HARDWARE_SERIAL ) \
|| defined(Z2_HARDWARE_SERIAL) \
|| defined(Z3_HARDWARE_SERIAL) \
|| defined(E0_HARDWARE_SERIAL) \
|| defined(E1_HARDWARE_SERIAL) \
|| defined(E2_HARDWARE_SERIAL) \
@ -1650,7 +1700,7 @@ static_assert(X_MAX_LENGTH >= X_BED_SIZE && Y_MAX_LENGTH >= Y_BED_SIZE,
#if ENABLED(HYBRID_THRESHOLD) && DISABLED(STEALTHCHOP)
#error "Enable STEALTHCHOP to use HYBRID_THRESHOLD."
#endif
#if ENABLED(TMC_Z_CALIBRATION) && !AXIS_IS_TMC(Z) && !AXIS_IS_TMC(Z2)
#if ENABLED(TMC_Z_CALIBRATION) && !AXIS_IS_TMC(Z) && !AXIS_IS_TMC(Z2) && !AXIS_IS_TMC(Z3)
#error "TMC_Z_CALIBRATION requires at least one TMC driver on Z axis"
#endif

126
Marlin/src/module/configuration_store.cpp

@ -194,10 +194,13 @@ typedef struct SettingsDataStruct {
delta_segments_per_second, // M665 S
delta_calibration_radius, // M665 B
delta_tower_angle_trim[ABC]; // M665 XYZ
#elif ENABLED(X_DUAL_ENDSTOPS) || ENABLED(Y_DUAL_ENDSTOPS) || ENABLED(Z_DUAL_ENDSTOPS)
float x_endstop_adj, // M666 X
y_endstop_adj, // M666 Y
z_endstop_adj; // M666 Z
#elif ENABLED(X_DUAL_ENDSTOPS) || ENABLED(Y_DUAL_ENDSTOPS) || Z_MULTI_ENDSTOPS
float x2_endstop_adj, // M666 X
y2_endstop_adj, // M666 Y
z2_endstop_adj; // M666 Z
#if ENABLED(Z_TRIPLE_ENDSTOPS)
float z3_endstop_adj; // M666 Z
#endif
#endif
//
@ -246,9 +249,9 @@ typedef struct SettingsDataStruct {
//
// HAS_TRINAMIC
//
#define TMC_AXES (MAX_EXTRUDERS + 6)
uint16_t tmc_stepper_current[TMC_AXES]; // M906 X Y Z X2 Y2 Z2 E0 E1 E2 E3 E4
uint32_t tmc_hybrid_threshold[TMC_AXES]; // M913 X Y Z X2 Y2 Z2 E0 E1 E2 E3 E4
#define TMC_AXES (MAX_EXTRUDERS + 7)
uint16_t tmc_stepper_current[TMC_AXES]; // M906 X Y Z X2 Y2 Z2 Z3 E0 E1 E2 E3 E4
uint32_t tmc_hybrid_threshold[TMC_AXES]; // M913 X Y Z X2 Y2 Z2 Z3 E0 E1 E2 E3 E4
int16_t tmc_sgt[XYZ]; // M914 X Y Z
//
@ -574,26 +577,32 @@ void MarlinSettings::postprocess() {
EEPROM_WRITE(delta_calibration_radius); // 1 float
EEPROM_WRITE(delta_tower_angle_trim); // 3 floats
#elif ENABLED(X_DUAL_ENDSTOPS) || ENABLED(Y_DUAL_ENDSTOPS) || ENABLED(Z_DUAL_ENDSTOPS)
#elif ENABLED(X_DUAL_ENDSTOPS) || ENABLED(Y_DUAL_ENDSTOPS) || Z_MULTI_ENDSTOPS
_FIELD_TEST(x_endstop_adj);
_FIELD_TEST(x2_endstop_adj);
// Write dual endstops in X, Y, Z order. Unused = 0.0
dummy = 0;
#if ENABLED(X_DUAL_ENDSTOPS)
EEPROM_WRITE(endstops.x_endstop_adj); // 1 float
EEPROM_WRITE(endstops.x2_endstop_adj); // 1 float
#else
EEPROM_WRITE(dummy);
#endif
#if ENABLED(Y_DUAL_ENDSTOPS)
EEPROM_WRITE(endstops.y_endstop_adj); // 1 float
EEPROM_WRITE(endstops.y2_endstop_adj); // 1 float
#else
EEPROM_WRITE(dummy);
#endif
#if ENABLED(Z_DUAL_ENDSTOPS)
EEPROM_WRITE(endstops.z_endstop_adj); // 1 float
#if Z_MULTI_ENDSTOPS
EEPROM_WRITE(endstops.z2_endstop_adj); // 1 float
#else
EEPROM_WRITE(dummy);
#endif
#if ENABLED(Z_TRIPLE_ENDSTOPS)
EEPROM_WRITE(endstops.z3_endstop_adj); // 1 float
#else
EEPROM_WRITE(dummy);
#endif
@ -740,6 +749,11 @@ void MarlinSettings::postprocess() {
#else
0,
#endif
#if AXIS_IS_TMC(Z3)
stepperZ3.getCurrent(),
#else
0,
#endif
#if AXIS_IS_TMC(E0)
stepperE0.getCurrent(),
#else
@ -809,6 +823,11 @@ void MarlinSettings::postprocess() {
#else
Z2_HYBRID_THRESHOLD,
#endif
#if AXIS_HAS_STEALTHCHOP(Z3)
TMC_GET_PWMTHRS(Z, Z3),
#else
Z3_HYBRID_THRESHOLD,
#endif
#if AXIS_HAS_STEALTHCHOP(E0)
TMC_GET_PWMTHRS(E, E0),
#else
@ -836,7 +855,7 @@ void MarlinSettings::postprocess() {
#endif
#else
100, 100, 3, // X, Y, Z
100, 100, 3, // X2, Y2, Z2
100, 100, 3, 3, // X2, Y2, Z2, Z3
30, 30, 30, 30, 30 // E0, E1, E2, E3, E4
#endif
};
@ -1187,22 +1206,27 @@ void MarlinSettings::postprocess() {
EEPROM_READ(delta_calibration_radius); // 1 float
EEPROM_READ(delta_tower_angle_trim); // 3 floats
#elif ENABLED(X_DUAL_ENDSTOPS) || ENABLED(Y_DUAL_ENDSTOPS) || ENABLED(Z_DUAL_ENDSTOPS)
#elif ENABLED(X_DUAL_ENDSTOPS) || ENABLED(Y_DUAL_ENDSTOPS) || Z_MULTI_ENDSTOPS
_FIELD_TEST(x_endstop_adj);
_FIELD_TEST(x2_endstop_adj);
#if ENABLED(X_DUAL_ENDSTOPS)
EEPROM_READ(endstops.x_endstop_adj); // 1 float
EEPROM_READ(endstops.x2_endstop_adj); // 1 float
#else
EEPROM_READ(dummy);
#endif
#if ENABLED(Y_DUAL_ENDSTOPS)
EEPROM_READ(endstops.y_endstop_adj); // 1 float
EEPROM_READ(endstops.y2_endstop_adj); // 1 float
#else
EEPROM_READ(dummy);
#endif
#if Z_MULTI_ENDSTOPS
EEPROM_READ(endstops.z2_endstop_adj); // 1 float
#else
EEPROM_READ(dummy);
#endif
#if ENABLED(Z_DUAL_ENDSTOPS)
EEPROM_READ(endstops.z_endstop_adj); // 1 float
#if ENABLED(Z_TRIPLE_ENDSTOPS)
EEPROM_READ(endstops.z3_endstop_adj); // 1 float
#else
EEPROM_READ(dummy);
#endif
@ -1365,6 +1389,9 @@ void MarlinSettings::postprocess() {
#if AXIS_IS_TMC(Z2)
SET_CURR(Z2);
#endif
#if AXIS_IS_TMC(Z3)
SET_CURR(Z3);
#endif
#if AXIS_IS_TMC(E0)
SET_CURR(E0);
#endif
@ -1409,6 +1436,9 @@ void MarlinSettings::postprocess() {
#if AXIS_HAS_STEALTHCHOP(Z2)
TMC_SET_PWMTHRS(Z, Z2);
#endif
#if AXIS_HAS_STEALTHCHOP(Z3)
TMC_SET_PWMTHRS(Z, Z3);
#endif
#if AXIS_HAS_STEALTHCHOP(E0)
TMC_SET_PWMTHRS(E, E0);
#endif
@ -1434,7 +1464,7 @@ void MarlinSettings::postprocess() {
* TMC2130 Sensorless homing threshold.
* X and X2 use the same value
* Y and Y2 use the same value
* Z and Z2 use the same value
* Z, Z2 and Z3 use the same value
*/
int16_t tmc_sgt[XYZ];
EEPROM_READ(tmc_sgt);
@ -1463,6 +1493,9 @@ void MarlinSettings::postprocess() {
#if AXIS_HAS_STALLGUARD(Z2)
stepperZ2.sgt(tmc_sgt[2]);
#endif
#if AXIS_HAS_STALLGUARD(Z3)
stepperZ3.sgt(tmc_sgt[2]);
#endif
#endif
}
#endif
@ -1860,10 +1893,10 @@ void MarlinSettings::reset(PORTARG_SOLO) {
delta_calibration_radius = DELTA_CALIBRATION_RADIUS;
COPY(delta_tower_angle_trim, dta);
#elif ENABLED(X_DUAL_ENDSTOPS) || ENABLED(Y_DUAL_ENDSTOPS) || ENABLED(Z_DUAL_ENDSTOPS)
#elif ENABLED(X_DUAL_ENDSTOPS) || ENABLED(Y_DUAL_ENDSTOPS) || Z_MULTI_ENDSTOPS
#if ENABLED(X_DUAL_ENDSTOPS)
endstops.x_endstop_adj = (
endstops.x2_endstop_adj = (
#ifdef X_DUAL_ENDSTOPS_ADJUSTMENT
X_DUAL_ENDSTOPS_ADJUSTMENT
#else
@ -1872,7 +1905,7 @@ void MarlinSettings::reset(PORTARG_SOLO) {
);
#endif
#if ENABLED(Y_DUAL_ENDSTOPS)
endstops.y_endstop_adj = (
endstops.y2_endstop_adj = (
#ifdef Y_DUAL_ENDSTOPS_ADJUSTMENT
Y_DUAL_ENDSTOPS_ADJUSTMENT
#else
@ -1881,13 +1914,28 @@ void MarlinSettings::reset(PORTARG_SOLO) {
);
#endif
#if ENABLED(Z_DUAL_ENDSTOPS)
endstops.z_endstop_adj = (
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
@ -2391,13 +2439,17 @@ void MarlinSettings::reset(PORTARG_SOLO) {
CONFIG_ECHO_START;
SERIAL_ECHOPGM_P(port, " M666");
#if ENABLED(X_DUAL_ENDSTOPS)
SERIAL_ECHOPAIR_P(port, " X", LINEAR_UNIT(endstops.x_endstop_adj));
SERIAL_ECHOPAIR_P(port, " X", LINEAR_UNIT(endstops.x2_endstop_adj));
#endif
#if ENABLED(Y_DUAL_ENDSTOPS)
SERIAL_ECHOPAIR_P(port, " Y", LINEAR_UNIT(endstops.y_endstop_adj));
SERIAL_ECHOPAIR_P(port, " Y", LINEAR_UNIT(endstops.y2_endstop_adj));
#endif
#if ENABLED(Z_DUAL_ENDSTOPS)
SERIAL_ECHOPAIR_P(port, " Z", LINEAR_UNIT(endstops.z_endstop_adj));
#if ENABLED(Z_TRIPLE_ENDSTOPS)
SERIAL_ECHOLNPAIR_P(port, "S1 Z", LINEAR_UNIT(endstops.z2_endstop_adj));
CONFIG_ECHO_START;
SERIAL_ECHOPAIR_P(port, " M666 S2 Z", LINEAR_UNIT(endstops.z3_endstop_adj));
#elif ENABLED(Z_DUAL_ENDSTOPS)
SERIAL_ECHOPAIR_P(port, " Z", LINEAR_UNIT(endstops.z2_endstop_adj));
#endif
SERIAL_EOL_P(port);
@ -2582,6 +2634,10 @@ void MarlinSettings::reset(PORTARG_SOLO) {
#if AXIS_IS_TMC(X2) || AXIS_IS_TMC(Y2) || AXIS_IS_TMC(Z2)
SERIAL_EOL_P(port);
#endif
#if AXIS_IS_TMC(Z3)
say_M906(PORTVAR_SOLO);
SERIAL_ECHOLNPAIR_P(port, " I2 Z", stepperZ3.getCurrent());
#endif
#if AXIS_IS_TMC(E0)
say_M906(PORTVAR_SOLO);
SERIAL_ECHOLNPAIR_P(port, " T0 E", stepperE0.getCurrent());
@ -2644,6 +2700,11 @@ void MarlinSettings::reset(PORTARG_SOLO) {
#if AXIS_IS_TMC(X2) || AXIS_IS_TMC(Y2) || AXIS_IS_TMC(Z2)
SERIAL_EOL_P(port);
#endif
#if AXIS_IS_TMC(Z3)
say_M913(PORTVAR_SOLO);
SERIAL_ECHOPGM_P(port, " I2");
SERIAL_ECHOLNPAIR_P(port, " Z", TMC_GET_PWMTHRS(Z, Z3));
#endif
#if AXIS_IS_TMC(E0)
say_M913(PORTVAR_SOLO);
SERIAL_ECHOLNPAIR_P(port, " T0 E", TMC_GET_PWMTHRS(E, E0));
@ -2693,6 +2754,7 @@ void MarlinSettings::reset(PORTARG_SOLO) {
#define HAS_X2_SENSORLESS (defined(X_HOMING_SENSITIVITY) && AXIS_HAS_STALLGUARD(X2))
#define HAS_Y2_SENSORLESS (defined(Y_HOMING_SENSITIVITY) && AXIS_HAS_STALLGUARD(Y2))
#define HAS_Z2_SENSORLESS (defined(Z_HOMING_SENSITIVITY) && AXIS_HAS_STALLGUARD(Z2))
#define HAS_Z3_SENSORLESS (defined(Z_HOMING_SENSITIVITY) && AXIS_HAS_STALLGUARD(Z3))
#if HAS_X2_SENSORLESS || HAS_Y2_SENSORLESS || HAS_Z2_SENSORLESS
say_M914(PORTVAR_SOLO);
SERIAL_ECHOPGM_P(port, " I1");
@ -2708,6 +2770,12 @@ void MarlinSettings::reset(PORTARG_SOLO) {
SERIAL_EOL_P(port);
#endif
#if HAS_Z3_SENSORLESS
say_M914(PORTVAR_SOLO);
SERIAL_ECHOPGM_P(port, " I2");
SERIAL_ECHOLNPAIR_P(port, " Z", stepperZ3.sgt());
#endif
#endif // SENSORLESS_HOMING
#endif // HAS_TRINAMIC

87
Marlin/src/module/endstops.cpp

@ -56,13 +56,16 @@ Endstops::esbits_t Endstops::live_state = 0;
// Initialized by settings.load()
#if ENABLED(X_DUAL_ENDSTOPS)
float Endstops::x_endstop_adj;
float Endstops::x2_endstop_adj;
#endif
#if ENABLED(Y_DUAL_ENDSTOPS)
float Endstops::y_endstop_adj;
float Endstops::y2_endstop_adj;
#endif
#if ENABLED(Z_DUAL_ENDSTOPS)
float Endstops::z_endstop_adj;
#if Z_MULTI_ENDSTOPS
float Endstops::z2_endstop_adj;
#endif
#if ENABLED(Z_TRIPLE_ENDSTOPS)
float Endstops::z3_endstop_adj;
#endif
/**
@ -131,6 +134,16 @@ void Endstops::init() {
#endif
#endif
#if HAS_Z3_MIN
#if ENABLED(ENDSTOPPULLUP_ZMIN)
SET_INPUT_PULLUP(Z3_MIN_PIN);
#elif ENABLED(ENDSTOPPULLDOWN_ZMIN)
SET_INPUT_PULLDOWN(Z3_MIN_PIN);
#else
SET_INPUT(Z3_MIN_PIN);
#endif
#endif
#if HAS_X_MAX
#if ENABLED(ENDSTOPPULLUP_XMAX)
SET_INPUT_PULLUP(X_MAX_PIN);
@ -191,6 +204,16 @@ void Endstops::init() {
#endif
#endif
#if HAS_Z3_MAX
#if ENABLED(ENDSTOPPULLUP_ZMAX)
SET_INPUT_PULLUP(Z3_MAX_PIN);
#elif ENABLED(ENDSTOPPULLDOWN_ZMAX)
SET_INPUT_PULLDOWN(Z3_MAX_PIN);
#else
SET_INPUT(Z3_MAX_PIN);
#endif
#endif
#if ENABLED(Z_MIN_PROBE_ENDSTOP)
#if ENABLED(ENDSTOPPULLUP_ZMIN_PROBE)
SET_INPUT_PULLUP(Z_MIN_PROBE_PIN);
@ -371,12 +394,18 @@ void Endstops::M119() {
#if HAS_Z2_MIN
ES_REPORT(Z2_MIN);
#endif
#if HAS_Z3_MIN
ES_REPORT(Z3_MIN);
#endif
#if HAS_Z_MAX
ES_REPORT(Z_MAX);
#endif
#if HAS_Z2_MAX
ES_REPORT(Z2_MAX);
#endif
#if HAS_Z3_MAX
ES_REPORT(Z3_MAX);
#endif
#if ENABLED(Z_MIN_PROBE_ENDSTOP)
SERIAL_PROTOCOLPGM(MSG_Z_PROBE);
SERIAL_PROTOCOLLN(((READ(Z_MIN_PROBE_PIN)^Z_MIN_PROBE_ENDSTOP_INVERTING) ? MSG_ENDSTOP_HIT : MSG_ENDSTOP_OPEN));
@ -492,13 +521,20 @@ void Endstops::update() {
#endif
#if HAS_Z_MIN
#if ENABLED(Z_DUAL_ENDSTOPS)
#if Z_MULTI_ENDSTOPS
UPDATE_ENDSTOP_BIT(Z, MIN);
#if HAS_Z2_MIN
UPDATE_ENDSTOP_BIT(Z2, MIN);
#else
COPY_LIVE_STATE(Z_MIN, Z2_MIN);
#endif
#if ENABLED(Z_TRIPLE_ENDSTOPS)
#if HAS_Z3_MIN
UPDATE_ENDSTOP_BIT(Z3, MIN);
#else
COPY_LIVE_STATE(Z_MIN, Z3_MIN);
#endif
#endif
#elif ENABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN)
UPDATE_ENDSTOP_BIT(Z, MIN);
#elif Z_HOME_DIR < 0
@ -513,13 +549,20 @@ void Endstops::update() {
#if HAS_Z_MAX
// Check both Z dual endstops
#if ENABLED(Z_DUAL_ENDSTOPS)
#if Z_MULTI_ENDSTOPS
UPDATE_ENDSTOP_BIT(Z, MAX);
#if HAS_Z2_MAX
UPDATE_ENDSTOP_BIT(Z2, MAX);
#else
COPY_LIVE_STATE(Z_MAX, Z2_MAX);
#endif
#if ENABLED(Z_TRIPLE_ENDSTOPS)
#if HAS_Z3_MAX
UPDATE_ENDSTOP_BIT(Z3, MAX);
#else
COPY_LIVE_STATE(Z_MAX, Z3_MAX);
#endif
#endif
#elif DISABLED(Z_MIN_PROBE_ENDSTOP) || Z_MAX_PIN != Z_MIN_PROBE_PIN
// If this pin isn't the bed probe it's the Z endstop
UPDATE_ENDSTOP_BIT(Z, MAX);
@ -569,7 +612,17 @@ void Endstops::update() {
if (dual_hit) { \
_ENDSTOP_HIT(AXIS1, MINMAX); \
/* if not performing home or if both endstops were trigged during homing... */ \
if (!stepper.homing_dual_axis || dual_hit == 0b11) \
if (!stepper.separate_multi_axis || dual_hit == 0b11) \
planner.endstop_triggered(_AXIS(AXIS1)); \
} \
}while(0)
#define PROCESS_TRIPLE_ENDSTOP(AXIS1, AXIS2, AXIS3, MINMAX) do { \
const byte triple_hit = TEST_ENDSTOP(_ENDSTOP(AXIS1, MINMAX)) | (TEST_ENDSTOP(_ENDSTOP(AXIS2, MINMAX)) << 1) | (TEST_ENDSTOP(_ENDSTOP(AXIS3, MINMAX)) << 2); \
if (triple_hit) { \
_ENDSTOP_HIT(AXIS1, MINMAX); \
/* if not performing home or if both endstops were trigged during homing... */ \
if (!stepper.separate_multi_axis || triple_hit == 0x7) \
planner.endstop_triggered(_AXIS(AXIS1)); \
} \
}while(0)
@ -632,7 +685,9 @@ void Endstops::update() {
if (stepper.axis_is_moving(Z_AXIS)) {
if (stepper.motor_direction(Z_AXIS_HEAD)) { // Z -direction. Gantry down, bed up.
#if HAS_Z_MIN
#if ENABLED(Z_DUAL_ENDSTOPS)
#if ENABLED(Z_TRIPLE_ENDSTOPS)
PROCESS_TRIPLE_ENDSTOP(Z, Z2, Z3, MIN);
#elif ENABLED(Z_DUAL_ENDSTOPS)
PROCESS_DUAL_ENDSTOP(Z, Z2, MIN);
#else
#if ENABLED(Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN)
@ -652,7 +707,9 @@ void Endstops::update() {
}
else { // Z +direction. Gantry up, bed down.
#if HAS_Z_MAX
#if ENABLED(Z_DUAL_ENDSTOPS)
#if ENABLED(Z_TRIPLE_ENDSTOPS)
PROCESS_TRIPLE_ENDSTOP(Z, Z2, Z3, MAX);
#elif ENABLED(Z_DUAL_ENDSTOPS)
PROCESS_DUAL_ENDSTOP(Z, Z2, MAX);
#elif DISABLED(Z_MIN_PROBE_ENDSTOP) || Z_MAX_PIN != Z_MIN_PROBE_PIN
// If this pin is not hijacked for the bed probe
@ -723,6 +780,12 @@ void Endstops::update() {
#if HAS_Z2_MAX
if (READ(Z2_MAX_PIN)) SBI(live_state_local, Z2_MAX);
#endif
#if HAS_Z3_MIN
if (READ(Z3_MIN_PIN)) SBI(live_state_local, Z3_MIN);
#endif
#if HAS_Z3_MAX
if (READ(Z3_MAX_PIN)) SBI(live_state_local, Z3_MAX);
#endif
uint16_t endstop_change = live_state_local ^ old_live_state_local;
@ -766,6 +829,12 @@ void Endstops::update() {
#if HAS_Z2_MAX
if (TEST(endstop_change, Z2_MAX)) SERIAL_PROTOCOLPAIR(" Z2_MAX:", TEST(live_state_local, Z2_MAX));
#endif
#if HAS_Z3_MIN
if (TEST(endstop_change, Z3_MIN)) SERIAL_PROTOCOLPAIR(" Z3_MIN:", TEST(live_state_local, Z3_MIN));
#endif
#if HAS_Z3_MAX
if (TEST(endstop_change, Z3_MAX)) SERIAL_PROTOCOLPAIR(" Z3_MAX:", TEST(live_state_local, Z3_MAX));
#endif
SERIAL_PROTOCOLPGM("\n\n");
analogWrite(LED_PIN, local_LED_status);
local_LED_status ^= 255;

17
Marlin/src/module/endstops.h

@ -45,7 +45,9 @@ enum EndstopEnum : char {
Y2_MIN,
Y2_MAX,
Z2_MIN,
Z2_MAX
Z2_MAX,
Z3_MIN,
Z3_MAX
};
class Endstops {
@ -54,16 +56,19 @@ class Endstops {
static bool enabled, enabled_globally;
#if ENABLED(X_DUAL_ENDSTOPS) || ENABLED(Y_DUAL_ENDSTOPS) || ENABLED(Z_DUAL_ENDSTOPS)
#if ENABLED(X_DUAL_ENDSTOPS) || ENABLED(Y_DUAL_ENDSTOPS) || Z_MULTI_ENDSTOPS
typedef uint16_t esbits_t;
#if ENABLED(X_DUAL_ENDSTOPS)
static float x_endstop_adj;
static float x2_endstop_adj;
#endif
#if ENABLED(Y_DUAL_ENDSTOPS)
static float y_endstop_adj;
static float y2_endstop_adj;
#endif
#if ENABLED(Z_DUAL_ENDSTOPS)
static float z_endstop_adj;
#if Z_MULTI_ENDSTOPS
static float z2_endstop_adj;
#endif
#if ENABLED(Z_TRIPLE_ENDSTOPS)
static float z3_endstop_adj;
#endif
#else
typedef uint8_t esbits_t;

76
Marlin/src/module/motion.cpp

@ -1313,7 +1313,7 @@ void homeaxis(const AxisEnum axis) {
#endif
// Set flags for X, Y, Z motor locking
#if ENABLED(X_DUAL_ENDSTOPS) || ENABLED(Y_DUAL_ENDSTOPS) || ENABLED(Z_DUAL_ENDSTOPS)
#if ENABLED(X_DUAL_ENDSTOPS) || ENABLED(Y_DUAL_ENDSTOPS) || Z_MULTI_ENDSTOPS
switch (axis) {
#if ENABLED(X_DUAL_ENDSTOPS)
case X_AXIS:
@ -1324,7 +1324,17 @@ void homeaxis(const AxisEnum axis) {
#if ENABLED(Z_DUAL_ENDSTOPS)
case Z_AXIS:
#endif
stepper.set_homing_dual_axis(true);
stepper.set_separate_multi_axis(true);
default: break;
}
#endif
#if ENABLED(Z_TRIPLE_ENDSTOPS)
switch (axis) {
#if ENABLED(Z_TRIPLE_ENDSTOPS)
case Z_AXIS:
#endif
stepper.set_separate_multi_axis(true);
default: break;
}
#endif
@ -1384,13 +1394,13 @@ void homeaxis(const AxisEnum axis) {
#endif
}
#if ENABLED(X_DUAL_ENDSTOPS) || ENABLED(Y_DUAL_ENDSTOPS) || ENABLED(Z_DUAL_ENDSTOPS)
#if ENABLED(X_DUAL_ENDSTOPS) || ENABLED(Y_DUAL_ENDSTOPS) || Z_MULTI_ENDSTOPS
const bool pos_dir = axis_home_dir > 0;
#if ENABLED(X_DUAL_ENDSTOPS)
if (axis == X_AXIS) {
const float adj = ABS(endstops.x_endstop_adj);
const float adj = ABS(endstops.x2_endstop_adj);
if (adj) {
if (pos_dir ? (endstops.x_endstop_adj > 0) : (endstops.x_endstop_adj < 0)) stepper.set_x_lock(true); else stepper.set_x2_lock(true);
if (pos_dir ? (endstops.x2_endstop_adj > 0) : (endstops.x2_endstop_adj < 0)) stepper.set_x_lock(true); else stepper.set_x2_lock(true);
do_homing_move(axis, pos_dir ? -adj : adj);
stepper.set_x_lock(false);
stepper.set_x2_lock(false);
@ -1399,9 +1409,9 @@ void homeaxis(const AxisEnum axis) {
#endif
#if ENABLED(Y_DUAL_ENDSTOPS)
if (axis == Y_AXIS) {
const float adj = ABS(endstops.y_endstop_adj);
const float adj = ABS(endstops.y2_endstop_adj);
if (adj) {
if (pos_dir ? (endstops.y_endstop_adj > 0) : (endstops.y_endstop_adj < 0)) stepper.set_y_lock(true); else stepper.set_y2_lock(true);
if (pos_dir ? (endstops.y2_endstop_adj > 0) : (endstops.y2_endstop_adj < 0)) stepper.set_y_lock(true); else stepper.set_y2_lock(true);
do_homing_move(axis, pos_dir ? -adj : adj);
stepper.set_y_lock(false);
stepper.set_y2_lock(false);
@ -1410,16 +1420,62 @@ void homeaxis(const AxisEnum axis) {
#endif
#if ENABLED(Z_DUAL_ENDSTOPS)
if (axis == Z_AXIS) {
const float adj = ABS(endstops.z_endstop_adj);
const float adj = ABS(endstops.z2_endstop_adj);
if (adj) {
if (pos_dir ? (endstops.z_endstop_adj > 0) : (endstops.z_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);
do_homing_move(axis, pos_dir ? -adj : adj);
stepper.set_z_lock(false);
stepper.set_z2_lock(false);
}
}
#endif
stepper.set_homing_dual_axis(false);
#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);
float tempAdj;
// manual bubble sort by adjust value
if (adj[1] < adj[0]) {
tempLock = lock[0], tempAdj = adj[0];
lock[0] = lock[1], adj[0] = adj[1];
lock[1] = tempLock, adj[1] = 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;
}
if (adj[1] < adj[0]) {
tempLock = lock[0], tempAdj = adj[0];
lock[0] = lock[1], adj[0] = adj[1];
lock[1] = tempLock, adj[1] = tempAdj;
}
if (pos_dir) {
// normalize adj to smallest value and do the first move
(*lock[0])(true);
do_homing_move(axis, adj[1] - adj[0]);
// lock the second stepper for the final correction
(*lock[1])(true);
do_homing_move(axis, adj[2] - adj[1]);
}
else {
(*lock[2])(true);
do_homing_move(axis, adj[1] - adj[2]);
(*lock[1])(true);
do_homing_move(axis, adj[0] - adj[1]);
}
stepper.set_z_lock(false);
stepper.set_z2_lock(false);
stepper.set_z3_lock(false);
}
#endif
#endif
#if IS_SCARA

86
Marlin/src/module/stepper.cpp

@ -107,8 +107,8 @@ Stepper stepper; // Singleton
// public:
#if ENABLED(X_DUAL_ENDSTOPS) || ENABLED(Y_DUAL_ENDSTOPS) || ENABLED(Z_DUAL_ENDSTOPS)
bool Stepper::homing_dual_axis = false;
#if ENABLED(X_DUAL_ENDSTOPS) || ENABLED(Y_DUAL_ENDSTOPS) || Z_MULTI_ENDSTOPS
bool Stepper::separate_multi_axis = false;
#endif
#if HAS_MOTOR_CURRENT_PWM
@ -134,9 +134,12 @@ bool Stepper::abort_current_block;
#if ENABLED(Y_DUAL_ENDSTOPS)
bool Stepper::locked_Y_motor = false, Stepper::locked_Y2_motor = false;
#endif
#if ENABLED(Z_DUAL_ENDSTOPS)
#if Z_MULTI_ENDSTOPS
bool Stepper::locked_Z_motor = false, Stepper::locked_Z2_motor = false;
#endif
#if ENABLED(Z_TRIPLE_ENDSTOPS)
bool Stepper::locked_Z3_motor = false;
#endif
uint32_t Stepper::acceleration_time, Stepper::deceleration_time;
uint8_t Stepper::steps_per_isr;
@ -202,23 +205,40 @@ volatile int32_t Stepper::endstops_trigsteps[XYZ];
volatile int32_t Stepper::count_position[NUM_AXIS] = { 0 };
int8_t Stepper::count_direction[NUM_AXIS] = { 0, 0, 0, 0 };
#if ENABLED(X_DUAL_ENDSTOPS) || ENABLED(Y_DUAL_ENDSTOPS) || ENABLED(Z_DUAL_ENDSTOPS)
#define DUAL_ENDSTOP_APPLY_STEP(A,V) \
if (homing_dual_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); \
} \
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); \
} \
} \
else { \
A##_STEP_WRITE(V); \
A##2_STEP_WRITE(V); \
}
#endif
#define DUAL_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); \
} \
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); \
} \
} \
else { \
A##_STEP_WRITE(V); \
A##2_STEP_WRITE(V); \
}
#define TRIPLE_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); \
} \
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); \
} \
} \
else { \
A##_STEP_WRITE(V); \
A##2_STEP_WRITE(V); \
A##3_STEP_WRITE(V); \
}
#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)
@ -261,7 +281,14 @@ int8_t Stepper::count_direction[NUM_AXIS] = { 0, 0, 0, 0 };
#define Y_APPLY_STEP(v,Q) Y_STEP_WRITE(v)
#endif
#if ENABLED(Z_DUAL_STEPPER_DRIVERS)
#if ENABLED(Z_TRIPLE_STEPPER_DRIVERS)
#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)
#define Z_APPLY_STEP(v,Q) TRIPLE_ENDSTOP_APPLY_STEP(Z,v)
#else
#define Z_APPLY_STEP(v,Q) do{ Z_STEP_WRITE(v); Z2_STEP_WRITE(v); Z3_STEP_WRITE(v); }while(0)
#endif
#elif ENABLED(Z_DUAL_STEPPER_DRIVERS)
#define Z_APPLY_DIR(v,Q) do{ Z_DIR_WRITE(v); Z2_DIR_WRITE(v); }while(0)
#if ENABLED(Z_DUAL_ENDSTOPS)
#define Z_APPLY_STEP(v,Q) DUAL_ENDSTOP_APPLY_STEP(Z,v)
@ -1933,9 +1960,12 @@ void Stepper::init() {
#endif
#if HAS_Z_DIR
Z_DIR_INIT;
#if ENABLED(Z_DUAL_STEPPER_DRIVERS) && HAS_Z2_DIR
#if Z_MULTI_STEPPER_DRIVERS && HAS_Z2_DIR
Z2_DIR_INIT;
#endif
#if ENABLED(Z_TRIPLE_STEPPER_DRIVERS) && HAS_Z3_DIR
Z3_DIR_INIT;
#endif
#endif
#if HAS_E0_DIR
E0_DIR_INIT;
@ -1973,10 +2003,14 @@ void Stepper::init() {
#if HAS_Z_ENABLE
Z_ENABLE_INIT;
if (!Z_ENABLE_ON) Z_ENABLE_WRITE(HIGH);
#if ENABLED(Z_DUAL_STEPPER_DRIVERS) && HAS_Z2_ENABLE
#if Z_MULTI_STEPPER_DRIVERS && HAS_Z2_ENABLE
Z2_ENABLE_INIT;
if (!Z_ENABLE_ON) Z2_ENABLE_WRITE(HIGH);
#endif
#if ENABLED(Z_TRIPLE_STEPPER_DRIVERS) && HAS_Z3_ENABLE
Z3_ENABLE_INIT;
if (!Z_ENABLE_ON) Z3_ENABLE_WRITE(HIGH);
#endif
#endif
#if HAS_E0_ENABLE
E0_ENABLE_INIT;
@ -2028,10 +2062,14 @@ void Stepper::init() {
#endif
#if HAS_Z_STEP
#if ENABLED(Z_DUAL_STEPPER_DRIVERS)
#if Z_MULTI_STEPPER_DRIVERS
Z2_STEP_INIT;
Z2_STEP_WRITE(INVERT_Z_STEP_PIN);
#endif
#if ENABLED(Z_TRIPLE_STEPPER_DRIVERS)
Z3_STEP_INIT;
Z3_STEP_WRITE(INVERT_Z_STEP_PIN);
#endif
AXIS_INIT(Z, Z);
#endif

18
Marlin/src/module/stepper.h

@ -234,8 +234,8 @@ class Stepper {
public:
#if ENABLED(X_DUAL_ENDSTOPS) || ENABLED(Y_DUAL_ENDSTOPS) || ENABLED(Z_DUAL_ENDSTOPS)
static bool homing_dual_axis;
#if ENABLED(X_DUAL_ENDSTOPS) || ENABLED(Y_DUAL_ENDSTOPS) || Z_MULTI_ENDSTOPS
static bool separate_multi_axis;
#endif
#if HAS_MOTOR_CURRENT_PWM
@ -267,9 +267,12 @@ class Stepper {
#if ENABLED(Y_DUAL_ENDSTOPS)
static bool locked_Y_motor, locked_Y2_motor;
#endif
#if ENABLED(Z_DUAL_ENDSTOPS)
#if Z_MULTI_ENDSTOPS
static bool locked_Z_motor, locked_Z2_motor;
#endif
#if ENABLED(Z_TRIPLE_ENDSTOPS)
static bool locked_Z3_motor;
#endif
static uint32_t acceleration_time, deceleration_time; // time measured in Stepper Timer ticks
static uint8_t steps_per_isr; // Count of steps to perform per Stepper ISR call
@ -415,8 +418,8 @@ class Stepper {
static void microstep_readings();
#endif
#if ENABLED(X_DUAL_ENDSTOPS) || ENABLED(Y_DUAL_ENDSTOPS) || ENABLED(Z_DUAL_ENDSTOPS)
FORCE_INLINE static void set_homing_dual_axis(const bool state) { homing_dual_axis = state; }
#if ENABLED(X_DUAL_ENDSTOPS) || ENABLED(Y_DUAL_ENDSTOPS) || Z_MULTI_ENDSTOPS
FORCE_INLINE static void set_separate_multi_axis(const bool state) { separate_multi_axis = state; }
#endif
#if ENABLED(X_DUAL_ENDSTOPS)
FORCE_INLINE static void set_x_lock(const bool state) { locked_X_motor = state; }
@ -426,10 +429,13 @@ class Stepper {
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; }
#endif
#if ENABLED(Z_DUAL_ENDSTOPS)
#if Z_MULTI_ENDSTOPS
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; }
#endif
#if ENABLED(Z_TRIPLE_ENDSTOPS)
FORCE_INLINE static void set_z3_lock(const bool state) { locked_Z3_motor = state; }
#endif
#if ENABLED(BABYSTEPPING)
static void babystep(const AxisEnum axis, const bool direction); // perform a short step with a single stepper motor, outside of any convention

41
Marlin/src/module/stepper_indirection.cpp

@ -69,6 +69,9 @@
#if AXIS_DRIVER_TYPE(Z2, TMC26X)
_TMC26X_DEFINE(Z2);
#endif
#if AXIS_DRIVER_TYPE(Z3, TMC26X)
_TMC26X_DEFINE(Z3);
#endif
#if AXIS_DRIVER_TYPE(E0, TMC26X)
_TMC26X_DEFINE(E0);
#endif
@ -109,6 +112,9 @@
#if AXIS_DRIVER_TYPE(Z2, TMC26X)
_TMC26X_INIT(Z2);
#endif
#if AXIS_DRIVER_TYPE(Z3, TMC26X)
_TMC26X_INIT(Z3);
#endif
#if AXIS_DRIVER_TYPE(E0, TMC26X)
_TMC26X_INIT(E0);
#endif
@ -166,6 +172,9 @@
#if AXIS_DRIVER_TYPE(Z2, TMC2130)
_TMC2130_DEFINE(Z2);
#endif
#if AXIS_DRIVER_TYPE(Z3, TMC2130)
_TMC2130_DEFINE(Z3);
#endif
#if AXIS_DRIVER_TYPE(E0, TMC2130)
_TMC2130_DEFINE(E0);
#endif
@ -233,6 +242,9 @@
#if AXIS_DRIVER_TYPE(Z2, TMC2130)
_TMC2130_INIT(Z2, planner.axis_steps_per_mm[Z_AXIS]);
#endif
#if AXIS_DRIVER_TYPE(Z3, TMC2130)
_TMC2130_INIT(Z3, planner.axis_steps_per_mm[Z_AXIS]);
#endif
#if AXIS_DRIVER_TYPE(E0, TMC2130)
_TMC2130_INIT(E0, planner.axis_steps_per_mm[E_AXIS]);
#endif
@ -274,6 +286,9 @@
#if AXIS_DRIVER_TYPE(Z2, TMC2130)
stepperZ2.sgt(Z_HOMING_SENSITIVITY);
#endif
#if ENABLED(Z3_IS_TMC2130)
stepperZ3.sgt(Z_HOMING_SENSITIVITY);
#endif
#endif
#endif
}
@ -337,6 +352,13 @@
_TMC2208_DEFINE_SOFTWARE(Z2);
#endif
#endif
#if AXIS_DRIVER_TYPE(Z3, TMC2208)
#ifdef Z3_HARDWARE_SERIAL
_TMC2208_DEFINE_HARDWARE(Z3);
#else
_TMC2208_DEFINE_SOFTWARE(Z3);
#endif
#endif
#if AXIS_DRIVER_TYPE(E0, TMC2208)
#ifdef E0_HARDWARE_SERIAL
_TMC2208_DEFINE_HARDWARE(E0);
@ -416,6 +438,13 @@
stepperZ2.beginSerial(115200);
#endif
#endif
#if AXIS_DRIVER_TYPE(Z3, TMC2208)
#ifdef Z3_HARDWARE_SERIAL
Z3_HARDWARE_SERIAL.begin(115200);
#else
stepperZ3.beginSerial(115200);
#endif
#endif
#if AXIS_DRIVER_TYPE(E0, TMC2208)
#ifdef E0_HARDWARE_SERIAL
E0_HARDWARE_SERIAL.begin(115200);
@ -510,6 +539,9 @@
#if AXIS_DRIVER_TYPE(Z2, TMC2208)
_TMC2208_INIT(Z2, planner.axis_steps_per_mm[Z_AXIS]);
#endif
#if AXIS_DRIVER_TYPE(Z3, TMC2208)
_TMC2208_INIT(Z3, planner.axis_steps_per_mm[Z_AXIS]);
#endif
#if AXIS_DRIVER_TYPE(E0, TMC2208)
_TMC2208_INIT(E0, planner.axis_steps_per_mm[E_AXIS]);
#endif
@ -547,6 +579,9 @@ void restore_stepper_drivers() {
#if AXIS_IS_TMC(Z2)
stepperZ2.push();
#endif
#if AXIS_IS_TMC(Z3)
stepperZ3.push();
#endif
#if AXIS_IS_TMC(E0)
stepperE0.push();
#endif
@ -614,6 +649,9 @@ void reset_stepper_drivers() {
#if AXIS_DRIVER_TYPE(Z2, L6470)
_L6470_DEFINE(Z2);
#endif
#if AXIS_DRIVER_TYPE(Z3, L6470)
_L6470_DEFINE(Z3);
#endif
#if AXIS_DRIVER_TYPE(E0, L6470)
_L6470_DEFINE(E0);
#endif
@ -657,6 +695,9 @@ void reset_stepper_drivers() {
#if AXIS_DRIVER_TYPE(Z2, L6470)
_L6470_INIT(Z2);
#endif
#if AXIS_DRIVER_TYPE(Z3, L6470)
_L6470_INIT(Z3);
#endif
#if AXIS_DRIVER_TYPE(E0, L6470)
_L6470_INIT(E0);
#endif

35
Marlin/src/module/stepper_indirection.h

@ -282,6 +282,41 @@ void reset_stepper_drivers(); // Called by settings.load / settings.reset
#define Z2_STEP_READ READ(Z2_STEP_PIN)
#endif
// Z3 Stepper
#if HAS_Z3_ENABLE
#if ENABLED(Z3_IS_L6470)
extern L6470 stepperZ3;
#define Z3_ENABLE_INIT NOOP
#define Z3_ENABLE_WRITE(STATE) do{ if (STATE) stepperZ3.Step_Clock(stepperZ3.getStatus() & STATUS_HIZ); else stepperZ3.softFree(); }while(0)
#define Z3_ENABLE_READ (stepperZ3.getStatus() & STATUS_HIZ)
#define Z3_DIR_INIT NOOP
#define Z3_DIR_WRITE(STATE) stepperZ3.Step_Clock(STATE)
#define Z3_DIR_READ (stepperZ3.getStatus() & STATUS_DIR)
#else
#if ENABLED(Z3_IS_TMC26X)
extern TMC26XStepper stepperZ3;
#define Z3_ENABLE_INIT NOOP
#define Z3_ENABLE_WRITE(STATE) stepperZ3.setEnabled(STATE)
#define Z3_ENABLE_READ stepperZ3.isEnabled()
#else
#if ENABLED(Z3_IS_TMC2130)
extern TMC2130Stepper stepperZ3;
#elif ENABLED(Z3_IS_TMC2208)
extern TMC2208Stepper stepperZ3;
#endif
#define Z3_ENABLE_INIT SET_OUTPUT(Z3_ENABLE_PIN)
#define Z3_ENABLE_WRITE(STATE) WRITE(Z3_ENABLE_PIN,STATE)
#define Z3_ENABLE_READ READ(Z3_ENABLE_PIN)
#endif
#define Z3_DIR_INIT SET_OUTPUT(Z3_DIR_PIN)
#define Z3_DIR_WRITE(STATE) WRITE(Z3_DIR_PIN,STATE)
#define Z3_DIR_READ READ(Z3_DIR_PIN)
#endif
#define Z3_STEP_INIT SET_OUTPUT(Z3_STEP_PIN)
#define Z3_STEP_WRITE(STATE) WRITE(Z3_STEP_PIN,STATE)
#define Z3_STEP_READ READ(Z3_STEP_PIN)
#endif
// E0 Stepper
#if AXIS_DRIVER_TYPE(E0, L6470)
extern L6470 stepperE0;

29
Marlin/src/pins/pins.h

@ -842,6 +842,7 @@
#define _X2_PINS
#define _Y2_PINS
#define _Z2_PINS
#define _Z3_PINS
#define __EPIN(p,q) E##p##_##q##_PIN
#define _EPIN(p,q) __EPIN(p,q)
@ -897,7 +898,7 @@
#endif
// The Z2 axis, if any, should be the next open extruder port
#if ENABLED(Z_DUAL_STEPPER_DRIVERS)
#if Z_MULTI_STEPPER_DRIVERS
#ifndef Z2_STEP_PIN
#define Z2_STEP_PIN _EPIN(Z2_E_INDEX, STEP)
#define Z2_DIR_PIN _EPIN(Z2_E_INDEX, DIR)
@ -916,6 +917,30 @@
#else
#define _Z2_PINS __Z2_PINS
#endif
#define Z3_E_INDEX INCREMENT(Z2_E_INDEX)
#else
#define Z3_E_INDEX Z2_E_INDEX
#endif
#if ENABLED(Z_TRIPLE_STEPPER_DRIVERS)
#ifndef Z3_STEP_PIN
#define Z3_STEP_PIN _EPIN(Z3_E_INDEX, STEP)
#define Z3_DIR_PIN _EPIN(Z3_E_INDEX, DIR)
#define Z3_ENABLE_PIN _EPIN(Z3_E_INDEX, ENABLE)
#ifndef Z3_CS_PIN
#define Z3_CS_PIN _EPIN(Z3_E_INDEX, CS)
#endif
#if Z3_E_INDEX > 4 || !PIN_EXISTS(Z3_ENABLE)
#error "No E stepper plug left for Z3!"
#endif
#endif
#undef _Z3_PINS
#define __Z3_PINS Z3_STEP_PIN, Z3_DIR_PIN, Z3_ENABLE_PIN,
#ifdef Z3_CS_PIN
#define _Z3_PINS __Z3_PINS Z3_CS_PIN,
#else
#define _Z3_PINS __Z3_PINS
#endif
#endif
#ifndef HAL_SENSITIVE_PINS
@ -929,7 +954,7 @@
PS_ON_PIN, HEATER_BED_PIN, FAN_PIN, FAN1_PIN, FAN2_PIN, CONTROLLER_FAN_PIN, \
_E0_PINS _E1_PINS _E2_PINS _E3_PINS _E4_PINS BED_PINS \
_H0_PINS _H1_PINS _H2_PINS _H3_PINS _H4_PINS \
_X2_PINS _Y2_PINS _Z2_PINS \
_X2_PINS _Y2_PINS _Z2_PINS _Z3_PINS \
HAL_SENSITIVE_PINS \
}

27
Marlin/src/pins/pinsDebug_list.h

@ -944,6 +944,27 @@
#if PIN_EXISTS(Z2_STEP)
REPORT_NAME_DIGITAL(__LINE__, Z2_STEP_PIN)
#endif
#if PIN_EXISTS(Z3_CS)
REPORT_NAME_DIGITAL(__LINE__, Z3_CS_PIN)
#endif
#if PIN_EXISTS(Z3_DIR)
REPORT_NAME_DIGITAL(__LINE__, Z3_DIR_PIN)
#endif
#if PIN_EXISTS(Z3_ENABLE)
REPORT_NAME_DIGITAL(__LINE__, Z3_ENABLE_PIN)
#endif
#if PIN_EXISTS(Z3_MS1)
REPORT_NAME_DIGITAL(__LINE__, Z3_MS1_PIN)
#endif
#if PIN_EXISTS(Z3_MS2)
REPORT_NAME_DIGITAL(__LINE__, Z3_MS2_PIN)
#endif
#if PIN_EXISTS(Z3_MS3)
REPORT_NAME_DIGITAL(__LINE__, Z3_MS3_PIN)
#endif
#if PIN_EXISTS(Z3_STEP)
REPORT_NAME_DIGITAL(__LINE__, Z3_STEP_PIN)
#endif
#if PIN_EXISTS(ZRIB_V20_D6)
REPORT_NAME_DIGITAL(__LINE__, ZRIB_V20_D6_PIN)
#endif
@ -986,6 +1007,12 @@
#if PIN_EXISTS(Z2_SERIAL_RX)
REPORT_NAME_DIGITAL(__LINE__, Z2_SERIAL_RX_PIN)
#endif
#if PIN_EXISTS(Z3_SERIAL_TX)
REPORT_NAME_DIGITAL(__LINE__, Z3_SERIAL_TX_PIN)
#endif
#if PIN_EXISTS(Z3_SERIAL_RX)
REPORT_NAME_DIGITAL(__LINE__, Z3_SERIAL_RX_PIN)
#endif
#if PIN_EXISTS(E0_SERIAL_TX)
REPORT_NAME_DIGITAL(__LINE__, E0_SERIAL_TX_PIN)
#endif

12
buildroot/share/tests/DUE_tests

@ -9,3 +9,15 @@ opt_enable S_CURVE_ACCELERATION EEPROM_SETTINGS
opt_set E0_AUTO_FAN_PIN 8
opt_set EXTRUDER_AUTO_FAN_SPEED 100
exec_test $1 $2 "RAMPS4DUE_EFB S_CURVE_ACCELERATION EEPROM_SETTINGS"
restore_configs
opt_set MOTHERBOARD BOARD_RADDS
opt_enable USE_XMAX_PLUG USE_YMAX_PLUG
opt_enable_adv Z_TRIPLE_STEPPER_DRIVERS Z_TRIPLE_ENDSTOPS
opt_add_adv Z2_MAX_ENDSTOP_INVERTING false
opt_add_adv Z3_MAX_ENDSTOP_INVERTING false
pins_set RAMPS X_MAX_PIN -1
pins_set RAMPS Y_MAX_PIN -1
opt_add_adv Z2_MAX_PIN 2
opt_add_adv Z3_MAX_PIN 3
exec_test $1 $2 "RADDS Z_TRIPLE"

2
buildroot/share/tests/teensy35_tests

@ -92,5 +92,5 @@ opt_add_adv Z2_MAX_PIN 2
opt_enable USE_XMAX_PLUG
exec_test $1 $2 "Z_DUAL_STEPPER_DRIVERS, Z_DUAL_ENDSTOPS"
#cleanup
# Clean up
restore_configs

Loading…
Cancel
Save