Serial refactor. Default 8-bit ECHO to int, not char (#20985)

Co-authored-by: Scott Lahteine <thinkyhead@users.noreply.github.com>
This commit is contained in:
X-Ryl669 2021-02-08 07:37:24 +01:00 committed by GitHub
parent 1e726fe405
commit e7c711996b
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
72 changed files with 379 additions and 337 deletions

View File

@ -595,7 +595,7 @@ MSerialT customizedSerial1(MSerialT::HasEmergencyParser);
MarlinSerial<MMU2SerialCfg<MMU2_SERIAL_PORT>>::_tx_udr_empty_irq(); MarlinSerial<MMU2SerialCfg<MMU2_SERIAL_PORT>>::_tx_udr_empty_irq();
} }
template class MarlinSerial< MarlinSerialCfg<MMU2_SERIAL_PORT> >; template class MarlinSerial< MMU2SerialCfg<MMU2_SERIAL_PORT> >;
MSerialT3 mmuSerial(MSerialT3::HasEmergencyParser); MSerialT3 mmuSerial(MSerialT3::HasEmergencyParser);
#endif #endif

View File

@ -263,7 +263,7 @@
}; };
typedef Serial0Type< MarlinSerial< MMU2SerialCfg<MMU2_SERIAL_PORT> > > MSerialT3; typedef Serial0Type< MarlinSerial< MMU2SerialCfg<MMU2_SERIAL_PORT> > > MSerialT3;
extern MSerial3 mmuSerial; extern MSerialT3 mmuSerial;
#endif #endif
#ifdef LCD_SERIAL_PORT #ifdef LCD_SERIAL_PORT

View File

@ -235,8 +235,8 @@ static void print_is_also_tied() { SERIAL_ECHOPGM(" is also tied to this pin");
inline void com_print(const uint8_t N, const uint8_t Z) { inline void com_print(const uint8_t N, const uint8_t Z) {
const uint8_t *TCCRA = (uint8_t*)TCCR_A(N); const uint8_t *TCCRA = (uint8_t*)TCCR_A(N);
SERIAL_ECHOPGM(" COM"); SERIAL_ECHOPAIR(" COM", AS_CHAR('0' + N));
SERIAL_CHAR('0' + N, Z); SERIAL_CHAR(Z);
SERIAL_ECHOPAIR(": ", int((*TCCRA >> (6 - Z * 2)) & 0x03)); SERIAL_ECHOPAIR(": ", int((*TCCRA >> (6 - Z * 2)) & 0x03));
} }
@ -247,8 +247,8 @@ void timer_prefix(uint8_t T, char L, uint8_t N) { // T - timer L - pwm N -
uint8_t WGM = (((*TCCRB & _BV(WGM_2)) >> 1) | (*TCCRA & (_BV(WGM_0) | _BV(WGM_1)))); uint8_t WGM = (((*TCCRB & _BV(WGM_2)) >> 1) | (*TCCRA & (_BV(WGM_0) | _BV(WGM_1))));
if (N == 4) WGM |= ((*TCCRB & _BV(WGM_3)) >> 1); if (N == 4) WGM |= ((*TCCRB & _BV(WGM_3)) >> 1);
SERIAL_ECHOPGM(" TIMER"); SERIAL_ECHOPAIR(" TIMER", AS_CHAR(T + '0'));
SERIAL_CHAR(T + '0', L); SERIAL_CHAR(L);
SERIAL_ECHO_SP(3); SERIAL_ECHO_SP(3);
if (N == 3) { if (N == 3) {
@ -262,19 +262,11 @@ void timer_prefix(uint8_t T, char L, uint8_t N) { // T - timer L - pwm N -
SERIAL_ECHOPAIR(" WGM: ", WGM); SERIAL_ECHOPAIR(" WGM: ", WGM);
com_print(T,L); com_print(T,L);
SERIAL_ECHOPAIR(" CS: ", (*TCCRB & (_BV(CS_0) | _BV(CS_1) | _BV(CS_2)) )); SERIAL_ECHOPAIR(" CS: ", (*TCCRB & (_BV(CS_0) | _BV(CS_1) | _BV(CS_2)) ));
SERIAL_ECHOPAIR(" TCCR", AS_CHAR(T + '0'), "A: ", *TCCRA);
SERIAL_ECHOPGM(" TCCR"); SERIAL_ECHOPAIR(" TCCR", AS_CHAR(T + '0'), "B: ", *TCCRB);
SERIAL_CHAR(T + '0');
SERIAL_ECHOPAIR("A: ", *TCCRA);
SERIAL_ECHOPGM(" TCCR");
SERIAL_CHAR(T + '0');
SERIAL_ECHOPAIR("B: ", *TCCRB);
const uint8_t *TMSK = (uint8_t*)TIMSK(T); const uint8_t *TMSK = (uint8_t*)TIMSK(T);
SERIAL_ECHOPGM(" TIMSK"); SERIAL_ECHOPAIR(" TIMSK", AS_CHAR(T + '0'), ": ", *TMSK);
SERIAL_CHAR(T + '0');
SERIAL_ECHOPAIR(": ", *TMSK);
const uint8_t OCIE = L - 'A' + 1; const uint8_t OCIE = L - 'A' + 1;
if (N == 3) { if (WGM == 0 || WGM == 2 || WGM == 4 || WGM == 6) err_is_counter(); } if (N == 3) { if (WGM == 0 || WGM == 2 || WGM == 4 || WGM == 6) err_is_counter(); }

View File

@ -33,10 +33,6 @@
#include "MarlinSerialUSB.h" #include "MarlinSerialUSB.h"
#if ENABLED(EMERGENCY_PARSER)
#include "../../feature/e_parser.h"
#endif
// Imports from Atmel USB Stack/CDC implementation // Imports from Atmel USB Stack/CDC implementation
extern "C" { extern "C" {
bool usb_task_cdc_isenabled(); bool usb_task_cdc_isenabled();
@ -69,7 +65,7 @@ int MarlinSerialUSB::peek() {
pending_char = udi_cdc_getc(); pending_char = udi_cdc_getc();
TERN_(EMERGENCY_PARSER, emergency_parser.update(emergency_state, (char)pending_char)); TERN_(EMERGENCY_PARSER, emergency_parser.update(static_cast<MSerialT*>(this)->emergency_state, (char)pending_char));
return pending_char; return pending_char;
} }
@ -91,7 +87,7 @@ int MarlinSerialUSB::read() {
int c = udi_cdc_getc(); int c = udi_cdc_getc();
TERN_(EMERGENCY_PARSER, emergency_parser.update(emergency_state, (char)c)); TERN_(EMERGENCY_PARSER, emergency_parser.update(static_cast<MSerialT*>(this)->emergency_state, (char)c));
return c; return c;
} }
@ -105,7 +101,6 @@ bool MarlinSerialUSB::available() {
} }
void MarlinSerialUSB::flush() { } void MarlinSerialUSB::flush() { }
void MarlinSerialUSB::flushTX() { }
size_t MarlinSerialUSB::write(const uint8_t c) { size_t MarlinSerialUSB::write(const uint8_t c) {

View File

@ -34,21 +34,20 @@
struct MarlinSerialUSB { struct MarlinSerialUSB {
static void begin(const long); void begin(const long);
static void end(); void end();
static int peek(); int peek();
static int read(); int read();
static void flush(); void flush();
static void flushTX(); bool available();
static bool available(); size_t write(const uint8_t c);
static size_t write(const uint8_t c);
#if ENABLED(SERIAL_STATS_DROPPED_RX) #if ENABLED(SERIAL_STATS_DROPPED_RX)
FORCE_INLINE static uint32_t dropped() { return 0; } FORCE_INLINE uint32_t dropped() { return 0; }
#endif #endif
#if ENABLED(SERIAL_STATS_MAX_RX_QUEUED) #if ENABLED(SERIAL_STATS_MAX_RX_QUEUED)
FORCE_INLINE static int rxMaxEnqueued() { return 0; } FORCE_INLINE int rxMaxEnqueued() { return 0; }
#endif #endif
}; };
typedef Serial0Type<MarlinSerialUSB> MSerialT; typedef Serial0Type<MarlinSerialUSB> MSerialT;

View File

@ -84,16 +84,16 @@ static void debug_rw(const bool write, int &pos, const uint8_t *value, const siz
PGM_P const rw_str = write ? PSTR("write") : PSTR("read"); PGM_P const rw_str = write ? PSTR("write") : PSTR("read");
SERIAL_CHAR(' '); SERIAL_CHAR(' ');
serialprintPGM(rw_str); serialprintPGM(rw_str);
SERIAL_ECHOLNPAIR("_data(", pos, ",", int(value), ",", int(size), ", ...)"); SERIAL_ECHOLNPAIR("_data(", pos, ",", value, ",", size, ", ...)");
if (total) { if (total) {
SERIAL_ECHOPGM(" f_"); SERIAL_ECHOPGM(" f_");
serialprintPGM(rw_str); serialprintPGM(rw_str);
SERIAL_ECHOPAIR("()=", int(s), "\n size=", int(size), "\n bytes_"); SERIAL_ECHOPAIR("()=", s, "\n size=", size, "\n bytes_");
serialprintPGM(write ? PSTR("written=") : PSTR("read=")); serialprintPGM(write ? PSTR("written=") : PSTR("read="));
SERIAL_ECHOLN(total); SERIAL_ECHOLN(total);
} }
else else
SERIAL_ECHOLNPAIR(" f_lseek()=", int(s)); SERIAL_ECHOLNPAIR(" f_lseek()=", s);
} }
// File function return codes for type FRESULT. This goes away soon, but // File function return codes for type FRESULT. This goes away soon, but

View File

@ -28,10 +28,6 @@
#include "../../inc/MarlinConfigPre.h" #include "../../inc/MarlinConfigPre.h"
#include "../../core/serial_hook.h" #include "../../core/serial_hook.h"
#if HAS_TFT_LVGL_UI
extern "C" { extern char public_buf_m[100]; }
#endif
// Increase priority of serial interrupts, to reduce overflow errors // Increase priority of serial interrupts, to reduce overflow errors
#define UART_IRQ_PRIO 1 #define UART_IRQ_PRIO 1
@ -49,28 +45,6 @@ struct MarlinSerial : public HardwareSerial {
nvic_irq_set_priority(c_dev()->irq_num, UART_IRQ_PRIO); nvic_irq_set_priority(c_dev()->irq_num, UART_IRQ_PRIO);
} }
#endif #endif
#if HAS_TFT_LVGL_UI
// Hook the serial write method to capture the output of GCode command sent via LCD
uint32_t current_wpos;
void (*line_callback)(void *, const char * msg);
void *user_pointer;
void set_hook(void (*hook)(void *, const char *), void * that) { line_callback = hook; user_pointer = that; current_wpos = 0; }
size_t write(uint8_t c) {
if (line_callback) {
if (c == '\n' || current_wpos == sizeof(public_buf_m) - 1) { // End of line, probably end of command anyway
public_buf_m[current_wpos] = 0;
line_callback(user_pointer, public_buf_m);
current_wpos = 0;
}
else
public_buf_m[current_wpos++] = c;
}
return HardwareSerial::write(c);
}
#endif
}; };
typedef Serial0Type<MarlinSerial> MSerialT; typedef Serial0Type<MarlinSerial> MSerialT;

View File

@ -35,9 +35,9 @@ static bool UnwReportOut(void* ctx, const UnwReport* bte) {
(*p)++; (*p)++;
SERIAL_CHAR('#'); SERIAL_ECHO(*p); 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, PrintBase::Hex);
SERIAL_CHAR('+'); SERIAL_ECHO(bte->address - bte->function); 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, PrintBase::Hex); SERIAL_CHAR('\n');
return true; return true;
} }

View File

@ -1003,7 +1003,7 @@ void setup() {
); );
#endif #endif
SERIAL_ECHO_MSG("Compiled: " __DATE__); SERIAL_ECHO_MSG("Compiled: " __DATE__);
SERIAL_ECHO_MSG(STR_FREE_MEMORY, freeMemory(), STR_PLANNER_BUFFER_BYTES, (int)sizeof(block_t) * (BLOCK_BUFFER_SIZE)); SERIAL_ECHO_MSG(STR_FREE_MEMORY, freeMemory(), STR_PLANNER_BUFFER_BYTES, sizeof(block_t) * (BLOCK_BUFFER_SIZE));
// Some HAL need precise delay adjustment // Some HAL need precise delay adjustment
calibrate_delay_loop(); calibrate_delay_loop();

View File

@ -321,6 +321,12 @@
namespace Private { namespace Private {
template<bool, typename _Tp = void> struct enable_if { }; template<bool, typename _Tp = void> struct enable_if { };
template<typename _Tp> struct enable_if<true, _Tp> { typedef _Tp type; }; template<typename _Tp> struct enable_if<true, _Tp> { typedef _Tp type; };
template<typename T, typename U> struct is_same { enum { value = false }; };
template<typename T> struct is_same<T, T> { enum { value = true }; };
template <typename T, typename ... Args> struct first_type_of { typedef T type; };
template <typename T> struct first_type_of<T> { typedef T type; };
} }
// C++11 solution using SFINAE to detect the existance of a member in a class at compile time. // C++11 solution using SFINAE to detect the existance of a member in a class at compile time.
// It creates a HasMember<Type> structure containing 'value' set to true if the member exists // It creates a HasMember<Type> structure containing 'value' set to true if the member exists

View File

