More Trinamic cleanup
This commit is contained in:
parent
473c6d3a91
commit
b76344c080
|
@ -53,7 +53,7 @@ void tmc_get_current(TMC &st, const TMC_AxisEnum axis) {
|
|||
_tmc_say_current(axis, st.getCurrent());
|
||||
}
|
||||
template<typename TMC>
|
||||
void tmc_set_current(TMC &st, const TMC_AxisEnum axis, const int mA) {
|
||||
void tmc_set_current(TMC &st, const int mA) {
|
||||
st.setCurrent(mA, R_SENSE, HOLD_MULTIPLIER);
|
||||
}
|
||||
template<typename TMC>
|
||||
|
@ -70,7 +70,7 @@ void tmc_get_pwmthrs(TMC &st, const TMC_AxisEnum axis, const uint16_t spmm) {
|
|||
_tmc_say_pwmthrs(axis, _tmc_thrs(st.microsteps(), st.TPWMTHRS(), spmm));
|
||||
}
|
||||
template<typename TMC>
|
||||
void tmc_set_pwmthrs(TMC &st, const TMC_AxisEnum axis, const int32_t thrs, const uint32_t spmm) {
|
||||
void tmc_set_pwmthrs(TMC &st, const int32_t thrs, const uint32_t spmm) {
|
||||
st.TPWMTHRS(_tmc_thrs(st.microsteps(), thrs, spmm));
|
||||
}
|
||||
template<typename TMC>
|
||||
|
@ -78,7 +78,7 @@ void tmc_get_sgt(TMC &st, const TMC_AxisEnum axis) {
|
|||
_tmc_say_sgt(axis, st.sgt());
|
||||
}
|
||||
template<typename TMC>
|
||||
void tmc_set_sgt(TMC &st, const TMC_AxisEnum axis, const int8_t sgt_val) {
|
||||
void tmc_set_sgt(TMC &st, const int8_t sgt_val) {
|
||||
st.sgt(sgt_val);
|
||||
}
|
||||
|
||||
|
|
|
@ -34,7 +34,7 @@
|
|||
*/
|
||||
void GcodeSuite::M906() {
|
||||
#define TMC_SAY_CURRENT(Q) tmc_get_current(stepper##Q, TMC_##Q)
|
||||
#define TMC_SET_CURRENT(Q) tmc_set_current(stepper##Q, TMC_##Q, value)
|
||||
#define TMC_SET_CURRENT(Q) tmc_set_current(stepper##Q, value)
|
||||
|
||||
bool report = true;
|
||||
const uint8_t index = parser.byteval('I');
|
||||
|
|
|
@ -30,42 +30,48 @@
|
|||
#include "../../../module/planner.h"
|
||||
#include "../../queue.h"
|
||||
|
||||
#define M91x_USE(A) (ENABLED(A##_IS_TMC2130) || (ENABLED(A##_IS_TMC2208) && PIN_EXISTS(A##_SERIAL_RX)))
|
||||
#define M91x_USE_X (ENABLED(IS_TRAMS) || M91x_USE(X))
|
||||
#define M91x_USE_Y (ENABLED(IS_TRAMS) || M91x_USE(Y))
|
||||
#define M91x_USE_Z (ENABLED(IS_TRAMS) || M91x_USE(Z))
|
||||
#define M91x_USE_E0 (ENABLED(IS_TRAMS) || M91x_USE(E0))
|
||||
|
||||
/**
|
||||
* M911: Report TMC stepper driver overtemperature pre-warn flag
|
||||
* This flag is held by the library, persisting until cleared by M912
|
||||
*/
|
||||
void GcodeSuite::M911() {
|
||||
#if ENABLED(X_IS_TMC2130) || (ENABLED(X_IS_TMC2208) && PIN_EXISTS(X_SERIAL_RX)) || ENABLED(IS_TRAMS)
|
||||
#if M91x_USE_X
|
||||
tmc_report_otpw(stepperX, TMC_X);
|
||||
#endif
|
||||
#if ENABLED(X2_IS_TMC2130) || (ENABLED(X2_IS_TMC2208) && PIN_EXISTS(X2_SERIAL_RX))
|
||||
#if M91x_USE(X2)
|
||||
tmc_report_otpw(stepperX2, TMC_X2);
|
||||
#endif
|
||||
#if ENABLED(Y_IS_TMC2130) || (ENABLED(Y_IS_TMC2208) && PIN_EXISTS(Y_SERIAL_RX)) || ENABLED(IS_TRAMS)
|
||||
#if M91x_USE_Y
|
||||
tmc_report_otpw(stepperY, TMC_Y);
|
||||
#endif
|
||||
#if ENABLED(Y2_IS_TMC2130) || (ENABLED(Y2_IS_TMC2208) && PIN_EXISTS(Y2_SERIAL_RX))
|
||||
#if M91x_USE(Y2)
|
||||
tmc_report_otpw(stepperY2, TMC_Y2);
|
||||
#endif
|
||||
#if ENABLED(Z_IS_TMC2130) || (ENABLED(Z_IS_TMC2208) && PIN_EXISTS(Z_SERIAL_RX)) || ENABLED(IS_TRAMS)
|
||||
#if M91x_USE_Z
|
||||
tmc_report_otpw(stepperZ, TMC_Z);
|
||||
#endif
|
||||
#if ENABLED(Z2_IS_TMC2130) || (ENABLED(Z2_IS_TMC2208) && PIN_EXISTS(Z2_SERIAL_RX))
|
||||
#if M91x_USE(Z2)
|
||||
tmc_report_otpw(stepperZ2, TMC_Z2);
|
||||
#endif
|
||||
#if ENABLED(E0_IS_TMC2130) || (ENABLED(E0_IS_TMC2208) && PIN_EXISTS(E0_SERIAL_RX)) || ENABLED(IS_TRAMS)
|
||||
#if M91x_USE_E0
|
||||
tmc_report_otpw(stepperE0, TMC_E0);
|
||||
#endif
|
||||
#if ENABLED(E1_IS_TMC2130) || (ENABLED(E1_IS_TMC2208) && PIN_EXISTS(E1_SERIAL_RX))
|
||||
#if M91x_USE(E1)
|
||||
tmc_report_otpw(stepperE1, TMC_E1);
|
||||
#endif
|
||||
#if ENABLED(E2_IS_TMC2130) || (ENABLED(E2_IS_TMC2208) && PIN_EXISTS(E2_SERIAL_RX))
|
||||
#if M91x_USE(E2)
|
||||
tmc_report_otpw(stepperE2, TMC_E2);
|
||||
#endif
|
||||
#if ENABLED(E3_IS_TMC2130) || (ENABLED(E3_IS_TMC2208) && PIN_EXISTS(E3_SERIAL_RX))
|
||||
#if M91x_USE(E3)
|
||||
tmc_report_otpw(stepperE3, TMC_E3);
|
||||
#endif
|
||||
#if ENABLED(E4_IS_TMC2130) || (ENABLED(E4_IS_TMC2208) && PIN_EXISTS(E4_SERIAL_RX))
|
||||
#if M91x_USE(E4)
|
||||
tmc_report_otpw(stepperE4, TMC_E4);
|
||||
#endif
|
||||
}
|
||||
|
@ -83,45 +89,61 @@ void GcodeSuite::M911() {
|
|||
* M912 E1 ; clear E1 only
|
||||
*/
|
||||
void GcodeSuite::M912() {
|
||||
const bool hasX = parser.seen(axis_codes[X_AXIS]), hasY = parser.seen(axis_codes[Y_AXIS]),
|
||||
hasZ = parser.seen(axis_codes[Z_AXIS]), hasE = parser.seen(axis_codes[E_AXIS]),
|
||||
hasNone = !hasX && !hasY && !hasZ && !hasE;
|
||||
const uint8_t xval = parser.byteval(axis_codes[X_AXIS], 10), yval = parser.byteval(axis_codes[Y_AXIS], 10),
|
||||
zval = parser.byteval(axis_codes[Z_AXIS], 10), eval = parser.byteval(axis_codes[E_AXIS], 10);
|
||||
const bool hasX = parser.seen(axis_codes[X_AXIS]),
|
||||
hasY = parser.seen(axis_codes[Y_AXIS]),
|
||||
hasZ = parser.seen(axis_codes[Z_AXIS]),
|
||||
hasE = parser.seen(axis_codes[E_AXIS]),
|
||||
hasNone = !hasX && !hasY && !hasZ && !hasE;
|
||||
|
||||
#if (ENABLED(X_IS_TMC2130) || (ENABLED(X_IS_TMC2208) && PIN_EXISTS(X_SERIAL_RX)) || ENABLED(IS_TRAMS))
|
||||
if (hasNone || xval == 1 || (hasX && xval == 10)) tmc_clear_otpw(stepperX, TMC_X);
|
||||
#endif
|
||||
#if (ENABLED(X2_IS_TMC2130) || (ENABLED(X2_IS_TMC2208) && PIN_EXISTS(X2_SERIAL_RX)))
|
||||
if (hasNone || xval == 2 || (hasX && xval == 10)) tmc_clear_otpw(stepperX2, TMC_X2);
|
||||
#endif
|
||||
#if (ENABLED(Y_IS_TMC2130) || (ENABLED(Y_IS_TMC2208) && PIN_EXISTS(Y_SERIAL_RX)) || ENABLED(IS_TRAMS))
|
||||
if (hasNone || yval == 1 || (hasY && yval == 10)) tmc_clear_otpw(stepperY, TMC_Y);
|
||||
#endif
|
||||
#if (ENABLED(Y2_IS_TMC2130) || (ENABLED(Y2_IS_TMC2208) && PIN_EXISTS(Y2_SERIAL_RX)))
|
||||
if (hasNone || yval == 2 || (hasY && yval == 10)) tmc_clear_otpw(stepperY2, TMC_Y2);
|
||||
#endif
|
||||
#if (ENABLED(Z_IS_TMC2130) || (ENABLED(Z_IS_TMC2208) && PIN_EXISTS(Z_SERIAL_RX)) || ENABLED(IS_TRAMS))
|
||||
if (hasNone || zval == 1 || (hasZ && zval == 10)) tmc_clear_otpw(stepperZ, TMC_Z);
|
||||
#endif
|
||||
#if (ENABLED(Z2_IS_TMC2130) || (ENABLED(Z2_IS_TMC2208) && PIN_EXISTS(Z2_SERIAL_RX)))
|
||||
if (hasNone || zval == 2 || (hasZ && zval == 10)) tmc_clear_otpw(stepperZ2, TMC_Z2);
|
||||
#endif
|
||||
#if (ENABLED(E0_IS_TMC2130) || (ENABLED(E0_IS_TMC2208) && PIN_EXISTS(E0_SERIAL_RX)) || ENABLED(IS_TRAMS))
|
||||
if (hasNone || eval == 0 || (hasE && eval == 10)) tmc_clear_otpw(stepperE0, TMC_E0);
|
||||
#endif
|
||||
#if E_STEPPERS > 1 && (ENABLED(E1_IS_TMC2130) || (ENABLED(E1_IS_TMC2208) && PIN_EXISTS(E1_SERIAL_RX)))
|
||||
if (hasNone || eval == 1 || (hasE && eval == 10)) tmc_clear_otpw(stepperE1, TMC_E1);
|
||||
#endif
|
||||
#if E_STEPPERS > 2 && (ENABLED(E2_IS_TMC2130) || (ENABLED(E2_IS_TMC2208) && PIN_EXISTS(E2_SERIAL_RX)))
|
||||
if (hasNone || eval == 2 || (hasE && eval == 10)) tmc_clear_otpw(stepperE2, TMC_E2);
|
||||
#endif
|
||||
#if E_STEPPERS > 3 && (ENABLED(E3_IS_TMC2130) || (ENABLED(E3_IS_TMC2208) && PIN_EXISTS(E3_SERIAL_RX)))
|
||||
if (hasNone || eval == 3 || (hasE && eval == 10)) tmc_clear_otpw(stepperE3, TMC_E3);
|
||||
#endif
|
||||
#if E_STEPPERS > 4 && (ENABLED(E4_IS_TMC2130) || (ENABLED(E4_IS_TMC2208) && PIN_EXISTS(E4_SERIAL_RX)))
|
||||
if (hasNone || eval == 4 || (hasE && eval == 10)) tmc_clear_otpw(stepperE4, TMC_E4);
|
||||
#endif
|
||||
#if M91x_USE_X || M91x_USE(X2)
|
||||
const uint8_t xval = parser.byteval(axis_codes[X_AXIS], 10);
|
||||
#if M91x_USE_X
|
||||
if (hasNone || xval == 1 || (hasX && xval == 10)) tmc_clear_otpw(stepperX, TMC_X);
|
||||
#endif
|
||||
#if M91x_USE(X2)
|
||||
if (hasNone || xval == 2 || (hasX && xval == 10)) tmc_clear_otpw(stepperX2, TMC_X2);
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#define M91x_USE_Y (M91x_USE(Y) || ENABLED(IS_TRAMS))
|
||||
#if M91x_USE_Y || M91x_USE(Y2)
|
||||
const uint8_t yval = parser.byteval(axis_codes[Y_AXIS], 10);
|
||||
#if M91x_USE_Y
|
||||
if (hasNone || yval == 1 || (hasY && yval == 10)) tmc_clear_otpw(stepperY, TMC_Y);
|
||||
#endif
|
||||
#if M91x_USE(Y2)
|
||||
if (hasNone || yval == 2 || (hasY && yval == 10)) tmc_clear_otpw(stepperY2, TMC_Y2);
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#define M91x_USE_Z (M91x_USE(Z) || ENABLED(IS_TRAMS))
|
||||
#if M91x_USE_Z || M91x_USE(Z2)
|
||||
const uint8_t zval = parser.byteval(axis_codes[Z_AXIS], 10);
|
||||
#if M91x_USE_Z
|
||||
if (hasNone || zval == 1 || (hasZ && zval == 10)) tmc_clear_otpw(stepperZ, TMC_Z);
|
||||
#endif
|
||||
#if M91x_USE(Z2)
|
||||
if (hasNone || zval == 2 || (hasZ && zval == 10)) tmc_clear_otpw(stepperZ2, TMC_Z2);
|
||||
#endif
|
||||
#endif
|
||||
|
||||
const uint8_t eval = parser.byteval(axis_codes[E_AXIS], 10);
|
||||
|
||||
#if M91x_USE_E0
|
||||
if (hasNone || eval == 0 || (hasE && eval == 10)) tmc_clear_otpw(stepperE0, TMC_E0);
|
||||
#endif
|
||||
#if E_STEPPERS > 1 && M91x_USE(E1)
|
||||
if (hasNone || eval == 1 || (hasE && eval == 10)) tmc_clear_otpw(stepperE1, TMC_E1);
|
||||
#endif
|
||||
#if E_STEPPERS > 2 && M91x_USE(E2)
|
||||
if (hasNone || eval == 2 || (hasE && eval == 10)) tmc_clear_otpw(stepperE2, TMC_E2);
|
||||
#endif
|
||||
#if E_STEPPERS > 3 && M91x_USE(E3)
|
||||
if (hasNone || eval == 3 || (hasE && eval == 10)) tmc_clear_otpw(stepperE3, TMC_E3);
|
||||
#endif
|
||||
#if E_STEPPERS > 4 && M91x_USE(E4)
|
||||
if (hasNone || eval == 4 || (hasE && eval == 10)) tmc_clear_otpw(stepperE4, TMC_E4);
|
||||
#endif
|
||||
}
|
||||
|
||||
/**
|
||||
|
@ -130,9 +152,9 @@ void GcodeSuite::M912() {
|
|||
#if ENABLED(HYBRID_THRESHOLD)
|
||||
void GcodeSuite::M913() {
|
||||
#define TMC_SAY_PWMTHRS(P,Q) tmc_get_pwmthrs(stepper##Q, TMC_##Q, planner.axis_steps_per_mm[P##_AXIS])
|
||||
#define TMC_SET_PWMTHRS(P,Q) tmc_set_pwmthrs(stepper##Q, TMC_##Q, value, planner.axis_steps_per_mm[P##_AXIS])
|
||||
#define TMC_SET_PWMTHRS(P,Q) tmc_set_pwmthrs(stepper##Q, value, planner.axis_steps_per_mm[P##_AXIS])
|
||||
#define TMC_SAY_PWMTHRS_E(E) do{ const uint8_t extruder = E; tmc_get_pwmthrs(stepperE##E, TMC_E##E, planner.axis_steps_per_mm[E_AXIS_N]); }while(0)
|
||||
#define TMC_SET_PWMTHRS_E(E) do{ const uint8_t extruder = E; tmc_set_pwmthrs(stepperE##E, TMC_E##E, value, planner.axis_steps_per_mm[E_AXIS_N]); }while(0)
|
||||
#define TMC_SET_PWMTHRS_E(E) do{ const uint8_t extruder = E; tmc_set_pwmthrs(stepperE##E, value, planner.axis_steps_per_mm[E_AXIS_N]); }while(0)
|
||||
|
||||
bool report = true;
|
||||
const uint8_t index = parser.byteval('I');
|
||||
|
@ -238,7 +260,7 @@ void GcodeSuite::M912() {
|
|||
#if ENABLED(SENSORLESS_HOMING)
|
||||
void GcodeSuite::M914() {
|
||||
#define TMC_SAY_SGT(Q) tmc_get_sgt(stepper##Q, TMC_##Q)
|
||||
#define TMC_SET_SGT(Q) tmc_set_sgt(stepper##Q, TMC_##Q, value)
|
||||
#define TMC_SET_SGT(Q) tmc_set_sgt(stepper##Q, value)
|
||||
|
||||
bool report = true;
|
||||
const uint8_t index = parser.byteval('I');
|
||||
|
|
|
@ -1326,7 +1326,7 @@ void MarlinSettings::postprocess() {
|
|||
#endif
|
||||
|
||||
#if ENABLED(HYBRID_THRESHOLD)
|
||||
#define TMC_SET_PWMTHRS(P,Q) tmc_set_pwmthrs(stepper##Q, TMC_##Q, tmc_hybrid_threshold[TMC_##Q], planner.axis_steps_per_mm[P##_AXIS])
|
||||
#define TMC_SET_PWMTHRS(P,Q) tmc_set_pwmthrs(stepper##Q, tmc_hybrid_threshold[TMC_##Q], planner.axis_steps_per_mm[P##_AXIS])
|
||||
uint32_t tmc_hybrid_threshold[TMC_AXES];
|
||||
EEPROM_READ(tmc_hybrid_threshold);
|
||||
if (!validating) {
|
||||
|
|
|
@ -184,6 +184,10 @@
|
|||
// 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 mA, const uint16_t microsteps, const uint32_t thrs, const float spmm) {
|
||||
#if DISABLED(STEALTHCHOP) || DISABLED(HYBRID_THRESHOLD)
|
||||
UNUSED(thrs);
|
||||
UNUSED(spmm);
|
||||
#endif
|
||||
st.begin();
|
||||
st.setCurrent(mA, R_SENSE, HOLD_MULTIPLIER);
|
||||
st.microsteps(microsteps);
|
||||
|
@ -201,9 +205,6 @@
|
|||
st.stealthChop(1);
|
||||
#if ENABLED(HYBRID_THRESHOLD)
|
||||
st.stealth_max_speed(12650000UL*microsteps/(256*thrs*spmm));
|
||||
#else
|
||||
UNUSED(thrs);
|
||||
UNUSED(spmm);
|
||||
#endif
|
||||
#elif ENABLED(SENSORLESS_HOMING)
|
||||
st.coolstep_min_speed(1024UL * 1024UL - 1UL);
|
||||
|
|
Loading…
Reference in a new issue