Fix some serial char, echo
Co-Authored-By: X-Ryl669 <3277165+X-Ryl669@users.noreply.github.com>
This commit is contained in:
parent
6dac71e618
commit
604afd52d1
@ -34,9 +34,9 @@ static bool UnwReportOut(void* ctx, const UnwReport* bte) {
|
|||||||
|
|
||||||
(*p)++;
|
(*p)++;
|
||||||
|
|
||||||
SERIAL_CHAR('#'); SERIAL_PRINT(*p, DEC); SERIAL_ECHOPGM(" : ");
|
SERIAL_CHAR('#'); SERIAL_ECHO(*p); SERIAL_ECHOPGM(" : ");
|
||||||
SERIAL_ECHOPGM(bte->name ? bte->name : "unknown"); SERIAL_ECHOPGM("@0x"); SERIAL_PRINT(bte->function, HEX);
|
SERIAL_ECHOPGM(bte->name ? bte->name : "unknown"); SERIAL_ECHOPGM("@0x"); SERIAL_PRINT(bte->function, HEX);
|
||||||
SERIAL_CHAR('+'); SERIAL_PRINT(bte->address - bte->function,DEC);
|
SERIAL_CHAR('+'); SERIAL_ECHO(bte->address - bte->function);
|
||||||
SERIAL_ECHOPGM(" PC:"); SERIAL_PRINT(bte->address,HEX); SERIAL_CHAR('\n');
|
SERIAL_ECHOPGM(" PC:"); SERIAL_PRINT(bte->address,HEX); SERIAL_CHAR('\n');
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
@ -196,7 +196,7 @@ void reset_bed_level() {
|
|||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
#ifdef SCAD_MESH_OUTPUT
|
#ifdef SCAD_MESH_OUTPUT
|
||||||
SERIAL_CHAR(' ', ']'); // close sub-array
|
SERIAL_ECHOPGM(" ]"); // close sub-array
|
||||||
if (y < sy - 1) SERIAL_CHAR(',');
|
if (y < sy - 1) SERIAL_CHAR(',');
|
||||||
#endif
|
#endif
|
||||||
SERIAL_EOL();
|
SERIAL_EOL();
|
||||||
|
@ -180,7 +180,7 @@ namespace DirectStepping {
|
|||||||
if (!page_states_dirty) return;
|
if (!page_states_dirty) return;
|
||||||
page_states_dirty = false;
|
page_states_dirty = false;
|
||||||
|
|
||||||
SERIAL_ECHO(Cfg::CONTROL_CHAR);
|
SERIAL_CHAR(Cfg::CONTROL_CHAR);
|
||||||
constexpr int state_bits = 2;
|
constexpr int state_bits = 2;
|
||||||
constexpr int n_bytes = Cfg::NUM_PAGES >> state_bits;
|
constexpr int n_bytes = Cfg::NUM_PAGES >> state_bits;
|
||||||
volatile uint8_t bits_b[n_bytes] = { 0 };
|
volatile uint8_t bits_b[n_bytes] = { 0 };
|
||||||
@ -192,10 +192,10 @@ namespace DirectStepping {
|
|||||||
uint8_t crc = 0;
|
uint8_t crc = 0;
|
||||||
for (uint8_t i = 0 ; i < n_bytes ; i++) {
|
for (uint8_t i = 0 ; i < n_bytes ; i++) {
|
||||||
crc ^= bits_b[i];
|
crc ^= bits_b[i];
|
||||||
SERIAL_ECHO(bits_b[i]);
|
SERIAL_CHAR(bits_b[i]);
|
||||||
}
|
}
|
||||||
|
|
||||||
SERIAL_ECHO(crc);
|
SERIAL_CHAR(crc);
|
||||||
SERIAL_EOL();
|
SERIAL_EOL();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -172,7 +172,7 @@ void I2CPositionEncoder::update() {
|
|||||||
float sumP = 0;
|
float sumP = 0;
|
||||||
LOOP_L_N(i, I2CPE_ERR_PRST_ARRAY_SIZE) sumP += errPrst[i];
|
LOOP_L_N(i, I2CPE_ERR_PRST_ARRAY_SIZE) sumP += errPrst[i];
|
||||||
const int32_t errorP = int32_t(sumP * RECIPROCAL(I2CPE_ERR_PRST_ARRAY_SIZE));
|
const int32_t errorP = int32_t(sumP * RECIPROCAL(I2CPE_ERR_PRST_ARRAY_SIZE));
|
||||||
SERIAL_ECHO(axis_codes[encoderAxis]);
|
SERIAL_CHAR(axis_codes[encoderAxis]);
|
||||||
SERIAL_ECHOLNPAIR(" : CORRECT ERR ", errorP * planner.steps_to_mm[encoderAxis], "mm");
|
SERIAL_ECHOLNPAIR(" : CORRECT ERR ", errorP * planner.steps_to_mm[encoderAxis], "mm");
|
||||||
babystep.add_steps(encoderAxis, -LROUND(errorP));
|
babystep.add_steps(encoderAxis, -LROUND(errorP));
|
||||||
errPrstIdx = 0;
|
errPrstIdx = 0;
|
||||||
@ -192,7 +192,7 @@ void I2CPositionEncoder::update() {
|
|||||||
if (ABS(error) > I2CPE_ERR_CNT_THRESH * planner.settings.axis_steps_per_mm[encoderAxis]) {
|
if (ABS(error) > I2CPE_ERR_CNT_THRESH * planner.settings.axis_steps_per_mm[encoderAxis]) {
|
||||||
const millis_t ms = millis();
|
const millis_t ms = millis();
|
||||||
if (ELAPSED(ms, nextErrorCountTime)) {
|
if (ELAPSED(ms, nextErrorCountTime)) {
|
||||||
SERIAL_ECHO(axis_codes[encoderAxis]);
|
SERIAL_CHAR(axis_codes[encoderAxis]);
|
||||||
SERIAL_ECHOLNPAIR(" : LARGE ERR ", int(error), "; diffSum=", diffSum);
|
SERIAL_ECHOLNPAIR(" : LARGE ERR ", int(error), "; diffSum=", diffSum);
|
||||||
errorCount++;
|
errorCount++;
|
||||||
nextErrorCountTime = ms + I2CPE_ERR_CNT_DEBOUNCE_MS;
|
nextErrorCountTime = ms + I2CPE_ERR_CNT_DEBOUNCE_MS;
|
||||||
@ -213,7 +213,7 @@ void I2CPositionEncoder::set_homed() {
|
|||||||
trusted++;
|
trusted++;
|
||||||
|
|
||||||
#ifdef I2CPE_DEBUG
|
#ifdef I2CPE_DEBUG
|
||||||
SERIAL_ECHO(axis_codes[encoderAxis]);
|
SERIAL_CHAR(axis_codes[encoderAxis]);
|
||||||
SERIAL_ECHOLNPAIR(" axis encoder homed, offset of ", zeroOffset, " ticks.");
|
SERIAL_ECHOLNPAIR(" axis encoder homed, offset of ", zeroOffset, " ticks.");
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
@ -224,7 +224,7 @@ void I2CPositionEncoder::set_unhomed() {
|
|||||||
homed = trusted = false;
|
homed = trusted = false;
|
||||||
|
|
||||||
#ifdef I2CPE_DEBUG
|
#ifdef I2CPE_DEBUG
|
||||||
SERIAL_ECHO(axis_codes[encoderAxis]);
|
SERIAL_CHAR(axis_codes[encoderAxis]);
|
||||||
SERIAL_ECHOLNPGM(" axis encoder unhomed.");
|
SERIAL_ECHOLNPGM(" axis encoder unhomed.");
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
@ -232,7 +232,7 @@ void I2CPositionEncoder::set_unhomed() {
|
|||||||
bool I2CPositionEncoder::passes_test(const bool report) {
|
bool I2CPositionEncoder::passes_test(const bool report) {
|
||||||
if (report) {
|
if (report) {
|
||||||
if (H != I2CPE_MAG_SIG_GOOD) SERIAL_ECHOPGM("Warning. ");
|
if (H != I2CPE_MAG_SIG_GOOD) SERIAL_ECHOPGM("Warning. ");
|
||||||
SERIAL_ECHO(axis_codes[encoderAxis]);
|
SERIAL_CHAR(axis_codes[encoderAxis]);
|
||||||
serial_ternary(H == I2CPE_MAG_SIG_BAD, PSTR(" axis "), PSTR("magnetic strip "), PSTR("encoder "));
|
serial_ternary(H == I2CPE_MAG_SIG_BAD, PSTR(" axis "), PSTR("magnetic strip "), PSTR("encoder "));
|
||||||
switch (H) {
|
switch (H) {
|
||||||
case I2CPE_MAG_SIG_GOOD:
|
case I2CPE_MAG_SIG_GOOD:
|
||||||
@ -253,7 +253,7 @@ float I2CPositionEncoder::get_axis_error_mm(const bool report) {
|
|||||||
error = ABS(diff) > 10000 ? 0 : diff; // Huge error is a bad reading
|
error = ABS(diff) > 10000 ? 0 : diff; // Huge error is a bad reading
|
||||||
|
|
||||||
if (report) {
|
if (report) {
|
||||||
SERIAL_ECHO(axis_codes[encoderAxis]);
|
SERIAL_CHAR(axis_codes[encoderAxis]);
|
||||||
SERIAL_ECHOLNPAIR(" axis target=", target, "mm; actual=", actual, "mm; err=", error, "mm");
|
SERIAL_ECHOLNPAIR(" axis target=", target, "mm; actual=", actual, "mm; err=", error, "mm");
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -263,7 +263,7 @@ float I2CPositionEncoder::get_axis_error_mm(const bool report) {
|
|||||||
int32_t I2CPositionEncoder::get_axis_error_steps(const bool report) {
|
int32_t I2CPositionEncoder::get_axis_error_steps(const bool report) {
|
||||||
if (!active) {
|
if (!active) {
|
||||||
if (report) {
|
if (report) {
|
||||||
SERIAL_ECHO(axis_codes[encoderAxis]);
|
SERIAL_CHAR(axis_codes[encoderAxis]);
|
||||||
SERIAL_ECHOLNPGM(" axis encoder not active!");
|
SERIAL_ECHOLNPGM(" axis encoder not active!");
|
||||||
}
|
}
|
||||||
return 0;
|
return 0;
|
||||||
@ -288,7 +288,7 @@ int32_t I2CPositionEncoder::get_axis_error_steps(const bool report) {
|
|||||||
errorPrev = error;
|
errorPrev = error;
|
||||||
|
|
||||||
if (report) {
|
if (report) {
|
||||||
SERIAL_ECHO(axis_codes[encoderAxis]);
|
SERIAL_CHAR(axis_codes[encoderAxis]);
|
||||||
SERIAL_ECHOLNPAIR(" axis target=", target, "; actual=", encoderCountInStepperTicksScaled, "; err=", error);
|
SERIAL_ECHOLNPAIR(" axis target=", target, "; actual=", encoderCountInStepperTicksScaled, "; err=", error);
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -667,8 +667,7 @@ void I2CPositionEncodersMgr::report_position(const int8_t idx, const bool units,
|
|||||||
else {
|
else {
|
||||||
if (noOffset) {
|
if (noOffset) {
|
||||||
const int32_t raw_count = encoders[idx].get_raw_count();
|
const int32_t raw_count = encoders[idx].get_raw_count();
|
||||||
SERIAL_ECHO(axis_codes[encoders[idx].get_axis()]);
|
SERIAL_CHAR(axis_codes[encoders[idx].get_axis()], ' ');
|
||||||
SERIAL_CHAR(' ');
|
|
||||||
|
|
||||||
for (uint8_t j = 31; j > 0; j--)
|
for (uint8_t j = 31; j > 0; j--)
|
||||||
SERIAL_ECHO((bool)(0x00000001 & (raw_count >> j)));
|
SERIAL_ECHO((bool)(0x00000001 & (raw_count >> j)));
|
||||||
@ -723,7 +722,7 @@ void I2CPositionEncodersMgr::change_module_address(const uint8_t oldaddr, const
|
|||||||
// and enable it (it will likely have failed initialization on power-up, before the address change).
|
// and enable it (it will likely have failed initialization on power-up, before the address change).
|
||||||
const int8_t idx = idx_from_addr(newaddr);
|
const int8_t idx = idx_from_addr(newaddr);
|
||||||
if (idx >= 0 && !encoders[idx].get_active()) {
|
if (idx >= 0 && !encoders[idx].get_active()) {
|
||||||
SERIAL_ECHO(axis_codes[encoders[idx].get_axis()]);
|
SERIAL_CHAR(axis_codes[encoders[idx].get_axis()]);
|
||||||
SERIAL_ECHOLNPGM(" axis encoder was not detected on printer startup. Trying again.");
|
SERIAL_ECHOLNPGM(" axis encoder was not detected on printer startup. Trying again.");
|
||||||
encoders[idx].set_active(encoders[idx].passes_test(true));
|
encoders[idx].set_active(encoders[idx].passes_test(true));
|
||||||
}
|
}
|
||||||
@ -748,7 +747,7 @@ void I2CPositionEncodersMgr::report_module_firmware(const uint8_t address) {
|
|||||||
if (Wire.requestFrom(I2C_ADDRESS(address), uint8_t(32))) {
|
if (Wire.requestFrom(I2C_ADDRESS(address), uint8_t(32))) {
|
||||||
char c;
|
char c;
|
||||||
while (Wire.available() > 0 && (c = (char)Wire.read()) > 0)
|
while (Wire.available() > 0 && (c = (char)Wire.read()) > 0)
|
||||||
SERIAL_ECHO(c);
|
SERIAL_CHAR(c);
|
||||||
SERIAL_EOL();
|
SERIAL_EOL();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -233,10 +233,10 @@
|
|||||||
void report_polled_driver_data(TMC &st, const TMC_driver_data &data) {
|
void report_polled_driver_data(TMC &st, const TMC_driver_data &data) {
|
||||||
const uint32_t pwm_scale = get_pwm_scale(st);
|
const uint32_t pwm_scale = get_pwm_scale(st);
|
||||||
st.printLabel();
|
st.printLabel();
|
||||||
SERIAL_CHAR(':'); SERIAL_PRINT(pwm_scale, DEC);
|
SERIAL_CHAR(':'); SERIAL_ECHO(pwm_scale);
|
||||||
#if ENABLED(TMC_DEBUG)
|
#if ENABLED(TMC_DEBUG)
|
||||||
#if HAS_TMCX1X0 || HAS_TMC220x
|
#if HAS_TMCX1X0 || HAS_TMC220x
|
||||||
SERIAL_CHAR('/'); SERIAL_PRINT(data.cs_actual, DEC);
|
SERIAL_CHAR('/'); SERIAL_ECHO(data.cs_actual);
|
||||||
#endif
|
#endif
|
||||||
#if HAS_STALLGUARD
|
#if HAS_STALLGUARD
|
||||||
SERIAL_CHAR('/');
|
SERIAL_CHAR('/');
|
||||||
@ -257,7 +257,7 @@
|
|||||||
#endif
|
#endif
|
||||||
if (st.flag_otpw) SERIAL_CHAR('F'); // otpw Flag
|
if (st.flag_otpw) SERIAL_CHAR('F'); // otpw Flag
|
||||||
SERIAL_CHAR('|');
|
SERIAL_CHAR('|');
|
||||||
if (st.otpw_count > 0) SERIAL_PRINT(st.otpw_count, DEC);
|
if (st.otpw_count > 0) SERIAL_ECHO(st.otpw_count);
|
||||||
SERIAL_CHAR('\t');
|
SERIAL_CHAR('\t');
|
||||||
}
|
}
|
||||||
|
|
||||||
@ -551,8 +551,8 @@
|
|||||||
#if HAS_DRIVER(TMC2130) || HAS_DRIVER(TMC5130)
|
#if HAS_DRIVER(TMC2130) || HAS_DRIVER(TMC5130)
|
||||||
static void _tmc_status(TMC2130Stepper &st, const TMC_debug_enum i) {
|
static void _tmc_status(TMC2130Stepper &st, const TMC_debug_enum i) {
|
||||||
switch (i) {
|
switch (i) {
|
||||||
case TMC_PWM_SCALE: SERIAL_PRINT(st.PWM_SCALE(), DEC); break;
|
case TMC_PWM_SCALE: SERIAL_ECHO(st.PWM_SCALE()); break;
|
||||||
case TMC_SGT: SERIAL_PRINT(st.sgt(), DEC); break;
|
case TMC_SGT: SERIAL_ECHO(st.sgt()); break;
|
||||||
case TMC_STEALTHCHOP: serialprint_truefalse(st.en_pwm_mode()); break;
|
case TMC_STEALTHCHOP: serialprint_truefalse(st.en_pwm_mode()); break;
|
||||||
case TMC_INTERPOLATE: serialprint_truefalse(st.intpol()); break;
|
case TMC_INTERPOLATE: serialprint_truefalse(st.intpol()); break;
|
||||||
default: break;
|
default: break;
|
||||||
@ -563,9 +563,9 @@
|
|||||||
static void _tmc_parse_drv_status(TMC2130Stepper &st, const TMC_drv_status_enum i) {
|
static void _tmc_parse_drv_status(TMC2130Stepper &st, const TMC_drv_status_enum i) {
|
||||||
switch (i) {
|
switch (i) {
|
||||||
case TMC_STALLGUARD: if (st.stallguard()) SERIAL_CHAR('*'); break;
|
case TMC_STALLGUARD: if (st.stallguard()) SERIAL_CHAR('*'); break;
|
||||||
case TMC_SG_RESULT: SERIAL_PRINT(st.sg_result(), DEC); break;
|
case TMC_SG_RESULT: SERIAL_ECHO(st.sg_result()); break;
|
||||||
case TMC_FSACTIVE: if (st.fsactive()) SERIAL_CHAR('*'); break;
|
case TMC_FSACTIVE: if (st.fsactive()) SERIAL_CHAR('*'); break;
|
||||||
case TMC_DRV_CS_ACTUAL: SERIAL_PRINT(st.cs_actual(), DEC); break;
|
case TMC_DRV_CS_ACTUAL: SERIAL_ECHO(st.cs_actual()); break;
|
||||||
default: break;
|
default: break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -580,13 +580,13 @@
|
|||||||
|
|
||||||
static void _tmc_status(TMC2160Stepper &st, const TMC_debug_enum i) {
|
static void _tmc_status(TMC2160Stepper &st, const TMC_debug_enum i) {
|
||||||
switch (i) {
|
switch (i) {
|
||||||
case TMC_PWM_SCALE: SERIAL_PRINT(st.PWM_SCALE(), DEC); break;
|
case TMC_PWM_SCALE: SERIAL_ECHO(st.PWM_SCALE()); break;
|
||||||
case TMC_SGT: SERIAL_PRINT(st.sgt(), DEC); break;
|
case TMC_SGT: SERIAL_ECHO(st.sgt()); break;
|
||||||
case TMC_STEALTHCHOP: serialprint_truefalse(st.en_pwm_mode()); break;
|
case TMC_STEALTHCHOP: serialprint_truefalse(st.en_pwm_mode()); break;
|
||||||
case TMC_GLOBAL_SCALER:
|
case TMC_GLOBAL_SCALER:
|
||||||
{
|
{
|
||||||
uint16_t value = st.GLOBAL_SCALER();
|
uint16_t value = st.GLOBAL_SCALER();
|
||||||
SERIAL_PRINT(value ?: 256, DEC);
|
SERIAL_ECHO(value ? value : 256);
|
||||||
SERIAL_ECHOPGM("/256");
|
SERIAL_ECHOPGM("/256");
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
@ -599,10 +599,10 @@
|
|||||||
#if HAS_TMC220x
|
#if HAS_TMC220x
|
||||||
static void _tmc_status(TMC2208Stepper &st, const TMC_debug_enum i) {
|
static void _tmc_status(TMC2208Stepper &st, const TMC_debug_enum i) {
|
||||||
switch (i) {
|
switch (i) {
|
||||||
case TMC_PWM_SCALE_SUM: SERIAL_PRINT(st.pwm_scale_sum(), DEC); break;
|
case TMC_PWM_SCALE_SUM: SERIAL_ECHO(st.pwm_scale_sum()); break;
|
||||||
case TMC_PWM_SCALE_AUTO: SERIAL_PRINT(st.pwm_scale_auto(), DEC); break;
|
case TMC_PWM_SCALE_AUTO: SERIAL_ECHO(st.pwm_scale_auto()); break;
|
||||||
case TMC_PWM_OFS_AUTO: SERIAL_PRINT(st.pwm_ofs_auto(), DEC); break;
|
case TMC_PWM_OFS_AUTO: SERIAL_ECHO(st.pwm_ofs_auto()); break;
|
||||||
case TMC_PWM_GRAD_AUTO: SERIAL_PRINT(st.pwm_grad_auto(), DEC); break;
|
case TMC_PWM_GRAD_AUTO: SERIAL_ECHO(st.pwm_grad_auto()); break;
|
||||||
case TMC_STEALTHCHOP: serialprint_truefalse(st.stealth()); break;
|
case TMC_STEALTHCHOP: serialprint_truefalse(st.stealth()); break;
|
||||||
case TMC_INTERPOLATE: serialprint_truefalse(st.intpol()); break;
|
case TMC_INTERPOLATE: serialprint_truefalse(st.intpol()); break;
|
||||||
default: break;
|
default: break;
|
||||||
@ -613,8 +613,8 @@
|
|||||||
template<char AXIS_LETTER, char DRIVER_ID, AxisEnum AXIS_ID>
|
template<char AXIS_LETTER, char DRIVER_ID, AxisEnum AXIS_ID>
|
||||||
static void _tmc_status(TMCMarlin<TMC2209Stepper, AXIS_LETTER, DRIVER_ID, AXIS_ID> &st, const TMC_debug_enum i) {
|
static void _tmc_status(TMCMarlin<TMC2209Stepper, AXIS_LETTER, DRIVER_ID, AXIS_ID> &st, const TMC_debug_enum i) {
|
||||||
switch (i) {
|
switch (i) {
|
||||||
case TMC_SGT: SERIAL_PRINT(st.SGTHRS(), DEC); break;
|
case TMC_SGT: SERIAL_ECHO(st.SGTHRS()); break;
|
||||||
case TMC_UART_ADDR: SERIAL_PRINT(st.get_address(), DEC); break;
|
case TMC_UART_ADDR: SERIAL_ECHO(st.get_address()); break;
|
||||||
default:
|
default:
|
||||||
TMC2208Stepper *parent = &st;
|
TMC2208Stepper *parent = &st;
|
||||||
_tmc_status(*parent, i);
|
_tmc_status(*parent, i);
|
||||||
@ -631,7 +631,7 @@
|
|||||||
case TMC_T120: if (st.t120()) SERIAL_CHAR('*'); break;
|
case TMC_T120: if (st.t120()) SERIAL_CHAR('*'); break;
|
||||||
case TMC_S2VSA: if (st.s2vsa()) SERIAL_CHAR('*'); break;
|
case TMC_S2VSA: if (st.s2vsa()) SERIAL_CHAR('*'); break;
|
||||||
case TMC_S2VSB: if (st.s2vsb()) SERIAL_CHAR('*'); break;
|
case TMC_S2VSB: if (st.s2vsb()) SERIAL_CHAR('*'); break;
|
||||||
case TMC_DRV_CS_ACTUAL: SERIAL_PRINT(st.cs_actual(), DEC); break;
|
case TMC_DRV_CS_ACTUAL: SERIAL_ECHO(st.cs_actual()); break;
|
||||||
default: break;
|
default: break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -639,7 +639,7 @@
|
|||||||
#if HAS_DRIVER(TMC2209)
|
#if HAS_DRIVER(TMC2209)
|
||||||
static void _tmc_parse_drv_status(TMC2209Stepper &st, const TMC_drv_status_enum i) {
|
static void _tmc_parse_drv_status(TMC2209Stepper &st, const TMC_drv_status_enum i) {
|
||||||
switch (i) {
|
switch (i) {
|
||||||
case TMC_SG_RESULT: SERIAL_PRINT(st.SG_RESULT(), DEC); break;
|
case TMC_SG_RESULT: SERIAL_ECHO(st.SG_RESULT()); break;
|
||||||
default: _tmc_parse_drv_status(static_cast<TMC2208Stepper &>(st), i); break;
|
default: _tmc_parse_drv_status(static_cast<TMC2208Stepper &>(st), i); break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -666,15 +666,15 @@
|
|||||||
case TMC_RMS_CURRENT: SERIAL_ECHO(st.rms_current()); break;
|
case TMC_RMS_CURRENT: SERIAL_ECHO(st.rms_current()); break;
|
||||||
case TMC_MAX_CURRENT: SERIAL_PRINT((float)st.rms_current() * 1.41, 0); break;
|
case TMC_MAX_CURRENT: SERIAL_PRINT((float)st.rms_current() * 1.41, 0); break;
|
||||||
case TMC_IRUN:
|
case TMC_IRUN:
|
||||||
SERIAL_PRINT(st.irun(), DEC);
|
SERIAL_ECHO(st.irun());
|
||||||
SERIAL_ECHOPGM("/31");
|
SERIAL_ECHOPGM("/31");
|
||||||
break;
|
break;
|
||||||
case TMC_IHOLD:
|
case TMC_IHOLD:
|
||||||
SERIAL_PRINT(st.ihold(), DEC);
|
SERIAL_ECHO(st.ihold());
|
||||||
SERIAL_ECHOPGM("/31");
|
SERIAL_ECHOPGM("/31");
|
||||||
break;
|
break;
|
||||||
case TMC_CS_ACTUAL:
|
case TMC_CS_ACTUAL:
|
||||||
SERIAL_PRINT(st.cs_actual(), DEC);
|
SERIAL_ECHO(st.cs_actual());
|
||||||
SERIAL_ECHOPGM("/31");
|
SERIAL_ECHOPGM("/31");
|
||||||
break;
|
break;
|
||||||
case TMC_VSENSE: print_vsense(st); break;
|
case TMC_VSENSE: print_vsense(st); break;
|
||||||
@ -694,11 +694,11 @@
|
|||||||
#if ENABLED(MONITOR_DRIVER_STATUS)
|
#if ENABLED(MONITOR_DRIVER_STATUS)
|
||||||
case TMC_OTPW_TRIGGERED: serialprint_truefalse(st.getOTPW()); break;
|
case TMC_OTPW_TRIGGERED: serialprint_truefalse(st.getOTPW()); break;
|
||||||
#endif
|
#endif
|
||||||
case TMC_TOFF: SERIAL_PRINT(st.toff(), DEC); break;
|
case TMC_TOFF: SERIAL_ECHO(st.toff()); break;
|
||||||
case TMC_TBL: SERIAL_PRINT(st.blank_time(), DEC); break;
|
case TMC_TBL: SERIAL_ECHO(st.blank_time()); break;
|
||||||
case TMC_HEND: SERIAL_PRINT(st.hysteresis_end(), DEC); break;
|
case TMC_HEND: SERIAL_ECHO(st.hysteresis_end()); break;
|
||||||
case TMC_HSTRT: SERIAL_PRINT(st.hysteresis_start(), DEC); break;
|
case TMC_HSTRT: SERIAL_ECHO(st.hysteresis_start()); break;
|
||||||
case TMC_MSCNT: SERIAL_PRINT(st.get_microstep_counter(), DEC); break;
|
case TMC_MSCNT: SERIAL_ECHO(st.get_microstep_counter()); break;
|
||||||
default: _tmc_status(st, i); break;
|
default: _tmc_status(st, i); break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
@ -714,18 +714,18 @@
|
|||||||
case TMC_RMS_CURRENT: SERIAL_ECHO(st.rms_current()); break;
|
case TMC_RMS_CURRENT: SERIAL_ECHO(st.rms_current()); break;
|
||||||
case TMC_MAX_CURRENT: SERIAL_PRINT((float)st.rms_current() * 1.41, 0); break;
|
case TMC_MAX_CURRENT: SERIAL_PRINT((float)st.rms_current() * 1.41, 0); break;
|
||||||
case TMC_IRUN:
|
case TMC_IRUN:
|
||||||
SERIAL_PRINT(st.cs(), DEC);
|
SERIAL_ECHO(st.cs());
|
||||||
SERIAL_ECHOPGM("/31");
|
SERIAL_ECHOPGM("/31");
|
||||||
break;
|
break;
|
||||||
case TMC_VSENSE: serialprintPGM(st.vsense() ? PSTR("1=.165") : PSTR("0=.310")); break;
|
case TMC_VSENSE: serialprintPGM(st.vsense() ? PSTR("1=.165") : PSTR("0=.310")); break;
|
||||||
case TMC_MICROSTEPS: SERIAL_ECHO(st.microsteps()); break;
|
case TMC_MICROSTEPS: SERIAL_ECHO(st.microsteps()); break;
|
||||||
//case TMC_OTPW: serialprint_truefalse(st.otpw()); break;
|
//case TMC_OTPW: serialprint_truefalse(st.otpw()); break;
|
||||||
//case TMC_OTPW_TRIGGERED: serialprint_truefalse(st.getOTPW()); break;
|
//case TMC_OTPW_TRIGGERED: serialprint_truefalse(st.getOTPW()); break;
|
||||||
case TMC_SGT: SERIAL_PRINT(st.sgt(), DEC); break;
|
case TMC_SGT: SERIAL_ECHO(st.sgt()); break;
|
||||||
case TMC_TOFF: SERIAL_PRINT(st.toff(), DEC); break;
|
case TMC_TOFF: SERIAL_ECHO(st.toff()); break;
|
||||||
case TMC_TBL: SERIAL_PRINT(st.blank_time(), DEC); break;
|
case TMC_TBL: SERIAL_ECHO(st.blank_time()); break;
|
||||||
case TMC_HEND: SERIAL_PRINT(st.hysteresis_end(), DEC); break;
|
case TMC_HEND: SERIAL_ECHO(st.hysteresis_end()); break;
|
||||||
case TMC_HSTRT: SERIAL_PRINT(st.hysteresis_start(), DEC); break;
|
case TMC_HSTRT: SERIAL_ECHO(st.hysteresis_start()); break;
|
||||||
default: break;
|
default: break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -43,7 +43,7 @@
|
|||||||
void GcodeSuite::M900() {
|
void GcodeSuite::M900() {
|
||||||
|
|
||||||
auto echo_value_oor = [](const char ltr, const bool ten=true) {
|
auto echo_value_oor = [](const char ltr, const bool ten=true) {
|
||||||
SERIAL_CHAR('?'); SERIAL_CHAR(ltr);
|
SERIAL_CHAR('?', ltr);
|
||||||
SERIAL_ECHOPGM(" value out of range");
|
SERIAL_ECHOPGM(" value out of range");
|
||||||
if (ten) SERIAL_ECHOPGM(" (0-10)");
|
if (ten) SERIAL_ECHOPGM(" (0-10)");
|
||||||
SERIAL_ECHOLNPGM(".");
|
SERIAL_ECHOLNPGM(".");
|
||||||
|
@ -298,10 +298,9 @@ void GCodeQueue::ok_to_send() {
|
|||||||
#if ENABLED(ADVANCED_OK)
|
#if ENABLED(ADVANCED_OK)
|
||||||
char* p = command_buffer[index_r];
|
char* p = command_buffer[index_r];
|
||||||
if (*p == 'N') {
|
if (*p == 'N') {
|
||||||
SERIAL_ECHO(' ');
|
SERIAL_CHAR(' ', *p++);
|
||||||
SERIAL_ECHO(*p++);
|
|
||||||
while (NUMERIC_SIGNED(*p))
|
while (NUMERIC_SIGNED(*p))
|
||||||
SERIAL_ECHO(*p++);
|
SERIAL_CHAR(*p++);
|
||||||
}
|
}
|
||||||
SERIAL_ECHOPAIR_P(SP_P_STR, int(planner.moves_free()),
|
SERIAL_ECHOPAIR_P(SP_P_STR, int(planner.moves_free()),
|
||||||
SP_B_STR, int(BUFSIZE - length));
|
SP_B_STR, int(BUFSIZE - length));
|
||||||
|
@ -141,9 +141,7 @@ void AnycubicTFTClass::OnKillTFT() {
|
|||||||
|
|
||||||
void AnycubicTFTClass::OnSDCardStateChange(bool isInserted) {
|
void AnycubicTFTClass::OnSDCardStateChange(bool isInserted) {
|
||||||
#if ENABLED(ANYCUBIC_LCD_DEBUG)
|
#if ENABLED(ANYCUBIC_LCD_DEBUG)
|
||||||
SERIAL_ECHOPGM("TFT Serial Debug: OnSDCardStateChange event triggered...");
|
SERIAL_ECHOLNPAIR("TFT Serial Debug: OnSDCardStateChange event triggered...", (int)isInserted);
|
||||||
SERIAL_ECHO(ui8tostr2(isInserted));
|
|
||||||
SERIAL_EOL();
|
|
||||||
#endif
|
#endif
|
||||||
DoSDCardStateCheck();
|
DoSDCardStateCheck();
|
||||||
}
|
}
|
||||||
@ -164,8 +162,7 @@ void AnycubicTFTClass::OnFilamentRunout() {
|
|||||||
|
|
||||||
void AnycubicTFTClass::OnUserConfirmRequired(const char * const msg) {
|
void AnycubicTFTClass::OnUserConfirmRequired(const char * const msg) {
|
||||||
#if ENABLED(ANYCUBIC_LCD_DEBUG)
|
#if ENABLED(ANYCUBIC_LCD_DEBUG)
|
||||||
SERIAL_ECHOPGM("TFT Serial Debug: OnUserConfirmRequired triggered... ");
|
SERIAL_ECHOLNPAIR("TFT Serial Debug: OnUserConfirmRequired triggered... ", msg);
|
||||||
SERIAL_ECHOLN(msg);
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if ENABLED(SDSUPPORT)
|
#if ENABLED(SDSUPPORT)
|
||||||
|
@ -369,7 +369,7 @@ void CardReader::printFilename() {
|
|||||||
#if ENABLED(LONG_FILENAME_HOST_SUPPORT)
|
#if ENABLED(LONG_FILENAME_HOST_SUPPORT)
|
||||||
selectFileByName(dosFilename);
|
selectFileByName(dosFilename);
|
||||||
if (longFilename[0]) {
|
if (longFilename[0]) {
|
||||||
SERIAL_ECHO(' ');
|
SERIAL_CHAR(' ');
|
||||||
SERIAL_ECHO(longFilename);
|
SERIAL_ECHO(longFilename);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
Loading…
Reference in New Issue
Block a user