@ -59,12 +59,14 @@ void serialprintPGM(PGM_P str) {
void serial_echo_start() { static PGMSTR(echomagic, "echo:"); serialprintPGM(echomagic); } void serial_echo_start() { static PGMSTR(echomagic, "echo:"); serialprintPGM(echomagic); }
void serial_error_start() { static PGMSTR(errormagic, "Error:"); serialprintPGM(errormagic); } void serial_error_start() { static PGMSTR(errormagic, "Error:"); serialprintPGM(errormagic); }
void serial_echopair_PGM(PGM_P const s_P, serial_char_t v) { serialprintPGM(s_P); SERIAL_CHAR(v.c); }
void serial_echopair_PGM(PGM_P const s_P, const char *v) { serialprintPGM(s_P); SERIAL_ECHO(v); } void serial_echopair_PGM(PGM_P const s_P, const char *v) { serialprintPGM(s_P); SERIAL_ECHO(v); }
void serial_echopair_PGM(PGM_P const s_P, char v) { serialprintPGM(s_P); SERIAL_CHAR(v); } void serial_echopair_PGM(PGM_P const s_P, char v) { serialprintPGM(s_P); SERIAL_ECHO(v); }
void serial_echopair_PGM(PGM_P const s_P, int v) { serialprintPGM(s_P); SERIAL_ECHO(v); } void serial_echopair_PGM(PGM_P const s_P, int v) { serialprintPGM(s_P); SERIAL_ECHO(v); }
void serial_echopair_PGM(PGM_P const s_P, long v) { serialprintPGM(s_P); SERIAL_ECHO(v); } void serial_echopair_PGM(PGM_P const s_P, long v) { serialprintPGM(s_P); SERIAL_ECHO(v); }
void serial_echopair_PGM(PGM_P const s_P, float v) { serialprintPGM(s_P); SERIAL_DECIMAL(v); } void serial_echopair_PGM(PGM_P const s_P, float v) { serialprintPGM(s_P); SERIAL_DECIMAL(v); }
void serial_echopair_PGM(PGM_P const s_P, double v) { serialprintPGM(s_P); SERIAL_DECIMAL(v); } void serial_echopair_PGM(PGM_P const s_P, double v) { serialprintPGM(s_P); SERIAL_DECIMAL(v); }
void serial_echopair_PGM(PGM_P const s_P, unsigned char v) { serialprintPGM(s_P); SERIAL_ECHO(v); }
void serial_echopair_PGM(PGM_P const s_P, unsigned int v) { serialprintPGM(s_P); SERIAL_ECHO(v); } void serial_echopair_PGM(PGM_P const s_P, unsigned int v) { serialprintPGM(s_P); SERIAL_ECHO(v); }
void serial_echopair_PGM(PGM_P const s_P, unsigned long v) { serialprintPGM(s_P); SERIAL_ECHO(v); } void serial_echopair_PGM(PGM_P const s_P, unsigned long v) { serialprintPGM(s_P); SERIAL_ECHO(v); }

View File

@ -81,37 +81,49 @@ typedef int8_t serial_index_t;
#define PORT_REDIRECT(p) _PORT_REDIRECT(1,p) #define PORT_REDIRECT(p) _PORT_REDIRECT(1,p)
#define SERIAL_PORTMASK(P) _BV(P) #define SERIAL_PORTMASK(P) _BV(P)
#define SERIAL_ECHO(x) SERIAL_OUT(print, x) //
#define SERIAL_ECHO_F(V...) SERIAL_OUT(print, V) // SERIAL_CHAR - Print one or more individual chars
#define SERIAL_ECHOLN(x) SERIAL_OUT(println, x) //
#define SERIAL_PRINT(x,b) SERIAL_OUT(print, x, b) inline void SERIAL_CHAR(char a) { SERIAL_IMPL.write(a); }
#define SERIAL_PRINTLN(x,b) SERIAL_OUT(println, x, b) template <typename ... Args>
#define SERIAL_FLUSH() SERIAL_OUT(flush) void SERIAL_CHAR(char a, Args ... args) { SERIAL_IMPL.write(a); SERIAL_CHAR(args ...); }
#ifdef ARDUINO_ARCH_STM32 /**
#define SERIAL_FLUSHTX() SERIAL_OUT(flush) * SERIAL_ECHO - Print a single string or value.
#elif TX_BUFFER_SIZE > 0 * Any numeric parameter (including char) is printed as a base-10 number.
#define SERIAL_FLUSHTX() SERIAL_OUT(flushTX) * A string pointer or literal will be output as a string.
#else *
#define SERIAL_FLUSHTX() * NOTE: Use SERIAL_CHAR to print char as a single character.
#endif */
template <typename T>
void SERIAL_ECHO(T x) { SERIAL_IMPL.print(x); }
// Print up to 10 chars from a list // Wrapper for ECHO commands to interpret a char
#define __CHAR_N(N,V...) _CHAR_##N(V) typedef struct SerialChar { char c; SerialChar(char n) : c(n) { } } serial_char_t;
#define _CHAR_N(N,V...) __CHAR_N(N,V) inline void SERIAL_ECHO(serial_char_t x) { SERIAL_IMPL.write(x.c); }
#define _CHAR_1(c) SERIAL_OUT(write, c) #define AS_CHAR(C) serial_char_t(C)
#define _CHAR_2(a,b) do{ _CHAR_1(a); _CHAR_1(b); }while(0)
#define _CHAR_3(a,V...) do{ _CHAR_1(a); _CHAR_2(V); }while(0)
#define _CHAR_4(a,V...) do{ _CHAR_1(a); _CHAR_3(V); }while(0)
#define _CHAR_5(a,V...) do{ _CHAR_1(a); _CHAR_4(V); }while(0)
#define _CHAR_6(a,V...) do{ _CHAR_1(a); _CHAR_5(V); }while(0)
#define _CHAR_7(a,V...) do{ _CHAR_1(a); _CHAR_6(V); }while(0)
#define _CHAR_8(a,V...) do{ _CHAR_1(a); _CHAR_7(V); }while(0)
#define _CHAR_9(a,V...) do{ _CHAR_1(a); _CHAR_8(V); }while(0)
#define _CHAR_10(a,V...) do{ _CHAR_1(a); _CHAR_9(V); }while(0)
#define SERIAL_CHAR(V...) _CHAR_N(NUM_ARGS(V),V) // SERIAL_ECHO_F prints a floating point value with optional precision
inline void SERIAL_ECHO_F(EnsureDouble x, int digit = 2) { SERIAL_IMPL.print(x, digit); }
template <typename T>
void SERIAL_ECHOLN(T x) { SERIAL_IMPL.println(x); }
// SERIAL_PRINT works like SERIAL_ECHO but allow to specify the encoding base of the number printed
template <typename T, typename U>
void SERIAL_PRINT(T x, U y) { SERIAL_IMPL.print(x, y); }
template <typename T, typename U>
void SERIAL_PRINTLN(T x, U y) { SERIAL_IMPL.println(x, y); }
// Flush the serial port
inline void SERIAL_FLUSH() { SERIAL_IMPL.flush(); }
inline void SERIAL_FLUSHTX() { SERIAL_IMPL.flushTX(); }
// Print a single PROGMEM string to serial
void serialprintPGM(PGM_P str);
// SERIAL_ECHOPAIR / SERIAL_ECHOPAIR_P is used to output a key value pair. The key must be a string and the value can be anything
// Print up to 12 pairs of values. Odd elements auto-wrapped in PSTR(). // Print up to 12 pairs of values. Odd elements auto-wrapped in PSTR().
#define __SEP_N(N,V...) _SEP_##N(V) #define __SEP_N(N,V...) _SEP_##N(V)
#define _SEP_N(N,V...) __SEP_N(N,V) #define _SEP_N(N,V...) __SEP_N(N,V)
@ -170,6 +182,7 @@ typedef int8_t serial_index_t;
#define _SEP_23_P(a,b,V...) do{ _SEP_2_P(a,b); _SEP_21_P(V); }while(0) #define _SEP_23_P(a,b,V...) do{ _SEP_2_P(a,b); _SEP_21_P(V); }while(0)
#define _SEP_24_P(a,b,V...) do{ _SEP_2_P(a,b); _SEP_22_P(V); }while(0) #define _SEP_24_P(a,b,V...) do{ _SEP_2_P(a,b); _SEP_22_P(V); }while(0)
// SERIAL_ECHOPAIR_P is used to output a key value pair. Unlike SERIAL_ECHOPAIR, the key must be a PGM string already and the value can be anything
#define SERIAL_ECHOPAIR_P(V...) _SEP_N_P(NUM_ARGS(V),V) #define SERIAL_ECHOPAIR_P(V...) _SEP_N_P(NUM_ARGS(V),V)
// Print up to 12 pairs of values followed by newline // Print up to 12 pairs of values followed by newline
@ -244,32 +257,39 @@ typedef int8_t serial_index_t;
#define SERIAL_ECHOLNPAIR_P(V...) _SELP_N_P(NUM_ARGS(V),V) #define SERIAL_ECHOLNPAIR_P(V...) _SELP_N_P(NUM_ARGS(V),V)
// Print up to 20 comma-separated pairs of values #ifdef AllowDifferentTypeInList
#define __SLST_N(N,V...) _SLST_##N(V)
#define _SLST_N(N,V...) __SLST_N(N,V)
#define _SLST_1(a) SERIAL_ECHO(a)
#define _SLST_2(a,b) do{ SERIAL_ECHO(a); SERIAL_ECHOPAIR(", ",b); }while(0)
#define _SLST_3(a,b,c) do{ SERIAL_ECHO(a); _SEP_2(", ",b); _SLST_1(c); }while(0)
#define _SLST_4(a,b,V...) do{ SERIAL_ECHO(a); _SEP_2(", ",b); _SLST_2(V); }while(0)
#define _SLST_5(a,b,V...) do{ SERIAL_ECHO(a); _SEP_2(", ",b); _SLST_3(V); }while(0)
#define _SLST_6(a,b,V...) do{ SERIAL_ECHO(a); _SEP_2(", ",b); _SLST_4(V); }while(0)
#define _SLST_7(a,b,V...) do{ SERIAL_ECHO(a); _SEP_2(", ",b); _SLST_5(V); }while(0)
#define _SLST_8(a,b,V...) do{ SERIAL_ECHO(a); _SEP_2(", ",b); _SLST_6(V); }while(0)
#define _SLST_9(a,b,V...) do{ SERIAL_ECHO(a); _SEP_2(", ",b); _SLST_7(V); }while(0)
#define _SLST_10(a,b,V...) do{ SERIAL_ECHO(a); _SEP_2(", ",b); _SLST_8(V); }while(0)
#define _SLST_11(a,b,V...) do{ SERIAL_ECHO(a); _SEP_2(", ",b); _SLST_9(V); }while(0)
#define _SLST_12(a,b,V...) do{ SERIAL_ECHO(a); _SEP_2(", ",b); _SLST_10(V); }while(0)
#define _SLST_13(a,b,V...) do{ SERIAL_ECHO(a); _SEP_2(", ",b); _SLST_11(V); }while(0)
#define _SLST_14(a,b,V...) do{ SERIAL_ECHO(a); _SEP_2(", ",b); _SLST_12(V); }while(0)
#define _SLST_15(a,b,V...) do{ SERIAL_ECHO(a); _SEP_2(", ",b); _SLST_13(V); }while(0)
#define _SLST_16(a,b,V...) do{ SERIAL_ECHO(a); _SEP_2(", ",b); _SLST_14(V); }while(0)
#define _SLST_17(a,b,V...) do{ SERIAL_ECHO(a); _SEP_2(", ",b); _SLST_15(V); }while(0)
#define _SLST_18(a,b,V...) do{ SERIAL_ECHO(a); _SEP_2(", ",b); _SLST_16(V); }while(0)
#define _SLST_19(a,b,V...) do{ SERIAL_ECHO(a); _SEP_2(", ",b); _SLST_17(V); }while(0)
#define _SLST_20(a,b,V...) do{ SERIAL_ECHO(a); _SEP_2(", ",b); _SLST_18(V); }while(0) // Eat two args, pass the rest up
#define SERIAL_ECHOLIST(pre,V...) do{ SERIAL_ECHOPGM(pre); _SLST_N(NUM_ARGS(V),V); }while(0) inline void SERIAL_ECHOLIST_IMPL() {}
#define SERIAL_ECHOLIST_N(N,V...) _SLST_N(N,LIST_N(N,V)) template <typename T>
void SERIAL_ECHOLIST_IMPL(T && t) { SERIAL_IMPL.print(t); }
template <typename T, typename ... Args>
void SERIAL_ECHOLIST_IMPL(T && t, Args && ... args) {
SERIAL_IMPL.print(t);
serialprintPGM(PSTR(", "));
SERIAL_ECHOLIST_IMPL(args...);
}
template <typename ... Args>
void SERIAL_ECHOLIST(PGM_P const str, Args && ... args) {
SERIAL_IMPL.print(str);
SERIAL_ECHOLIST_IMPL(args...);
}
#else // Optimization if the listed type are all the same (seems to be the case in the codebase so use that instead)
template <typename ... Args>
void SERIAL_ECHOLIST(PGM_P const str, Args && ... args) {
serialprintPGM(str);
typename Private::first_type_of<Args...>::type values[] = { args... };
constexpr size_t argsSize = sizeof...(args);
for (size_t i = 0; i < argsSize; i++) {
if (i) serialprintPGM(PSTR(", "));
SERIAL_IMPL.print(values[i]);
}
}
#endif
#define SERIAL_ECHOPGM_P(P) (serialprintPGM(P)) #define SERIAL_ECHOPGM_P(P) (serialprintPGM(P))
#define SERIAL_ECHOLNPGM_P(P) (serialprintPGM(P "\n")) #define SERIAL_ECHOLNPGM_P(P) (serialprintPGM(P "\n"))
@ -303,19 +323,19 @@ typedef int8_t serial_index_t;
// //
// Functions for serial printing from PROGMEM. (Saves loads of SRAM.) // Functions for serial printing from PROGMEM. (Saves loads of SRAM.)
// //
void serial_echopair_PGM(PGM_P const s_P, serial_char_t v);
void serial_echopair_PGM(PGM_P const s_P, const char *v); void serial_echopair_PGM(PGM_P const s_P, const char *v);
void serial_echopair_PGM(PGM_P const s_P, char v); void serial_echopair_PGM(PGM_P const s_P, char v);
void serial_echopair_PGM(PGM_P const s_P, int v); void serial_echopair_PGM(PGM_P const s_P, int v);
void serial_echopair_PGM(PGM_P const s_P, unsigned int v);
void serial_echopair_PGM(PGM_P const s_P, long v); void serial_echopair_PGM(PGM_P const s_P, long v);
void serial_echopair_PGM(PGM_P const s_P, unsigned long v);
void serial_echopair_PGM(PGM_P const s_P, float v); void serial_echopair_PGM(PGM_P const s_P, float v);
void serial_echopair_PGM(PGM_P const s_P, double v); void serial_echopair_PGM(PGM_P const s_P, double v);
inline void serial_echopair_PGM(PGM_P const s_P, uint8_t v) { serial_echopair_PGM(s_P, (int)v); } void serial_echopair_PGM(PGM_P const s_P, unsigned char v);
void serial_echopair_PGM(PGM_P const s_P, unsigned int v);
void serial_echopair_PGM(PGM_P const s_P, unsigned long v);
inline void serial_echopair_PGM(PGM_P const s_P, bool v) { serial_echopair_PGM(s_P, (int)v); } inline void serial_echopair_PGM(PGM_P const s_P, bool v) { serial_echopair_PGM(s_P, (int)v); }
inline void serial_echopair_PGM(PGM_P const s_P, void *v) { serial_echopair_PGM(s_P, (uintptr_t)v); } inline void serial_echopair_PGM(PGM_P const s_P, void *v) { serial_echopair_PGM(s_P, (uintptr_t)v); }
void serialprintPGM(PGM_P str);
void serial_echo_start(); void serial_echo_start();
void serial_error_start(); void serial_error_start();
void serial_ternary(const bool onoff, PGM_P const pre, PGM_P const on, PGM_P const off, PGM_P const post=nullptr); void serial_ternary(const bool onoff, PGM_P const pre, PGM_P const on, PGM_P const off, PGM_P const post=nullptr);

View File

@ -22,25 +22,41 @@
#pragma once #pragma once
#include "../inc/MarlinConfigPre.h" #include "../inc/MarlinConfigPre.h"
#include "macros.h"
#if ENABLED(EMERGENCY_PARSER) #if ENABLED(EMERGENCY_PARSER)
#include "../feature/e_parser.h" #include "../feature/e_parser.h"
#endif #endif
#ifndef DEC
#define DEC 10
#define HEX 16
#define OCT 8
#define BIN 2
#endif
// flushTX is not implemented in all HAL, so use SFINAE to call the method where it is. // flushTX is not implemented in all HAL, so use SFINAE to call the method where it is.
CALL_IF_EXISTS_IMPL(void, flushTX ); CALL_IF_EXISTS_IMPL(void, flushTX );
CALL_IF_EXISTS_IMPL(bool, connected, true); CALL_IF_EXISTS_IMPL(bool, connected, true);
// In order to catch usage errors in code, we make the base to encode number explicit
// If given a number (and not this enum), the compiler will reject the overload, falling back to the (double, digit) version
// We don't want hidden conversion of the first parameter to double, so it has to be as hard to do for the compiler as creating this enum
enum class PrintBase {
Dec = 10,
Hex = 16,
Oct = 8,
Bin = 2
};
// A simple forward struct that prevent the compiler to select print(double, int) as a default overload for any type different than
// double or float. For double or float, a conversion exists so the call will be transparent
struct EnsureDouble {
double a;
FORCE_INLINE operator double() { return a; }
// If the compiler breaks on ambiguity here, it's likely because you're calling print(X, base) with X not a double or a float, and a
// base that's not one of PrintBase's value. This exact code is made to detect such error, you NEED to set a base explicitely like this:
// SERIAL_PRINT(v, PrintBase::Hex)
FORCE_INLINE EnsureDouble(double a) : a(a) {}
FORCE_INLINE EnsureDouble(float a) : a(a) {}
};
// Using Curiously Recurring Template Pattern here to avoid virtual table cost when compiling. // Using Curiously Recurring Template Pattern here to avoid virtual table cost when compiling.
// Since the real serial class is known at compile time, this results in compiler writing a completely // Since the real serial class is known at compile time, this results in the compiler writing
// efficient code // a completely efficient code.
template <class Child> template <class Child>
struct SerialBase { struct SerialBase {
#if ENABLED(EMERGENCY_PARSER) #if ENABLED(EMERGENCY_PARSER)
@ -78,39 +94,47 @@ struct SerialBase {
FORCE_INLINE void write(const char* str) { while (*str) write(*str++); } FORCE_INLINE void write(const char* str) { while (*str) write(*str++); }
FORCE_INLINE void write(const uint8_t* buffer, size_t size) { while (size--) write(*buffer++); } FORCE_INLINE void write(const uint8_t* buffer, size_t size) { while (size--) write(*buffer++); }
FORCE_INLINE void print(const char* str) { write(str); } FORCE_INLINE void print(const char* str) { write(str); }
NO_INLINE void print(char c, int base = 0) { print((long)c, base); } // No default argument to avoid ambiguity
NO_INLINE void print(unsigned char c, int base = 0) { print((unsigned long)c, base); } NO_INLINE void print(char c, PrintBase base) { printNumber((signed long)c, (uint8_t)base); }
NO_INLINE void print(int c, int base = DEC) { print((long)c, base); } NO_INLINE void print(unsigned char c, PrintBase base) { printNumber((unsigned long)c, (uint8_t)base); }
NO_INLINE void print(unsigned int c, int base = DEC) { print((unsigned long)c, base); } NO_INLINE void print(int c, PrintBase base) { printNumber((signed long)c, (uint8_t)base); }
void print(unsigned long c, int base = DEC) { printNumber(c, base); } NO_INLINE void print(unsigned int c, PrintBase base) { printNumber((unsigned long)c, (uint8_t)base); }
void print(double c, int digits = 2) { printFloat(c, digits); } void print(unsigned long c, PrintBase base) { printNumber((unsigned long)c, (uint8_t)base); }
void print(long c, int base = DEC) { void print(long c, PrintBase base) { printNumber((signed long)c, (uint8_t)base); }
if (!base) { void print(EnsureDouble c, int digits) { printFloat(c, digits); }
write(c);
return;
}
if (base == DEC && c < 0) {
write((uint8_t)'-'); c = -c;
}
printNumber(c, base);
}
NO_INLINE void println(const char s[]) { print(s); println(); } // Forward the call to the former's method
NO_INLINE void println(char c, int base = 0) { print(c, base); println(); } FORCE_INLINE void print(char c) { print(c, PrintBase::Dec); }
NO_INLINE void println(unsigned char c, int base = 0) { print(c, base); println(); } FORCE_INLINE void print(unsigned char c) { print(c, PrintBase::Dec); }
NO_INLINE void println(int c, int base = DEC) { print(c, base); println(); } FORCE_INLINE void print(int c) { print(c, PrintBase::Dec); }
NO_INLINE void println(unsigned int c, int base = DEC) { print(c, base); println(); } FORCE_INLINE void print(unsigned int c) { print(c, PrintBase::Dec); }
NO_INLINE void println(long c, int base = DEC) { print(c, base); println(); } FORCE_INLINE void print(unsigned long c) { print(c, PrintBase::Dec); }
NO_INLINE void println(unsigned long c, int base = DEC) { print(c, base); println(); } FORCE_INLINE void print(long c) { print(c, PrintBase::Dec); }
NO_INLINE void println(double c, int digits = 2) { print(c, digits); println(); } FORCE_INLINE void print(double c) { print(c, 2); }
NO_INLINE void println() { write('\r'); write('\n'); }
FORCE_INLINE void println(const char s[]) { print(s); println(); }
FORCE_INLINE void println(char c, PrintBase base) { print(c, base); println(); }
FORCE_INLINE void println(unsigned char c, PrintBase base) { print(c, base); println(); }
FORCE_INLINE void println(int c, PrintBase base) { print(c, base); println(); }
FORCE_INLINE void println(unsigned int c, PrintBase base) { print(c, base); println(); }
FORCE_INLINE void println(long c, PrintBase base) { print(c, base); println(); }
FORCE_INLINE void println(unsigned long c, PrintBase base) { print(c, base); println(); }
FORCE_INLINE void println(double c, int digits) { print(c, digits); println(); }
FORCE_INLINE void println() { write('\r'); write('\n'); }
// Forward the call to the former's method
FORCE_INLINE void println(char c) { println(c, PrintBase::Dec); }
FORCE_INLINE void println(unsigned char c) { println(c, PrintBase::Dec); }
FORCE_INLINE void println(int c) { println(c, PrintBase::Dec); }
FORCE_INLINE void println(unsigned int c) { println(c, PrintBase::Dec); }
FORCE_INLINE void println(unsigned long c) { println(c, PrintBase::Dec); }
FORCE_INLINE void println(long c) { println(c, PrintBase::Dec); }
FORCE_INLINE void println(double c) { println(c, 2); }
// Print a number with the given base // Print a number with the given base
void printNumber(unsigned long n, const uint8_t base) { NO_INLINE void printNumber(unsigned long n, const uint8_t base) {
if (!base) { if (!base) return; // Hopefully, this should raise visible bug immediately
write((uint8_t)n);
return;
}
if (n) { if (n) {
unsigned char buf[8 * sizeof(long)]; // Enough space for base 2 unsigned char buf[8 * sizeof(long)]; // Enough space for base 2
int8_t i = 0; int8_t i = 0;
@ -122,9 +146,19 @@ struct SerialBase {
} }
else write('0'); else write('0');
} }
void printNumber(signed long n, const uint8_t base) {
if (base == 10 && n < 0) {
n = -n; // This works because all platforms Marlin's builds on are using 2-complement encoding for negative number
// On such CPU, changing the sign of a number is done by inverting the bits and adding one, so if n = 0x80000000 = -2147483648 then
// -n = 0x7FFFFFFF + 1 => 0x80000000 = 2147483648 (if interpreted as unsigned) or -2147483648 if interpreted as signed.
// On non 2-complement CPU, there would be no possible representation for 2147483648.
write('-');
}
printNumber((unsigned long)n , base);
}
// Print a decimal number // Print a decimal number
void printFloat(double number, uint8_t digits) { NO_INLINE void printFloat(double number, uint8_t digits) {
// Handle negative numbers // Handle negative numbers
if (number < 0.0) { if (number < 0.0) {
write('-'); write('-');
@ -147,7 +181,7 @@ struct SerialBase {
// Extract digits from the remainder one at a time // Extract digits from the remainder one at a time
while (digits--) { while (digits--) {
remainder *= 10.0; remainder *= 10.0;
int toPrint = int(remainder); unsigned long toPrint = (unsigned long)remainder;
printNumber(toPrint, 10); printNumber(toPrint, 10);
remainder -= toPrint; remainder -= toPrint;
} }
@ -155,5 +189,5 @@ struct SerialBase {
} }
}; };
// All serial instances will be built by chaining the features required for the function in a form of a template // All serial instances will be built by chaining the features required
// type definition // for the function in the form of a template type definition.

View File

@ -21,6 +21,7 @@
*/ */
#pragma once #pragma once
#include "macros.h"
#include "serial_base.h" #include "serial_base.h"
// The most basic serial class: it dispatch to the base serial class with no hook whatsoever. This will compile to nothing but the base serial class // The most basic serial class: it dispatch to the base serial class with no hook whatsoever. This will compile to nothing but the base serial class
@ -37,6 +38,8 @@ struct BaseSerial : public SerialBase< BaseSerial<SerialT> >, public SerialT {
bool available(uint8_t index) { return index == 0 && SerialT::available(); } bool available(uint8_t index) { return index == 0 && SerialT::available(); }
int read(uint8_t index) { return index == 0 ? SerialT::read() : -1; } int read(uint8_t index) { return index == 0 ? SerialT::read() : -1; }
bool connected() { return CALL_IF_EXISTS(bool, static_cast<SerialT*>(this), connected);; } bool connected() { return CALL_IF_EXISTS(bool, static_cast<SerialT*>(this), connected);; }
void flushTX() { CALL_IF_EXISTS(void, static_cast<SerialT*>(this), flushTX); }
// We have 2 implementation of the same method in both base class, let's say which one we want // We have 2 implementation of the same method in both base class, let's say which one we want
using SerialT::available; using SerialT::available;
using SerialT::read; using SerialT::read;
@ -68,6 +71,7 @@ struct ConditionalSerial : public SerialBase< ConditionalSerial<SerialT> > {
void msgDone() {} void msgDone() {}
bool connected() { return CALL_IF_EXISTS(bool, &out, connected); } bool connected() { return CALL_IF_EXISTS(bool, &out, connected); }
void flushTX() { CALL_IF_EXISTS(void, &out, flushTX); }
bool available(uint8_t index) { return index == 0 && out.available(); } bool available(uint8_t index) { return index == 0 && out.available(); }
int read(uint8_t index) { return index == 0 ? out.read() : -1; } int read(uint8_t index) { return index == 0 ? out.read() : -1; }
@ -91,6 +95,7 @@ struct ForwardSerial : public SerialBase< ForwardSerial<SerialT> > {
void msgDone() {} void msgDone() {}
// Existing instances implement Arduino's operator bool, so use that if it's available // Existing instances implement Arduino's operator bool, so use that if it's available
bool connected() { return Private::HasMember_connected<SerialT>::value ? CALL_IF_EXISTS(bool, &out, connected) : (bool)out; } bool connected() { return Private::HasMember_connected<SerialT>::value ? CALL_IF_EXISTS(bool, &out, connected) : (bool)out; }
void flushTX() { CALL_IF_EXISTS(void, &out, flushTX); }
bool available(uint8_t index) { return index == 0 && out.available(); } bool available(uint8_t index) { return index == 0 && out.available(); }
int read(uint8_t index) { return index == 0 ? out.read() : -1; } int read(uint8_t index) { return index == 0 ? out.read() : -1; }
@ -131,11 +136,11 @@ struct RuntimeSerial : public SerialBase< RuntimeSerial<SerialT> >, public Seria
using BaseClassT::print; using BaseClassT::print;
using BaseClassT::println; using BaseClassT::println;
// Underlying implementation might use Arduino's bool operator // Underlying implementation might use Arduino's bool operator
bool connected() { bool connected() {
return Private::HasMember_connected<SerialT>::value ? CALL_IF_EXISTS(bool, static_cast<SerialT*>(this), connected) : static_cast<SerialT*>(this)->operator bool(); return Private::HasMember_connected<SerialT>::value ? CALL_IF_EXISTS(bool, static_cast<SerialT*>(this), connected) : static_cast<SerialT*>(this)->operator bool();
} }
void flushTX() { CALL_IF_EXISTS(void, static_cast<SerialT*>(this), flushTX); }
void setHook(WriteHook writeHook = 0, EndOfMessageHook eofHook = 0, void * userPointer = 0) { void setHook(WriteHook writeHook = 0, EndOfMessageHook eofHook = 0, void * userPointer = 0) {
// Order is important here as serial code can be called inside interrupts // Order is important here as serial code can be called inside interrupts

View File

@ -47,11 +47,11 @@ static void extrapolate_one_point(const uint8_t x, const uint8_t y, const int8_t
if (DEBUGGING(LEVELING)) { if (DEBUGGING(LEVELING)) {
DEBUG_ECHOPGM("Extrapolate ["); DEBUG_ECHOPGM("Extrapolate [");
if (x < 10) DEBUG_CHAR(' '); if (x < 10) DEBUG_CHAR(' ');
DEBUG_ECHO((int)x); DEBUG_ECHO(x);
DEBUG_CHAR(xdir ? (xdir > 0 ? '+' : '-') : ' '); DEBUG_CHAR(xdir ? (xdir > 0 ? '+' : '-') : ' ');
DEBUG_CHAR(' '); DEBUG_CHAR(' ');
if (y < 10) DEBUG_CHAR(' '); if (y < 10) DEBUG_CHAR(' ');
DEBUG_ECHO((int)y); DEBUG_ECHO(y);
DEBUG_CHAR(ydir ? (ydir > 0 ? '+' : '-') : ' '); DEBUG_CHAR(ydir ? (ydir > 0 ? '+' : '-') : ' ');
DEBUG_ECHOLNPGM("]"); DEBUG_ECHOLNPGM("]");
} }

View File

@ -160,7 +160,7 @@ void reset_bed_level() {
#ifndef SCAD_MESH_OUTPUT #ifndef SCAD_MESH_OUTPUT
LOOP_L_N(x, sx) { LOOP_L_N(x, sx) {
serial_spaces(precision + (x < 10 ? 3 : 2)); serial_spaces(precision + (x < 10 ? 3 : 2));
SERIAL_ECHO(int(x)); SERIAL_ECHO(x);
} }
SERIAL_EOL(); SERIAL_EOL();
#endif #endif
@ -172,7 +172,7 @@ void reset_bed_level() {
SERIAL_ECHOPGM(" ["); // open sub-array SERIAL_ECHOPGM(" ["); // open sub-array
#else #else
if (y < 10) SERIAL_CHAR(' '); if (y < 10) SERIAL_CHAR(' ');
SERIAL_ECHO(int(y)); SERIAL_ECHO(y);
#endif #endif
LOOP_L_N(x, sx) { LOOP_L_N(x, sx) {
SERIAL_CHAR(' '); SERIAL_CHAR(' ');

View File

@ -50,7 +50,7 @@
GRID_LOOP(x, y) GRID_LOOP(x, y)
if (!isnan(z_values[x][y])) { if (!isnan(z_values[x][y])) {
SERIAL_ECHO_START(); SERIAL_ECHO_START();
SERIAL_ECHOPAIR(" M421 I", int(x), " J", int(y)); SERIAL_ECHOPAIR(" M421 I", x, " J", y);
SERIAL_ECHOLNPAIR_F_P(SP_Z_STR, z_values[x][y], 4); SERIAL_ECHOLNPAIR_F_P(SP_Z_STR, z_values[x][y], 4);
serial_delay(75); // Prevent Printrun from exploding serial_delay(75); // Prevent Printrun from exploding
} }
@ -150,7 +150,7 @@
SERIAL_ECHO_SP(7); SERIAL_ECHO_SP(7);
LOOP_L_N(i, GRID_MAX_POINTS_X) { LOOP_L_N(i, GRID_MAX_POINTS_X) {
if (i < 10) SERIAL_CHAR(' '); if (i < 10) SERIAL_CHAR(' ');
SERIAL_ECHO((int)i); SERIAL_ECHO(i);
SERIAL_ECHO_SP(sp); SERIAL_ECHO_SP(sp);
} }
serial_delay(10); serial_delay(10);

View File

@ -742,7 +742,7 @@
if (do_ubl_mesh_map) display_map(g29_map_type); if (do_ubl_mesh_map) display_map(g29_map_type);
const int point_num = (GRID_MAX_POINTS) - count + 1; const int point_num = (GRID_MAX_POINTS) - count + 1;
SERIAL_ECHOLNPAIR("Probing mesh point ", point_num, "/", int(GRID_MAX_POINTS), "."); SERIAL_ECHOLNPAIR("Probing mesh point ", point_num, "/", GRID_MAX_POINTS, ".");
TERN_(HAS_DISPLAY, ui.status_printf_P(0, PSTR(S_FMT " %i/%i"), GET_TEXT(MSG_PROBING_MESH), point_num, int(GRID_MAX_POINTS))); TERN_(HAS_DISPLAY, ui.status_printf_P(0, PSTR(S_FMT " %i/%i"), GET_TEXT(MSG_PROBING_MESH), point_num, int(GRID_MAX_POINTS)));
#if HAS_LCD_MENU #if HAS_LCD_MENU
@ -1694,7 +1694,7 @@
SERIAL_EOL(); SERIAL_EOL();
#if HAS_KILL #if HAS_KILL
SERIAL_ECHOLNPAIR("Kill pin on :", int(KILL_PIN), " state:", int(kill_state())); SERIAL_ECHOLNPAIR("Kill pin on :", KILL_PIN, " state:", kill_state());
#endif #endif
SERIAL_EOL(); SERIAL_EOL();
@ -1707,8 +1707,8 @@
SERIAL_ECHOLNPAIR("Meshes go from ", hex_address((void*)settings.meshes_start_index()), " to ", hex_address((void*)settings.meshes_end_index())); SERIAL_ECHOLNPAIR("Meshes go from ", hex_address((void*)settings.meshes_start_index()), " to ", hex_address((void*)settings.meshes_end_index()));
serial_delay(50); serial_delay(50);
SERIAL_ECHOLNPAIR("sizeof(ubl) : ", (int)sizeof(ubl)); SERIAL_EOL(); SERIAL_ECHOLNPAIR("sizeof(ubl) : ", sizeof(ubl)); SERIAL_EOL();
SERIAL_ECHOLNPAIR("z_value[][] size: ", (int)sizeof(z_values)); SERIAL_EOL(); SERIAL_ECHOLNPAIR("z_value[][] size: ", sizeof(z_values)); SERIAL_EOL();
serial_delay(25); serial_delay(25);
SERIAL_ECHOLNPAIR("EEPROM free for UBL: ", hex_address((void*)(settings.meshes_end_index() - settings.meshes_start_index()))); SERIAL_ECHOLNPAIR("EEPROM free for UBL: ", hex_address((void*)(settings.meshes_end_index() - settings.meshes_start_index())));

View File

@ -404,7 +404,7 @@ public:
if (packet_retries < MAX_RETRIES || MAX_RETRIES == 0) { if (packet_retries < MAX_RETRIES || MAX_RETRIES == 0) {
packet_retries++; packet_retries++;
stream_state = StreamState::PACKET_RESET; stream_state = StreamState::PACKET_RESET;
SERIAL_ECHO_MSG("Resend request ", int(packet_retries)); SERIAL_ECHO_MSG("Resend request ", packet_retries);
SERIAL_ECHOLNPAIR("rs", sync); SERIAL_ECHOLNPAIR("rs", sync);
} }
else else

View File

@ -64,7 +64,7 @@ void BLTouch::init(const bool set_voltage/*=false*/) {
#else #else
if (DEBUGGING(LEVELING)) { if (DEBUGGING(LEVELING)) {
DEBUG_ECHOLNPAIR("last_written_mode - ", (int)last_written_mode); DEBUG_ECHOLNPAIR("last_written_mode - ", last_written_mode);
DEBUG_ECHOLNPGM("config mode - " DEBUG_ECHOLNPGM("config mode - "
#if ENABLED(BLTOUCH_SET_5V_MODE) #if ENABLED(BLTOUCH_SET_5V_MODE)
"BLTOUCH_SET_5V_MODE" "BLTOUCH_SET_5V_MODE"
@ -175,7 +175,7 @@ bool BLTouch::status_proc() {
_set_SW_mode(); // Incidentally, _set_SW_mode() will also RESET any active alarm _set_SW_mode(); // Incidentally, _set_SW_mode() will also RESET any active alarm
const bool tr = triggered(); // If triggered in SW mode, the pin is up, it is STOWED const bool tr = triggered(); // If triggered in SW mode, the pin is up, it is STOWED
if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("BLTouch is ", (int)tr); if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("BLTouch is ", tr);
if (tr) _stow(); else _deploy(); // Turn off SW mode, reset any trigger, honor pin state if (tr) _stow(); else _deploy(); // Turn off SW mode, reset any trigger, honor pin state
return !tr; return !tr;
@ -187,7 +187,7 @@ void BLTouch::mode_conv_proc(const bool M5V) {
* BLTOUCH V3.0: This will set the mode (twice) and sadly, a STOW is needed at the end, because of the deploy * BLTOUCH V3.0: This will set the mode (twice) and sadly, a STOW is needed at the end, because of the deploy
* BLTOUCH V3.1: This will set the mode and store it in the eeprom. The STOW is not needed but does not hurt * BLTOUCH V3.1: This will set the mode and store it in the eeprom. The STOW is not needed but does not hurt
*/ */
if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("BLTouch Set Mode - ", (int)M5V); if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("BLTouch Set Mode - ", M5V);
_deploy(); _deploy();
if (M5V) _set_5V_mode(); else _set_OD_mode(); if (M5V) _set_5V_mode(); else _set_OD_mode();
_mode_store(); _mode_store();

View File

@ -66,9 +66,8 @@ void CancelObject::uncancel_object(const int8_t obj) {
} }
void CancelObject::report() { void CancelObject::report() {
if (active_object >= 0) { if (active_object >= 0)
SERIAL_ECHO_MSG("Active Object: ", int(active_object)); SERIAL_ECHO_MSG("Active Object: ", active_object);
}
if (canceled) { if (canceled) {
SERIAL_ECHO_START(); SERIAL_ECHO_START();

View File

@ -49,7 +49,7 @@ void I2CPositionEncoder::init(const uint8_t address, const AxisEnum axis) {
initialized++; initialized++;
SERIAL_ECHOLNPAIR("Setting up encoder on ", axis_codes[encoderAxis], " axis, addr = ", address); SERIAL_ECHOLNPAIR("Setting up encoder on ", AS_CHAR(axis_codes[encoderAxis]), " axis, addr = ", address);
position = get_position(); position = get_position();
} }
@ -67,7 +67,7 @@ void I2CPositionEncoder::update() {
/* /*
if (trusted) { //commented out as part of the note below if (trusted) { //commented out as part of the note below
trusted = false; trusted = false;
SERIAL_ECHOLMPAIR("Fault detected on ", axis_codes[encoderAxis], " axis encoder. Disengaging error correction until module is trusted again."); SERIAL_ECHOLNPAIR("Fault detected on ", AS_CHAR(axis_codes[encoderAxis]), " axis encoder. Disengaging error correction until module is trusted again.");
} }
*/ */
return; return;
@ -92,7 +92,7 @@ void I2CPositionEncoder::update() {
if (millis() - lastErrorTime > I2CPE_TIME_TRUSTED) { if (millis() - lastErrorTime > I2CPE_TIME_TRUSTED) {
trusted = true; trusted = true;
SERIAL_ECHOLNPAIR("Untrusted encoder module on ", axis_codes[encoderAxis], " axis has been fault-free for set duration, reinstating error correction."); SERIAL_ECHOLNPAIR("Untrusted encoder module on ", AS_CHAR(axis_codes[encoderAxis]), " axis has been fault-free for set duration, reinstating error correction.");
//the encoder likely lost its place when the error occured, so we'll reset and use the printer's //the encoder likely lost its place when the error occured, so we'll reset and use the printer's
//idea of where it the axis is to re-initialize //idea of where it the axis is to re-initialize
@ -193,7 +193,7 @@ void I2CPositionEncoder::update() {
const millis_t ms = millis(); const millis_t ms = millis();
if (ELAPSED(ms, nextErrorCountTime)) { if (ELAPSED(ms, nextErrorCountTime)) {
SERIAL_CHAR(axis_codes[encoderAxis]); SERIAL_CHAR(axis_codes[encoderAxis]);
SERIAL_ECHOLNPAIR(" : LARGE ERR ", int(error), "; diffSum=", diffSum); SERIAL_ECHOLNPAIR(" : LARGE ERR ", error, "; diffSum=", diffSum);
errorCount++; errorCount++;
nextErrorCountTime = ms + I2CPE_ERR_CNT_DEBOUNCE_MS; nextErrorCountTime = ms + I2CPE_ERR_CNT_DEBOUNCE_MS;
} }

View File

@ -261,32 +261,32 @@ class I2CPositionEncodersMgr {
static void report_error_count(const int8_t idx, const AxisEnum axis) { static void report_error_count(const int8_t idx, const AxisEnum axis) {
CHECK_IDX(); CHECK_IDX();
SERIAL_ECHOLNPAIR("Error count on ", axis_codes[axis], " axis is ", encoders[idx].get_error_count()); SERIAL_ECHOLNPAIR("Error count on ", AS_CHAR(axis_codes[axis]), " axis is ", encoders[idx].get_error_count());
} }
static void reset_error_count(const int8_t idx, const AxisEnum axis) { static void reset_error_count(const int8_t idx, const AxisEnum axis) {
CHECK_IDX(); CHECK_IDX();
encoders[idx].set_error_count(0); encoders[idx].set_error_count(0);
SERIAL_ECHOLNPAIR("Error count on ", axis_codes[axis], " axis has been reset."); SERIAL_ECHOLNPAIR("Error count on ", AS_CHAR(axis_codes[axis]), " axis has been reset.");
} }
static void enable_ec(const int8_t idx, const bool enabled, const AxisEnum axis) { static void enable_ec(const int8_t idx, const bool enabled, const AxisEnum axis) {
CHECK_IDX(); CHECK_IDX();
encoders[idx].set_ec_enabled(enabled); encoders[idx].set_ec_enabled(enabled);
SERIAL_ECHOPAIR("Error correction on ", axis_codes[axis]); SERIAL_ECHOPAIR("Error correction on ", AS_CHAR(axis_codes[axis]));
SERIAL_ECHO_TERNARY(encoders[idx].get_ec_enabled(), " axis is ", "en", "dis", "abled.\n"); SERIAL_ECHO_TERNARY(encoders[idx].get_ec_enabled(), " axis is ", "en", "dis", "abled.\n");
} }
static void set_ec_threshold(const int8_t idx, const float newThreshold, const AxisEnum axis) { static void set_ec_threshold(const int8_t idx, const float newThreshold, const AxisEnum axis) {
CHECK_IDX(); CHECK_IDX();
encoders[idx].set_ec_threshold(newThreshold); encoders[idx].set_ec_threshold(newThreshold);
SERIAL_ECHOLNPAIR("Error correct threshold for ", axis_codes[axis], " axis set to ", newThreshold, "mm."); SERIAL_ECHOLNPAIR("Error correct threshold for ", AS_CHAR(axis_codes[axis]), " axis set to ", newThreshold, "mm.");
} }
static void get_ec_threshold(const int8_t idx, const AxisEnum axis) { static void get_ec_threshold(const int8_t idx, const AxisEnum axis) {
CHECK_IDX(); CHECK_IDX();
const float threshold = encoders[idx].get_ec_threshold(); const float threshold = encoders[idx].get_ec_threshold();
SERIAL_ECHOLNPAIR("Error correct threshold for ", axis_codes[axis], " axis is ", threshold, "mm."); SERIAL_ECHOLNPAIR("Error correct threshold for ", AS_CHAR(axis_codes[axis]), " axis is ", threshold, "mm.");
} }
static int8_t idx_from_axis(const AxisEnum axis) { static int8_t idx_from_axis(const AxisEnum axis) {

View File

@ -135,11 +135,11 @@ void Mixer::refresh_collector(const float proportion/*=1.0*/, const uint8_t t/*=
cmax = _MAX(cmax, v); cmax = _MAX(cmax, v);
csum += v; csum += v;
} }
//SERIAL_ECHOPAIR("Mixer::refresh_collector(", proportion, ", ", int(t), ") cmax=", cmax, " csum=", csum, " color"); //SERIAL_ECHOPAIR("Mixer::refresh_collector(", proportion, ", ", t, ") cmax=", cmax, " csum=", csum, " color");
const float inv_prop = proportion / csum; const float inv_prop = proportion / csum;
MIXER_STEPPER_LOOP(i) { MIXER_STEPPER_LOOP(i) {
c[i] = color[t][i] * inv_prop; c[i] = color[t][i] * inv_prop;
//SERIAL_ECHOPAIR(" [", int(t), "][", int(i), "] = ", int(color[t][i]), " (", c[i], ") "); //SERIAL_ECHOPAIR(" [", t, "][", i, "] = ", color[t][i], " (", c[i], ") ");
} }
//SERIAL_EOL(); //SERIAL_EOL();
} }

View File

@ -139,9 +139,9 @@ class Mixer {
#ifdef MIXER_NORMALIZER_DEBUG #ifdef MIXER_NORMALIZER_DEBUG
SERIAL_ECHOPGM("Mix [ "); SERIAL_ECHOPGM("Mix [ ");
SERIAL_ECHOLIST_N(MIXING_STEPPERS, int(mix[0]), int(mix[1]), int(mix[2]), int(mix[3]), int(mix[4]), int(mix[5])); SERIAL_ECHOLIST_N(MIXING_STEPPERS, mix[0], mix[1], mix[2], mix[3], mix[4], mix[5]);
SERIAL_ECHOPGM(" ] to Color [ "); SERIAL_ECHOPGM(" ] to Color [ ");
SERIAL_ECHOLIST_N(MIXING_STEPPERS, int(tcolor[0]), int(tcolor[1]), int(tcolor[2]), int(tcolor[3]), int(tcolor[4]), int(tcolor[5])); SERIAL_ECHOLIST_N(MIXING_STEPPERS, tcolor[0], tcolor[1], tcolor[2], tcolor[3], tcolor[4], tcolor[5]);
SERIAL_ECHOLNPGM(" ]"); SERIAL_ECHOLNPGM(" ]");
#endif #endif
} }
@ -153,10 +153,10 @@ class Mixer {
MIXER_STEPPER_LOOP(i) mix[i] = mixer_perc_t(100.0f * color[j][i] / ctot); MIXER_STEPPER_LOOP(i) mix[i] = mixer_perc_t(100.0f * color[j][i] / ctot);
#ifdef MIXER_NORMALIZER_DEBUG #ifdef MIXER_NORMALIZER_DEBUG
SERIAL_ECHOPAIR("V-tool ", int(j), " [ "); SERIAL_ECHOPAIR("V-tool ", j, " [ ");
SERIAL_ECHOLIST_N(MIXING_STEPPERS, int(color[j][0]), int(color[j][1]), int(color[j][2]), int(color[j][3]), int(color[j][4]), int(color[j][5])); SERIAL_ECHOLIST_N(MIXING_STEPPERS, color[j][0], color[j][1], color[j][2], color[j][3], color[j][4], color[j][5]);
SERIAL_ECHOPGM(" ] to Mix [ "); SERIAL_ECHOPGM(" ] to Mix [ ");
SERIAL_ECHOLIST_N(MIXING_STEPPERS, int(mix[0]), int(mix[1]), int(mix[2]), int(mix[3]), int(mix[4]), int(mix[5])); SERIAL_ECHOLIST_N(MIXING_STEPPERS, mix[0], mix[1], mix[2], mix[3], mix[4], mix[5]);
SERIAL_ECHOLNPGM(" ]"); SERIAL_ECHOLNPGM(" ]");
#endif #endif
} }
@ -199,9 +199,9 @@ class Mixer {
#ifdef MIXER_NORMALIZER_DEBUG #ifdef MIXER_NORMALIZER_DEBUG
SERIAL_ECHOPGM("Gradient [ "); SERIAL_ECHOPGM("Gradient [ ");
SERIAL_ECHOLIST_N(MIXING_STEPPERS, int(gradient.color[0]), int(gradient.color[1]), int(gradient.color[2]), int(gradient.color[3]), int(gradient.color[4]), int(gradient.color[5])); SERIAL_ECHOLIST_N(MIXING_STEPPERS, gradient.color[0], gradient.color[1], gradient.color[2], gradient.color[3], gradient.color[4], gradient.color[5]);
SERIAL_ECHOPGM(" ] to Mix [ "); SERIAL_ECHOPGM(" ] to Mix [ ");
SERIAL_ECHOLIST_N(MIXING_STEPPERS, int(mix[0]), int(mix[1]), int(mix[2]), int(mix[3]), int(mix[4]), int(mix[5])); SERIAL_ECHOLIST_N(MIXING_STEPPERS, mix[0], mix[1], mix[2], mix[3], mix[4], mix[5]);
SERIAL_ECHOLNPGM(" ]"); SERIAL_ECHOLNPGM(" ]");
#endif #endif
} }

View File

@ -514,7 +514,7 @@ static void mmu2_not_responding() {
extruder = index; // filament change is finished extruder = index; // filament change is finished
active_extruder = 0; active_extruder = 0;
ENABLE_AXIS_E0(); ENABLE_AXIS_E0();
SERIAL_ECHO_MSG(STR_ACTIVE_EXTRUDER, int(extruder)); SERIAL_ECHO_MSG(STR_ACTIVE_EXTRUDER, extruder);
} }
ui.reset_status(); ui.reset_status();
} }
@ -601,7 +601,7 @@ static void mmu2_not_responding() {
active_extruder = 0; active_extruder = 0;
ENABLE_AXIS_E0(); ENABLE_AXIS_E0();
SERIAL_ECHO_MSG(STR_ACTIVE_EXTRUDER, int(extruder)); SERIAL_ECHO_MSG(STR_ACTIVE_EXTRUDER, extruder);
ui.reset_status(); ui.reset_status();
} }
@ -696,7 +696,7 @@ static void mmu2_not_responding() {
extruder = index; //filament change is finished extruder = index; //filament change is finished
active_extruder = 0; active_extruder = 0;
ENABLE_AXIS_E0(); ENABLE_AXIS_E0();
SERIAL_ECHO_MSG(STR_ACTIVE_EXTRUDER, int(extruder)); SERIAL_ECHO_MSG(STR_ACTIVE_EXTRUDER, extruder);
ui.reset_status(); ui.reset_status();
} }

View File

@ -130,7 +130,7 @@ fil_change_settings_t fc_settings[EXTRUDERS];
*/ */
static bool ensure_safe_temperature(const bool wait=true, const PauseMode mode=PAUSE_MODE_SAME) { static bool ensure_safe_temperature(const bool wait=true, const PauseMode mode=PAUSE_MODE_SAME) {
DEBUG_SECTION(est, "ensure_safe_temperature", true); DEBUG_SECTION(est, "ensure_safe_temperature", true);
DEBUG_ECHOLNPAIR("... wait:", int(wait), " mode:", int(mode)); DEBUG_ECHOLNPAIR("... wait:", wait, " mode:", mode);
#if ENABLED(PREVENT_COLD_EXTRUSION) #if ENABLED(PREVENT_COLD_EXTRUSION)
if (!DEBUGGING(DRYRUN) && thermalManager.targetTooColdToExtrude(active_extruder)) if (!DEBUGGING(DRYRUN) && thermalManager.targetTooColdToExtrude(active_extruder))
@ -176,7 +176,7 @@ bool load_filament(const float &slow_load_length/*=0*/, const float &fast_load_l
DXC_ARGS DXC_ARGS
) { ) {
DEBUG_SECTION(lf, "load_filament", true); DEBUG_SECTION(lf, "load_filament", true);
DEBUG_ECHOLNPAIR("... slowlen:", slow_load_length, " fastlen:", fast_load_length, " purgelen:", purge_length, " maxbeep:", int(max_beep_count), " showlcd:", int(show_lcd), " pauseforuser:", int(pause_for_user), " pausemode:", int(mode) DXC_SAY); DEBUG_ECHOLNPAIR("... slowlen:", slow_load_length, " fastlen:", fast_load_length, " purgelen:", purge_length, " maxbeep:", max_beep_count, " showlcd:", show_lcd, " pauseforuser:", pause_for_user, " pausemode:", mode DXC_SAY);
if (!ensure_safe_temperature(false, mode)) { if (!ensure_safe_temperature(false, mode)) {
if (show_lcd) ui.pause_show_message(PAUSE_MESSAGE_STATUS, mode); if (show_lcd) ui.pause_show_message(PAUSE_MESSAGE_STATUS, mode);
@ -309,7 +309,7 @@ bool unload_filament(const float &unload_length, const bool show_lcd/*=false*/,
#endif #endif
) { ) {
DEBUG_SECTION(uf, "unload_filament", true); DEBUG_SECTION(uf, "unload_filament", true);
DEBUG_ECHOLNPAIR("... unloadlen:", unload_length, " showlcd:", int(show_lcd), " mode:", int(mode) DEBUG_ECHOLNPAIR("... unloadlen:", unload_length, " showlcd:", show_lcd, " mode:", mode
#if BOTH(FILAMENT_UNLOAD_ALL_EXTRUDERS, MIXING_EXTRUDER) #if BOTH(FILAMENT_UNLOAD_ALL_EXTRUDERS, MIXING_EXTRUDER)
, " mixmult:", mix_multiplier , " mixmult:", mix_multiplier
#endif #endif
@ -373,7 +373,7 @@ uint8_t did_pause_print = 0;
bool pause_print(const float &retract, const xyz_pos_t &park_point, const float &unload_length/*=0*/, const bool show_lcd/*=false*/ DXC_ARGS) { bool pause_print(const float &retract, const xyz_pos_t &park_point, const float &unload_length/*=0*/, const bool show_lcd/*=false*/ DXC_ARGS) {
DEBUG_SECTION(pp, "pause_print", true); DEBUG_SECTION(pp, "pause_print", true);
DEBUG_ECHOLNPAIR("... park.x:", park_point.x, " y:", park_point.y, " z:", park_point.z, " unloadlen:", unload_length, " showlcd:", int(show_lcd) DXC_SAY); DEBUG_ECHOLNPAIR("... park.x:", park_point.x, " y:", park_point.y, " z:", park_point.z, " unloadlen:", unload_length, " showlcd:", show_lcd DXC_SAY);
UNUSED(show_lcd); UNUSED(show_lcd);
@ -456,7 +456,7 @@ bool pause_print(const float &retract, const xyz_pos_t &park_point, const float
void show_continue_prompt(const bool is_reload) { void show_continue_prompt(const bool is_reload) {
DEBUG_SECTION(scp, "pause_print", true); DEBUG_SECTION(scp, "pause_print", true);
DEBUG_ECHOLNPAIR("... is_reload:", int(is_reload)); DEBUG_ECHOLNPAIR("... is_reload:", is_reload);
ui.pause_show_message(is_reload ? PAUSE_MESSAGE_INSERT : PAUSE_MESSAGE_WAITING); ui.pause_show_message(is_reload ? PAUSE_MESSAGE_INSERT : PAUSE_MESSAGE_WAITING);
SERIAL_ECHO_START(); SERIAL_ECHO_START();
@ -465,7 +465,7 @@ void show_continue_prompt(const bool is_reload) {
void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep_count/*=0*/ DXC_ARGS) { void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep_count/*=0*/ DXC_ARGS) {
DEBUG_SECTION(wfc, "wait_for_confirmation", true); DEBUG_SECTION(wfc, "wait_for_confirmation", true);
DEBUG_ECHOLNPAIR("... is_reload:", is_reload, " maxbeep:", int(max_beep_count) DXC_SAY); DEBUG_ECHOLNPAIR("... is_reload:", is_reload, " maxbeep:", max_beep_count DXC_SAY);
bool nozzle_timed_out = false; bool nozzle_timed_out = false;
@ -561,7 +561,7 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep
*/ */
void resume_print(const float &slow_load_length/*=0*/, const float &fast_load_length/*=0*/, const float &purge_length/*=ADVANCED_PAUSE_PURGE_LENGTH*/, const int8_t max_beep_count/*=0*/, int16_t targetTemp/*=0*/ DXC_ARGS) { void resume_print(const float &slow_load_length/*=0*/, const float &fast_load_length/*=0*/, const float &purge_length/*=ADVANCED_PAUSE_PURGE_LENGTH*/, const int8_t max_beep_count/*=0*/, int16_t targetTemp/*=0*/ DXC_ARGS) {
DEBUG_SECTION(rp, "resume_print", true); DEBUG_SECTION(rp, "resume_print", true);
DEBUG_ECHOLNPAIR("... slowlen:", slow_load_length, " fastlen:", fast_load_length, " purgelen:", purge_length, " maxbeep:", int(max_beep_count), " targetTemp:", targetTemp DXC_SAY); DEBUG_ECHOLNPAIR("... slowlen:", slow_load_length, " fastlen:", fast_load_length, " purgelen:", purge_length, " maxbeep:", max_beep_count, " targetTemp:", targetTemp DXC_SAY);
/* /*
SERIAL_ECHOLNPAIR( SERIAL_ECHOLNPAIR(

View File

@ -532,7 +532,7 @@ void PrintJobRecovery::resume() {
void PrintJobRecovery::debug(PGM_P const prefix) { void PrintJobRecovery::debug(PGM_P const prefix) {
DEBUG_PRINT_P(prefix); DEBUG_PRINT_P(prefix);
DEBUG_ECHOLNPAIR(" Job Recovery Info...\nvalid_head:", int(info.valid_head), " valid_foot:", int(info.valid_foot)); DEBUG_ECHOLNPAIR(" Job Recovery Info...\nvalid_head:", info.valid_head, " valid_foot:", info.valid_foot);
if (info.valid_head) { if (info.valid_head) {
if (info.valid_head == info.valid_foot) { if (info.valid_head == info.valid_foot) {
DEBUG_ECHOPGM("current_position: "); DEBUG_ECHOPGM("current_position: ");
@ -565,7 +565,7 @@ void PrintJobRecovery::resume() {
DEBUG_ECHOLNPAIR("feedrate: ", info.feedrate); DEBUG_ECHOLNPAIR("feedrate: ", info.feedrate);
#if HAS_MULTI_EXTRUDER #if HAS_MULTI_EXTRUDER
DEBUG_ECHOLNPAIR("active_extruder: ", int(info.active_extruder)); DEBUG_ECHOLNPAIR("active_extruder: ", info.active_extruder);
#endif #endif
#if HAS_HOTEND #if HAS_HOTEND
@ -584,14 +584,14 @@ void PrintJobRecovery::resume() {
#if HAS_FAN #if HAS_FAN
DEBUG_ECHOPGM("fan_speed: "); DEBUG_ECHOPGM("fan_speed: ");
FANS_LOOP(i) { FANS_LOOP(i) {
DEBUG_ECHO(int(info.fan_speed[i])); DEBUG_ECHO(info.fan_speed[i]);
if (i < FAN_COUNT - 1) DEBUG_CHAR(','); if (i < FAN_COUNT - 1) DEBUG_CHAR(',');
} }
DEBUG_EOL(); DEBUG_EOL();
#endif #endif
#if HAS_LEVELING #if HAS_LEVELING
DEBUG_ECHOLNPAIR("leveling: ", int(info.flag.leveling), " fade: ", info.fade); DEBUG_ECHOLNPAIR("leveling: ", info.flag.leveling, " fade: ", info.fade);
#endif #endif
#if ENABLED(FWRETRACT) #if ENABLED(FWRETRACT)
DEBUG_ECHOPGM("retract: "); DEBUG_ECHOPGM("retract: ");
@ -605,8 +605,8 @@ void PrintJobRecovery::resume() {
DEBUG_ECHOLNPAIR("sd_filename: ", info.sd_filename); DEBUG_ECHOLNPAIR("sd_filename: ", info.sd_filename);
DEBUG_ECHOLNPAIR("sdpos: ", info.sdpos); DEBUG_ECHOLNPAIR("sdpos: ", info.sdpos);
DEBUG_ECHOLNPAIR("print_job_elapsed: ", info.print_job_elapsed); DEBUG_ECHOLNPAIR("print_job_elapsed: ", info.print_job_elapsed);
DEBUG_ECHOLNPAIR("dryrun: ", int(info.flag.dryrun)); DEBUG_ECHOLNPAIR("dryrun: ", info.flag.dryrun);
DEBUG_ECHOLNPAIR("allow_cold_extrusion: ", int(info.flag.allow_cold_extrusion)); DEBUG_ECHOLNPAIR("allow_cold_extrusion: ", info.flag.allow_cold_extrusion);
} }
else else
DEBUG_ECHOLNPGM("INVALID DATA"); DEBUG_ECHOLNPGM("INVALID DATA");

View File

@ -43,7 +43,7 @@ void Repeat::add_marker(const uint32_t sdpos, const uint16_t count) {
marker[index].sdpos = sdpos; marker[index].sdpos = sdpos;
marker[index].counter = count ?: -1; marker[index].counter = count ?: -1;
index++; index++;
DEBUG_ECHOLNPAIR("Add Marker ", int(index), " at ", sdpos, " (", count, ")"); DEBUG_ECHOLNPAIR("Add Marker ", index, " at ", sdpos, " (", count, ")");
} }
} }
@ -53,14 +53,14 @@ void Repeat::loop() {
else { else {
const uint8_t ind = index - 1; // Active marker's index const uint8_t ind = index - 1; // Active marker's index
if (!marker[ind].counter) { // Did its counter run out? if (!marker[ind].counter) { // Did its counter run out?
DEBUG_ECHOLNPAIR("Pass Marker ", int(index)); DEBUG_ECHOLNPAIR("Pass Marker ", index);
index--; // Carry on. Previous marker on the next 'M808'. index--; // Carry on. Previous marker on the next 'M808'.
} }
else { else {
card.setIndex(marker[ind].sdpos); // Loop back to the marker. card.setIndex(marker[ind].sdpos); // Loop back to the marker.
if (marker[ind].counter > 0) // Ignore a negative (or zero) counter. if (marker[ind].counter > 0) // Ignore a negative (or zero) counter.
--marker[ind].counter; // Decrement the counter. If zero this 'M808' will be skipped next time. --marker[ind].counter; // Decrement the counter. If zero this 'M808' will be skipped next time.
DEBUG_ECHOLNPAIR("Goto Marker ", int(index), " at ", marker[ind].sdpos, " (", marker[ind].counter, ")"); DEBUG_ECHOLNPAIR("Goto Marker ", index, " at ", marker[ind].sdpos, " (", marker[ind].counter, ")");
} }
} }
} }

View File

@ -537,7 +537,7 @@ void GcodeSuite::G26() {
if (bedtemp) { if (bedtemp) {
if (!WITHIN(bedtemp, 40, BED_MAX_TARGET)) { if (!WITHIN(bedtemp, 40, BED_MAX_TARGET)) {
SERIAL_ECHOLNPAIR("?Specified bed temperature not plausible (40-", int(BED_MAX_TARGET), "C)."); SERIAL_ECHOLNPAIR("?Specified bed temperature not plausible (40-", BED_MAX_TARGET, "C).");
return; return;
} }
g26_bed_temp = bedtemp; g26_bed_temp = bedtemp;

View File

@ -104,7 +104,7 @@ void GcodeSuite::G35() {
const float z_probed_height = probe.probe_at_point(screws_tilt_adjust_pos[i], PROBE_PT_RAISE, 0, true); const float z_probed_height = probe.probe_at_point(screws_tilt_adjust_pos[i], PROBE_PT_RAISE, 0, true);
if (isnan(z_probed_height)) { if (isnan(z_probed_height)) {
SERIAL_ECHOPAIR("G35 failed at point ", int(i), " ("); SERIAL_ECHOPAIR("G35 failed at point ", i, " (");
SERIAL_ECHOPGM_P((char *)pgm_read_ptr(&tramming_point_name[i])); SERIAL_ECHOPGM_P((char *)pgm_read_ptr(&tramming_point_name[i]));
SERIAL_CHAR(')'); SERIAL_CHAR(')');
SERIAL_ECHOLNPAIR_P(SP_X_STR, screws_tilt_adjust_pos[i].x, SP_Y_STR, screws_tilt_adjust_pos[i].y); SERIAL_ECHOLNPAIR_P(SP_X_STR, screws_tilt_adjust_pos[i].x, SP_Y_STR, screws_tilt_adjust_pos[i].y);
@ -113,7 +113,7 @@ void GcodeSuite::G35() {
} }
if (DEBUGGING(LEVELING)) { if (DEBUGGING(LEVELING)) {
DEBUG_ECHOPAIR("Probing point ", int(i), " ("); DEBUG_ECHOPAIR("Probing point ", i, " (");
DEBUG_PRINT_P((char *)pgm_read_ptr(&tramming_point_name[i])); DEBUG_PRINT_P((char *)pgm_read_ptr(&tramming_point_name[i]));
DEBUG_CHAR(')'); DEBUG_CHAR(')');
DEBUG_ECHOLNPAIR_P(SP_X_STR, screws_tilt_adjust_pos[i].x, SP_Y_STR, screws_tilt_adjust_pos[i].y, SP_Z_STR, z_probed_height); DEBUG_ECHOLNPAIR_P(SP_X_STR, screws_tilt_adjust_pos[i].x, SP_Y_STR, screws_tilt_adjust_pos[i].y, SP_Z_STR, z_probed_height);

View File

@ -637,7 +637,7 @@ G29_TYPE GcodeSuite::G29() {
// Avoid probing outside the round or hexagonal area // Avoid probing outside the round or hexagonal area
if (TERN0(IS_KINEMATIC, !probe.can_reach(probePos))) continue; if (TERN0(IS_KINEMATIC, !probe.can_reach(probePos))) continue;
if (verbose_level) SERIAL_ECHOLNPAIR("Probing mesh point ", int(pt_index), "/", abl_points, "."); if (verbose_level) SERIAL_ECHOLNPAIR("Probing mesh point ", pt_index, "/", abl_points, ".");
TERN_(HAS_DISPLAY, ui.status_printf_P(0, PSTR(S_FMT " %i/%i"), GET_TEXT(MSG_PROBING_MESH), int(pt_index), int(abl_points))); TERN_(HAS_DISPLAY, ui.status_printf_P(0, PSTR(S_FMT " %i/%i"), GET_TEXT(MSG_PROBING_MESH), int(pt_index), int(abl_points)));
measured_z = faux ? 0.001f * random(-100, 101) : probe.probe_at_point(probePos, raise_after, verbose_level); measured_z = faux ? 0.001f * random(-100, 101) : probe.probe_at_point(probePos, raise_after, verbose_level);
@ -682,7 +682,7 @@ G29_TYPE GcodeSuite::G29() {
// Probe at 3 arbitrary points // Probe at 3 arbitrary points
LOOP_L_N(i, 3) { LOOP_L_N(i, 3) {
if (verbose_level) SERIAL_ECHOLNPAIR("Probing point ", int(i + 1), "/3."); if (verbose_level) SERIAL_ECHOLNPAIR("Probing point ", i + 1, "/3.");
TERN_(HAS_DISPLAY, ui.status_printf_P(0, PSTR(S_FMT " %i/3"), GET_TEXT(MSG_PROBING_MESH), int(i + 1))); TERN_(HAS_DISPLAY, ui.status_printf_P(0, PSTR(S_FMT " %i/3"), GET_TEXT(MSG_PROBING_MESH), int(i + 1)));
// Retain the last probe position // Retain the last probe position

View File

@ -142,7 +142,7 @@ void GcodeSuite::G29() {
if (parser.seenval('I')) { if (parser.seenval('I')) {
ix = parser.value_int(); ix = parser.value_int();
if (!WITHIN(ix, 0, GRID_MAX_POINTS_X - 1)) { if (!WITHIN(ix, 0, GRID_MAX_POINTS_X - 1)) {
SERIAL_ECHOLNPAIR("I out of range (0-", int(GRID_MAX_POINTS_X - 1), ")"); SERIAL_ECHOLNPAIR("I out of range (0-", GRID_MAX_POINTS_X - 1, ")");
return; return;
} }
} }
@ -152,7 +152,7 @@ void GcodeSuite::G29() {
if (parser.seenval('J')) { if (parser.seenval('J')) {
iy = parser.value_int(); iy = parser.value_int();
if (!WITHIN(iy, 0, GRID_MAX_POINTS_Y - 1)) { if (!WITHIN(iy, 0, GRID_MAX_POINTS_Y - 1)) {
SERIAL_ECHOLNPAIR("J out of range (0-", int(GRID_MAX_POINTS_Y - 1), ")"); SERIAL_ECHOLNPAIR("J out of range (0-", GRID_MAX_POINTS_Y - 1, ")");
return; return;
} }
} }
@ -181,7 +181,7 @@ void GcodeSuite::G29() {
} // switch(state) } // switch(state)
if (state == MeshNext) if (state == MeshNext)
SERIAL_ECHOLNPAIR("MBL G29 point ", _MIN(mbl_probe_index, GRID_MAX_POINTS), " of ", int(GRID_MAX_POINTS)); SERIAL_ECHOLNPAIR("MBL G29 point ", _MIN(mbl_probe_index, GRID_MAX_POINTS), " of ", GRID_MAX_POINTS);
report_current_position(); report_current_position();
} }

View File

@ -238,7 +238,7 @@ void GcodeSuite::G34() {
// the next iteration of probing. This allows adjustments to be made away from the bed. // the next iteration of probing. This allows adjustments to be made away from the bed.
z_measured[iprobe] = z_probed_height + Z_CLEARANCE_BETWEEN_PROBES; z_measured[iprobe] = z_probed_height + Z_CLEARANCE_BETWEEN_PROBES;
if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("> Z", int(iprobe + 1), " measured position is ", z_measured[iprobe]); if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("> Z", iprobe + 1, " measured position is ", z_measured[iprobe]);
// Remember the minimum measurement to calculate the correction later on // Remember the minimum measurement to calculate the correction later on
z_measured_min = _MIN(z_measured_min, z_measured[iprobe]); z_measured_min = _MIN(z_measured_min, z_measured[iprobe]);
@ -267,7 +267,7 @@ void GcodeSuite::G34() {
linear_fit_data lfd; linear_fit_data lfd;
incremental_LSF_reset(&lfd); incremental_LSF_reset(&lfd);
LOOP_L_N(i, NUM_Z_STEPPER_DRIVERS) { LOOP_L_N(i, NUM_Z_STEPPER_DRIVERS) {
SERIAL_ECHOLNPAIR("PROBEPT_", int(i), ": ", z_measured[i]); SERIAL_ECHOLNPAIR("PROBEPT_", i, ": ", z_measured[i]);
incremental_LSF(&lfd, z_stepper_align.xy[i], z_measured[i]); incremental_LSF(&lfd, z_stepper_align.xy[i], z_measured[i]);
} }
finish_incremental_LSF(&lfd); finish_incremental_LSF(&lfd);
@ -357,8 +357,8 @@ void GcodeSuite::G34() {
// Check for less accuracy compared to last move // Check for less accuracy compared to last move
if (decreasing_accuracy(last_z_align_move[zstepper], z_align_abs)) { if (decreasing_accuracy(last_z_align_move[zstepper], z_align_abs)) {
if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("> Z", int(zstepper + 1), " last_z_align_move = ", last_z_align_move[zstepper]); if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("> Z", zstepper + 1, " last_z_align_move = ", last_z_align_move[zstepper]);
if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("> Z", int(zstepper + 1), " z_align_abs = ", z_align_abs); if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("> Z", zstepper + 1, " z_align_abs = ", z_align_abs);
adjustment_reverse = !adjustment_reverse; adjustment_reverse = !adjustment_reverse;
} }
@ -370,7 +370,7 @@ void GcodeSuite::G34() {
// Stop early if all measured points achieve accuracy target // Stop early if all measured points achieve accuracy target
if (z_align_abs > z_auto_align_accuracy) success_break = false; if (z_align_abs > z_auto_align_accuracy) success_break = false;
if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("> Z", int(zstepper + 1), " corrected by ", z_align_move); if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("> Z", zstepper + 1, " corrected by ", z_align_move);
// Lock all steppers except one // Lock all steppers except one
stepper.set_all_z_lock(true, zstepper); stepper.set_all_z_lock(true, zstepper);
@ -380,7 +380,7 @@ void GcodeSuite::G34() {
// Will match reversed Z steppers on dual steppers. Triple will need more work to map. // Will match reversed Z steppers on dual steppers. Triple will need more work to map.
if (adjustment_reverse) { if (adjustment_reverse) {
z_align_move = -z_align_move; z_align_move = -z_align_move;
if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("> Z", int(zstepper + 1), " correction reversed to ", z_align_move); if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("> Z", zstepper + 1, " correction reversed to ", z_align_move);
} }
#endif #endif
@ -406,7 +406,7 @@ void GcodeSuite::G34() {
if (err_break) if (err_break)
SERIAL_ECHOLNPGM("G34 aborted."); SERIAL_ECHOLNPGM("G34 aborted.");
else { else {
SERIAL_ECHOLNPAIR("Did ", int(iteration + (iteration != z_auto_align_iterations)), " of ", int(z_auto_align_iterations)); SERIAL_ECHOLNPAIR("Did ", iteration + (iteration != z_auto_align_iterations), " of ", z_auto_align_iterations);
SERIAL_ECHOLNPAIR_F("Accuracy: ", z_maxdiff); SERIAL_ECHOLNPAIR_F("Accuracy: ", z_maxdiff);
} }
@ -467,10 +467,10 @@ void GcodeSuite::M422() {
if (!parser.seen_any()) { if (!parser.seen_any()) {
LOOP_L_N(i, NUM_Z_STEPPER_DRIVERS) LOOP_L_N(i, NUM_Z_STEPPER_DRIVERS)
SERIAL_ECHOLNPAIR_P(PSTR("M422 S"), int(i + 1), SP_X_STR, z_stepper_align.xy[i].x, SP_Y_STR, z_stepper_align.xy[i].y); SERIAL_ECHOLNPAIR_P(PSTR("M422 S"), i + 1, SP_X_STR, z_stepper_align.xy[i].x, SP_Y_STR, z_stepper_align.xy[i].y);
#if ENABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS) #if ENABLED(Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS)
LOOP_L_N(i, NUM_Z_STEPPER_DRIVERS) LOOP_L_N(i, NUM_Z_STEPPER_DRIVERS)
SERIAL_ECHOLNPAIR_P(PSTR("M422 W"), int(i + 1), SP_X_STR, z_stepper_align.stepper_xy[i].x, SP_Y_STR, z_stepper_align.stepper_xy[i].y); SERIAL_ECHOLNPAIR_P(PSTR("M422 W"), i + 1, SP_X_STR, z_stepper_align.stepper_xy[i].x, SP_Y_STR, z_stepper_align.stepper_xy[i].y);
#endif #endif
return; return;
} }

View File

@ -375,7 +375,7 @@ inline void probe_sides(measurements_t &m, const float uncertainty) {
inline void report_measured_positional_error(const measurements_t &m) { inline void report_measured_positional_error(const measurements_t &m) {
SERIAL_CHAR('T'); SERIAL_CHAR('T');
SERIAL_ECHO(int(active_extruder)); SERIAL_ECHO(active_extruder);
SERIAL_ECHOLNPGM(" Positional Error:"); SERIAL_ECHOLNPGM(" Positional Error:");
#if HAS_X_CENTER #if HAS_X_CENTER
SERIAL_ECHOLNPAIR_P(SP_X_STR, m.pos_error.x); SERIAL_ECHOLNPAIR_P(SP_X_STR, m.pos_error.x);
@ -408,7 +408,7 @@ inline void probe_sides(measurements_t &m, const float uncertainty) {
// //
inline void report_hotend_offsets() { inline void report_hotend_offsets() {
LOOP_S_L_N(e, 1, HOTENDS) LOOP_S_L_N(e, 1, HOTENDS)
SERIAL_ECHOLNPAIR_P(PSTR("T"), int(e), PSTR(" Hotend Offset X"), hotend_offset[e].x, SP_Y_STR, hotend_offset[e].y, SP_Z_STR, hotend_offset[e].z); SERIAL_ECHOLNPAIR_P(PSTR("T"), e, PSTR(" Hotend Offset X"), hotend_offset[e].x, SP_Y_STR, hotend_offset[e].y, SP_Z_STR, hotend_offset[e].z);
} }
#endif #endif

View File

@ -240,8 +240,8 @@ void GcodeSuite::M48() {
sigma = SQRT(dev_sum / (n + 1)); sigma = SQRT(dev_sum / (n + 1));
if (verbose_level > 1) { if (verbose_level > 1) {
SERIAL_ECHO((int)(n + 1)); SERIAL_ECHO(n + 1);
SERIAL_ECHOPAIR(" of ", (int)n_samples); SERIAL_ECHOPAIR(" of ", n_samples);
SERIAL_ECHOPAIR_F(": z: ", pz, 3); SERIAL_ECHOPAIR_F(": z: ", pz, 3);
SERIAL_CHAR(' '); SERIAL_CHAR(' ');
dev_report(verbose_level > 2, mean, sigma, min, max); dev_report(verbose_level > 2, mean, sigma, min, max);

View File

@ -47,7 +47,7 @@ void M217_report(const bool eeprom=false) {
" G", toolchange_settings.fan_time); " G", toolchange_settings.fan_time);
#if ENABLED(TOOLCHANGE_MIGRATION_FEATURE) #if ENABLED(TOOLCHANGE_MIGRATION_FEATURE)
SERIAL_ECHOPAIR(" A", int(migration.automode)); SERIAL_ECHOPAIR(" A", migration.automode);
SERIAL_ECHOPAIR(" L", LINEAR_UNIT(migration.last)); SERIAL_ECHOPAIR(" L", LINEAR_UNIT(migration.last));
#endif #endif

View File

@ -50,7 +50,7 @@ void GcodeSuite::M305() {
// A valid P index is required // A valid P index is required
if (t_index >= (USER_THERMISTORS) || (do_set && t_index < 0)) if (t_index >= (USER_THERMISTORS) || (do_set && t_index < 0))
SERIAL_ECHO_MSG("!Invalid index. (0 <= P <= ", int(USER_THERMISTORS - 1), ")"); SERIAL_ECHO_MSG("!Invalid index. (0 <= P <= ", USER_THERMISTORS - 1, ")");
else if (do_set) { else if (do_set) {
if (parser.seen('R')) // Pullup resistor value if (parser.seen('R')) // Pullup resistor value
if (!thermalManager.set_pull_up_res(t_index, parser.value_float())) if (!thermalManager.set_pull_up_res(t_index, parser.value_float()))

View File

@ -131,7 +131,7 @@ inline void servo_probe_test() {
const uint8_t probe_index = parser.byteval('P', Z_PROBE_SERVO_NR); const uint8_t probe_index = parser.byteval('P', Z_PROBE_SERVO_NR);
SERIAL_ECHOLNPAIR("Servo probe test\n" SERIAL_ECHOLNPAIR("Servo probe test\n"
". using index: ", int(probe_index), ". using index: ", probe_index,
", deploy angle: ", servo_angles[probe_index][0], ", deploy angle: ", servo_angles[probe_index][0],
", stow angle: ", servo_angles[probe_index][1] ", stow angle: ", servo_angles[probe_index][1]
); );
@ -143,7 +143,7 @@ inline void servo_probe_test() {
#define PROBE_TEST_PIN Z_MIN_PIN #define PROBE_TEST_PIN Z_MIN_PIN
constexpr bool probe_inverting = Z_MIN_ENDSTOP_INVERTING; constexpr bool probe_inverting = Z_MIN_ENDSTOP_INVERTING;
SERIAL_ECHOLNPAIR(". Probe Z_MIN_PIN: ", int(PROBE_TEST_PIN)); SERIAL_ECHOLNPAIR(". Probe Z_MIN_PIN: ", PROBE_TEST_PIN);
SERIAL_ECHOPGM(". Z_MIN_ENDSTOP_INVERTING: "); SERIAL_ECHOPGM(". Z_MIN_ENDSTOP_INVERTING: ");
#else #else
@ -151,7 +151,7 @@ inline void servo_probe_test() {
#define PROBE_TEST_PIN Z_MIN_PROBE_PIN #define PROBE_TEST_PIN Z_MIN_PROBE_PIN
constexpr bool probe_inverting = Z_MIN_PROBE_ENDSTOP_INVERTING; constexpr bool probe_inverting = Z_MIN_PROBE_ENDSTOP_INVERTING;
SERIAL_ECHOLNPAIR(". Probe Z_MIN_PROBE_PIN: ", int(PROBE_TEST_PIN)); SERIAL_ECHOLNPAIR(". Probe Z_MIN_PROBE_PIN: ", PROBE_TEST_PIN);
SERIAL_ECHOPGM( ". Z_MIN_PROBE_ENDSTOP_INVERTING: "); SERIAL_ECHOPGM( ". Z_MIN_PROBE_ENDSTOP_INVERTING: ");
#endif #endif

View File

@ -37,7 +37,7 @@ void report_M92(const bool echo=true, const int8_t e=-1) {
LOOP_L_N(i, E_STEPPERS) { LOOP_L_N(i, E_STEPPERS) {
if (e >= 0 && i != e) continue; if (e >= 0 && i != e) continue;
if (echo) SERIAL_ECHO_START(); else SERIAL_CHAR(' '); if (echo) SERIAL_ECHO_START(); else SERIAL_CHAR(' ');
SERIAL_ECHOLNPAIR_P(PSTR(" M92 T"), (int)i, SERIAL_ECHOLNPAIR_P(PSTR(" M92 T"), i,
SP_E_STR, VOLUMETRIC_UNIT(planner.settings.axis_steps_per_mm[E_AXIS_N(i)])); SP_E_STR, VOLUMETRIC_UNIT(planner.settings.axis_steps_per_mm[E_AXIS_N(i)]));
} }
#endif #endif

View File

@ -122,26 +122,26 @@
case DXC_DUPLICATION_MODE: DEBUG_ECHOPGM("DUPLICATION"); break; case DXC_DUPLICATION_MODE: DEBUG_ECHOPGM("DUPLICATION"); break;
case DXC_MIRRORED_MODE: DEBUG_ECHOPGM("MIRRORED"); break; case DXC_MIRRORED_MODE: DEBUG_ECHOPGM("MIRRORED"); break;
} }
DEBUG_ECHOPAIR("\nActive Ext: ", int(active_extruder)); DEBUG_ECHOPAIR("\nActive Ext: ", active_extruder);
if (!active_extruder_parked) DEBUG_ECHOPGM(" NOT "); if (!active_extruder_parked) DEBUG_ECHOPGM(" NOT ");
DEBUG_ECHOPGM(" parked."); DEBUG_ECHOPGM(" parked.");
DEBUG_ECHOPAIR("\nactive_extruder_x_pos: ", current_position.x); DEBUG_ECHOPAIR("\nactive_extruder_x_pos: ", current_position.x);
DEBUG_ECHOPAIR("\ninactive_extruder_x: ", inactive_extruder_x); DEBUG_ECHOPAIR("\ninactive_extruder_x: ", inactive_extruder_x);
DEBUG_ECHOPAIR("\nextruder_duplication_enabled: ", int(extruder_duplication_enabled)); DEBUG_ECHOPAIR("\nextruder_duplication_enabled: ", extruder_duplication_enabled);
DEBUG_ECHOPAIR("\nduplicate_extruder_x_offset: ", duplicate_extruder_x_offset); DEBUG_ECHOPAIR("\nduplicate_extruder_x_offset: ", duplicate_extruder_x_offset);
DEBUG_ECHOPAIR("\nduplicate_extruder_temp_offset: ", duplicate_extruder_temp_offset); DEBUG_ECHOPAIR("\nduplicate_extruder_temp_offset: ", duplicate_extruder_temp_offset);
DEBUG_ECHOPAIR("\ndelayed_move_time: ", delayed_move_time); DEBUG_ECHOPAIR("\ndelayed_move_time: ", delayed_move_time);
DEBUG_ECHOPAIR("\nX1 Home X: ", x_home_pos(0), "\nX1_MIN_POS=", int(X1_MIN_POS), "\nX1_MAX_POS=", int(X1_MAX_POS)); DEBUG_ECHOPAIR("\nX1 Home X: ", x_home_pos(0), "\nX1_MIN_POS=", X1_MIN_POS, "\nX1_MAX_POS=", X1_MAX_POS);
DEBUG_ECHOPAIR("\nX2 Home X: ", x_home_pos(1), "\nX2_MIN_POS=", int(X2_MIN_POS), "\nX2_MAX_POS=", int(X2_MAX_POS)); DEBUG_ECHOPAIR("\nX2 Home X: ", x_home_pos(1), "\nX2_MIN_POS=", X2_MIN_POS, "\nX2_MAX_POS=", X2_MAX_POS);
DEBUG_ECHOPAIR("\nX2_HOME_DIR=", int(X2_HOME_DIR), "\nX2_HOME_POS=", int(X2_HOME_POS)); DEBUG_ECHOPAIR("\nX2_HOME_DIR=", X2_HOME_DIR, "\nX2_HOME_POS=", X2_HOME_POS);
DEBUG_ECHOPAIR("\nDEFAULT_DUAL_X_CARRIAGE_MODE=", STRINGIFY(DEFAULT_DUAL_X_CARRIAGE_MODE)); DEBUG_ECHOPAIR("\nDEFAULT_DUAL_X_CARRIAGE_MODE=", STRINGIFY(DEFAULT_DUAL_X_CARRIAGE_MODE));
DEBUG_ECHOPAIR("\toolchange_settings.z_raise=", toolchange_settings.z_raise); DEBUG_ECHOPAIR("\toolchange_settings.z_raise=", toolchange_settings.z_raise);
DEBUG_ECHOPAIR("\nDEFAULT_DUPLICATION_X_OFFSET=", int(DEFAULT_DUPLICATION_X_OFFSET)); DEBUG_ECHOPAIR("\nDEFAULT_DUPLICATION_X_OFFSET=", DEFAULT_DUPLICATION_X_OFFSET);
DEBUG_EOL(); DEBUG_EOL();
HOTEND_LOOP() { HOTEND_LOOP() {
DEBUG_ECHOPAIR_P(SP_T_STR, int(e)); DEBUG_ECHOPAIR_P(SP_T_STR, e);
LOOP_XYZ(a) DEBUG_ECHOPAIR(" hotend_offset[", int(e), "].", XYZ_CHAR(a) | 0x20, "=", hotend_offset[e][a]); LOOP_XYZ(a) DEBUG_ECHOPAIR(" hotend_offset[", e, "].", XYZ_CHAR(a) | 0x20, "=", hotend_offset[e][a]);
DEBUG_EOL(); DEBUG_EOL();
} }
DEBUG_EOL(); DEBUG_EOL();

View File

@ -75,7 +75,7 @@ void GcodeSuite::M502() {
if (dowrite) { if (dowrite) {
val = parser.byteval('V'); val = parser.byteval('V');
persistentStore.write_data(addr, &val); persistentStore.write_data(addr, &val);
SERIAL_ECHOLNPAIR("Wrote address ", addr, " with ", int(val)); SERIAL_ECHOLNPAIR("Wrote address ", addr, " with ", val);
} }
else { else {
if (parser.seenval('T')) { if (parser.seenval('T')) {
@ -90,7 +90,7 @@ void GcodeSuite::M502() {
} }
else { else {
persistentStore.read_data(addr, &val); persistentStore.read_data(addr, &val);
SERIAL_ECHOLNPAIR("Read address ", addr, " and got ", int(val)); SERIAL_ECHOLNPAIR("Read address ", addr, " and got ", val);
} }
} }
return; return;

View File

@ -115,12 +115,12 @@ void GcodeSuite::M900() {
#if ENABLED(EXTRA_LIN_ADVANCE_K) #if ENABLED(EXTRA_LIN_ADVANCE_K)
#if EXTRUDERS < 2 #if EXTRUDERS < 2
SERIAL_ECHOLNPAIR("Advance S", int(new_slot), " K", kref, "(S", int(!new_slot), " K", lref, ")"); SERIAL_ECHOLNPAIR("Advance S", new_slot, " K", kref, "(S", !new_slot, " K", lref, ")");
#else #else
LOOP_L_N(i, EXTRUDERS) { LOOP_L_N(i, EXTRUDERS) {
const bool slot = TEST(lin_adv_slot, i); const bool slot = TEST(lin_adv_slot, i);
SERIAL_ECHOLNPAIR("Advance T", int(i), " S", int(slot), " K", planner.extruder_advance_K[i], SERIAL_ECHOLNPAIR("Advance T", i, " S", slot, " K", planner.extruder_advance_K[i],
"(S", int(!slot), " K", other_extruder_advance_K[i], ")"); "(S", !slot, " K", other_extruder_advance_K[i], ")");
SERIAL_EOL(); SERIAL_EOL();
} }
#endif #endif

View File

@ -82,7 +82,7 @@ void GcodeSuite::M7219() {
LOOP_L_N(r, MAX7219_LINES) { LOOP_L_N(r, MAX7219_LINES) {
SERIAL_ECHOPGM("led_line["); SERIAL_ECHOPGM("led_line[");
if (r < 10) SERIAL_CHAR(' '); if (r < 10) SERIAL_CHAR(' ');
SERIAL_ECHO(int(r)); SERIAL_ECHO(r);
SERIAL_ECHOPGM("]="); SERIAL_ECHOPGM("]=");
for (uint8_t b = 8; b--;) SERIAL_CHAR('0' + TEST(max7219.led_line[r], b)); for (uint8_t b = 8; b--;) SERIAL_CHAR('0' + TEST(max7219.led_line[r], b));
SERIAL_EOL(); SERIAL_EOL();

View File

@ -30,7 +30,7 @@
#include "../../../feature/mixing.h" #include "../../../feature/mixing.h"
inline void echo_mix() { inline void echo_mix() {
SERIAL_ECHOPAIR(" (", int(mixer.mix[0]), "%|", int(mixer.mix[1]), "%)"); SERIAL_ECHOPAIR(" (", mixer.mix[0], "%|", mixer.mix[1], "%)");
} }
inline void echo_zt(const int t, const float &z) { inline void echo_zt(const int t, const float &z) {
@ -74,7 +74,7 @@ void GcodeSuite::M166() {
#if ENABLED(GRADIENT_VTOOL) #if ENABLED(GRADIENT_VTOOL)
if (mixer.gradient.vtool_index >= 0) { if (mixer.gradient.vtool_index >= 0) {
SERIAL_ECHOPAIR(" (T", int(mixer.gradient.vtool_index)); SERIAL_ECHOPAIR(" (T", mixer.gradient.vtool_index);
SERIAL_CHAR(')'); SERIAL_CHAR(')');
} }
#endif #endif

View File

@ -48,7 +48,7 @@ void MAC_report() {
SERIAL_ECHOPGM(" MAC: "); SERIAL_ECHOPGM(" MAC: ");
LOOP_L_N(i, 6) { LOOP_L_N(i, 6) {
if (mac[i] < 16) SERIAL_CHAR('0'); if (mac[i] < 16) SERIAL_CHAR('0');
SERIAL_PRINT(mac[i], HEX); SERIAL_PRINT(mac[i], PrintBase::Hex);
if (i < 5) SERIAL_CHAR(':'); if (i < 5) SERIAL_CHAR(':');
} }
} }

View File

@ -49,7 +49,7 @@ void GcodeSuite::G61(void) {
// No saved position? No axes being restored? // No saved position? No axes being restored?
if (!TEST(saved_slots[slot >> 3], slot & 0x07) || !parser.seen("XYZ")) return; if (!TEST(saved_slots[slot >> 3], slot & 0x07) || !parser.seen("XYZ")) return;
SERIAL_ECHOPAIR(STR_RESTORING_POS " S", int(slot)); SERIAL_ECHOPAIR(STR_RESTORING_POS " S", slot);
LOOP_XYZ(i) { LOOP_XYZ(i) {
destination[i] = parser.seen(XYZ_CHAR(i)) destination[i] = parser.seen(XYZ_CHAR(i))
? stored_position[slot][i] + parser.value_axis_units((AxisEnum)i) ? stored_position[slot][i] + parser.value_axis_units((AxisEnum)i)

View File

@ -105,7 +105,7 @@ int8_t GcodeSuite::get_target_extruder_from_command() {
if (e < EXTRUDERS) return e; if (e < EXTRUDERS) return e;
SERIAL_ECHO_START(); SERIAL_ECHO_START();
SERIAL_CHAR('M'); SERIAL_ECHO(parser.codenum); SERIAL_CHAR('M'); SERIAL_ECHO(parser.codenum);
SERIAL_ECHOLNPAIR(" " STR_INVALID_EXTRUDER " ", int(e)); SERIAL_ECHOLNPAIR(" " STR_INVALID_EXTRUDER " ", e);
return -1; return -1;
} }
return active_extruder; return active_extruder;
@ -124,7 +124,7 @@ int8_t GcodeSuite::get_target_e_stepper_from_command() {
if (e == -1) if (e == -1)
SERIAL_ECHOLNPGM(" " STR_E_STEPPER_NOT_SPECIFIED); SERIAL_ECHOLNPGM(" " STR_E_STEPPER_NOT_SPECIFIED);
else else
SERIAL_ECHOLNPAIR(" " STR_INVALID_E_STEPPER " ", int(e)); SERIAL_ECHOLNPAIR(" " STR_INVALID_E_STEPPER " ", e);
return -1; return -1;
} }

View File

@ -38,7 +38,7 @@ void GcodeSuite::M113() {
NOMORE(host_keepalive_interval, 60); NOMORE(host_keepalive_interval, 60);
} }
else else
SERIAL_ECHO_MSG("M113 S", (uint16_t)host_keepalive_interval); SERIAL_ECHO_MSG("M113 S", host_keepalive_interval);
} }

View File

@ -35,7 +35,7 @@
static void config_prefix(PGM_P const name, PGM_P const pref=nullptr, const int8_t ind=-1) { static void config_prefix(PGM_P const name, PGM_P const pref=nullptr, const int8_t ind=-1) {
SERIAL_ECHOPGM("Config:"); SERIAL_ECHOPGM("Config:");
if (pref) serialprintPGM(pref); if (pref) serialprintPGM(pref);
if (ind >= 0) { SERIAL_ECHO(int(ind)); SERIAL_CHAR(':'); } if (ind >= 0) { SERIAL_ECHO(ind); SERIAL_CHAR(':'); }
serialprintPGM(name); serialprintPGM(name);
SERIAL_CHAR(':'); SERIAL_CHAR(':');
} }

View File

@ -97,7 +97,7 @@ void GcodeSuite::M290() {
#if ENABLED(BABYSTEP_HOTEND_Z_OFFSET) #if ENABLED(BABYSTEP_HOTEND_Z_OFFSET)
{ {
SERIAL_ECHOLNPAIR_P( SERIAL_ECHOLNPAIR_P(
PSTR("Hotend "), int(active_extruder) PSTR("Hotend "), active_extruder
#if ENABLED(BABYSTEP_XY) #if ENABLED(BABYSTEP_XY)
, PSTR("Offset X"), hotend_offset[active_extruder].x , PSTR("Offset X"), hotend_offset[active_extruder].x
, SP_Y_STR, hotend_offset[active_extruder].y , SP_Y_STR, hotend_offset[active_extruder].y

View File

@ -307,7 +307,7 @@ void GCodeParser::parse(char *p) {
#if ENABLED(DEBUG_GCODE_PARSER) #if ENABLED(DEBUG_GCODE_PARSER)
if (debug) { if (debug) {
SERIAL_ECHOPAIR("Got param ", param, " at index ", (int)(p - command_ptr - 1)); SERIAL_ECHOPAIR("Got param ", param, " at index ", p - command_ptr - 1);
if (has_val) SERIAL_ECHOPGM(" (has_val)"); if (has_val) SERIAL_ECHOPGM(" (has_val)");
} }
#endif #endif
@ -391,8 +391,8 @@ void GCodeParser::unknown_command_warning() {
"\n sec-ms: ", value_millis_from_seconds(), "\n sec-ms: ", value_millis_from_seconds(),
"\n int: ", value_int(), "\n int: ", value_int(),
"\n ushort: ", value_ushort(), "\n ushort: ", value_ushort(),
"\n byte: ", (int)value_byte(), "\n byte: ", value_byte(),
"\n bool: ", (int)value_bool(), "\n bool: ", value_bool(),
"\n linear: ", value_linear_units(), "\n linear: ", value_linear_units(),
"\n celsius: ", value_celsius() "\n celsius: ", value_celsius()
); );

View File

@ -133,9 +133,9 @@ public:
param[ind] = ptr ? ptr - command_ptr : 0; // parameter offset or 0 param[ind] = ptr ? ptr - command_ptr : 0; // parameter offset or 0
#if ENABLED(DEBUG_GCODE_PARSER) #if ENABLED(DEBUG_GCODE_PARSER)
if (codenum == 800) { if (codenum == 800) {
SERIAL_ECHOPAIR("Set bit ", (int)ind, " of codebits (", hex_address((void*)(codebits >> 16))); SERIAL_ECHOPAIR("Set bit ", ind, " of codebits (", hex_address((void*)(codebits >> 16)));
print_hex_word((uint16_t)(codebits & 0xFFFF)); print_hex_word((uint16_t)(codebits & 0xFFFF));
SERIAL_ECHOLNPAIR(") | param = ", (int)param[ind]); SERIAL_ECHOLNPAIR(") | param = ", param[ind]);
} }
#endif #endif
} }

View File

@ -58,7 +58,7 @@ void GcodeSuite::M851() {
if (WITHIN(x, -(X_BED_SIZE), X_BED_SIZE)) if (WITHIN(x, -(X_BED_SIZE), X_BED_SIZE))
offs.x = x; offs.x = x;
else { else {
SERIAL_ECHOLNPAIR("?X out of range (-", int(X_BED_SIZE), " to ", int(X_BED_SIZE), ")"); SERIAL_ECHOLNPAIR("?X out of range (-", X_BED_SIZE, " to ", X_BED_SIZE, ")");
ok = false; ok = false;
} }
#else #else
@ -72,7 +72,7 @@ void GcodeSuite::M851() {
if (WITHIN(y, -(Y_BED_SIZE), Y_BED_SIZE)) if (WITHIN(y, -(Y_BED_SIZE), Y_BED_SIZE))
offs.y = y; offs.y = y;
else { else {
SERIAL_ECHOLNPAIR("?Y out of range (-", int(Y_BED_SIZE), " to ", int(Y_BED_SIZE), ")"); SERIAL_ECHOLNPAIR("?Y out of range (-", Y_BED_SIZE, " to ", Y_BED_SIZE, ")");
ok = false; ok = false;
} }
#else #else
@ -85,7 +85,7 @@ void GcodeSuite::M851() {
if (WITHIN(z, Z_PROBE_OFFSET_RANGE_MIN, Z_PROBE_OFFSET_RANGE_MAX)) if (WITHIN(z, Z_PROBE_OFFSET_RANGE_MIN, Z_PROBE_OFFSET_RANGE_MAX))
offs.z = z; offs.z = z;
else { else {
SERIAL_ECHOLNPAIR("?Z out of range (", int(Z_PROBE_OFFSET_RANGE_MIN), " to ", int(Z_PROBE_OFFSET_RANGE_MAX), ")"); SERIAL_ECHOLNPAIR("?Z out of range (", Z_PROBE_OFFSET_RANGE_MIN, " to ", Z_PROBE_OFFSET_RANGE_MAX, ")");
ok = false; ok = false;
} }
} }

View File

@ -302,8 +302,8 @@ void GCodeQueue::ok_to_send() {
while (NUMERIC_SIGNED(*p)) while (NUMERIC_SIGNED(*p))
SERIAL_CHAR(*p++); SERIAL_CHAR(*p++);
} }
SERIAL_ECHOPAIR_P(SP_P_STR, int(planner.moves_free()), SERIAL_ECHOPAIR_P(SP_P_STR, planner.moves_free(),
SP_B_STR, int(BUFSIZE - length)); SP_B_STR, BUFSIZE - length);
#endif #endif
SERIAL_EOL(); SERIAL_EOL();
} }

View File

@ -1772,7 +1772,7 @@ void HMI_SDCardUpdate() {
if (HMI_flag.home_flag) return; if (HMI_flag.home_flag) return;
if (DWIN_lcd_sd_status != card.isMounted()) { if (DWIN_lcd_sd_status != card.isMounted()) {
DWIN_lcd_sd_status = card.isMounted(); DWIN_lcd_sd_status = card.isMounted();
// SERIAL_ECHOLNPAIR("HMI_SDCardUpdate: ", int(DWIN_lcd_sd_status)); // SERIAL_ECHOLNPAIR("HMI_SDCardUpdate: ", DWIN_lcd_sd_status);
if (DWIN_lcd_sd_status) { if (DWIN_lcd_sd_status) {
if (checkkey == SelectFile) if (checkkey == SelectFile)
Redraw_SD_List(); Redraw_SD_List();

View File

@ -141,7 +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_ECHOLNPAIR("TFT Serial Debug: OnSDCardStateChange event triggered...", (int)isInserted); SERIAL_ECHOLNPAIR("TFT Serial Debug: OnSDCardStateChange event triggered...", isInserted);
#endif #endif
DoSDCardStateCheck(); DoSDCardStateCheck();
} }

View File

@ -1083,7 +1083,7 @@ void CLCD::init() {
if (counter == 249) { if (counter == 249) {
#if ENABLED(TOUCH_UI_DEBUG) #if ENABLED(TOUCH_UI_DEBUG)
SERIAL_ECHO_MSG("Timeout waiting for device ID, should be 124, got ", int(device_id)); SERIAL_ECHO_MSG("Timeout waiting for device ID, should be 124, got ", device_id);
#endif #endif
} }
} }
@ -1101,7 +1101,7 @@ void CLCD::init() {
delay(1); delay(1);
if (ENABLED(TOUCH_UI_DEBUG) && counter == 99) if (ENABLED(TOUCH_UI_DEBUG) && counter == 99)
SERIAL_ECHO_MSG("Timeout waiting for reset status. Should be 0x00, got ", int(reset_status)); SERIAL_ECHO_MSG("Timeout waiting for reset status. Should be 0x00, got ", reset_status);
} }
mem_write_8(REG::PWM_DUTY, 0); // turn off Backlight, Frequency already is set to 250Hz default mem_write_8(REG::PWM_DUTY, 0); // turn off Backlight, Frequency already is set to 250Hz default

View File

@ -124,7 +124,7 @@ namespace FTDI {
case UNPRESSED: case UNPRESSED:
if (tag != 0) { if (tag != 0) {
#if ENABLED(TOUCH_UI_DEBUG) #if ENABLED(TOUCH_UI_DEBUG)
SERIAL_ECHO_MSG("Touch start: ", int(tag)); SERIAL_ECHO_MSG("Touch start: ", tag);
#endif #endif
pressed_tag = tag; pressed_tag = tag;
@ -185,7 +185,7 @@ namespace FTDI {
if (UIData::flags.bits.touch_end_sound) sound.play(unpress_sound); if (UIData::flags.bits.touch_end_sound) sound.play(unpress_sound);
#if ENABLED(TOUCH_UI_DEBUG) #if ENABLED(TOUCH_UI_DEBUG)
SERIAL_ECHO_MSG("Touch end: ", int(pressed_tag)); SERIAL_ECHO_MSG("Touch end: ", pressed_tag);
#endif #endif
const uint8_t saved_pressed_tag = pressed_tag; const uint8_t saved_pressed_tag = pressed_tag;

View File

@ -43,7 +43,7 @@ void ScreenRef::setScreen(onRedraw_func_t onRedraw_ptr) {
if (type != 0xFF) { if (type != 0xFF) {
setType(type); setType(type);
#if ENABLED(TOUCH_UI_DEBUG) #if ENABLED(TOUCH_UI_DEBUG)
SERIAL_ECHO_MSG("New screen: ", int(type)); SERIAL_ECHO_MSG("New screen: ", type);
#endif #endif
} }
} }

View File

@ -37,9 +37,7 @@ namespace FTDI {
void SoundPlayer::play(effect_t effect, note_t note) { void SoundPlayer::play(effect_t effect, note_t note) {
#if ENABLED(TOUCH_UI_DEBUG) #if ENABLED(TOUCH_UI_DEBUG)
SERIAL_ECHO_START(); SERIAL_ECHO_MSG("Playing note ", note, ", instrument ", effect);
SERIAL_ECHOPAIR ("Playing note ", int(note));
SERIAL_ECHOLNPAIR(", instrument ", int(effect));
#endif #endif
// Play the note // Play the note

View File

@ -751,7 +751,7 @@ void MarlinUI::quick_feedback(const bool clear_buttons/*=true*/) {
// For Cartesian / Core motion simply move to the current_position // For Cartesian / Core motion simply move to the current_position
planner.buffer_line(current_position, fr_mm_s, axis == E_AXIS ? e_index : active_extruder); planner.buffer_line(current_position, fr_mm_s, axis == E_AXIS ? e_index : active_extruder);
//SERIAL_ECHOLNPAIR("Add planner.move with Axis ", int(axis), " at FR ", fr_mm_s); //SERIAL_ECHOLNPAIR("Add planner.move with Axis ", axis, " at FR ", fr_mm_s);
axis = NO_AXIS; axis = NO_AXIS;
@ -772,7 +772,7 @@ void MarlinUI::quick_feedback(const bool clear_buttons/*=true*/) {
#endif #endif
start_time = millis() + (menu_scale < 0.99f ? 0UL : 250UL); // delay for bigger moves start_time = millis() + (menu_scale < 0.99f ? 0UL : 250UL); // delay for bigger moves
axis = move_axis; axis = move_axis;
//SERIAL_ECHOLNPAIR("Post Move with Axis ", int(axis), " soon."); //SERIAL_ECHOLNPAIR("Post Move with Axis ", axis, " soon.");
} }
#if ENABLED(AUTO_BED_LEVELING_UBL) #if ENABLED(AUTO_BED_LEVELING_UBL)

View File

@ -216,7 +216,7 @@ void menu_advanced_settings();
#if ENABLED(BLTOUCH_LCD_VOLTAGE_MENU) #if ENABLED(BLTOUCH_LCD_VOLTAGE_MENU)
void bltouch_report() { void bltouch_report() {
SERIAL_ECHOLNPAIR("EEPROM Last BLTouch Mode - ", (int)bltouch.last_written_mode); SERIAL_ECHOLNPAIR("EEPROM Last BLTouch Mode - ", bltouch.last_written_mode);
SERIAL_ECHOLNPGM("Configuration BLTouch Mode - " TERN(BLTOUCH_SET_5V_MODE, "5V", "OD")); SERIAL_ECHOLNPGM("Configuration BLTouch Mode - " TERN(BLTOUCH_SET_5V_MODE, "5V", "OD"));
char mess[21]; char mess[21];
strcpy_P(mess, PSTR("BLTouch Mode - ")); strcpy_P(mess, PSTR("BLTouch Mode - "));

View File

@ -120,7 +120,7 @@ public:
static void report(const uint8_t index) { static void report(const uint8_t index) {
if (index < Cfg::SIZE) { if (index < Cfg::SIZE) {
SERIAL_ECHOPAIR("bresenham ", int(index), " : (", dividend[index], "/", divisor, ") "); SERIAL_ECHOPAIR("bresenham ", index, " : (", dividend[index], "/", divisor, ") ");
if (counter[index] >= 0) SERIAL_CHAR(' '); if (counter[index] >= 0) SERIAL_CHAR(' ');
if (labs(counter[index]) < 100) { SERIAL_CHAR(' '); if (labs(counter[index]) < 10) SERIAL_CHAR(' '); } if (labs(counter[index]) < 100) { SERIAL_CHAR(' '); if (labs(counter[index]) < 10) SERIAL_CHAR(' '); }
SERIAL_ECHO(counter[index]); SERIAL_ECHO(counter[index]);

View File

@ -1305,7 +1305,7 @@ void do_homing_move(const AxisEnum axis, const float distance, const feedRate_t
const feedRate_t home_fr_mm_s = fr_mm_s ?: homing_feedrate(axis); const feedRate_t home_fr_mm_s = fr_mm_s ?: homing_feedrate(axis);
if (DEBUGGING(LEVELING)) { if (DEBUGGING(LEVELING)) {
DEBUG_ECHOPAIR("...(", axis_codes[axis], ", ", distance, ", "); DEBUG_ECHOPAIR("...(", AS_CHAR(axis_codes[axis]), ", ", distance, ", ");
if (fr_mm_s) if (fr_mm_s)
DEBUG_ECHO(fr_mm_s); DEBUG_ECHO(fr_mm_s);
else else
@ -1398,7 +1398,7 @@ void do_homing_move(const AxisEnum axis, const float distance, const feedRate_t
* Callers must sync the planner position after calling this! * Callers must sync the planner position after calling this!
*/ */
void set_axis_is_at_home(const AxisEnum axis) { void set_axis_is_at_home(const AxisEnum axis) {
if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR(">>> set_axis_is_at_home(", axis_codes[axis], ")"); if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR(">>> set_axis_is_at_home(", AS_CHAR(axis_codes[axis]), ")");
set_axis_trusted(axis); set_axis_trusted(axis);
set_axis_homed(axis); set_axis_homed(axis);
@ -1448,7 +1448,7 @@ void set_axis_is_at_home(const AxisEnum axis) {
if (DEBUGGING(LEVELING)) { if (DEBUGGING(LEVELING)) {
#if HAS_HOME_OFFSET #if HAS_HOME_OFFSET
DEBUG_ECHOLNPAIR("> home_offset[", axis_codes[axis], "] = ", home_offset[axis]); DEBUG_ECHOLNPAIR("> home_offset[", AS_CHAR(axis_codes[axis]), "] = ", home_offset[axis]);
#endif #endif
DEBUG_POS("", current_position); DEBUG_POS("", current_position);
DEBUG_ECHOLNPAIR("<<< set_axis_is_at_home(", axis_codes[axis], ")"); DEBUG_ECHOLNPAIR("<<< set_axis_is_at_home(", axis_codes[axis], ")");

View File

@ -719,7 +719,7 @@ float Probe::probe_at_point(const float &rx, const float &ry, const ProbePtRaise
DEBUG_ECHOLNPAIR( DEBUG_ECHOLNPAIR(
"...(", LOGICAL_X_POSITION(rx), ", ", LOGICAL_Y_POSITION(ry), "...(", LOGICAL_X_POSITION(rx), ", ", LOGICAL_Y_POSITION(ry),
", ", raise_after == PROBE_PT_RAISE ? "raise" : raise_after == PROBE_PT_STOW ? "stow" : "none", ", ", raise_after == PROBE_PT_RAISE ? "raise" : raise_after == PROBE_PT_STOW ? "stow" : "none",
", ", int(verbose_level), ", ", verbose_level,
", ", probe_relative ? "probe" : "nozzle", "_relative)" ", ", probe_relative ? "probe" : "nozzle", "_relative)"
); );
DEBUG_POS("", current_position); DEBUG_POS("", current_position);

View File

@ -2289,7 +2289,7 @@ void MarlinSettings::postprocess() {
eeprom_error = size_error(eeprom_index - (EEPROM_OFFSET)); eeprom_error = size_error(eeprom_index - (EEPROM_OFFSET));
if (eeprom_error) { if (eeprom_error) {
DEBUG_ECHO_START(); DEBUG_ECHO_START();
DEBUG_ECHOLNPAIR("Index: ", int(eeprom_index - (EEPROM_OFFSET)), " Size: ", datasize()); DEBUG_ECHOLNPAIR("Index: ", eeprom_index - (EEPROM_OFFSET), " Size: ", datasize());
IF_DISABLED(EEPROM_AUTO_INIT, ui.eeprom_alert_index()); IF_DISABLED(EEPROM_AUTO_INIT, ui.eeprom_alert_index());
} }
else if (working_crc != stored_crc) { else if (working_crc != stored_crc) {
@ -3039,7 +3039,7 @@ void MarlinSettings::reset() {
} }
#if EXTRUDERS == 1 #if EXTRUDERS == 1
CONFIG_ECHO_MSG(" M200 S", int(parser.volumetric_enabled) CONFIG_ECHO_MSG(" M200 S", parser.volumetric_enabled
, " D", LINEAR_UNIT(planner.filament_size[0]) , " D", LINEAR_UNIT(planner.filament_size[0])
#if ENABLED(VOLUMETRIC_EXTRUDER_LIMIT) #if ENABLED(VOLUMETRIC_EXTRUDER_LIMIT)
, " L", LINEAR_UNIT(planner.volumetric_extruder_limit[0]) , " L", LINEAR_UNIT(planner.volumetric_extruder_limit[0])
@ -3047,14 +3047,14 @@ void MarlinSettings::reset() {
); );
#else #else
LOOP_L_N(i, EXTRUDERS) { LOOP_L_N(i, EXTRUDERS) {
CONFIG_ECHO_MSG(" M200 T", int(i) CONFIG_ECHO_MSG(" M200 T", i
, " D", LINEAR_UNIT(planner.filament_size[i]) , " D", LINEAR_UNIT(planner.filament_size[i])
#if ENABLED(VOLUMETRIC_EXTRUDER_LIMIT) #if ENABLED(VOLUMETRIC_EXTRUDER_LIMIT)
, " L", LINEAR_UNIT(planner.volumetric_extruder_limit[i]) , " L", LINEAR_UNIT(planner.volumetric_extruder_limit[i])
#endif #endif
); );
} }
CONFIG_ECHO_MSG(" M200 S", int(parser.volumetric_enabled)); CONFIG_ECHO_MSG(" M200 S", parser.volumetric_enabled);
#endif #endif
#endif // EXTRUDERS && !NO_VOLUMETRICS #endif // EXTRUDERS && !NO_VOLUMETRICS
@ -3076,7 +3076,7 @@ void MarlinSettings::reset() {
LOOP_L_N(i, E_STEPPERS) { LOOP_L_N(i, E_STEPPERS) {
CONFIG_ECHO_START(); CONFIG_ECHO_START();
SERIAL_ECHOLNPAIR_P( SERIAL_ECHOLNPAIR_P(
PSTR(" M203 T"), (int)i PSTR(" M203 T"), i
, SP_E_STR, VOLUMETRIC_UNIT(planner.settings.max_feedrate_mm_s[E_AXIS_N(i)]) , SP_E_STR, VOLUMETRIC_UNIT(planner.settings.max_feedrate_mm_s[E_AXIS_N(i)])
); );
} }
@ -3096,7 +3096,7 @@ void MarlinSettings::reset() {
LOOP_L_N(i, E_STEPPERS) { LOOP_L_N(i, E_STEPPERS) {
CONFIG_ECHO_START(); CONFIG_ECHO_START();
SERIAL_ECHOLNPAIR_P( SERIAL_ECHOLNPAIR_P(
PSTR(" M201 T"), (int)i PSTR(" M201 T"), i
, SP_E_STR, VOLUMETRIC_UNIT(planner.settings.max_acceleration_mm_per_s2[E_AXIS_N(i)]) , SP_E_STR, VOLUMETRIC_UNIT(planner.settings.max_acceleration_mm_per_s2[E_AXIS_N(i)])
); );
} }
@ -3158,7 +3158,7 @@ void MarlinSettings::reset() {
CONFIG_ECHO_START(); CONFIG_ECHO_START();
LOOP_S_L_N(e, 1, HOTENDS) { LOOP_S_L_N(e, 1, HOTENDS) {
SERIAL_ECHOPAIR_P( SERIAL_ECHOPAIR_P(
PSTR(" M218 T"), (int)e, PSTR(" M218 T"), e,
SP_X_STR, LINEAR_UNIT(hotend_offset[e].x), SP_X_STR, LINEAR_UNIT(hotend_offset[e].x),
SP_Y_STR, LINEAR_UNIT(hotend_offset[e].y) SP_Y_STR, LINEAR_UNIT(hotend_offset[e].y)
); );
@ -3192,7 +3192,7 @@ void MarlinSettings::reset() {
CONFIG_ECHO_START(); CONFIG_ECHO_START();
SERIAL_ECHOLNPAIR_P( SERIAL_ECHOLNPAIR_P(
PSTR(" M420 S"), int(planner.leveling_active) PSTR(" M420 S"), planner.leveling_active
#if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT)
, SP_Z_STR, LINEAR_UNIT(planner.z_fade_height) , SP_Z_STR, LINEAR_UNIT(planner.z_fade_height)
#endif #endif
@ -3204,7 +3204,7 @@ void MarlinSettings::reset() {
LOOP_L_N(py, GRID_MAX_POINTS_Y) { LOOP_L_N(py, GRID_MAX_POINTS_Y) {
LOOP_L_N(px, GRID_MAX_POINTS_X) { LOOP_L_N(px, GRID_MAX_POINTS_X) {
CONFIG_ECHO_START(); CONFIG_ECHO_START();
SERIAL_ECHOPAIR_P(PSTR(" G29 S3 I"), (int)px, PSTR(" J"), (int)py); SERIAL_ECHOPAIR_P(PSTR(" G29 S3 I"), px, PSTR(" J"), py);
SERIAL_ECHOLNPAIR_F_P(SP_Z_STR, LINEAR_UNIT(mbl.z_values[px][py]), 5); SERIAL_ECHOLNPAIR_F_P(SP_Z_STR, LINEAR_UNIT(mbl.z_values[px][py]), 5);
} }
} }
@ -3233,7 +3233,7 @@ void MarlinSettings::reset() {
LOOP_L_N(py, GRID_MAX_POINTS_Y) { LOOP_L_N(py, GRID_MAX_POINTS_Y) {
LOOP_L_N(px, GRID_MAX_POINTS_X) { LOOP_L_N(px, GRID_MAX_POINTS_X) {
CONFIG_ECHO_START(); CONFIG_ECHO_START();
SERIAL_ECHOPAIR(" G29 W I", (int)px, " J", (int)py); SERIAL_ECHOPAIR(" G29 W I", px, " J", py);
SERIAL_ECHOLNPAIR_F_P(SP_Z_STR, LINEAR_UNIT(z_values[px][py]), 5); SERIAL_ECHOLNPAIR_F_P(SP_Z_STR, LINEAR_UNIT(z_values[px][py]), 5);
} }
} }
@ -3258,7 +3258,7 @@ void MarlinSettings::reset() {
#elif ENABLED(BLTOUCH) || (HAS_Z_SERVO_PROBE && defined(Z_SERVO_ANGLES)) #elif ENABLED(BLTOUCH) || (HAS_Z_SERVO_PROBE && defined(Z_SERVO_ANGLES))
case Z_PROBE_SERVO_NR: case Z_PROBE_SERVO_NR:
#endif #endif
CONFIG_ECHO_MSG(" M281 P", int(i), " L", servo_angles[i][0], " U", servo_angles[i][1]); CONFIG_ECHO_MSG(" M281 P", i, " L", servo_angles[i][0], " U", servo_angles[i][1]);
default: break; default: break;
} }
} }
@ -3334,7 +3334,7 @@ void MarlinSettings::reset() {
LOOP_L_N(i, PREHEAT_COUNT) { LOOP_L_N(i, PREHEAT_COUNT) {
CONFIG_ECHO_START(); CONFIG_ECHO_START();
SERIAL_ECHOLNPAIR_P( SERIAL_ECHOLNPAIR_P(
PSTR(" M145 S"), (int)i PSTR(" M145 S"), i
#if HAS_HOTEND #if HAS_HOTEND
, PSTR(" H"), TEMP_UNIT(ui.material_preset[i].hotend_temp) , PSTR(" H"), TEMP_UNIT(ui.material_preset[i].hotend_temp)
#endif #endif
@ -3403,7 +3403,7 @@ void MarlinSettings::reset() {
#if ENABLED(POWER_LOSS_RECOVERY) #if ENABLED(POWER_LOSS_RECOVERY)
CONFIG_ECHO_HEADING("Power-Loss Recovery:"); CONFIG_ECHO_HEADING("Power-Loss Recovery:");
CONFIG_ECHO_MSG(" M413 S", int(recovery.enabled)); CONFIG_ECHO_MSG(" M413 S", recovery.enabled);
#endif #endif
#if ENABLED(FWRETRACT) #if ENABLED(FWRETRACT)
@ -3425,11 +3425,9 @@ void MarlinSettings::reset() {
); );
#if ENABLED(FWRETRACT_AUTORETRACT) #if ENABLED(FWRETRACT_AUTORETRACT)
CONFIG_ECHO_HEADING("Auto-Retract: S=0 to disable, 1 to interpret E-only moves as retract/recover"); CONFIG_ECHO_HEADING("Auto-Retract: S=0 to disable, 1 to interpret E-only moves as retract/recover");
CONFIG_ECHO_MSG(" M209 S", int(fwretract.autoretract_enabled)); CONFIG_ECHO_MSG(" M209 S", fwretract.autoretract_enabled);
#endif
#endif // FWRETRACT_AUTORETRACT
#endif // FWRETRACT #endif // FWRETRACT
@ -3775,7 +3773,7 @@ void MarlinSettings::reset() {
CONFIG_ECHO_MSG(" M900 K", planner.extruder_advance_K[0]); CONFIG_ECHO_MSG(" M900 K", planner.extruder_advance_K[0]);
#else #else
LOOP_L_N(i, EXTRUDERS) LOOP_L_N(i, EXTRUDERS)
CONFIG_ECHO_MSG(" M900 T", int(i), " K", planner.extruder_advance_K[i]); CONFIG_ECHO_MSG(" M900 T", i, " K", planner.extruder_advance_K[i]);
#endif #endif
#endif #endif
@ -3841,7 +3839,7 @@ void MarlinSettings::reset() {
#if HAS_FILAMENT_SENSOR #if HAS_FILAMENT_SENSOR
CONFIG_ECHO_HEADING("Filament runout sensor:"); CONFIG_ECHO_HEADING("Filament runout sensor:");
CONFIG_ECHO_MSG( CONFIG_ECHO_MSG(
" M412 S", int(runout.enabled) " M412 S", runout.enabled
#if HAS_FILAMENT_RUNOUT_DISTANCE #if HAS_FILAMENT_RUNOUT_DISTANCE
, " D", LINEAR_UNIT(runout.runout_distance()) , " D", LINEAR_UNIT(runout.runout_distance())
#endif #endif
@ -3859,7 +3857,7 @@ void MarlinSettings::reset() {
#if HAS_MULTI_LANGUAGE #if HAS_MULTI_LANGUAGE
CONFIG_ECHO_HEADING("UI Language:"); CONFIG_ECHO_HEADING("UI Language:");
SERIAL_ECHO_MSG(" M414 S", int(ui.language)); SERIAL_ECHO_MSG(" M414 S", ui.language);
#endif #endif
} }

View File

@ -828,7 +828,7 @@ void Temperature::_temp_error(const heater_id_t heater_id, PGM_P const serial_ms
serialprintPGM(serial_msg); serialprintPGM(serial_msg);
SERIAL_ECHOPGM(STR_STOPPED_HEATER); SERIAL_ECHOPGM(STR_STOPPED_HEATER);
if (heater_id >= 0) if (heater_id >= 0)
SERIAL_ECHO((int)heater_id); SERIAL_ECHO(heater_id);
else if (TERN0(HAS_HEATED_CHAMBER, heater_id == H_CHAMBER)) else if (TERN0(HAS_HEATED_CHAMBER, heater_id == H_CHAMBER))
SERIAL_ECHOPGM(STR_HEATER_CHAMBER); SERIAL_ECHOPGM(STR_HEATER_CHAMBER);
else else
@ -1494,7 +1494,7 @@ void Temperature::manage_heater() {
float Temperature::analog_to_celsius_hotend(const int raw, const uint8_t e) { float Temperature::analog_to_celsius_hotend(const int raw, const uint8_t e) {
if (e > HOTENDS - DISABLED(TEMP_SENSOR_1_AS_REDUNDANT)) { if (e > HOTENDS - DISABLED(TEMP_SENSOR_1_AS_REDUNDANT)) {
SERIAL_ERROR_START(); SERIAL_ERROR_START();
SERIAL_ECHO((int)e); SERIAL_ECHO(e);
SERIAL_ECHOLNPGM(STR_INVALID_EXTRUDER_NUM); SERIAL_ECHOLNPGM(STR_INVALID_EXTRUDER_NUM);
kill(); kill();
return 0; return 0;
@ -2065,7 +2065,7 @@ void Temperature::init() {
switch (heater_id) { switch (heater_id) {
case H_BED: SERIAL_ECHOPGM("bed"); break; case H_BED: SERIAL_ECHOPGM("bed"); break;
case H_CHAMBER: SERIAL_ECHOPGM("chamber"); break; case H_CHAMBER: SERIAL_ECHOPGM("chamber"); break;
default: SERIAL_ECHO((int)heater_id); default: SERIAL_ECHO(heater_id);
} }
SERIAL_ECHOLNPAIR( SERIAL_ECHOLNPAIR(
" ; sizeof(running_temp):", sizeof(running_temp), " ; sizeof(running_temp):", sizeof(running_temp),

View File

@ -186,7 +186,7 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a
current_position.x = mpe_settings.parking_xpos[new_tool] + offsetcompensation; current_position.x = mpe_settings.parking_xpos[new_tool] + offsetcompensation;
DEBUG_ECHOPAIR("(1) Move extruder ", int(new_tool)); DEBUG_ECHOPAIR("(1) Move extruder ", new_tool);
DEBUG_POS(" to new extruder ParkPos", current_position); DEBUG_POS(" to new extruder ParkPos", current_position);
planner.buffer_line(current_position, mpe_settings.fast_feedrate, new_tool); planner.buffer_line(current_position, mpe_settings.fast_feedrate, new_tool);
@ -196,7 +196,7 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a
current_position.x = grabpos + offsetcompensation; current_position.x = grabpos + offsetcompensation;
DEBUG_ECHOPAIR("(2) Couple extruder ", int(new_tool)); DEBUG_ECHOPAIR("(2) Couple extruder ", new_tool);
DEBUG_POS(" to new extruder GrabPos", current_position); DEBUG_POS(" to new extruder GrabPos", current_position);
planner.buffer_line(current_position, mpe_settings.slow_feedrate, new_tool); planner.buffer_line(current_position, mpe_settings.slow_feedrate, new_tool);
@ -209,7 +209,7 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a
current_position.x = mpe_settings.parking_xpos[new_tool] + offsetcompensation; current_position.x = mpe_settings.parking_xpos[new_tool] + offsetcompensation;
DEBUG_ECHOPAIR("(3) Move extruder ", int(new_tool)); DEBUG_ECHOPAIR("(3) Move extruder ", new_tool);
DEBUG_POS(" back to new extruder ParkPos", current_position); DEBUG_POS(" back to new extruder ParkPos", current_position);
planner.buffer_line(current_position, mpe_settings.slow_feedrate, new_tool); planner.buffer_line(current_position, mpe_settings.slow_feedrate, new_tool);
@ -219,7 +219,7 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a
current_position.x = mpe_settings.parking_xpos[active_extruder] + (active_extruder == 0 ? MPE_TRAVEL_DISTANCE : -MPE_TRAVEL_DISTANCE) + offsetcompensation; current_position.x = mpe_settings.parking_xpos[active_extruder] + (active_extruder == 0 ? MPE_TRAVEL_DISTANCE : -MPE_TRAVEL_DISTANCE) + offsetcompensation;
DEBUG_ECHOPAIR("(4) Move extruder ", int(new_tool)); DEBUG_ECHOPAIR("(4) Move extruder ", new_tool);
DEBUG_POS(" close to old extruder ParkPos", current_position); DEBUG_POS(" close to old extruder ParkPos", current_position);
planner.buffer_line(current_position, mpe_settings.fast_feedrate, new_tool); planner.buffer_line(current_position, mpe_settings.fast_feedrate, new_tool);
@ -229,7 +229,7 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a
current_position.x = mpe_settings.parking_xpos[active_extruder] + offsetcompensation; current_position.x = mpe_settings.parking_xpos[active_extruder] + offsetcompensation;
DEBUG_ECHOPAIR("(5) Park extruder ", int(new_tool)); DEBUG_ECHOPAIR("(5) Park extruder ", new_tool);
DEBUG_POS(" at old extruder ParkPos", current_position); DEBUG_POS(" at old extruder ParkPos", current_position);
planner.buffer_line(current_position, mpe_settings.slow_feedrate, new_tool); planner.buffer_line(current_position, mpe_settings.slow_feedrate, new_tool);
@ -239,7 +239,7 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a
current_position.x = oldx; current_position.x = oldx;
DEBUG_ECHOPAIR("(6) Move extruder ", int(new_tool)); DEBUG_ECHOPAIR("(6) Move extruder ", new_tool);
DEBUG_POS(" to starting position", current_position); DEBUG_POS(" to starting position", current_position);
planner.buffer_line(current_position, mpe_settings.fast_feedrate, new_tool); planner.buffer_line(current_position, mpe_settings.fast_feedrate, new_tool);
@ -274,9 +274,9 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a
if (homed_towards_final_tool) { if (homed_towards_final_tool) {
pe_solenoid_magnet_off(1 - final_tool); pe_solenoid_magnet_off(1 - final_tool);
DEBUG_ECHOLNPAIR("Disengage magnet", (int)(1 - final_tool)); DEBUG_ECHOLNPAIR("Disengage magnet", 1 - final_tool);
pe_solenoid_magnet_on(final_tool); pe_solenoid_magnet_on(final_tool);
DEBUG_ECHOLNPAIR("Engage magnet", (int)final_tool); DEBUG_ECHOLNPAIR("Engage magnet", final_tool);
parking_extruder_set_parked(false); parking_extruder_set_parked(false);
return false; return false;
} }
@ -315,7 +315,7 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a
if (!extruder_parked) { if (!extruder_parked) {
current_position.x = parkingposx[active_extruder] + x_offset; current_position.x = parkingposx[active_extruder] + x_offset;
DEBUG_ECHOLNPAIR("(1) Park extruder ", int(active_extruder)); DEBUG_ECHOLNPAIR("(1) Park extruder ", active_extruder);
DEBUG_POS("Moving ParkPos", current_position); DEBUG_POS("Moving ParkPos", current_position);
fast_line_to_current(X_AXIS); fast_line_to_current(X_AXIS);
@ -411,7 +411,7 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a
current_position.x = placexpos; current_position.x = placexpos;
DEBUG_ECHOLNPAIR("(1) Place old tool ", int(active_extruder)); DEBUG_ECHOLNPAIR("(1) Place old tool ", active_extruder);
DEBUG_POS("Move X SwitchPos", current_position); DEBUG_POS("Move X SwitchPos", current_position);
fast_line_to_current(X_AXIS); fast_line_to_current(X_AXIS);
@ -509,7 +509,7 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a
current_position.y = SWITCHING_TOOLHEAD_Y_POS + SWITCHING_TOOLHEAD_Y_CLEAR; current_position.y = SWITCHING_TOOLHEAD_Y_POS + SWITCHING_TOOLHEAD_Y_CLEAR;
SERIAL_ECHOLNPAIR("(1) Place old tool ", int(active_extruder)); SERIAL_ECHOLNPAIR("(1) Place old tool ", active_extruder);
DEBUG_POS("Move Y SwitchPos + Security", current_position); DEBUG_POS("Move Y SwitchPos + Security", current_position);
fast_line_to_current(Y_AXIS); fast_line_to_current(Y_AXIS);
@ -709,7 +709,7 @@ inline void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_a
#if EXTRUDERS #if EXTRUDERS
inline void invalid_extruder_error(const uint8_t e) { inline void invalid_extruder_error(const uint8_t e) {
SERIAL_ECHO_START(); SERIAL_ECHO_START();
SERIAL_CHAR('T'); SERIAL_ECHO((int)e); SERIAL_CHAR('T'); SERIAL_ECHO(e);
SERIAL_CHAR(' '); SERIAL_ECHOLNPGM(STR_INVALID_EXTRUDER); SERIAL_CHAR(' '); SERIAL_ECHOLNPGM(STR_INVALID_EXTRUDER);
} }
#endif #endif
@ -1196,7 +1196,7 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) {
gcode.process_subcommands_now_P(PSTR(EVENT_GCODE_AFTER_TOOLCHANGE)); gcode.process_subcommands_now_P(PSTR(EVENT_GCODE_AFTER_TOOLCHANGE));
#endif #endif
SERIAL_ECHO_MSG(STR_ACTIVE_EXTRUDER, int(active_extruder)); SERIAL_ECHO_MSG(STR_ACTIVE_EXTRUDER, active_extruder);
#endif // HAS_MULTI_EXTRUDER #endif // HAS_MULTI_EXTRUDER
} }

View File

@ -926,7 +926,7 @@ int SdBaseFile::peek() {
// print uint8_t with width 2 // print uint8_t with width 2
static void print2u(const uint8_t v) { static void print2u(const uint8_t v) {
if (v < 10) SERIAL_CHAR('0'); if (v < 10) SERIAL_CHAR('0');
SERIAL_ECHO((int)v); SERIAL_ECHO(v);
} }
/** /**

View File

@ -583,7 +583,7 @@ void CardReader::openFileRead(char * const path, const uint8_t subcall_type/*=0*
// Too deep? The firmware has to bail. // Too deep? The firmware has to bail.
if (file_subcall_ctr > SD_PROCEDURE_DEPTH - 1) { if (file_subcall_ctr > SD_PROCEDURE_DEPTH - 1) {
SERIAL_ERROR_MSG("Exceeded max SUBROUTINE depth:", int(SD_PROCEDURE_DEPTH)); SERIAL_ERROR_MSG("Exceeded max SUBROUTINE depth:", SD_PROCEDURE_DEPTH);
kill(GET_TEXT(MSG_KILL_SUBCALL_OVERFLOW)); kill(GET_TEXT(MSG_KILL_SUBCALL_OVERFLOW));
return; return;
} }

View File

@ -40,5 +40,25 @@ typedef MultiSerial< RuntimeSerial<Serial>, ConditionalSerial<TelnetClient> > Se
By default, the serial base interface provide an emergency parser that's only enable for serial classes that support it. By default, the serial base interface provide an emergency parser that's only enable for serial classes that support it.
Because of this condition, all underlying type takes a first `bool emergencyParserEnabled` argument to their constructor. You must take into account this parameter when defining the actual type used. Because of this condition, all underlying type takes a first `bool emergencyParserEnabled` argument to their constructor. You must take into account this parameter when defining the actual type used.
## SERIAL macros
The following macros are defined (in `serial.h`) to output data to the serial ports:
| MACRO | Parameters | Usage | Example | Expected output |
|-------|------------|-------|---------|-----------------|
| `SERIAL_ECHO` | Any basic type is supported (`char`, `uint8_t`, `int16_t`, `int32_t`, `float`, `long`, `const char*`, ...). | For a numeric type it prints the number in decimal. A string is output as a string. | `uint8_t a = 123; SERIAL_ECHO(a); SERIAL_CHAR(' '); SERIAL_ECHO(' '); ` | `123 32` |
| `SERIAL_ECHOLN` | Same as `SERIAL_ECHO` | Do `SERIAL_ECHO`, adding a newline | `int a = 456; SERIAL_ECHOLN(a);` | `456\n` |
| `SERIAL_ECHO_F` | `float` or `double` | Print a decimal value with a given precision (default 2) | `float a = 3.1415; SERIAL_ECHO_F(a); SERIAL_CHAR(' '); SERIAL_ECHO_F(a, 4);` | `3.14 3.1415`|
| `SERIAL_ECHOPAIR` | String / Value pairs | Print a series of string literals and values alternately | `SERIAL_ECHOPAIR("Bob", 34);` | `Bob34` |
| `SERIAL_ECHOLNPAIR` | Same as `SERIAL_ECHOPAIR` | Do `SERIAL_ECHOPAIR`, adding a newline | `SERIAL_ECHOPAIR("Alice", 56);` | `alice56` |
| `SERIAL_ECHOPAIR_P` | Like `SERIAL_ECHOPAIR` but takes PGM strings | Print a series of PGM strings and values alternately | `SERIAL_ECHOPAIR_P(GET_TEXT(MSG_HELLO), 123);` | `Hello123` |
| `SERIAL_ECHOLNPAIR_P` | Same as `SERIAL_ECHOPAIR_P` | Do `SERIAL_ECHOPAIR_P`, adding a newline | `SERIAL_ECHOLNPAIR_P(PSTR("Alice"), 78);` | `alice78\n` |
| `SERIAL_ECHOLIST` | String literal, values | Print a string literal and a list of values | `SERIAL_ECHOLIST("Key ", 1, 2, 3);` | `Key 1, 2, 3` |
| `SERIAL_ECHO_START` | None | Prefix an echo line | `SERIAL_ECHO_START();` | `echo:` |
| `SERIAL_ECHO_MSG` | Same as `SERIAL_ECHOLN_PAIR` | Print a full echo line | `SERIAL_ECHO_MSG("Count is ", count);` | `echo:Count is 3` |
| `SERIAL_ERROR_START`| None | Prefix an error line | `SERIAL_ERROR_START();` | `Error:` |
| `SERIAL_ERROR_MSG` | Same as `SERIAL_ECHOLN_PAIR` | Print a full error line | `SERIAL_ERROR_MSG("Not found");` | `Error:Not found` |
| `SERIAL_ECHO_SP` | Number of spaces | Print one or more spaces | `SERIAL_ECHO_SP(3)` | ` ` |
| `SERIAL_EOL` | None | Print an end of line | `SERIAL_EOL();` | `\n` |
| `SERIAL_OUT` | `SERIAL_OUT(myMethod)` | Call a custom serial method | `SERIAL_OUT(msgDone);` | ... |
*This document was written by [X-Ryl669](https://blog.cyril.by) and is under [CC-SA license](https://creativecommons.org/licenses/by-sa)* *This document was written by [X-Ryl669](https://blog.cyril.by) and is under [CC-SA license](https://creativecommons.org/licenses/by-sa)*