Consolidate smart stepper driver initialization
This commit is contained in:
parent
72776f647b
commit
a03502080e
5 changed files with 180 additions and 119 deletions
|
|
@ -42,83 +42,82 @@
|
|||
#include <SPI.h>
|
||||
#include <TMC26XStepper.h>
|
||||
|
||||
#define _TMC_DEFINE(ST) TMC26XStepper stepper##ST(200, ST##_ENABLE_PIN, ST##_STEP_PIN, ST##_DIR_PIN, ST##_MAX_CURRENT, ST##_SENSE_RESISTOR)
|
||||
#define _TMC26X_DEFINE(ST) TMC26XStepper stepper##ST(200, ST##_ENABLE_PIN, ST##_STEP_PIN, ST##_DIR_PIN, ST##_MAX_CURRENT, ST##_SENSE_RESISTOR)
|
||||
|
||||
#if ENABLED(X_IS_TMC26X)
|
||||
_TMC_DEFINE(X);
|
||||
_TMC26X_DEFINE(X);
|
||||
#endif
|
||||
#if ENABLED(X2_IS_TMC26X)
|
||||
_TMC_DEFINE(X2);
|
||||
_TMC26X_DEFINE(X2);
|
||||
#endif
|
||||
#if ENABLED(Y_IS_TMC26X)
|
||||
_TMC_DEFINE(Y);
|
||||
_TMC26X_DEFINE(Y);
|
||||
#endif
|
||||
#if ENABLED(Y2_IS_TMC26X)
|
||||
_TMC_DEFINE(Y2);
|
||||
_TMC26X_DEFINE(Y2);
|
||||
#endif
|
||||
#if ENABLED(Z_IS_TMC26X)
|
||||
_TMC_DEFINE(Z);
|
||||
_TMC26X_DEFINE(Z);
|
||||
#endif
|
||||
#if ENABLED(Z2_IS_TMC26X)
|
||||
_TMC_DEFINE(Z2);
|
||||
_TMC26X_DEFINE(Z2);
|
||||
#endif
|
||||
#if ENABLED(E0_IS_TMC26X)
|
||||
_TMC_DEFINE(E0);
|
||||
_TMC26X_DEFINE(E0);
|
||||
#endif
|
||||
#if ENABLED(E1_IS_TMC26X)
|
||||
_TMC_DEFINE(E1);
|
||||
_TMC26X_DEFINE(E1);
|
||||
#endif
|
||||
#if ENABLED(E2_IS_TMC26X)
|
||||
_TMC_DEFINE(E2);
|
||||
_TMC26X_DEFINE(E2);
|
||||
#endif
|
||||
#if ENABLED(E3_IS_TMC26X)
|
||||
_TMC_DEFINE(E3);
|
||||
_TMC26X_DEFINE(E3);
|
||||
#endif
|
||||
#if ENABLED(E4_IS_TMC26X)
|
||||
_TMC_DEFINE(E4);
|
||||
_TMC26X_DEFINE(E4);
|
||||
#endif
|
||||
|
||||
#define _TMC_INIT(A) do{ \
|
||||
#define _TMC26X_INIT(A) do{ \
|
||||
stepper##A.setMicrosteps(A##_MICROSTEPS); \
|
||||
stepper##A.start(); \
|
||||
}while(0)
|
||||
|
||||
void tmc_init() {
|
||||
void tmc26x_init_to_defaults() {
|
||||
#if ENABLED(X_IS_TMC26X)
|
||||
_TMC_INIT(X);
|
||||
_TMC26X_INIT(X);
|
||||
#endif
|
||||
#if ENABLED(X2_IS_TMC26X)
|
||||
_TMC_INIT(X2);
|
||||
_TMC26X_INIT(X2);
|
||||
#endif
|
||||
#if ENABLED(Y_IS_TMC26X)
|
||||
_TMC_INIT(Y);
|
||||
_TMC26X_INIT(Y);
|
||||
#endif
|
||||
#if ENABLED(Y2_IS_TMC26X)
|
||||
_TMC_INIT(Y2);
|
||||
_TMC26X_INIT(Y2);
|
||||
#endif
|
||||
#if ENABLED(Z_IS_TMC26X)
|
||||
_TMC_INIT(Z);
|
||||
_TMC26X_INIT(Z);
|
||||
#endif
|
||||
#if ENABLED(Z2_IS_TMC26X)
|
||||
_TMC_INIT(Z2);
|
||||
_TMC26X_INIT(Z2);
|
||||
#endif
|
||||
#if ENABLED(E0_IS_TMC26X)
|
||||
_TMC_INIT(E0);
|
||||
_TMC26X_INIT(E0);
|
||||
#endif
|
||||
#if ENABLED(E1_IS_TMC26X)
|
||||
_TMC_INIT(E1);
|
||||
_TMC26X_INIT(E1);
|
||||
#endif
|
||||
#if ENABLED(E2_IS_TMC26X)
|
||||
_TMC_INIT(E2);
|
||||
_TMC26X_INIT(E2);
|
||||
#endif
|
||||
#if ENABLED(E3_IS_TMC26X)
|
||||
_TMC_INIT(E3);
|
||||
_TMC26X_INIT(E3);
|
||||
#endif
|
||||
#if ENABLED(E4_IS_TMC26X)
|
||||
_TMC_INIT(E4);
|
||||
_TMC26X_INIT(E4);
|
||||
#endif
|
||||
}
|
||||
|
||||
#endif // HAVE_TMC26X
|
||||
|
||||
//
|
||||
|
|
@ -137,7 +136,6 @@
|
|||
#define _TMC2130_DEFINE(ST) TMC2130Stepper stepper##ST(ST##_ENABLE_PIN, ST##_DIR_PIN, ST##_STEP_PIN, ST##_CS_PIN)
|
||||
#endif
|
||||
|
||||
|
||||
// Stepper objects of TMC2130 steppers used
|
||||
#if ENABLED(X_IS_TMC2130)
|
||||
_TMC2130_DEFINE(X);
|
||||
|
|
@ -176,9 +174,9 @@
|
|||
// Use internal reference voltage for current calculations. This is the default.
|
||||
// Following values from Trinamic's spreadsheet with values for a NEMA17 (42BYGHW609)
|
||||
// https://www.trinamic.com/products/integrated-circuits/details/tmc2130/
|
||||
void tmc2130_init(TMC2130Stepper &st, const uint16_t microsteps, const uint32_t thrs, const float spmm) {
|
||||
void tmc2130_init(TMC2130Stepper &st, const uint16_t mA, const uint16_t microsteps, const uint32_t thrs, const float spmm) {
|
||||
st.begin();
|
||||
st.setCurrent(st.getCurrent(), R_SENSE, HOLD_MULTIPLIER);
|
||||
st.setCurrent(mA, R_SENSE, HOLD_MULTIPLIER);
|
||||
st.microsteps(microsteps);
|
||||
st.blank_time(24);
|
||||
st.off_time(5); // Only enables the driver if used with stealthChop
|
||||
|
|
@ -205,9 +203,9 @@
|
|||
st.GSTAT(); // Clear GSTAT
|
||||
}
|
||||
|
||||
#define _TMC2130_INIT(ST, SPMM) tmc2130_init(stepper##ST, ST##_MICROSTEPS, ST##_HYBRID_THRESHOLD, SPMM)
|
||||
#define _TMC2130_INIT(ST, SPMM) tmc2130_init(stepper##ST, ST##_CURRENT, ST##_MICROSTEPS, ST##_HYBRID_THRESHOLD, SPMM)
|
||||
|
||||
void tmc2130_init() {
|
||||
void tmc2130_init_to_defaults() {
|
||||
#if ENABLED(X_IS_TMC2130)
|
||||
_TMC2130_INIT( X, planner.axis_steps_per_mm[X_AXIS]);
|
||||
#endif
|
||||
|
|
@ -242,7 +240,35 @@
|
|||
{ constexpr int extruder = 4; _TMC2130_INIT(E4, planner.axis_steps_per_mm[E_AXIS_N]); }
|
||||
#endif
|
||||
|
||||
#if ENABLED(SENSORLESS_HOMING)
|
||||
#define TMC_INIT_SGT(P,Q) stepper##Q.sgt(P##_HOMING_SENSITIVITY);
|
||||
#ifdef X_HOMING_SENSITIVITY
|
||||
#if ENABLED(X_IS_TMC2130) || ENABLED(IS_TRAMS)
|
||||
stepperX.sgt(X_HOMING_SENSITIVITY);
|
||||
#endif
|
||||
#if ENABLED(X2_IS_TMC2130)
|
||||
stepperX2.sgt(X_HOMING_SENSITIVITY);
|
||||
#endif
|
||||
#endif
|
||||
#ifdef Y_HOMING_SENSITIVITY
|
||||
#if ENABLED(Y_IS_TMC2130) || ENABLED(IS_TRAMS)
|
||||
stepperY.sgt(Y_HOMING_SENSITIVITY);
|
||||
#endif
|
||||
#if ENABLED(Y2_IS_TMC2130)
|
||||
stepperY2.sgt(Y_HOMING_SENSITIVITY);
|
||||
#endif
|
||||
#endif
|
||||
#ifdef Z_HOMING_SENSITIVITY
|
||||
#if ENABLED(Z_IS_TMC2130) || ENABLED(IS_TRAMS)
|
||||
stepperZ.sgt(Z_HOMING_SENSITIVITY);
|
||||
#endif
|
||||
#if ENABLED(Z2_IS_TMC2130)
|
||||
stepperZ2.sgt(Z_HOMING_SENSITIVITY);
|
||||
#endif
|
||||
#endif
|
||||
#endif
|
||||
}
|
||||
|
||||
#endif // HAVE_TMC2130
|
||||
|
||||
//
|
||||
|
|
@ -377,11 +403,11 @@
|
|||
|
||||
// Use internal reference voltage for current calculations. This is the default.
|
||||
// Following values from Trinamic's spreadsheet with values for a NEMA17 (42BYGHW609)
|
||||
void tmc2208_init(TMC2208Stepper &st, const uint16_t microsteps, const uint32_t thrs, const float spmm) {
|
||||
void tmc2208_init(TMC2208Stepper &st, const uint16_t mA, const uint16_t microsteps, const uint32_t thrs, const float spmm) {
|
||||
st.pdn_disable(true); // Use UART
|
||||
st.mstep_reg_select(true); // Select microsteps with UART
|
||||
st.I_scale_analog(false);
|
||||
st.rms_current(st.getCurrent(), HOLD_MULTIPLIER, R_SENSE);
|
||||
st.rms_current(mA, HOLD_MULTIPLIER, R_SENSE);
|
||||
st.microsteps(microsteps);
|
||||
st.blank_time(24);
|
||||
st.toff(5);
|
||||
|
|
@ -411,9 +437,9 @@
|
|||
delay(200);
|
||||
}
|
||||
|
||||
#define _TMC2208_INIT(ST, SPMM) tmc2208_init(stepper##ST, ST##_MICROSTEPS, ST##_HYBRID_THRESHOLD, SPMM)
|
||||
#define _TMC2208_INIT(ST, SPMM) tmc2208_init(stepper##ST, ST##_CURRENT, ST##_MICROSTEPS, ST##_HYBRID_THRESHOLD, SPMM)
|
||||
|
||||
void tmc2208_init() {
|
||||
void tmc2208_init_to_defaults() {
|
||||
#if ENABLED(X_IS_TMC2208)
|
||||
_TMC2208_INIT(X, planner.axis_steps_per_mm[X_AXIS]);
|
||||
#endif
|
||||
|
|
@ -448,8 +474,63 @@
|
|||
{ constexpr int extruder = 4; _TMC2208_INIT(E4, planner.axis_steps_per_mm[E_AXIS_N]); }
|
||||
#endif
|
||||
}
|
||||
|
||||
#endif // HAVE_TMC2208
|
||||
|
||||
void restore_stepper_drivers() {
|
||||
#if X_IS_TRINAMIC
|
||||
stepperX.push();
|
||||
#endif
|
||||
#if X2_IS_TRINAMIC
|
||||
stepperX2.push();
|
||||
#endif
|
||||
#if Y_IS_TRINAMIC
|
||||
stepperY.push();
|
||||
#endif
|
||||
#if Y2_IS_TRINAMIC
|
||||
stepperY2.push();
|
||||
#endif
|
||||
#if Z_IS_TRINAMIC
|
||||
stepperZ.push();
|
||||
#endif
|
||||
#if Z2_IS_TRINAMIC
|
||||
stepperZ2.push();
|
||||
#endif
|
||||
#if E0_IS_TRINAMIC
|
||||
stepperE0.push();
|
||||
#endif
|
||||
#if E1_IS_TRINAMIC
|
||||
stepperE1.push();
|
||||
#endif
|
||||
#if E2_IS_TRINAMIC
|
||||
stepperE2.push();
|
||||
#endif
|
||||
#if E3_IS_TRINAMIC
|
||||
stepperE3.push();
|
||||
#endif
|
||||
#if E4_IS_TRINAMIC
|
||||
stepperE4.push();
|
||||
#endif
|
||||
}
|
||||
|
||||
void reset_stepper_drivers() {
|
||||
#if ENABLED(HAVE_TMC26X)
|
||||
tmc26x_init_to_defaults();
|
||||
#endif
|
||||
#if ENABLED(HAVE_TMC2130)
|
||||
tmc2130_init_to_defaults();
|
||||
#endif
|
||||
#if ENABLED(HAVE_TMC2208)
|
||||
tmc2208_init_to_defaults();
|
||||
#endif
|
||||
#ifdef TMC_ADV
|
||||
TMC_ADV()
|
||||
#endif
|
||||
#if ENABLED(HAVE_L6470DRIVER)
|
||||
L6470_init_to_defaults();
|
||||
#endif
|
||||
}
|
||||
|
||||
//
|
||||
// L6470 Driver objects and inits
|
||||
//
|
||||
|
|
@ -503,7 +584,7 @@
|
|||
stepper##A.setStallCurrent(A##_STALLCURRENT); \
|
||||
}while(0)
|
||||
|
||||
void L6470_init() {
|
||||
void L6470_init_to_defaults() {
|
||||
#if ENABLED(X_IS_L6470)
|
||||
_L6470_INIT(X);
|
||||
#endif
|
||||
|
|
|
|||
Loading…
Add table
Add a link
Reference in a new issue