Переглянути джерело

Allow SERIAL_ECHOPAIR to take up to 12 pairs (#13311)

Scott Lahteine 5 роки тому
джерело
коміт
cfdb38eda4
Аккаунт користувача з таким Email не знайдено

+ 1
- 2
Marlin/src/Marlin.cpp Переглянути файл

@@ -910,8 +910,7 @@ void setup() {
910 910
   #endif
911 911
 
912 912
   SERIAL_ECHO_START();
913
-  SERIAL_ECHOPAIR(MSG_FREE_MEMORY, freeMemory());
914
-  SERIAL_ECHOLNPAIR(MSG_PLANNER_BUFFER_BYTES, (int)sizeof(block_t)*BLOCK_BUFFER_SIZE);
913
+  SERIAL_ECHOLNPAIR(MSG_FREE_MEMORY, freeMemory(), MSG_PLANNER_BUFFER_BYTES, (int)sizeof(block_t) * (BLOCK_BUFFER_SIZE));
915 914
 
916 915
   queue_setup();
917 916
 

+ 18
- 10
Marlin/src/core/minmax.h Переглянути файл

@@ -23,6 +23,10 @@
23 23
 #undef MIN
24 24
 #undef MAX
25 25
 
26
+// Pass NUM_ARGS(__VA_ARGS__) to use the number of arguments
27
+#define _NUM_ARGS(_0,_24_,_23,_22,_21,_20,_19,_18,_17,_16,_15,_14,_13,_12,_11,_10,_9,_8,_7,_6,_5,_4,_3,_2,_1,N,...) N
28
+#define NUM_ARGS(...) _NUM_ARGS(0, __VA_ARGS__ ,24,23,22,21,20,19,18,17,16,15,14,13,12,11,10,9,8,7,6,5,4,3,2,1,0)
29
+
26 30
 #ifdef __cplusplus
27 31
 
28 32
   #ifndef _MINMAX_H_
@@ -46,26 +50,30 @@
46 50
 
47 51
 #else
48 52
 
49
-  // NUM_ARGS(...) evaluates to the number of arguments
50
-  #define _NUM_ARGS(X,X6,X5,X4,X3,X2,X1,N,...) N
51
-  #define NUM_ARGS(...) _NUM_ARGS(0, __VA_ARGS__ ,6,5,4,3,2,1,0)
52
-
53
-  #define MIN_2(a,b)      ({__typeof__(a) _a = (a); __typeof__(b) _b = (b); _a < _b ? _a : _b;})
53
+  #define MIN_2(a,b)      ((a)<(b)?(a):(b))
54 54
   #define MIN_3(a,...)    MIN_2(a,MIN_2(__VA_ARGS__))
55 55
   #define MIN_4(a,...)    MIN_2(a,MIN_3(__VA_ARGS__))
56 56
   #define MIN_5(a,...)    MIN_2(a,MIN_4(__VA_ARGS__))
57 57
   #define MIN_6(a,...)    MIN_2(a,MIN_5(__VA_ARGS__))
58
-  #define __MIN_N(N, ...) MIN_ ## N(__VA_ARGS__)
59
-  #define _MIN_N(N, ...)  __MIN_N(N, __VA_ARGS__)
58
+  #define MIN_7(a,...)    MIN_2(a,MIN_6(__VA_ARGS__))
59
+  #define MIN_8(a,...)    MIN_2(a,MIN_7(__VA_ARGS__))
60
+  #define MIN_9(a,...)    MIN_2(a,MIN_8(__VA_ARGS__))
61
+  #define MIN_10(a,...)   MIN_2(a,MIN_9(__VA_ARGS__))
62
+  #define __MIN_N(N, ...) MIN_##N(__VA_ARGS__)
63
+  #define _MIN_N(N, ...)  __MIN_N(N,__VA_ARGS__)
60 64
   #define MIN(...)        _MIN_N(NUM_ARGS(__VA_ARGS__), __VA_ARGS__)
61 65
 
62
-  #define MAX_2(a,b)      ({__typeof__(a) _a = (a); __typeof__(b) _b = (b); _a > _b ? _a : _b;})
66
+  #define MAX_2(a,b)      ((a)>(b)?(a):(b))
63 67
   #define MAX_3(a,...)    MAX_2(a,MAX_2(__VA_ARGS__))
64 68
   #define MAX_4(a,...)    MAX_2(a,MAX_3(__VA_ARGS__))
65 69
   #define MAX_5(a,...)    MAX_2(a,MAX_4(__VA_ARGS__))
66 70
   #define MAX_6(a,...)    MAX_2(a,MAX_5(__VA_ARGS__))
67
-  #define __MAX_N(N, ...) MAX_ ## N(__VA_ARGS__)
68
-  #define _MAX_N(N, ...)  __MAX_N(N, __VA_ARGS__)
71
+  #define MAX_7(a,...)    MAX_2(a,MAX_6(__VA_ARGS__))
72
+  #define MAX_8(a,...)    MAX_2(a,MAX_7(__VA_ARGS__))
73
+  #define MAX_9(a,...)    MAX_2(a,MAX_8(__VA_ARGS__))
74
+  #define MAX_10(a,...)   MAX_2(a,MAX_9(__VA_ARGS__))
75
+  #define __MAX_N(N, ...) MAX_##N(__VA_ARGS__)
76
+  #define _MAX_N(N, ...)  __MAX_N(N,__VA_ARGS__)
69 77
   #define MAX(...)        _MAX_N(NUM_ARGS(__VA_ARGS__), __VA_ARGS__)
70 78
 
71 79
 #endif

+ 1
- 2
Marlin/src/core/serial.cpp Переглянути файл

@@ -69,8 +69,7 @@ void print_bin(const uint16_t val) {
69 69
     serialprintPGM(prefix);
70 70
     SERIAL_CHAR('(');
71 71
     SERIAL_ECHO(x);
72
-    SERIAL_ECHOPAIR(", ", y);
73
-    SERIAL_ECHOPAIR(", ", z);
72
+    SERIAL_ECHOPAIR(", ", y, ", ", z);
74 73
     SERIAL_CHAR(')');
75 74
     if (suffix) serialprintPGM(suffix); else SERIAL_EOL();
76 75
   }

+ 74
- 17
Marlin/src/core/serial.h Переглянути файл

@@ -22,6 +22,7 @@
22 22
 #pragma once
23 23
 
24 24
 #include "../inc/MarlinConfigPre.h"
25
+#include "../core/minmax.h"
25 26
 #include HAL_PATH(../HAL, HAL.h)
26 27
 
27 28
 /**
@@ -62,7 +63,7 @@ extern uint8_t marlin_debug_flags;
62 63
 
63 64
 #define SERIAL_CHAR(x)          SERIAL_OUT(write, x)
64 65
 #define SERIAL_ECHO(x)          SERIAL_OUT(print, x)
65
-#define SERIAL_ECHO_F(x,y)      SERIAL_OUT(print, x, y)
66
+#define SERIAL_ECHO_F(...)      SERIAL_OUT(print, __VA_ARGS__)
66 67
 #define SERIAL_ECHOLN(x)        SERIAL_OUT(println, x)
67 68
 #define SERIAL_PRINT(x,b)       SERIAL_OUT(print, x, b)
68 69
 #define SERIAL_PRINTLN(x,b)     SERIAL_OUT(println, x, b)
@@ -75,22 +76,78 @@ extern uint8_t marlin_debug_flags;
75 76
   #define SERIAL_FLUSHTX()
76 77
 #endif
77 78
 
78
-#define SERIAL_ECHOPGM(x)                   (serialprintPGM(PSTR(x)))
79
-#define SERIAL_ECHOLNPGM(x)                 (serialprintPGM(PSTR(x "\n")))
80
-#define SERIAL_ECHOPAIR(pre, value)         (serial_echopair_PGM(PSTR(pre), value))
81
-#define SERIAL_ECHOLNPAIR(pre, value)       do{ SERIAL_ECHOPAIR(pre, value); SERIAL_EOL(); }while(0)
82
-
83
-#define SERIAL_ECHOPAIR_F(pre, value, y)    do{ SERIAL_ECHO(pre); SERIAL_ECHO_F(value, y); }while(0)
84
-#define SERIAL_ECHOLNPAIR_F(pre, value, y)  do{ SERIAL_ECHOPAIR_F(pre, value, y); SERIAL_EOL(); }while(0)
85
-
86
-#define SERIAL_ECHO_START()                 serial_echo_start()
87
-#define SERIAL_ERROR_START()                serial_error_start()
88
-#define SERIAL_EOL()                        SERIAL_CHAR('\n')
89
-
90
-#define SERIAL_ECHO_MSG(STR)                do{ SERIAL_ECHO_START(); SERIAL_ECHOLNPGM(STR); }while(0)
91
-#define SERIAL_ERROR_MSG(STR)               do{ SERIAL_ERROR_START(); SERIAL_ECHOLNPGM(STR); }while(0)
92
-
93
-#define SERIAL_ECHO_SP(C)                   serial_spaces(C)
79
+// Print up to 12 pairs of values
80
+#define __SEP_N(N,...)      _SEP_##N(__VA_ARGS__)
81
+#define _SEP_N(N,...)       __SEP_N(N,__VA_ARGS__)
82
+#define _SEP_2(PRE,V)       serial_echopair_PGM(PSTR(PRE),V)
83
+#define _SEP_3(a,b,ETC)     do{ _SEP_2(a,b); SERIAL_ECHOPGM(ETC); }while(0)
84
+#define _SEP_4(a,b,...)     do{ _SEP_2(a,b); _SEP_2(__VA_ARGS__); }while(0)
85
+#define _SEP_5(a,b,...)     do{ _SEP_2(a,b); _SEP_3(__VA_ARGS__); }while(0)
86
+#define _SEP_6(a,b,...)     do{ _SEP_2(a,b); _SEP_4(__VA_ARGS__); }while(0)
87
+#define _SEP_7(a,b,...)     do{ _SEP_2(a,b); _SEP_5(__VA_ARGS__); }while(0)
88
+#define _SEP_8(a,b,...)     do{ _SEP_2(a,b); _SEP_6(__VA_ARGS__); }while(0)
89
+#define _SEP_9(a,b,...)     do{ _SEP_2(a,b); _SEP_7(__VA_ARGS__); }while(0)
90
+#define _SEP_10(a,b,...)    do{ _SEP_2(a,b); _SEP_8(__VA_ARGS__); }while(0)
91
+#define _SEP_11(a,b,...)    do{ _SEP_2(a,b); _SEP_9(__VA_ARGS__); }while(0)
92
+#define _SEP_12(a,b,...)    do{ _SEP_2(a,b); _SEP_10(__VA_ARGS__); }while(0)
93
+#define _SEP_13(a,b,...)    do{ _SEP_2(a,b); _SEP_11(__VA_ARGS__); }while(0)
94
+#define _SEP_14(a,b,...)    do{ _SEP_2(a,b); _SEP_12(__VA_ARGS__); }while(0)
95
+#define _SEP_15(a,b,...)    do{ _SEP_2(a,b); _SEP_13(__VA_ARGS__); }while(0)
96
+#define _SEP_16(a,b,...)    do{ _SEP_2(a,b); _SEP_14(__VA_ARGS__); }while(0)
97
+#define _SEP_17(a,b,...)    do{ _SEP_2(a,b); _SEP_15(__VA_ARGS__); }while(0)
98
+#define _SEP_18(a,b,...)    do{ _SEP_2(a,b); _SEP_16(__VA_ARGS__); }while(0)
99
+#define _SEP_19(a,b,...)    do{ _SEP_2(a,b); _SEP_17(__VA_ARGS__); }while(0)
100
+#define _SEP_20(a,b,...)    do{ _SEP_2(a,b); _SEP_18(__VA_ARGS__); }while(0)
101
+#define _SEP_21(a,b,...)    do{ _SEP_2(a,b); _SEP_19(__VA_ARGS__); }while(0)
102
+#define _SEP_22(a,b,...)    do{ _SEP_2(a,b); _SEP_20(__VA_ARGS__); }while(0)
103
+#define _SEP_23(a,b,...)    do{ _SEP_2(a,b); _SEP_21(__VA_ARGS__); }while(0)
104
+#define _SEP_24(a,b,...)    do{ _SEP_2(a,b); _SEP_22(__VA_ARGS__); }while(0)
105
+
106
+#define SERIAL_ECHOPAIR(...) _SEP_N(NUM_ARGS(__VA_ARGS__),__VA_ARGS__)
107
+
108
+// Print up to 12 pairs of values followed by newline
109
+#define __SELP_N(N,...)     _SELP_##N(__VA_ARGS__)
110
+#define _SELP_N(N,...)      __SELP_N(N,__VA_ARGS__)
111
+#define _SELP_2(PRE,V)      do{ serial_echopair_PGM(PSTR(PRE),V); SERIAL_EOL(); }while(0)
112
+#define _SELP_3(PRE,V,ETC)  do{ serial_echopair_PGM(PSTR(PRE),V); SERIAL_ECHOLNPGM(ETC); }while(0)
113
+#define _SELP_4(a,b,...)    do{ _SELP_2(a,b); _SELP_2(__VA_ARGS__); }while(0)
114
+#define _SELP_5(a,b,...)    do{ _SELP_2(a,b); _SELP_3(__VA_ARGS__); }while(0)
115
+#define _SELP_6(a,b,...)    do{ _SELP_2(a,b); _SELP_4(__VA_ARGS__); }while(0)
116
+#define _SELP_7(a,b,...)    do{ _SELP_2(a,b); _SELP_5(__VA_ARGS__); }while(0)
117
+#define _SELP_8(a,b,...)    do{ _SELP_2(a,b); _SELP_6(__VA_ARGS__); }while(0)
118
+#define _SELP_9(a,b,...)    do{ _SELP_2(a,b); _SELP_7(__VA_ARGS__); }while(0)
119
+#define _SELP_10(a,b,...)   do{ _SELP_2(a,b); _SELP_8(__VA_ARGS__); }while(0)
120
+#define _SELP_11(a,b,...)   do{ _SELP_2(a,b); _SELP_9(__VA_ARGS__); }while(0)
121
+#define _SELP_12(a,b,...)   do{ _SELP_2(a,b); _SELP_10(__VA_ARGS__); }while(0)
122
+#define _SELP_13(a,b,...)   do{ _SELP_2(a,b); _SELP_11(__VA_ARGS__); }while(0)
123
+#define _SELP_14(a,b,...)   do{ _SELP_2(a,b); _SELP_12(__VA_ARGS__); }while(0)
124
+#define _SELP_15(a,b,...)   do{ _SELP_2(a,b); _SELP_13(__VA_ARGS__); }while(0)
125
+#define _SELP_16(a,b,...)   do{ _SELP_2(a,b); _SELP_14(__VA_ARGS__); }while(0)
126
+#define _SELP_17(a,b,...)   do{ _SELP_2(a,b); _SELP_15(__VA_ARGS__); }while(0)
127
+#define _SELP_18(a,b,...)   do{ _SELP_2(a,b); _SELP_16(__VA_ARGS__); }while(0)
128
+#define _SELP_19(a,b,...)   do{ _SELP_2(a,b); _SELP_17(__VA_ARGS__); }while(0)
129
+#define _SELP_20(a,b,...)   do{ _SELP_2(a,b); _SELP_18(__VA_ARGS__); }while(0)
130
+#define _SELP_21(a,b,...)   do{ _SELP_2(a,b); _SELP_19(__VA_ARGS__); }while(0)
131
+#define _SELP_22(a,b,...)   do{ _SELP_2(a,b); _SELP_20(__VA_ARGS__); }while(0)
132
+#define _SELP_23(a,b,...)   do{ _SELP_2(a,b); _SELP_21(__VA_ARGS__); }while(0)
133
+#define _SELP_24(a,b,...)   do{ _SELP_2(a,b); _SELP_22(__VA_ARGS__); }while(0)
134
+
135
+#define SERIAL_ECHOLNPAIR(...) _SELP_N(NUM_ARGS(__VA_ARGS__),__VA_ARGS__)
136
+
137
+#define SERIAL_ECHOPGM(S)           (serialprintPGM(PSTR(S)))
138
+#define SERIAL_ECHOLNPGM(S)         (serialprintPGM(PSTR(S "\n")))
139
+
140
+#define SERIAL_ECHOPAIR_F(pre, ...) do{ SERIAL_ECHO(pre); SERIAL_ECHO_F(__VA_ARGS__); }while(0)
141
+#define SERIAL_ECHOLNPAIR_F(...)    do{ SERIAL_ECHOPAIR_F(__VA_ARGS__); SERIAL_EOL(); }while(0)
142
+
143
+#define SERIAL_ECHO_START()         serial_echo_start()
144
+#define SERIAL_ERROR_START()        serial_error_start()
145
+#define SERIAL_EOL()                SERIAL_CHAR('\n')
146
+
147
+#define SERIAL_ECHO_MSG(S)          do{ SERIAL_ECHO_START(); SERIAL_ECHOLNPGM(S); }while(0)
148
+#define SERIAL_ERROR_MSG(S)         do{ SERIAL_ERROR_START(); SERIAL_ECHOLNPGM(S); }while(0)
149
+
150
+#define SERIAL_ECHO_SP(C)           serial_spaces(C)
94 151
 
95 152
 //
96 153
 // Functions for serial printing from PROGMEM. (Saves loads of SRAM.)

+ 18
- 40
Marlin/src/feature/I2CPositionEncoder.cpp Переглянути файл

@@ -47,8 +47,7 @@ void I2CPositionEncoder::init(const uint8_t address, const AxisEnum axis) {
47 47
 
48 48
   initialized++;
49 49
 
50
-  SERIAL_ECHOPAIR("Setting up encoder on ", axis_codes[encoderAxis]);
51
-  SERIAL_ECHOLNPAIR(" axis, addr = ", address);
50
+  SERIAL_ECHOLNPAIR("Setting up encoder on ", axis_codes[encoderAxis], " axis, addr = ", address);
52 51
 
53 52
   position = get_position();
54 53
 }
@@ -66,8 +65,7 @@ void I2CPositionEncoder::update() {
66 65
     /*
67 66
     if (trusted) { //commented out as part of the note below
68 67
       trusted = false;
69
-      SERIAL_ECHOPAIR("Fault detected on ", axis_codes[encoderAxis]);
70
-      SERIAL_ECHOLNPGM(" axis encoder. Disengaging error correction until module is trusted again.");
68
+      SERIAL_ECHOLMPAIR("Fault detected on ", axis_codes[encoderAxis], " axis encoder. Disengaging error correction until module is trusted again.");
71 69
     }
72 70
     */
73 71
     return;
@@ -92,8 +90,7 @@ void I2CPositionEncoder::update() {
92 90
       if (millis() - lastErrorTime > I2CPE_TIME_TRUSTED) {
93 91
         trusted = true;
94 92
 
95
-        SERIAL_ECHOPAIR("Untrusted encoder module on ", axis_codes[encoderAxis]);
96
-        SERIAL_ECHOLNPGM(" axis has been fault-free for set duration, reinstating error correction.");
93
+        SERIAL_ECHOLNPAIR("Untrusted encoder module on ", axis_codes[encoderAxis], " axis has been fault-free for set duration, reinstating error correction.");
97 94
 
98 95
         //the encoder likely lost its place when the error occured, so we'll reset and use the printer's
99 96
         //idea of where it the axis is to re-initialize
@@ -172,8 +169,7 @@ void I2CPositionEncoder::update() {
172 169
             LOOP_L_N(i, I2CPE_ERR_PRST_ARRAY_SIZE) sumP += errPrst[i];
173 170
             const int32_t errorP = int32_t(sumP * (1.0f / (I2CPE_ERR_PRST_ARRAY_SIZE)));
174 171
             SERIAL_ECHO(axis_codes[encoderAxis]);
175
-            SERIAL_ECHOPAIR(" - err detected: ", errorP * planner.steps_to_mm[encoderAxis]);
176
-            SERIAL_ECHOLNPGM("mm; correcting!");
172
+            SERIAL_ECHOLNPAIR(" - err detected: ", errorP * planner.steps_to_mm[encoderAxis], "mm; correcting!");
177 173
             thermalManager.babystepsTodo[encoderAxis] = -LROUND(errorP);
178 174
             errPrstIdx = 0;
179 175
           }
@@ -192,9 +188,7 @@ void I2CPositionEncoder::update() {
192 188
     if (ABS(error) > I2CPE_ERR_CNT_THRESH * planner.settings.axis_steps_per_mm[encoderAxis]) {
193 189
       const millis_t ms = millis();
194 190
       if (ELAPSED(ms, nextErrorCountTime)) {
195
-        SERIAL_ECHOPAIR("Large error on ", axis_codes[encoderAxis]);
196
-        SERIAL_ECHOPAIR(" axis. error: ", (int)error);
197
-        SERIAL_ECHOLNPAIR("; diffSum: ", diffSum);
191
+        SERIAL_ECHOLNPAIR("Large error on ", axis_codes[encoderAxis], " axis. error: ", (int)error, "; diffSum: ", diffSum);
198 192
         errorCount++;
199 193
         nextErrorCountTime = ms + I2CPE_ERR_CNT_DEBOUNCE_MS;
200 194
       }
@@ -215,8 +209,7 @@ void I2CPositionEncoder::set_homed() {
215 209
 
216 210
     #ifdef I2CPE_DEBUG
217 211
       SERIAL_ECHO(axis_codes[encoderAxis]);
218
-      SERIAL_ECHOPAIR(" axis encoder homed, offset of ", zeroOffset);
219
-      SERIAL_ECHOLNPGM(" ticks.");
212
+      SERIAL_ECHOLNPAIR(" axis encoder homed, offset of ", zeroOffset, " ticks.");
220 213
     #endif
221 214
   }
222 215
 }
@@ -261,9 +254,7 @@ float I2CPositionEncoder::get_axis_error_mm(const bool report) {
261 254
 
262 255
   if (report) {
263 256
     SERIAL_ECHO(axis_codes[encoderAxis]);
264
-    SERIAL_ECHOPAIR(" axis target: ", target);
265
-    SERIAL_ECHOPAIR(", actual: ", actual);
266
-    SERIAL_ECHOLNPAIR(", error : ",error);
257
+    SERIAL_ECHOLNPAIR(" axis target: ", target, ", actual: ", actual, ", error : ",error);
267 258
   }
268 259
 
269 260
   return error;
@@ -296,10 +287,7 @@ int32_t I2CPositionEncoder::get_axis_error_steps(const bool report) {
296 287
 
297 288
   if (report) {
298 289
     SERIAL_ECHO(axis_codes[encoderAxis]);
299
-    SERIAL_ECHOPAIR(" axis target: ", target);
300
-    SERIAL_ECHOPAIR(", actual: ", encoderCountInStepperTicksScaled);
301
-    SERIAL_ECHOLNPAIR(", error : ", error);
302
-
290
+    SERIAL_ECHOLNPAIR(" axis target: ", target, ", actual: ", encoderCountInStepperTicksScaled, ", error : ", error);
303 291
     if (suppressOutput) SERIAL_ECHOLNPGM("Discontinuity detected, suppressing error.");
304 292
   }
305 293
 
@@ -436,11 +424,9 @@ void I2CPositionEncoder::calibrate_steps_mm(const uint8_t iter) {
436 424
 
437 425
     travelledDistance = mm_from_count(ABS(stopCount - startCount));
438 426
 
439
-    SERIAL_ECHOPAIR("Attempted travel: ", travelDistance);
440
-    SERIAL_ECHOLNPGM("mm");
427
+    SERIAL_ECHOLNPAIR("Attempted travel: ", travelDistance, "mm");
441 428
 
442
-    SERIAL_ECHOPAIR("   Actual travel:  ", travelledDistance);
443
-    SERIAL_ECHOLNPGM("mm");
429
+    SERIAL_ECHOLNPAIR("   Actual travel:  ", travelledDistance, "mm");
444 430
 
445 431
     //Calculate new axis steps per unit
446 432
     old_steps_mm = planner.settings.axis_steps_per_mm[encoderAxis];
@@ -705,21 +691,18 @@ void I2CPositionEncodersMgr::change_module_address(const uint8_t oldaddr, const
705 691
   // First check 'new' address is not in use
706 692
   Wire.beginTransmission(I2C_ADDRESS(newaddr));
707 693
   if (!Wire.endTransmission()) {
708
-    SERIAL_ECHOPAIR("?There is already a device with that address on the I2C bus! (", newaddr);
709
-    SERIAL_ECHOLNPGM(")");
694
+    SERIAL_ECHOLNPAIR("?There is already a device with that address on the I2C bus! (", newaddr, ")");
710 695
     return;
711 696
   }
712 697
 
713 698
   // Now check that we can find the module on the oldaddr address
714 699
   Wire.beginTransmission(I2C_ADDRESS(oldaddr));
715 700
   if (Wire.endTransmission()) {
716
-    SERIAL_ECHOPAIR("?No module detected at this address! (", oldaddr);
717
-    SERIAL_ECHOLNPGM(")");
701
+    SERIAL_ECHOLNPAIR("?No module detected at this address! (", oldaddr, ")");
718 702
     return;
719 703
   }
720 704
 
721
-  SERIAL_ECHOPAIR("Module found at ", oldaddr);
722
-  SERIAL_ECHOLNPAIR(", changing address to ", newaddr);
705
+  SERIAL_ECHOLNPAIR("Module found at ", oldaddr, ", changing address to ", newaddr);
723 706
 
724 707
   // Change the modules address
725 708
   Wire.beginTransmission(I2C_ADDRESS(oldaddr));
@@ -755,13 +738,11 @@ void I2CPositionEncodersMgr::report_module_firmware(const uint8_t address) {
755 738
   // First check there is a module
756 739
   Wire.beginTransmission(I2C_ADDRESS(address));
757 740
   if (Wire.endTransmission()) {
758
-    SERIAL_ECHOPAIR("?No module detected at this address! (", address);
759
-    SERIAL_ECHOLNPGM(")");
741
+    SERIAL_ECHOLNPAIR("?No module detected at this address! (", address, ")");
760 742
     return;
761 743
   }
762 744
 
763
-  SERIAL_ECHOPAIR("Requesting version info from module at address ", address);
764
-  SERIAL_ECHOLNPGM(":");
745
+  SERIAL_ECHOLNPAIR("Requesting version info from module at address ", address, ":");
765 746
 
766 747
   Wire.beginTransmission(I2C_ADDRESS(address));
767 748
   Wire.write(I2CPE_SET_REPORT_MODE);
@@ -808,15 +789,13 @@ int8_t I2CPositionEncodersMgr::parse() {
808 789
   else if (parser.seenval('I')) {
809 790
 
810 791
     if (!parser.has_value()) {
811
-      SERIAL_ECHOLNPAIR("?I seen, but no index specified! [0-", I2CPE_ENCODER_CNT - 1);
812
-      SERIAL_ECHOLNPGM("]");
792
+      SERIAL_ECHOLNPAIR("?I seen, but no index specified! [0-", I2CPE_ENCODER_CNT - 1, "]");
813 793
       return I2CPE_PARSE_ERR;
814 794
     };
815 795
 
816 796
     I2CPE_idx = parser.value_byte();
817 797
     if (I2CPE_idx >= I2CPE_ENCODER_CNT) {
818
-      SERIAL_ECHOLNPAIR("?Index out of range. [0-", I2CPE_ENCODER_CNT - 1);
819
-      SERIAL_ECHOLNPGM("]");
798
+      SERIAL_ECHOLNPAIR("?Index out of range. [0-", I2CPE_ENCODER_CNT - 1, "]");
820 799
       return I2CPE_PARSE_ERR;
821 800
     }
822 801
 
@@ -995,8 +974,7 @@ void I2CPositionEncodersMgr::M864() {
995 974
     else return;
996 975
   }
997 976
 
998
-  SERIAL_ECHOPAIR("Changing module at address ", I2CPE_addr);
999
-  SERIAL_ECHOLNPAIR(" to address ", newAddress);
977
+  SERIAL_ECHOLNPAIR("Changing module at address ", I2CPE_addr, " to address ", newAddress);
1000 978
 
1001 979
   change_module_address(I2CPE_addr, newAddress);
1002 980
 }

+ 6
- 14
Marlin/src/feature/I2CPositionEncoder.h Переглянути файл

@@ -238,8 +238,7 @@ class I2CPositionEncodersMgr {
238 238
 
239 239
     static void report_status(const int8_t idx) {
240 240
       CHECK_IDX();
241
-      SERIAL_ECHOPAIR("Encoder ", idx);
242
-      SERIAL_ECHOPGM(": ");
241
+      SERIAL_ECHOLNPAIR("Encoder ", idx, ": ");
243 242
       encoders[idx].get_raw_count();
244 243
       encoders[idx].passes_test(true);
245 244
     }
@@ -264,22 +263,19 @@ class I2CPositionEncodersMgr {
264 263
 
265 264
     static void report_error_count(const int8_t idx, const AxisEnum axis) {
266 265
       CHECK_IDX();
267
-      SERIAL_ECHOPAIR("Error count on ", axis_codes[axis]);
268
-      SERIAL_ECHOLNPAIR(" axis is ", encoders[idx].get_error_count());
266
+      SERIAL_ECHOLNPAIR("Error count on ", axis_codes[axis], " axis is ", encoders[idx].get_error_count());
269 267
     }
270 268
 
271 269
     static void reset_error_count(const int8_t idx, const AxisEnum axis) {
272 270
       CHECK_IDX();
273 271
       encoders[idx].set_error_count(0);
274
-      SERIAL_ECHOPAIR("Error count on ", axis_codes[axis]);
275
-      SERIAL_ECHOLNPGM(" axis has been reset.");
272
+      SERIAL_ECHOLNPAIR("Error count on ", axis_codes[axis], " axis has been reset.");
276 273
     }
277 274
 
278 275
     static void enable_ec(const int8_t idx, const bool enabled, const AxisEnum axis) {
279 276
       CHECK_IDX();
280 277
       encoders[idx].set_ec_enabled(enabled);
281
-      SERIAL_ECHOPAIR("Error correction on ", axis_codes[axis]);
282
-      SERIAL_ECHOPGM(" axis is ");
278
+      SERIAL_ECHOPAIR("Error correction on ", axis_codes[axis], " axis is ");
283 279
       serialprintPGM(encoders[idx].get_ec_enabled() ? PSTR("en") : PSTR("dis"));
284 280
       SERIAL_ECHOLNPGM("abled.");
285 281
     }
@@ -287,17 +283,13 @@ class I2CPositionEncodersMgr {
287 283
     static void set_ec_threshold(const int8_t idx, const float newThreshold, const AxisEnum axis) {
288 284
       CHECK_IDX();
289 285
       encoders[idx].set_ec_threshold(newThreshold);
290
-      SERIAL_ECHOPAIR("Error correct threshold for ", axis_codes[axis]);
291
-      SERIAL_ECHOPAIR(" axis set to ", FIXFLOAT(newThreshold));
292
-      SERIAL_ECHOLNPGM("mm.");
286
+      SERIAL_ECHOLNPAIR("Error correct threshold for ", axis_codes[axis], " axis set to ", FIXFLOAT(newThreshold), "mm.");
293 287
     }
294 288
 
295 289
     static void get_ec_threshold(const int8_t idx, const AxisEnum axis) {
296 290
       CHECK_IDX();
297 291
       const float threshold = encoders[idx].get_ec_threshold();
298
-      SERIAL_ECHOPAIR("Error correct threshold for ", axis_codes[axis]);
299
-      SERIAL_ECHOPAIR(" axis is ", FIXFLOAT(threshold));
300
-      SERIAL_ECHOLNPGM("mm.");
292
+      SERIAL_ECHOLNPAIR("Error correct threshold for ", axis_codes[axis], " axis is ", FIXFLOAT(threshold), "mm.");
301 293
     }
302 294
 
303 295
     static int8_t idx_from_axis(const AxisEnum axis) {

+ 5
- 16
Marlin/src/feature/bedlevel/abl/abl.cpp Переглянути файл

@@ -338,22 +338,11 @@ float bilinear_z_offset(const float raw[XYZ]) {
338 338
   /*
339 339
   static float last_offset = 0;
340 340
   if (ABS(last_offset - offset) > 0.2) {
341
-    SERIAL_ECHOPGM("Sudden Shift at ");
342
-    SERIAL_ECHOPAIR("x=", rx);
343
-    SERIAL_ECHOPAIR(" / ", bilinear_grid_spacing[X_AXIS]);
344
-    SERIAL_ECHOLNPAIR(" -> gridx=", gridx);
345
-    SERIAL_ECHOPAIR(" y=", ry);
346
-    SERIAL_ECHOPAIR(" / ", bilinear_grid_spacing[Y_AXIS]);
347
-    SERIAL_ECHOLNPAIR(" -> gridy=", gridy);
348
-    SERIAL_ECHOPAIR(" ratio_x=", ratio_x);
349
-    SERIAL_ECHOLNPAIR(" ratio_y=", ratio_y);
350
-    SERIAL_ECHOPAIR(" z1=", z1);
351
-    SERIAL_ECHOPAIR(" z2=", z2);
352
-    SERIAL_ECHOPAIR(" z3=", z3);
353
-    SERIAL_ECHOLNPAIR(" z4=", z4);
354
-    SERIAL_ECHOPAIR(" L=", L);
355
-    SERIAL_ECHOPAIR(" R=", R);
356
-    SERIAL_ECHOLNPAIR(" offset=", offset);
341
+    SERIAL_ECHOLNPAIR("Sudden Shift at x=", rx, " / ", bilinear_grid_spacing[X_AXIS], " -> gridx=", gridx);
342
+    SERIAL_ECHOLNPAIR(" y=", ry, " / ", bilinear_grid_spacing[Y_AXIS], " -> gridy=", gridy);
343
+    SERIAL_ECHOLNPAIR(" ratio_x=", ratio_x, " ratio_y=", ratio_y);
344
+    SERIAL_ECHOLNPAIR(" z1=", z1, " z2=", z2, " z3=", z3, " z4=", z4);
345
+    SERIAL_ECHOLNPAIR(" L=", L, " R=", R, " offset=", offset);
357 346
   }
358 347
   last_offset = offset;
359 348
   //*/

+ 1
- 2
Marlin/src/feature/bedlevel/ubl/ubl.cpp Переглянути файл

@@ -45,8 +45,7 @@
45 45
       for (uint8_t y = 0;  y < GRID_MAX_POINTS_Y; y++)
46 46
         if (!isnan(z_values[x][y])) {
47 47
           SERIAL_ECHO_START();
48
-          SERIAL_ECHOPAIR("  M421 I", x);
49
-          SERIAL_ECHOPAIR(" J", y);
48
+          SERIAL_ECHOPAIR("  M421 I", x, " J", y);
50 49
           SERIAL_ECHOPAIR_F(" Z", z_values[x][y], 2);
51 50
           SERIAL_EOL();
52 51
           serial_delay(75); // Prevent Printrun from exploding

+ 3
- 11
Marlin/src/feature/bedlevel/ubl/ubl.h Переглянути файл

@@ -202,11 +202,7 @@ class unified_bed_leveling {
202 202
         #if ENABLED(DEBUG_LEVELING_FEATURE)
203 203
           if (DEBUGGING(LEVELING)) {
204 204
             serialprintPGM( !WITHIN(x1_i, 0, GRID_MAX_POINTS_X - 1) ? PSTR("x1_i") : PSTR("yi") );
205
-            SERIAL_ECHOPAIR(" out of bounds in z_correction_for_x_on_horizontal_mesh_line(rx0=", rx0);
206
-            SERIAL_ECHOPAIR(",x1_i=", x1_i);
207
-            SERIAL_ECHOPAIR(",yi=", yi);
208
-            SERIAL_CHAR(')');
209
-            SERIAL_EOL();
205
+            SERIAL_ECHOLNPAIR(" out of bounds in z_correction_for_x_on_horizontal_mesh_line(rx0=", rx0, ",x1_i=", x1_i, ",yi=", yi, ")");
210 206
           }
211 207
         #endif
212 208
 
@@ -235,12 +231,8 @@ class unified_bed_leveling {
235 231
       if (!WITHIN(xi, 0, GRID_MAX_POINTS_X - 1) || !WITHIN(y1_i, 0, GRID_MAX_POINTS_Y - 1)) {
236 232
         #if ENABLED(DEBUG_LEVELING_FEATURE)
237 233
           if (DEBUGGING(LEVELING)) {
238
-            serialprintPGM( !WITHIN(xi, 0, GRID_MAX_POINTS_X - 1) ? PSTR("xi") : PSTR("y1_i") );
239
-            SERIAL_ECHOPAIR(" out of bounds in z_correction_for_y_on_vertical_mesh_line(ry0=", ry0);
240
-            SERIAL_ECHOPAIR(", xi=", xi);
241
-            SERIAL_ECHOPAIR(", y1_i=", y1_i);
242
-            SERIAL_CHAR(')');
243
-            SERIAL_EOL();
234
+            serialprintPGM(!WITHIN(xi, 0, GRID_MAX_POINTS_X - 1) ? PSTR("xi") : PSTR("y1_i"));
235
+            SERIAL_ECHOLNPAIR(" out of bounds in z_correction_for_y_on_vertical_mesh_line(ry0=", ry0, ", xi=", xi, ", y1_i=", y1_i, ")");
244 236
           }
245 237
         #endif
246 238
 

+ 11
- 22
Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp Переглянути файл

@@ -598,8 +598,7 @@
598 598
       }
599 599
 
600 600
       if (!WITHIN(g29_storage_slot, 0, a - 1)) {
601
-        SERIAL_ECHOLNPGM("?Invalid storage slot.");
602
-        SERIAL_ECHOLNPAIR("?Use 0 to ", a - 1);
601
+        SERIAL_ECHOLNPAIR("?Invalid storage slot.\n?Use 0 to ", a - 1);
603 602
         return;
604 603
       }
605 604
 
@@ -627,8 +626,7 @@
627 626
       }
628 627
 
629 628
       if (!WITHIN(g29_storage_slot, 0, a - 1)) {
630
-        SERIAL_ECHOLNPGM("?Invalid storage slot.");
631
-        SERIAL_ECHOLNPAIR("?Use 0 to ", a - 1);
629
+        SERIAL_ECHOLNPAIR("?Invalid storage slot.\n?Use 0 to ", a - 1);
632 630
         goto LEAVE;
633 631
       }
634 632
 
@@ -1640,10 +1638,8 @@
1640 1638
 
1641 1639
       if (storage_slot == -1)
1642 1640
         SERIAL_ECHOPGM("No Mesh Loaded.");
1643
-      else {
1644
-        SERIAL_ECHOPAIR("Mesh ", storage_slot);
1645
-        SERIAL_ECHOPGM(" Loaded.");
1646
-      }
1641
+      else
1642
+        SERIAL_ECHOPAIR("Mesh ", storage_slot, " Loaded.");
1647 1643
       SERIAL_EOL();
1648 1644
       serial_delay(50);
1649 1645
 
@@ -1683,19 +1679,16 @@
1683 1679
       SERIAL_EOL();
1684 1680
 
1685 1681
       #if HAS_KILL
1686
-        SERIAL_ECHOPAIR("Kill pin on :", KILL_PIN);
1687
-        SERIAL_ECHOLNPAIR("  state:", READ(KILL_PIN));
1682
+        SERIAL_ECHOLNPAIR("Kill pin on :", int(KILL_PIN), "  state:", READ(KILL_PIN));
1688 1683
       #endif
1689 1684
       SERIAL_EOL();
1690 1685
       serial_delay(50);
1691 1686
 
1692 1687
       #if ENABLED(UBL_DEVEL_DEBUGGING)
1693
-        SERIAL_ECHOLNPAIR("ubl_state_at_invocation :", ubl_state_at_invocation); SERIAL_EOL();
1694
-        SERIAL_ECHOLNPAIR("ubl_state_recursion_chk :", ubl_state_recursion_chk); SERIAL_EOL();
1688
+        SERIAL_ECHOLNPAIR("ubl_state_at_invocation :", ubl_state_at_invocation, "\nubl_state_recursion_chk :", ubl_state_recursion_chk);
1695 1689
         serial_delay(50);
1696 1690
 
1697
-        SERIAL_ECHOPAIR("Meshes go from ", hex_address((void*)settings.meshes_start_index()));
1698
-        SERIAL_ECHOLNPAIR(" to ", hex_address((void*)settings.meshes_end_index()));
1691
+        SERIAL_ECHOLNPAIR("Meshes go from ", hex_address((void*)settings.meshes_start_index()), " to ", hex_address((void*)settings.meshes_end_index()));
1699 1692
         serial_delay(50);
1700 1693
 
1701 1694
         SERIAL_ECHOLNPAIR("sizeof(ubl) :  ", (int)sizeof(ubl));         SERIAL_EOL();
@@ -1705,8 +1698,7 @@
1705 1698
         SERIAL_ECHOLNPAIR("EEPROM free for UBL: ", hex_address((void*)(settings.meshes_end_index() - settings.meshes_start_index())));
1706 1699
         serial_delay(50);
1707 1700
 
1708
-        SERIAL_ECHOPAIR("EEPROM can hold ", settings.calc_num_meshes());
1709
-        SERIAL_ECHOLNPGM(" meshes.\n");
1701
+        SERIAL_ECHOLNPAIR("EEPROM can hold ", settings.calc_num_meshes(), " meshes.\n");
1710 1702
         serial_delay(25);
1711 1703
       #endif // UBL_DEVEL_DEBUGGING
1712 1704
 
@@ -1753,24 +1745,21 @@
1753 1745
       }
1754 1746
 
1755 1747
       if (!parser.has_value()) {
1756
-        SERIAL_ECHOLNPGM("?Storage slot # required.");
1757
-        SERIAL_ECHOLNPAIR("?Use 0 to ", a - 1);
1748
+        SERIAL_ECHOLNPAIR("?Storage slot # required.\n?Use 0 to ", a - 1);
1758 1749
         return;
1759 1750
       }
1760 1751
 
1761 1752
       g29_storage_slot = parser.value_int();
1762 1753
 
1763 1754
       if (!WITHIN(g29_storage_slot, 0, a - 1)) {
1764
-        SERIAL_ECHOLNPGM("?Invalid storage slot.");
1765
-        SERIAL_ECHOLNPAIR("?Use 0 to ", a - 1);
1755
+        SERIAL_ECHOLNPAIR("?Invalid storage slot.\n?Use 0 to ", a - 1);
1766 1756
         return;
1767 1757
       }
1768 1758
 
1769 1759
       float tmp_z_values[GRID_MAX_POINTS_X][GRID_MAX_POINTS_Y];
1770 1760
       settings.load_mesh(g29_storage_slot, &tmp_z_values);
1771 1761
 
1772
-      SERIAL_ECHOPAIR("Subtracting mesh in slot ", g29_storage_slot);
1773
-      SERIAL_ECHOLNPGM(" from current mesh.");
1762
+      SERIAL_ECHOLNPAIR("Subtracting mesh in slot ", g29_storage_slot, " from current mesh.");
1774 1763
 
1775 1764
       for (uint8_t x = 0; x < GRID_MAX_POINTS_X; x++)
1776 1765
         for (uint8_t y = 0; y < GRID_MAX_POINTS_Y; y++)

+ 7
- 6
Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp Переглянути файл

@@ -65,12 +65,13 @@
65 65
               cell_dest_yi  = get_cell_index_y(end[Y_AXIS]);
66 66
 
67 67
     if (g26_debug_flag) {
68
-      SERIAL_ECHOPAIR(" ubl.line_to_destination_cartesian(xe=", destination[X_AXIS]);
69
-      SERIAL_ECHOPAIR(", ye=", destination[Y_AXIS]);
70
-      SERIAL_ECHOPAIR(", ze=", destination[Z_AXIS]);
71
-      SERIAL_ECHOPAIR(", ee=", destination[E_AXIS]);
72
-      SERIAL_CHAR(')');
73
-      SERIAL_EOL();
68
+      SERIAL_ECHOLNPAIR(
69
+        " ubl.line_to_destination_cartesian(xe=", destination[X_AXIS],
70
+        ", ye=", destination[Y_AXIS],
71
+        ", ze=", destination[Z_AXIS],
72
+        ", ee=", destination[E_AXIS],
73
+        ")"
74
+      );
74 75
       debug_current_and_destination(PSTR("Start of ubl.line_to_destination_cartesian()"));
75 76
     }
76 77
 

+ 6
- 9
Marlin/src/feature/dac/stepper_dac.cpp Переглянути файл

@@ -105,15 +105,12 @@ void dac_print_values() {
105 105
 
106 106
   SERIAL_ECHO_MSG("Stepper current values in % (Amps):");
107 107
   SERIAL_ECHO_START();
108
-  SERIAL_ECHOPAIR(" X:",  dac_perc(X_AXIS));
109
-  SERIAL_ECHOPAIR(" (",   dac_amps(X_AXIS));
110
-  SERIAL_ECHOPAIR(") Y:", dac_perc(Y_AXIS));
111
-  SERIAL_ECHOPAIR(" (",   dac_amps(Y_AXIS));
112
-  SERIAL_ECHOPAIR(") Z:", dac_perc(Z_AXIS));
113
-  SERIAL_ECHOPAIR(" (",   dac_amps(Z_AXIS));
114
-  SERIAL_ECHOPAIR(") E:", dac_perc(E_AXIS));
115
-  SERIAL_ECHOPAIR(" (",   dac_amps(E_AXIS));
116
-  SERIAL_ECHOLNPGM(")");
108
+  SERIAL_ECHOLNPAIR(
109
+    " X:", dac_perc(X_AXIS), " (", dac_amps(X_AXIS), ")"
110
+    " Y:", dac_perc(Y_AXIS), " (", dac_amps(Y_AXIS), ")"
111
+    " Z:", dac_perc(Z_AXIS), " (", dac_amps(Z_AXIS), ")"
112
+    " E:", dac_perc(E_AXIS), " (", dac_amps(E_AXIS), ")"
113
+  );
117 114
 }
118 115
 
119 116
 void dac_commit_eeprom() {

+ 9
- 11
Marlin/src/feature/fwretract.cpp Переглянути файл

@@ -112,15 +112,15 @@ void FWRetract::retract(const bool retracting
112 112
   #endif
113 113
 
114 114
   /* // debugging
115
-    SERIAL_ECHOLNPAIR("retracting ", retracting);
116
-    SERIAL_ECHOLNPAIR("swapping ", swapping);
117
-    SERIAL_ECHOLNPAIR("active extruder ", active_extruder);
115
+    SERIAL_ECHOLNPAIR(
116
+      "retracting ", retracting,
117
+      "swapping ", swapping
118
+      "active extruder ", active_extruder
119
+    );
118 120
     for (uint8_t i = 0; i < EXTRUDERS; ++i) {
119
-      SERIAL_ECHOPAIR("retracted[", i);
120
-      SERIAL_ECHOLNPAIR("] ", retracted[i]);
121
+      SERIAL_ECHOLNPAIR("retracted[", i, "] ", retracted[i]);
121 122
       #if EXTRUDERS > 1
122
-        SERIAL_ECHOPAIR("retracted_swap[", i);
123
-        SERIAL_ECHOLNPAIR("] ", retracted_swap[i]);
123
+        SERIAL_ECHOLNPAIR("retracted_swap[", i, "] ", retracted_swap[i]);
124 124
       #endif
125 125
     }
126 126
     SERIAL_ECHOLNPAIR("current_position[z] ", current_position[Z_AXIS]);
@@ -209,11 +209,9 @@ void FWRetract::retract(const bool retracting
209 209
     SERIAL_ECHOLNPAIR("swapping ", swapping);
210 210
     SERIAL_ECHOLNPAIR("active_extruder ", active_extruder);
211 211
     for (uint8_t i = 0; i < EXTRUDERS; ++i) {
212
-      SERIAL_ECHOPAIR("retracted[", i);
213
-      SERIAL_ECHOLNPAIR("] ", retracted[i]);
212
+      SERIAL_ECHOLNPAIR("retracted[", i, "] ", retracted[i]);
214 213
       #if EXTRUDERS > 1
215
-        SERIAL_ECHOPAIR("retracted_swap[", i);
216
-        SERIAL_ECHOLNPAIR("] ", retracted_swap[i]);
214
+        SERIAL_ECHOLNPAIR("retracted_swap[", i, "] ", retracted_swap[i]);
217 215
       #endif
218 216
     }
219 217
     SERIAL_ECHOLNPAIR("current_position[z] ", current_position[Z_AXIS]);

+ 2
- 10
Marlin/src/feature/mixing.cpp Переглянути файл

@@ -139,19 +139,11 @@ void Mixer::refresh_collector(const float proportion/*=1.0*/, const uint8_t t/*=
139 139
     cmax = MAX(cmax, v);
140 140
     csum += v;
141 141
   }
142
-  //SERIAL_ECHOPAIR("Mixer::refresh_collector(", proportion);
143
-  //SERIAL_ECHOPAIR(", ", int(t));
144
-  //SERIAL_ECHOPAIR(") cmax=", cmax);
145
-  //SERIAL_ECHOPAIR("  csum=", csum);
146
-  //SERIAL_ECHOPGM("  color");
142
+  //SERIAL_ECHOPAIR("Mixer::refresh_collector(", proportion, ", ", int(t), ") cmax=", cmax, "  csum=", csum, "  color");
147 143
   const float inv_prop = proportion / csum;
148 144
   MIXER_STEPPER_LOOP(i) {
149 145
     collector[i] = color[t][i] * inv_prop;
150
-    //SERIAL_ECHOPAIR(" [", int(t));
151
-    //SERIAL_ECHOPAIR("][", int(i));
152
-    //SERIAL_ECHOPAIR("] = ", int(color[t][i]));
153
-    //SERIAL_ECHOPAIR(" (", collector[i]);
154
-    //SERIAL_ECHOPGM(")  ");
146
+    //SERIAL_ECHOPAIR(" [", int(t), "][", int(i), "] = ", int(color[t][i]), " (", collector[i], ")  ");
155 147
   }
156 148
   //SERIAL_EOL();
157 149
 }

+ 3
- 16
Marlin/src/feature/mixing.h Переглянути файл

@@ -148,11 +148,7 @@ class Mixer {
148 148
       MIXER_STEPPER_LOOP(i) tcolor[i] = mix[i] * scale;
149 149
 
150 150
       #ifdef MIXER_NORMALIZER_DEBUG
151
-        SERIAL_ECHOPAIR("Mix [", int(mix[0]));
152
-        SERIAL_ECHOPAIR(", ", int(mix[1]));
153
-        SERIAL_ECHOPAIR("] to Color [", int(tcolor[0]));
154
-        SERIAL_ECHOPAIR(", ", int(tcolor[1]));
155
-        SERIAL_ECHOLNPGM("]");
151
+        SERIAL_ECHOLNPAIR("Mix [", int(mix[0]), ", ", int(mix[1]), "] to Color [", int(tcolor[0]), ", ", int(tcolor[1]), "]");
156 152
       #endif
157 153
     }
158 154
 
@@ -163,12 +159,7 @@ class Mixer {
163 159
       mix[0] = mixer_perc_t(100.0f * color[j][0] / ctot);
164 160
       mix[1] = 100 - mix[0];
165 161
       #ifdef MIXER_NORMALIZER_DEBUG
166
-        SERIAL_ECHOPAIR("V-tool ", int(j));
167
-        SERIAL_ECHOPAIR(" [", int(color[j][0]));
168
-        SERIAL_ECHOPAIR(", ", int(color[j][1]));
169
-        SERIAL_ECHOPAIR("] to Mix [", int(mix[0]));
170
-        SERIAL_ECHOPAIR(", ", int(mix[1]));
171
-        SERIAL_ECHOLNPGM("]");
162
+        SERIAL_ECHOLNPAIR("V-tool ", int(j), " [", int(color[j][0]), ", ", int(color[j][1]), "] to Mix [", int(mix[0]), ", ", int(mix[1]), "]");
172 163
       #endif
173 164
     }
174 165
 
@@ -211,11 +202,7 @@ class Mixer {
211 202
       mix[0] = (mixer_perc_t)CEIL(100.0f * gradient.color[0] / ctot);
212 203
       mix[1] = 100 - mix[0];
213 204
       #ifdef MIXER_NORMALIZER_DEBUG
214
-        SERIAL_ECHOPAIR("Gradient [", int(gradient.color[0]));
215
-        SERIAL_ECHOPAIR(", ", int(gradient.color[1]));
216
-        SERIAL_ECHOPAIR("] to Mix [", int(mix[0]));
217
-        SERIAL_ECHOPAIR(", ", int(mix[1]));
218
-        SERIAL_ECHOLNPGM("]");
205
+        SERIAL_ECHOLNPAIR("Gradient [", int(gradient.color[0]), ", ", int(gradient.color[1]), "] to Mix [", int(mix[0]), ", ", int(mix[1]), "]");
219 206
       #endif
220 207
     }
221 208
 

+ 6
- 5
Marlin/src/feature/pause.cpp Переглянути файл

@@ -581,11 +581,12 @@ void wait_for_confirmation(const bool is_reload/*=false*/, const int8_t max_beep
581 581
  */
582 582
 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*/ DXC_ARGS) {
583 583
   /*
584
-  SERIAL_ECHOLNPGM("start of resume_print()");
585
-  SERIAL_ECHOPAIR("\ndual_x_carriage_mode:", dual_x_carriage_mode);
586
-  SERIAL_ECHOPAIR("\nextruder_duplication_enabled:", extruder_duplication_enabled);
587
-  SERIAL_ECHOPAIR("\nactive_extruder:", active_extruder);
588
-  SERIAL_ECHOLNPGM("\n");
584
+  SERIAL_ECHOLNPAIR(
585
+    "start of resume_print()\ndual_x_carriage_mode:", dual_x_carriage_mode,
586
+    "\nextruder_duplication_enabled:", extruder_duplication_enabled,
587
+    "\nactive_extruder:", active_extruder,
588
+    "\n"
589
+  );
589 590
   //*/
590 591
 
591 592
   if (!did_pause_print) return;

+ 2
- 4
Marlin/src/feature/power_loss_recovery.cpp Переглянути файл

@@ -357,8 +357,7 @@ void PrintJobRecovery::resume() {
357 357
 
358 358
   void PrintJobRecovery::debug(PGM_P const prefix) {
359 359
     serialprintPGM(prefix);
360
-    SERIAL_ECHOPAIR(" Job Recovery Info...\nvalid_head:", int(info.valid_head));
361
-    SERIAL_ECHOLNPAIR(" valid_foot:", int(info.valid_foot));
360
+    SERIAL_ECHOLNPAIR(" Job Recovery Info...\nvalid_head:", int(info.valid_head), " valid_foot:", int(info.valid_foot));
362 361
     if (info.valid_head) {
363 362
       if (info.valid_head == info.valid_foot) {
364 363
         SERIAL_ECHOPGM("current_position: ");
@@ -394,8 +393,7 @@ void PrintJobRecovery::resume() {
394 393
         #endif
395 394
 
396 395
         #if HAS_LEVELING
397
-          SERIAL_ECHOPAIR("leveling: ", int(info.leveling));
398
-          SERIAL_ECHOLNPAIR(" fade: ", int(info.fade));
396
+          SERIAL_ECHOLNPAIR("leveling: ", int(info.leveling), "\n fade: ", int(info.fade));
399 397
         #endif
400 398
         #if ENABLED(FWRETRACT)
401 399
           SERIAL_ECHOPGM("retract: ");

+ 3
- 6
Marlin/src/feature/prusa_MMU2/mmu2.cpp Переглянути файл

@@ -174,8 +174,7 @@ void MMU2::mmuLoop() {
174 174
         sscanf(rx_buffer, "%uok\n", &version);
175 175
 
176 176
         #if ENABLED(MMU2_DEBUG)
177
-          SERIAL_ECHOLNPAIR("MMU => ", version);
178
-          SERIAL_ECHOLNPGM("MMU <= 'S2'");
177
+          SERIAL_ECHOLNPAIR("MMU => ", version, "\nMMU <= 'S2'");
179 178
         #endif
180 179
 
181 180
         tx_str_P(PSTR("S2\n")); // read build number
@@ -234,8 +233,7 @@ void MMU2::mmuLoop() {
234 233
         sscanf(rx_buffer, "%hhuok\n", &finda);
235 234
 
236 235
         #if ENABLED(MMU2_DEBUG)
237
-          SERIAL_ECHOLNPAIR("MMU => ", finda);
238
-          SERIAL_ECHOLNPGM("MMU - ENABLED");
236
+          SERIAL_ECHOLNPAIR("MMU => ", finda, "\nMMU - ENABLED");
239 237
         #endif
240 238
 
241 239
         enabled = true;
@@ -309,8 +307,7 @@ void MMU2::mmuLoop() {
309 307
           // filament type
310 308
           int filament = cmd - MMU_CMD_F0;
311 309
           #if ENABLED(MMU2_DEBUG)
312
-            SERIAL_ECHOPAIR("MMU <= F", filament);
313
-            SERIAL_ECHOPGM(" ");
310
+            SERIAL_ECHOPAIR("MMU <= F", filament, " ");
314 311
             SERIAL_ECHO_F(cmd_arg, DEC);
315 312
             SERIAL_ECHOPGM("\n");
316 313
           #endif

+ 1
- 3
Marlin/src/feature/twibus.cpp Переглянути файл

@@ -92,9 +92,7 @@ void TWIBus::send() {
92 92
 void TWIBus::echoprefix(uint8_t bytes, const char prefix[], uint8_t adr) {
93 93
   SERIAL_ECHO_START();
94 94
   serialprintPGM(prefix);
95
-  SERIAL_ECHOPAIR(": from:", adr);
96
-  SERIAL_ECHOPAIR(" bytes:", bytes);
97
-  SERIAL_ECHOPGM(" data:");
95
+  SERIAL_ECHOPAIR(": from:", adr, " bytes:", bytes, " data:");
98 96
 }
99 97
 
100 98
 // static

+ 1
- 6
Marlin/src/gcode/bedlevel/G26.cpp Переглянути файл

@@ -346,12 +346,7 @@ inline bool look_for_lines_to_connect() {
346 346
             if (position_is_reachable(sx, sy) && position_is_reachable(ex, ey)) {
347 347
 
348 348
               if (g26_debug_flag) {
349
-                SERIAL_ECHOPAIR(" Connecting with horizontal line (sx=", sx);
350
-                SERIAL_ECHOPAIR(", sy=", sy);
351
-                SERIAL_ECHOPAIR(") -> (ex=", ex);
352
-                SERIAL_ECHOPAIR(", ey=", ey);
353
-                SERIAL_CHAR(')');
354
-                SERIAL_EOL();
349
+                SERIAL_ECHOLNPAIR(" Connecting with horizontal line (sx=", sx, ", sy=", sy, ") -> (ex=", ex, ", ey=", ey, ")");
355 350
                 //debug_current_and_destination(PSTR("Connecting horizontal line."));
356 351
               }
357 352
               print_line_from_here_to_there(sx, sy, g26_layer_height, ex, ey, g26_layer_height);

+ 21
- 28
Marlin/src/gcode/parser.cpp Переглянути файл

@@ -272,8 +272,7 @@ void GCodeParser::parse(char *p) {
272 272
 
273 273
       #if ENABLED(DEBUG_GCODE_PARSER)
274 274
         if (debug) {
275
-          SERIAL_ECHOPAIR("Got letter ", code);
276
-          SERIAL_ECHOPAIR(" at index ", (int)(p - command_ptr - 1));
275
+          SERIAL_ECHOPAIR("Got letter ", code, " at index ", (int)(p - command_ptr - 1));
277 276
           if (has_num) SERIAL_ECHOPGM(" (has_num)");
278 277
         }
279 278
       #endif
@@ -329,47 +328,41 @@ void GCodeParser::parse(char *p) {
329 328
 
330 329
 void GCodeParser::unknown_command_error() {
331 330
   SERIAL_ECHO_START();
332
-  SERIAL_ECHOPAIR(MSG_UNKNOWN_COMMAND, command_ptr);
333
-  SERIAL_CHAR('"');
334
-  SERIAL_EOL();
331
+  SERIAL_ECHOLNPAIR(MSG_UNKNOWN_COMMAND, command_ptr, "\"");
335 332
 }
336 333
 
337 334
 #if ENABLED(DEBUG_GCODE_PARSER)
338 335
 
339 336
   void GCodeParser::debug() {
340
-    SERIAL_ECHOPAIR("Command: ", command_ptr);
341
-    SERIAL_ECHOPAIR(" (", command_letter);
337
+    SERIAL_ECHOPAIR("Command: ", command_ptr, " (", command_letter);
342 338
     SERIAL_ECHO(codenum);
343 339
     SERIAL_ECHOLNPGM(")");
344 340
     #if ENABLED(FASTER_GCODE_PARSER)
345
-      SERIAL_ECHOPGM(" args: \"");
346
-      for (char c = 'A'; c <= 'Z'; ++c)
347
-        if (seen(c)) { SERIAL_CHAR(c); SERIAL_CHAR(' '); }
341
+      SERIAL_ECHOPGM(" args: { ");
342
+      for (char c = 'A'; c <= 'Z'; ++c) if (seen(c)) { SERIAL_CHAR(c); SERIAL_CHAR(' '); }
343
+      SERIAL_CHAR('}');
348 344
     #else
349
-      SERIAL_ECHOPAIR(" args: \"", command_args);
345
+      SERIAL_ECHOPAIR(" args: { ", command_args, " }");
350 346
     #endif
351
-    SERIAL_CHAR('"');
352
-    if (string_arg) {
353
-      SERIAL_ECHOPGM(" string: \"");
354
-      SERIAL_ECHO(string_arg);
355
-      SERIAL_CHAR('"');
356
-    }
347
+    if (string_arg) SERIAL_ECHOPAIR(" string: \"", string_arg, "\"");
357 348
     SERIAL_ECHOLNPGM("\n");
358 349
     for (char c = 'A'; c <= 'Z'; ++c) {
359 350
       if (seen(c)) {
360 351
         SERIAL_ECHOPAIR("Code '", c); SERIAL_ECHOPGM("':");
361 352
         if (has_value()) {
362
-          SERIAL_ECHOPAIR("\n    float: ", value_float());
363
-          SERIAL_ECHOPAIR("\n     long: ", value_long());
364
-          SERIAL_ECHOPAIR("\n    ulong: ", value_ulong());
365
-          SERIAL_ECHOPAIR("\n   millis: ", value_millis());
366
-          SERIAL_ECHOPAIR("\n   sec-ms: ", value_millis_from_seconds());
367
-          SERIAL_ECHOPAIR("\n      int: ", value_int());
368
-          SERIAL_ECHOPAIR("\n   ushort: ", value_ushort());
369
-          SERIAL_ECHOPAIR("\n     byte: ", (int)value_byte());
370
-          SERIAL_ECHOPAIR("\n     bool: ", (int)value_bool());
371
-          SERIAL_ECHOPAIR("\n   linear: ", value_linear_units());
372
-          SERIAL_ECHOPAIR("\n  celsius: ", value_celsius());
353
+          SERIAL_ECHOPAIR(
354
+            "\n    float: ", value_float(),
355
+            "\n     long: ", value_long(),
356
+            "\n    ulong: ", value_ulong(),
357
+            "\n   millis: ", value_millis(),
358
+            "\n   sec-ms: ", value_millis_from_seconds(),
359
+            "\n      int: ", value_int(),
360
+            "\n   ushort: ", value_ushort(),
361
+            "\n     byte: ", (int)value_byte(),
362
+            "\n     bool: ", (int)value_bool(),
363
+            "\n   linear: ", value_linear_units(),
364
+            "\n  celsius: ", value_celsius()
365
+          );
373 366
         }
374 367
         else
375 368
           SERIAL_ECHOPGM(" (no value)");

+ 1
- 2
Marlin/src/gcode/parser.h Переглянути файл

@@ -120,8 +120,7 @@ public:
120 120
       param[ind] = ptr ? ptr - command_ptr : 0;  // parameter offset or 0
121 121
       #if ENABLED(DEBUG_GCODE_PARSER)
122 122
         if (codenum == 800) {
123
-          SERIAL_ECHOPAIR("Set bit ", (int)ind);
124
-          SERIAL_ECHOPAIR(" of codebits (", hex_address((void*)(codebits >> 16)));
123
+          SERIAL_ECHOPAIR("Set bit ", (int)ind, " of codebits (", hex_address((void*)(codebits >> 16)));
125 124
           print_hex_word((uint16_t)(codebits & 0xFFFF));
126 125
           SERIAL_ECHOLNPAIR(") | param = ", (int)param[ind]);
127 126
         }

+ 7
- 10
Marlin/src/gcode/queue.cpp Переглянути файл

@@ -150,9 +150,7 @@ bool enqueue_and_echo_command(const char* cmd) {
150 150
 
151 151
   if (_enqueuecommand(cmd)) {
152 152
     SERIAL_ECHO_START();
153
-    SERIAL_ECHOPAIR(MSG_ENQUEUEING, cmd);
154
-    SERIAL_CHAR('"');
155
-    SERIAL_EOL();
153
+    SERIAL_ECHOLNPAIR(MSG_ENQUEUEING, cmd, "\"");
156 154
     return true;
157 155
   }
158 156
   return false;
@@ -398,9 +396,10 @@ void gcode_line_error(PGM_P const err, const int8_t port) {
398 396
               stream_state = StreamState::PACKET_RESET;
399 397
               bytes_received = 0;
400 398
               time_stream_start = millis();
401
-              SERIAL_ECHOPAIR("echo: Datastream initialized (", stream_header.filesize);
402
-              SERIAL_ECHOLNPGM(" bytes expected)");
403
-              SERIAL_ECHOLNPAIR("so", buffer_size); // confirm active stream and the maximum block size supported
399
+              // confirm active stream and the maximum block size supported
400
+              SERIAL_ECHO_START();
401
+              SERIAL_ECHOLNPAIR("Datastream initialized (", stream_header.filesize, " bytes expected)");
402
+              SERIAL_ECHOLNPAIR("so", buffer_size);
404 403
             }
405 404
             else {
406 405
               SERIAL_ECHO_MSG("Datastream init error (invalid token)");
@@ -468,8 +467,7 @@ void gcode_line_error(PGM_P const err, const int8_t port) {
468 467
             }
469 468
             else {
470 469
               SERIAL_ECHO_START();
471
-              SERIAL_ECHOPAIR("Block(", packet.header.id);
472
-              SERIAL_ECHOLNPGM(") Corrupt");
470
+              SERIAL_ECHOLNPAIR("Block(", packet.header.id, ") Corrupt");
473 471
               stream_state = StreamState::PACKET_FLUSHRX;
474 472
             }
475 473
             break;
@@ -504,8 +502,7 @@ void gcode_line_error(PGM_P const err, const int8_t port) {
504 502
             card.flag.binary_mode = false;
505 503
             SERIAL_ECHO_START();
506 504
             SERIAL_ECHO(card.filename);
507
-            SERIAL_ECHOPAIR(" transfer completed @ ", ((bytes_received / (millis() - time_stream_start) * 1000) / 1024));
508
-            SERIAL_ECHOLNPGM("KiB/s");
505
+            SERIAL_ECHOLNPAIR(" transfer completed @ ", ((bytes_received / (millis() - time_stream_start) * 1000) / 1024), "KiB/s");
509 506
             SERIAL_ECHOLNPGM("sc"); // transmit stream complete token
510 507
             card.closefile();
511 508
             return;

+ 195
- 219
Marlin/src/module/configuration_store.cpp Переглянути файл

@@ -382,8 +382,8 @@ void MarlinSettings::postprocess() {
382 382
 #if ENABLED(EEPROM_CHITCHAT)
383 383
   #define CHITCHAT_ECHO(V)              SERIAL_ECHO(V)
384 384
   #define CHITCHAT_ECHOLNPGM(STR)       SERIAL_ECHOLNPGM(STR)
385
-  #define CHITCHAT_ECHOPAIR(STR,V)      SERIAL_ECHOPAIR(STR,V)
386
-  #define CHITCHAT_ECHOLNPAIR(STR,V)    SERIAL_ECHOLNPAIR(STR,V)
385
+  #define CHITCHAT_ECHOPAIR(...)        SERIAL_ECHOPAIR(__VA_ARGS__)
386
+  #define CHITCHAT_ECHOLNPAIR(...)      SERIAL_ECHOLNPAIR(__VA_ARGS__)
387 387
   #define CHITCHAT_ECHO_START()         SERIAL_ECHO_START()
388 388
   #define CHITCHAT_ERROR_START()        SERIAL_ERROR_START()
389 389
   #define CHITCHAT_ERROR_MSG(STR)       SERIAL_ERROR_MSG(STR)
@@ -392,8 +392,8 @@ void MarlinSettings::postprocess() {
392 392
 #else
393 393
   #define CHITCHAT_ECHO(V)              NOOP
394 394
   #define CHITCHAT_ECHOLNPGM(STR)       NOOP
395
-  #define CHITCHAT_ECHOPAIR(STR,V)      NOOP
396
-  #define CHITCHAT_ECHOLNPAIR(STR,V)    NOOP
395
+  #define CHITCHAT_ECHOPAIR(...)        NOOP
396
+  #define CHITCHAT_ECHOLNPAIR(...)      NOOP
397 397
   #define CHITCHAT_ECHO_START()         NOOP
398 398
   #define CHITCHAT_ERROR_START()        NOOP
399 399
   #define CHITCHAT_ERROR_MSG(STR)       NOOP
@@ -1104,9 +1104,7 @@ void MarlinSettings::postprocess() {
1104 1104
 
1105 1105
       // Report storage size
1106 1106
       CHITCHAT_ECHO_START();
1107
-      CHITCHAT_ECHOPAIR("Settings Stored (", eeprom_size);
1108
-      CHITCHAT_ECHOPAIR(" bytes; crc ", (uint32_t)final_crc);
1109
-      CHITCHAT_ECHOLNPGM(")");
1107
+      CHITCHAT_ECHOLNPAIR("Settings Stored (", eeprom_size, " bytes; crc ", (uint32_t)final_crc, ")");
1110 1108
 
1111 1109
       eeprom_error |= size_error(eeprom_size);
1112 1110
     }
@@ -1144,9 +1142,7 @@ void MarlinSettings::postprocess() {
1144 1142
         stored_ver[1] = '\0';
1145 1143
       }
1146 1144
       CHITCHAT_ECHO_START();
1147
-      CHITCHAT_ECHOPGM("EEPROM version mismatch ");
1148
-      CHITCHAT_ECHOPAIR("(EEPROM=", stored_ver);
1149
-      CHITCHAT_ECHOLNPGM(" Marlin=" EEPROM_VERSION ")");
1145
+      CHITCHAT_ECHOLNPAIR("EEPROM version mismatch (EEPROM=", stored_ver, " Marlin=" EEPROM_VERSION ")");
1150 1146
       eeprom_error = true;
1151 1147
     }
1152 1148
     else {
@@ -1812,24 +1808,17 @@ void MarlinSettings::postprocess() {
1812 1808
       eeprom_error = size_error(eeprom_index - (EEPROM_OFFSET));
1813 1809
       if (eeprom_error) {
1814 1810
         CHITCHAT_ECHO_START();
1815
-        CHITCHAT_ECHOPAIR("Index: ", int(eeprom_index - (EEPROM_OFFSET)));
1816
-        CHITCHAT_ECHOLNPAIR(" Size: ", datasize());
1811
+        CHITCHAT_ECHOLNPAIR("Index: ", int(eeprom_index - (EEPROM_OFFSET)), " Size: ", datasize());
1817 1812
       }
1818 1813
       else if (working_crc != stored_crc) {
1819 1814
         eeprom_error = true;
1820 1815
         CHITCHAT_ERROR_START();
1821
-        CHITCHAT_ECHOPGM("EEPROM CRC mismatch - (stored) ");
1822
-        CHITCHAT_ECHO(stored_crc);
1823
-        CHITCHAT_ECHOPGM(" != ");
1824
-        CHITCHAT_ECHO(working_crc);
1825
-        CHITCHAT_ECHOLNPGM(" (calculated)!");
1816
+        CHITCHAT_ECHOLNPAIR("EEPROM CRC mismatch - (stored) ", stored_crc, " != ", working_crc, " (calculated)!");
1826 1817
       }
1827 1818
       else if (!validating) {
1828 1819
         CHITCHAT_ECHO_START();
1829 1820
         CHITCHAT_ECHO(version);
1830
-        CHITCHAT_ECHOPAIR(" stored settings retrieved (", eeprom_index - (EEPROM_OFFSET));
1831
-        CHITCHAT_ECHOPAIR(" bytes; crc ", (uint32_t)working_crc);
1832
-        CHITCHAT_ECHOLNPGM(")");
1821
+        CHITCHAT_ECHOLNPAIR(" stored settings retrieved (", eeprom_index - (EEPROM_OFFSET), " bytes; crc ", (uint32_t)working_crc, ")");
1833 1822
       }
1834 1823
 
1835 1824
       if (!validating && !eeprom_error) postprocess();
@@ -1857,8 +1846,7 @@ void MarlinSettings::postprocess() {
1857 1846
 
1858 1847
           if (ubl.storage_slot >= 0) {
1859 1848
             load_mesh(ubl.storage_slot);
1860
-            CHITCHAT_ECHOPAIR("Mesh ", ubl.storage_slot);
1861
-            CHITCHAT_ECHOLNPGM(" loaded from storage.");
1849
+            CHITCHAT_ECHOLNPAIR("Mesh ", ubl.storage_slot, " loaded from storage.");
1862 1850
           }
1863 1851
           else {
1864 1852
             ubl.reset();
@@ -1924,9 +1912,7 @@ void MarlinSettings::postprocess() {
1924 1912
         const int16_t a = calc_num_meshes();
1925 1913
         if (!WITHIN(slot, 0, a - 1)) {
1926 1914
           ubl_invalid_slot(a);
1927
-          CHITCHAT_ECHOPAIR("E2END=", persistentStore.capacity() - 1);
1928
-          CHITCHAT_ECHOPAIR(" meshes_end=", meshes_end);
1929
-          CHITCHAT_ECHOLNPAIR(" slot=", slot);
1915
+          CHITCHAT_ECHOLNPAIR("E2END=", persistentStore.capacity() - 1, " meshes_end=", meshes_end, " slot=", slot);
1930 1916
           CHITCHAT_EOL();
1931 1917
           return;
1932 1918
         }
@@ -2314,7 +2300,7 @@ void MarlinSettings::reset() {
2314 2300
   #define CONFIG_ECHO_HEADING(STR)  do{ if (!forReplay) { CONFIG_ECHO_START(); SERIAL_ECHOLNPGM(STR); } }while(0)
2315 2301
 
2316 2302
   #if HAS_TRINAMIC
2317
-    void say_M906() { SERIAL_ECHOPGM("  M906"); }
2303
+    inline void say_M906(const bool forReplay) { CONFIG_ECHO_START(); SERIAL_ECHOPGM("  M906"); }
2318 2304
     #if HAS_STEALTHCHOP
2319 2305
       void say_M569(const char * const etc=NULL) {
2320 2306
         SERIAL_ECHOPGM("  M569 S1");
@@ -2326,15 +2312,15 @@ void MarlinSettings::reset() {
2326 2312
       }
2327 2313
     #endif
2328 2314
     #if ENABLED(HYBRID_THRESHOLD)
2329
-      void say_M913() { SERIAL_ECHOPGM("  M913"); }
2315
+      inline void say_M913() { SERIAL_ECHOPGM("  M913"); }
2330 2316
     #endif
2331 2317
     #if USE_SENSORLESS
2332
-      void say_M914() { SERIAL_ECHOPGM("  M914"); }
2318
+      inline void say_M914() { SERIAL_ECHOPGM("  M914"); }
2333 2319
     #endif
2334 2320
   #endif
2335 2321
 
2336 2322
   #if ENABLED(ADVANCED_PAUSE_FEATURE)
2337
-    void say_M603() { SERIAL_ECHOPGM("  M603 "); }
2323
+    inline void say_M603(const bool forReplay) { CONFIG_ECHO_START(); SERIAL_ECHOPGM("  M603 "); }
2338 2324
   #endif
2339 2325
 
2340 2326
   inline void say_units(const bool colon) {
@@ -2403,28 +2389,22 @@ void MarlinSettings::reset() {
2403 2389
       }
2404 2390
 
2405 2391
       CONFIG_ECHO_START();
2406
-      SERIAL_ECHOPAIR("  M200 D", LINEAR_UNIT(planner.filament_size[0]));
2407
-      SERIAL_EOL();
2392
+      SERIAL_ECHOLNPAIR("  M200 D", LINEAR_UNIT(planner.filament_size[0]));
2408 2393
       #if EXTRUDERS > 1
2409 2394
         CONFIG_ECHO_START();
2410
-        SERIAL_ECHOPAIR("  M200 T1 D", LINEAR_UNIT(planner.filament_size[1]));
2411
-        SERIAL_EOL();
2395
+        SERIAL_ECHOLNPAIR("  M200 T1 D", LINEAR_UNIT(planner.filament_size[1]));
2412 2396
         #if EXTRUDERS > 2
2413 2397
           CONFIG_ECHO_START();
2414
-          SERIAL_ECHOPAIR("  M200 T2 D", LINEAR_UNIT(planner.filament_size[2]));
2415
-          SERIAL_EOL();
2398
+          SERIAL_ECHOLNPAIR("  M200 T2 D", LINEAR_UNIT(planner.filament_size[2]));
2416 2399
           #if EXTRUDERS > 3
2417 2400
             CONFIG_ECHO_START();
2418
-            SERIAL_ECHOPAIR("  M200 T3 D", LINEAR_UNIT(planner.filament_size[3]));
2419
-            SERIAL_EOL();
2401
+            SERIAL_ECHOLNPAIR("  M200 T3 D", LINEAR_UNIT(planner.filament_size[3]));
2420 2402
             #if EXTRUDERS > 4
2421 2403
               CONFIG_ECHO_START();
2422
-              SERIAL_ECHOPAIR("  M200 T4 D", LINEAR_UNIT(planner.filament_size[4]));
2423
-              SERIAL_EOL();
2404
+              SERIAL_ECHOLNPAIR("  M200 T4 D", LINEAR_UNIT(planner.filament_size[4]));
2424 2405
               #if EXTRUDERS > 5
2425 2406
                 CONFIG_ECHO_START();
2426
-                SERIAL_ECHOPAIR("  M200 T5 D", LINEAR_UNIT(planner.filament_size[5]));
2427
-                SERIAL_EOL();
2407
+                SERIAL_ECHOLNPAIR("  M200 T5 D", LINEAR_UNIT(planner.filament_size[5]));
2428 2408
               #endif // EXTRUDERS > 5
2429 2409
             #endif // EXTRUDERS > 4
2430 2410
           #endif // EXTRUDERS > 3
@@ -2441,43 +2421,50 @@ void MarlinSettings::reset() {
2441 2421
 
2442 2422
     CONFIG_ECHO_HEADING("Maximum feedrates (units/s):");
2443 2423
     CONFIG_ECHO_START();
2444
-    SERIAL_ECHOPAIR("  M203 X", LINEAR_UNIT(planner.settings.max_feedrate_mm_s[X_AXIS]));
2445
-    SERIAL_ECHOPAIR(" Y", LINEAR_UNIT(planner.settings.max_feedrate_mm_s[Y_AXIS]));
2446
-    SERIAL_ECHOPAIR(" Z", LINEAR_UNIT(planner.settings.max_feedrate_mm_s[Z_AXIS]));
2447
-    #if DISABLED(DISTINCT_E_FACTORS)
2448
-      SERIAL_ECHOPAIR(" E", VOLUMETRIC_UNIT(planner.settings.max_feedrate_mm_s[E_AXIS]));
2449
-    #endif
2450
-    SERIAL_EOL();
2424
+    SERIAL_ECHOLNPAIR(
2425
+        "  M203 X", LINEAR_UNIT(planner.settings.max_feedrate_mm_s[X_AXIS])
2426
+      , " Y", LINEAR_UNIT(planner.settings.max_feedrate_mm_s[Y_AXIS])
2427
+      , " Z", LINEAR_UNIT(planner.settings.max_feedrate_mm_s[Z_AXIS])
2428
+      #if DISABLED(DISTINCT_E_FACTORS)
2429
+        , " E", VOLUMETRIC_UNIT(planner.settings.max_feedrate_mm_s[E_AXIS])
2430
+      #endif
2431
+    );
2451 2432
     #if ENABLED(DISTINCT_E_FACTORS)
2452 2433
       CONFIG_ECHO_START();
2453 2434
       for (uint8_t i = 0; i < E_STEPPERS; i++) {
2454
-        SERIAL_ECHOPAIR("  M203 T", (int)i);
2455
-        SERIAL_ECHOLNPAIR(" E", VOLUMETRIC_UNIT(planner.settings.max_feedrate_mm_s[E_AXIS_N(i)]));
2435
+        SERIAL_ECHOLNPAIR(
2436
+            "  M203 T", (int)i
2437
+          , " E", VOLUMETRIC_UNIT(planner.settings.max_feedrate_mm_s[E_AXIS_N(i)])
2438
+        );
2456 2439
       }
2457 2440
     #endif
2458 2441
 
2459 2442
     CONFIG_ECHO_HEADING("Maximum Acceleration (units/s2):");
2460 2443
     CONFIG_ECHO_START();
2461
-    SERIAL_ECHOPAIR("  M201 X", LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[X_AXIS]));
2462
-    SERIAL_ECHOPAIR(" Y", LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[Y_AXIS]));
2463
-    SERIAL_ECHOPAIR(" Z", LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[Z_AXIS]));
2464
-    #if DISABLED(DISTINCT_E_FACTORS)
2465
-      SERIAL_ECHOPAIR(" E", VOLUMETRIC_UNIT(planner.settings.max_acceleration_mm_per_s2[E_AXIS]));
2466
-    #endif
2467
-    SERIAL_EOL();
2444
+    SERIAL_ECHOLNPAIR(
2445
+        "  M201 X", LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[X_AXIS])
2446
+      , " Y", LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[Y_AXIS])
2447
+      , " Z", LINEAR_UNIT(planner.settings.max_acceleration_mm_per_s2[Z_AXIS])
2448
+      #if DISABLED(DISTINCT_E_FACTORS)
2449
+        , " E", VOLUMETRIC_UNIT(planner.settings.max_acceleration_mm_per_s2[E_AXIS])
2450
+      #endif
2451
+    );
2468 2452
     #if ENABLED(DISTINCT_E_FACTORS)
2469 2453
       CONFIG_ECHO_START();
2470
-      for (uint8_t i = 0; i < E_STEPPERS; i++) {
2471
-        SERIAL_ECHOPAIR("  M201 T", (int)i);
2472
-        SERIAL_ECHOLNPAIR(" E", VOLUMETRIC_UNIT(planner.settings.max_acceleration_mm_per_s2[E_AXIS_N(i)]));
2473
-      }
2454
+      for (uint8_t i = 0; i < E_STEPPERS; i++)
2455
+        SERIAL_ECHOLNPAIR(
2456
+            "  M201 T", (int)i
2457
+          , " E", VOLUMETRIC_UNIT(planner.settings.max_acceleration_mm_per_s2[E_AXIS_N(i)])
2458
+        );
2474 2459
     #endif
2475 2460
 
2476 2461
     CONFIG_ECHO_HEADING("Acceleration (units/s2): P<print_accel> R<retract_accel> T<travel_accel>");
2477 2462
     CONFIG_ECHO_START();
2478
-    SERIAL_ECHOPAIR("  M204 P", LINEAR_UNIT(planner.settings.acceleration));
2479
-    SERIAL_ECHOPAIR(" R", LINEAR_UNIT(planner.settings.retract_acceleration));
2480
-    SERIAL_ECHOLNPAIR(" T", LINEAR_UNIT(planner.settings.travel_acceleration));
2463
+    SERIAL_ECHOLNPAIR(
2464
+        "  M204 P", LINEAR_UNIT(planner.settings.acceleration)
2465
+      , " R", LINEAR_UNIT(planner.settings.retract_acceleration)
2466
+      , " T", LINEAR_UNIT(planner.settings.travel_acceleration)
2467
+    );
2481 2468
 
2482 2469
     if (!forReplay) {
2483 2470
       CONFIG_ECHO_START();
@@ -2494,39 +2481,42 @@ void MarlinSettings::reset() {
2494 2481
       SERIAL_EOL();
2495 2482
     }
2496 2483
     CONFIG_ECHO_START();
2497
-    SERIAL_ECHOPAIR("  M205 B", LINEAR_UNIT(planner.settings.min_segment_time_us));
2498
-    SERIAL_ECHOPAIR(" S", LINEAR_UNIT(planner.settings.min_feedrate_mm_s));
2499
-    SERIAL_ECHOPAIR(" T", LINEAR_UNIT(planner.settings.min_travel_feedrate_mm_s));
2500
-
2501
-    #if ENABLED(JUNCTION_DEVIATION)
2502
-      SERIAL_ECHOPAIR(" J", LINEAR_UNIT(planner.junction_deviation_mm));
2503
-    #endif
2504
-    #if HAS_CLASSIC_JERK
2505
-      SERIAL_ECHOPAIR(" X", LINEAR_UNIT(planner.max_jerk[X_AXIS]));
2506
-      SERIAL_ECHOPAIR(" Y", LINEAR_UNIT(planner.max_jerk[Y_AXIS]));
2507
-      SERIAL_ECHOPAIR(" Z", LINEAR_UNIT(planner.max_jerk[Z_AXIS]));
2508
-      #if DISABLED(JUNCTION_DEVIATION) || DISABLED(LIN_ADVANCE)
2509
-        SERIAL_ECHOPAIR(" E", LINEAR_UNIT(planner.max_jerk[E_AXIS]));
2484
+    SERIAL_ECHOLNPAIR(
2485
+        "  M205 B", LINEAR_UNIT(planner.settings.min_segment_time_us)
2486
+      , " S", LINEAR_UNIT(planner.settings.min_feedrate_mm_s)
2487
+      , " T", LINEAR_UNIT(planner.settings.min_travel_feedrate_mm_s)
2488
+      #if ENABLED(JUNCTION_DEVIATION)
2489
+        , " J", LINEAR_UNIT(planner.junction_deviation_mm)
2510 2490
       #endif
2511
-    #endif
2512
-
2513
-    SERIAL_EOL();
2491
+      #if HAS_CLASSIC_JERK
2492
+        , " X", LINEAR_UNIT(planner.max_jerk[X_AXIS])
2493
+        , " Y", LINEAR_UNIT(planner.max_jerk[Y_AXIS])
2494
+        , " Z", LINEAR_UNIT(planner.max_jerk[Z_AXIS])
2495
+        #if DISABLED(JUNCTION_DEVIATION) || DISABLED(LIN_ADVANCE)
2496
+          , " E", LINEAR_UNIT(planner.max_jerk[E_AXIS])
2497
+        #endif
2498
+      #endif
2499
+    );
2514 2500
 
2515 2501
     #if HAS_M206_COMMAND
2516 2502
       CONFIG_ECHO_HEADING("Home offset:");
2517 2503
       CONFIG_ECHO_START();
2518
-      SERIAL_ECHOPAIR("  M206 X", LINEAR_UNIT(home_offset[X_AXIS]));
2519
-      SERIAL_ECHOPAIR(" Y", LINEAR_UNIT(home_offset[Y_AXIS]));
2520
-      SERIAL_ECHOLNPAIR(" Z", LINEAR_UNIT(home_offset[Z_AXIS]));
2504
+      SERIAL_ECHOLNPAIR(
2505
+          "  M206 X", LINEAR_UNIT(home_offset[X_AXIS])
2506
+        , " Y", LINEAR_UNIT(home_offset[Y_AXIS])
2507
+        , " Z", LINEAR_UNIT(home_offset[Z_AXIS])
2508
+      );
2521 2509
     #endif
2522 2510
 
2523 2511
     #if HAS_HOTEND_OFFSET
2524 2512
       CONFIG_ECHO_HEADING("Hotend offsets:");
2525 2513
       CONFIG_ECHO_START();
2526 2514
       for (uint8_t e = 1; e < HOTENDS; e++) {
2527
-        SERIAL_ECHOPAIR("  M218 T", (int)e);
2528
-        SERIAL_ECHOPAIR(" X", LINEAR_UNIT(hotend_offset[X_AXIS][e]));
2529
-        SERIAL_ECHOPAIR(" Y", LINEAR_UNIT(hotend_offset[Y_AXIS][e]));
2515
+        SERIAL_ECHOPAIR(
2516
+            "  M218 T", (int)e
2517
+          , " X", LINEAR_UNIT(hotend_offset[X_AXIS][e])
2518
+          , " Y", LINEAR_UNIT(hotend_offset[Y_AXIS][e])
2519
+        );
2530 2520
         SERIAL_ECHOLNPAIR_F(" Z", LINEAR_UNIT(hotend_offset[Z_AXIS][e]), 3);
2531 2521
       }
2532 2522
     #endif
@@ -2555,11 +2545,12 @@ void MarlinSettings::reset() {
2555 2545
       #endif
2556 2546
 
2557 2547
       CONFIG_ECHO_START();
2558
-      SERIAL_ECHOPAIR("  M420 S", planner.leveling_active ? 1 : 0);
2559
-      #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT)
2560
-        SERIAL_ECHOPAIR(" Z", LINEAR_UNIT(planner.z_fade_height));
2561
-      #endif
2562
-      SERIAL_EOL();
2548
+      SERIAL_ECHOLNPAIR(
2549
+        "  M420 S", planner.leveling_active ? 1 : 0
2550
+        #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT)
2551
+          , " Z", LINEAR_UNIT(planner.z_fade_height)
2552
+        #endif
2553
+      );
2563 2554
 
2564 2555
       #if ENABLED(MESH_BED_LEVELING)
2565 2556
 
@@ -2567,8 +2558,7 @@ void MarlinSettings::reset() {
2567 2558
           for (uint8_t py = 0; py < GRID_MAX_POINTS_Y; py++) {
2568 2559
             for (uint8_t px = 0; px < GRID_MAX_POINTS_X; px++) {
2569 2560
               CONFIG_ECHO_START();
2570
-              SERIAL_ECHOPAIR("  G29 S3 X", (int)px + 1);
2571
-              SERIAL_ECHOPAIR(" Y", (int)py + 1);
2561
+              SERIAL_ECHOPAIR("  G29 S3 X", (int)px + 1, " Y", (int)py + 1);
2572 2562
               SERIAL_ECHOLNPAIR_F(" Z", LINEAR_UNIT(mbl.z_values[px][py]), 5);
2573 2563
             }
2574 2564
           }
@@ -2580,8 +2570,7 @@ void MarlinSettings::reset() {
2580 2570
           SERIAL_EOL();
2581 2571
           ubl.report_state();
2582 2572
           SERIAL_ECHOLNPAIR("\nActive Mesh Slot: ", ubl.storage_slot);
2583
-          SERIAL_ECHOPAIR("EEPROM can hold ", calc_num_meshes());
2584
-          SERIAL_ECHOLNPGM(" meshes.\n");
2573
+          SERIAL_ECHOLNPAIR("EEPROM can hold ", calc_num_meshes(), " meshes.\n");
2585 2574
         }
2586 2575
 
2587 2576
        //ubl.report_current_mesh();   // This is too verbose for large meshes. A better (more terse)
@@ -2592,8 +2581,7 @@ void MarlinSettings::reset() {
2592 2581
           for (uint8_t py = 0; py < GRID_MAX_POINTS_Y; py++) {
2593 2582
             for (uint8_t px = 0; px < GRID_MAX_POINTS_X; px++) {
2594 2583
               CONFIG_ECHO_START();
2595
-              SERIAL_ECHOPAIR("  G29 W I", (int)px);
2596
-              SERIAL_ECHOPAIR(" J", (int)py);
2584
+              SERIAL_ECHOPAIR("  G29 W I", (int)px, " J", (int)py);
2597 2585
               SERIAL_ECHOLNPAIR_F(" Z", LINEAR_UNIT(z_values[px][py]), 5);
2598 2586
             }
2599 2587
           }
@@ -2619,10 +2607,7 @@ void MarlinSettings::reset() {
2619 2607
             case Z_PROBE_SERVO_NR:
2620 2608
           #endif
2621 2609
             CONFIG_ECHO_START();
2622
-            SERIAL_ECHOPAIR("  M281 P", int(i));
2623
-            SERIAL_ECHOPAIR(" L", servo_angles[i][0]);
2624
-            SERIAL_ECHOPAIR(" U", servo_angles[i][1]);
2625
-            SERIAL_EOL();
2610
+            SERIAL_ECHOLNPAIR("  M281 P", int(i), " L", servo_angles[i][0], " U", servo_angles[i][1]);
2626 2611
           default: break;
2627 2612
         }
2628 2613
       }
@@ -2633,33 +2618,37 @@ void MarlinSettings::reset() {
2633 2618
 
2634 2619
       CONFIG_ECHO_HEADING("SCARA settings: S<seg-per-sec> P<theta-psi-offset> T<theta-offset>");
2635 2620
       CONFIG_ECHO_START();
2636
-      SERIAL_ECHOPAIR("  M665 S", delta_segments_per_second);
2637
-      SERIAL_ECHOPAIR(" P", scara_home_offset[A_AXIS]);
2638
-      SERIAL_ECHOPAIR(" T", scara_home_offset[B_AXIS]);
2639
-      SERIAL_ECHOPAIR(" Z", LINEAR_UNIT(scara_home_offset[Z_AXIS]));
2640
-      SERIAL_EOL();
2621
+      SERIAL_ECHOLNPAIR(
2622
+          "  M665 S", delta_segments_per_second
2623
+        , " P", scara_home_offset[A_AXIS]
2624
+        , " T", scara_home_offset[B_AXIS]
2625
+        , " Z", LINEAR_UNIT(scara_home_offset[Z_AXIS])
2626
+      );
2641 2627
 
2642 2628
     #elif ENABLED(DELTA)
2643 2629
 
2644 2630
       CONFIG_ECHO_HEADING("Endstop adjustment:");
2645 2631
       CONFIG_ECHO_START();
2646
-      SERIAL_ECHOPAIR("  M666 X", LINEAR_UNIT(delta_endstop_adj[X_AXIS]));
2647
-      SERIAL_ECHOPAIR(" Y", LINEAR_UNIT(delta_endstop_adj[Y_AXIS]));
2648
-      SERIAL_ECHOLNPAIR(" Z", LINEAR_UNIT(delta_endstop_adj[Z_AXIS]));
2632
+      SERIAL_ECHOLNPAIR(
2633
+          "  M666 X", LINEAR_UNIT(delta_endstop_adj[X_AXIS])
2634
+        , " Y", LINEAR_UNIT(delta_endstop_adj[Y_AXIS])
2635
+        , " Z", LINEAR_UNIT(delta_endstop_adj[Z_AXIS])
2636
+      );
2649 2637
 
2650 2638
       CONFIG_ECHO_HEADING("Delta settings: L<diagonal_rod> R<radius> H<height> S<segments_per_s> B<calibration radius> XYZ<tower angle corrections>");
2651 2639
       CONFIG_ECHO_START();
2652
-      SERIAL_ECHOPAIR("  M665 L", LINEAR_UNIT(delta_diagonal_rod));
2653
-      SERIAL_ECHOPAIR(" R", LINEAR_UNIT(delta_radius));
2654
-      SERIAL_ECHOPAIR(" H", LINEAR_UNIT(delta_height));
2655
-      SERIAL_ECHOPAIR(" S", delta_segments_per_second);
2656
-      SERIAL_ECHOPAIR(" B", LINEAR_UNIT(delta_calibration_radius));
2657
-      SERIAL_ECHOPAIR(" X", LINEAR_UNIT(delta_tower_angle_trim[A_AXIS]));
2658
-      SERIAL_ECHOPAIR(" Y", LINEAR_UNIT(delta_tower_angle_trim[B_AXIS]));
2659
-      SERIAL_ECHOPAIR(" Z", LINEAR_UNIT(delta_tower_angle_trim[C_AXIS]));
2660
-      SERIAL_EOL();
2640
+      SERIAL_ECHOLNPAIR(
2641
+          "  M665 L", LINEAR_UNIT(delta_diagonal_rod)
2642
+        , " R", LINEAR_UNIT(delta_radius)
2643
+        , " H", LINEAR_UNIT(delta_height)
2644
+        , " S", delta_segments_per_second
2645
+        , " B", LINEAR_UNIT(delta_calibration_radius)
2646
+        , " X", LINEAR_UNIT(delta_tower_angle_trim[A_AXIS])
2647
+        , " Y", LINEAR_UNIT(delta_tower_angle_trim[B_AXIS])
2648
+        , " Z", LINEAR_UNIT(delta_tower_angle_trim[C_AXIS])
2649
+      );
2661 2650
 
2662
-    #elif ENABLED(X_DUAL_ENDSTOPS) || ENABLED(Y_DUAL_ENDSTOPS) || ENABLED(Z_DUAL_ENDSTOPS)
2651
+    #elif ENABLED(X_DUAL_ENDSTOPS) || ENABLED(Y_DUAL_ENDSTOPS) || Z_MULTI_ENDSTOPS
2663 2652
 
2664 2653
       CONFIG_ECHO_HEADING("Endstop adjustment:");
2665 2654
       CONFIG_ECHO_START();
@@ -2686,10 +2675,12 @@ void MarlinSettings::reset() {
2686 2675
       CONFIG_ECHO_HEADING("Material heatup parameters:");
2687 2676
       for (uint8_t i = 0; i < COUNT(ui.preheat_hotend_temp); i++) {
2688 2677
         CONFIG_ECHO_START();
2689
-        SERIAL_ECHOPAIR("  M145 S", (int)i);
2690
-        SERIAL_ECHOPAIR(" H", TEMP_UNIT(ui.preheat_hotend_temp[i]));
2691
-        SERIAL_ECHOPAIR(" B", TEMP_UNIT(ui.preheat_bed_temp[i]));
2692
-        SERIAL_ECHOLNPAIR(" F", int(ui.preheat_fan_speed[i]));
2678
+        SERIAL_ECHOLNPAIR(
2679
+            "  M145 S", (int)i
2680
+          , " H", TEMP_UNIT(ui.preheat_hotend_temp[i])
2681
+          , " B", TEMP_UNIT(ui.preheat_bed_temp[i])
2682
+          , " F", int(ui.preheat_fan_speed[i])
2683
+        );
2693 2684
       }
2694 2685
 
2695 2686
     #endif
@@ -2702,10 +2693,12 @@ void MarlinSettings::reset() {
2702 2693
           if (forReplay) {
2703 2694
             HOTEND_LOOP() {
2704 2695
               CONFIG_ECHO_START();
2705
-              SERIAL_ECHOPAIR("  M301 E", e);
2706
-              SERIAL_ECHOPAIR(" P", PID_PARAM(Kp, e));
2707
-              SERIAL_ECHOPAIR(" I", unscalePID_i(PID_PARAM(Ki, e)));
2708
-              SERIAL_ECHOPAIR(" D", unscalePID_d(PID_PARAM(Kd, e)));
2696
+              SERIAL_ECHOPAIR(
2697
+                  "  M301 E", e
2698
+                , " P", PID_PARAM(Kp, e)
2699
+                , " I", unscalePID_i(PID_PARAM(Ki, e))
2700
+                , " D", unscalePID_d(PID_PARAM(Kd, e))
2701
+              );
2709 2702
               #if ENABLED(PID_EXTRUSION_SCALING)
2710 2703
                 SERIAL_ECHOPAIR(" C", PID_PARAM(Kc, e));
2711 2704
                 if (e == 0) SERIAL_ECHOPAIR(" L", thermalManager.lpq_len);
@@ -2718,23 +2711,25 @@ void MarlinSettings::reset() {
2718 2711
         // !forReplay || HOTENDS == 1
2719 2712
         {
2720 2713
           CONFIG_ECHO_START();
2721
-          SERIAL_ECHOPAIR("  M301 P", PID_PARAM(Kp, 0)); // for compatibility with hosts, only echo values for E0
2722
-          SERIAL_ECHOPAIR(" I", unscalePID_i(PID_PARAM(Ki, 0)));
2723
-          SERIAL_ECHOPAIR(" D", unscalePID_d(PID_PARAM(Kd, 0)));
2724
-          #if ENABLED(PID_EXTRUSION_SCALING)
2725
-            SERIAL_ECHOPAIR(" C", PID_PARAM(Kc, 0));
2726
-            SERIAL_ECHOPAIR(" L", thermalManager.lpq_len);
2727
-          #endif
2728
-          SERIAL_EOL();
2714
+          SERIAL_ECHOLNPAIR(
2715
+              "  M301 P", PID_PARAM(Kp, 0) // for compatibility with hosts, only echo values for E0
2716
+            , " I", unscalePID_i(PID_PARAM(Ki, 0))
2717
+            , " D", unscalePID_d(PID_PARAM(Kd, 0))
2718
+            #if ENABLED(PID_EXTRUSION_SCALING)
2719
+              , " C", PID_PARAM(Kc, 0)
2720
+              , " L", thermalManager.lpq_len
2721
+            #endif
2722
+          );
2729 2723
         }
2730 2724
       #endif // PIDTEMP
2731 2725
 
2732 2726
       #if ENABLED(PIDTEMPBED)
2733 2727
         CONFIG_ECHO_START();
2734
-        SERIAL_ECHOPAIR("  M304 P", thermalManager.bed_pid.Kp);
2735
-        SERIAL_ECHOPAIR(" I", unscalePID_i(thermalManager.bed_pid.Ki));
2736
-        SERIAL_ECHOPAIR(" D", unscalePID_d(thermalManager.bed_pid.Kd));
2737
-        SERIAL_EOL();
2728
+        SERIAL_ECHOLNPAIR(
2729
+            "  M304 P", thermalManager.bed_pid.Kp
2730
+          , " I", unscalePID_i(thermalManager.bed_pid.Ki)
2731
+          , " D", unscalePID_d(thermalManager.bed_pid.Kd)
2732
+        );
2738 2733
       #endif
2739 2734
 
2740 2735
     #endif // PIDTEMP || PIDTEMPBED
@@ -2755,16 +2750,20 @@ void MarlinSettings::reset() {
2755 2750
 
2756 2751
       CONFIG_ECHO_HEADING("Retract: S<length> F<units/m> Z<lift>");
2757 2752
       CONFIG_ECHO_START();
2758
-      SERIAL_ECHOPAIR("  M207 S", LINEAR_UNIT(fwretract.settings.retract_length));
2759
-      SERIAL_ECHOPAIR(" W", LINEAR_UNIT(fwretract.settings.swap_retract_length));
2760
-      SERIAL_ECHOPAIR(" F", MMS_TO_MMM(LINEAR_UNIT(fwretract.settings.retract_feedrate_mm_s)));
2761
-      SERIAL_ECHOLNPAIR(" Z", LINEAR_UNIT(fwretract.settings.retract_zraise));
2753
+      SERIAL_ECHOLNPAIR(
2754
+          "  M207 S", LINEAR_UNIT(fwretract.settings.retract_length)
2755
+        , " W", LINEAR_UNIT(fwretract.settings.swap_retract_length)
2756
+        , " F", MMS_TO_MMM(LINEAR_UNIT(fwretract.settings.retract_feedrate_mm_s))
2757
+        , " Z", LINEAR_UNIT(fwretract.settings.retract_zraise)
2758
+      );
2762 2759
 
2763 2760
       CONFIG_ECHO_HEADING("Recover: S<length> F<units/m>");
2764 2761
       CONFIG_ECHO_START();
2765
-      SERIAL_ECHOPAIR("  M208 S", LINEAR_UNIT(fwretract.settings.retract_recover_length));
2766
-      SERIAL_ECHOPAIR(" W", LINEAR_UNIT(fwretract.settings.swap_retract_recover_length));
2767
-      SERIAL_ECHOLNPAIR(" F", MMS_TO_MMM(LINEAR_UNIT(fwretract.settings.retract_recover_feedrate_mm_s)));
2762
+      SERIAL_ECHOLNPAIR(
2763
+          "  M208 S", LINEAR_UNIT(fwretract.settings.retract_recover_length)
2764
+        , " W", LINEAR_UNIT(fwretract.settings.swap_retract_recover_length)
2765
+        , " F", MMS_TO_MMM(LINEAR_UNIT(fwretract.settings.retract_recover_feedrate_mm_s))
2766
+      );
2768 2767
 
2769 2768
       #if ENABLED(FWRETRACT_AUTORETRACT)
2770 2769
 
@@ -2810,67 +2809,65 @@ void MarlinSettings::reset() {
2810 2809
        * TMC stepper driver current
2811 2810
        */
2812 2811
       CONFIG_ECHO_HEADING("Stepper driver current:");
2813
-      CONFIG_ECHO_START();
2814
-      #if AXIS_IS_TMC(X) || AXIS_IS_TMC(Y) || AXIS_IS_TMC(Z)
2815
-        say_M906();
2816
-      #endif
2817
-      #if AXIS_IS_TMC(X)
2818
-        SERIAL_ECHOPAIR(" X", stepperX.getMilliamps());
2819
-      #endif
2820
-      #if AXIS_IS_TMC(Y)
2821
-        SERIAL_ECHOPAIR(" Y", stepperY.getMilliamps());
2822
-      #endif
2823
-      #if AXIS_IS_TMC(Z)
2824
-        SERIAL_ECHOPAIR(" Z", stepperZ.getMilliamps());
2825
-      #endif
2812
+
2826 2813
       #if AXIS_IS_TMC(X) || AXIS_IS_TMC(Y) || AXIS_IS_TMC(Z)
2827
-        SERIAL_EOL();
2814
+        say_M906(forReplay);
2815
+        SERIAL_ECHOLNPAIR(
2816
+          #if AXIS_IS_TMC(X)
2817
+            " X", stepperX.getMilliamps(),
2818
+          #endif
2819
+          #if AXIS_IS_TMC(Y)
2820
+            " Y", stepperY.getMilliamps(),
2821
+          #endif
2822
+          #if AXIS_IS_TMC(Z)
2823
+            " Z", stepperZ.getMilliamps()
2824
+          #endif
2825
+        );
2828 2826
       #endif
2829 2827
 
2830 2828
       #if AXIS_IS_TMC(X2) || AXIS_IS_TMC(Y2) || AXIS_IS_TMC(Z2)
2831
-        say_M906();
2829
+        say_M906(forReplay);
2832 2830
         SERIAL_ECHOPGM(" I1");
2833
-      #endif
2834
-      #if AXIS_IS_TMC(X2)
2835
-        SERIAL_ECHOPAIR(" X", stepperX2.getMilliamps());
2836
-      #endif
2837
-      #if AXIS_IS_TMC(Y2)
2838
-        SERIAL_ECHOPAIR(" Y", stepperY2.getMilliamps());
2839
-      #endif
2840
-      #if AXIS_IS_TMC(Z2)
2841
-        SERIAL_ECHOPAIR(" Z", stepperZ2.getMilliamps());
2842
-      #endif
2843
-      #if AXIS_IS_TMC(X2) || AXIS_IS_TMC(Y2) || AXIS_IS_TMC(Z2)
2844
-        SERIAL_EOL();
2831
+        SERIAL_ECHOLNPAIR(
2832
+          #if AXIS_IS_TMC(X2)
2833
+            " X", stepperX2.getMilliamps(),
2834
+          #endif
2835
+          #if AXIS_IS_TMC(Y2)
2836
+            " Y", stepperY2.getMilliamps(),
2837
+          #endif
2838
+          #if AXIS_IS_TMC(Z2)
2839
+            " Z", stepperZ2.getMilliamps()
2840
+          #endif
2841
+        );
2845 2842
       #endif
2846 2843
 
2847 2844
       #if AXIS_IS_TMC(Z3)
2848
-        say_M906();
2845
+        say_M906(forReplay);
2849 2846
         SERIAL_ECHOLNPAIR(" I2 Z", stepperZ3.getMilliamps());
2850 2847
       #endif
2851 2848
 
2852 2849
       #if AXIS_IS_TMC(E0)
2853
-        say_M906();
2850
+        say_M906(forReplay);
2854 2851
         SERIAL_ECHOLNPAIR(" T0 E", stepperE0.getMilliamps());
2855 2852
       #endif
2856 2853
       #if AXIS_IS_TMC(E1)
2857
-        say_M906();
2854
+        say_M906(forReplay);
2858 2855
         SERIAL_ECHOLNPAIR(" T1 E", stepperE1.getMilliamps());
2859 2856
       #endif
2860 2857
       #if AXIS_IS_TMC(E2)
2861
-        say_M906();
2858
+        say_M906(forReplay);
2862 2859
         SERIAL_ECHOLNPAIR(" T2 E", stepperE2.getMilliamps());
2863 2860
       #endif
2864 2861
       #if AXIS_IS_TMC(E3)
2865
-        say_M906();
2862
+        say_M906(forReplay);
2866 2863
         SERIAL_ECHOLNPAIR(" T3 E", stepperE3.getMilliamps());
2867 2864
       #endif
2868 2865
       #if AXIS_IS_TMC(E4)
2869
-        say_M906();
2866
+        say_M906(forReplay);
2870 2867
         SERIAL_ECHOLNPAIR(" T4 E", stepperE4.getMilliamps());
2871 2868
       #endif
2872 2869
       #if AXIS_IS_TMC(E5)
2873
-        say_M906();
2870
+        say_M906(forReplay);
2874 2871
         SERIAL_ECHOLNPAIR(" T5 E", stepperE5.getMilliamps());
2875 2872
       #endif
2876 2873
       SERIAL_EOL();
@@ -2916,8 +2913,7 @@ void MarlinSettings::reset() {
2916 2913
 
2917 2914
         #if AXIS_HAS_STEALTHCHOP(Z3)
2918 2915
           say_M913();
2919
-          SERIAL_ECHOPGM(" I2");
2920
-          SERIAL_ECHOLNPAIR(" Z", TMC_GET_PWMTHRS(Z, Z3));
2916
+          SERIAL_ECHOLNPAIR(" I2 Z", TMC_GET_PWMTHRS(Z, Z3));
2921 2917
         #endif
2922 2918
 
2923 2919
         #if AXIS_HAS_STEALTHCHOP(E0)
@@ -2988,8 +2984,7 @@ void MarlinSettings::reset() {
2988 2984
 
2989 2985
         #if HAS_Z3_SENSORLESS
2990 2986
           say_M914();
2991
-          SERIAL_ECHOPGM(" I2");
2992
-          SERIAL_ECHOLNPAIR(" Z", stepperZ3.sgt());
2987
+          SERIAL_ECHOLNPAIR(" I2 Z", stepperZ3.sgt());
2993 2988
         #endif
2994 2989
 
2995 2990
       #endif // USE_SENSORLESS
@@ -3080,20 +3075,19 @@ void MarlinSettings::reset() {
3080 3075
       #if EXTRUDERS < 2
3081 3076
         SERIAL_ECHOLNPAIR("  M900 K", planner.extruder_advance_K[0]);
3082 3077
       #else
3083
-        LOOP_L_N(i, EXTRUDERS) {
3084
-          SERIAL_ECHOPAIR("  M900 T", int(i));
3085
-          SERIAL_ECHOLNPAIR(" K", planner.extruder_advance_K[i]);
3086
-        }
3078
+        LOOP_L_N(i, EXTRUDERS)
3079
+          SERIAL_ECHOLNPAIR("  M900 T", int(i), " K", planner.extruder_advance_K[i]);
3087 3080
       #endif
3088 3081
     #endif
3089 3082
 
3090 3083
     #if HAS_MOTOR_CURRENT_PWM
3091 3084
       CONFIG_ECHO_HEADING("Stepper motor currents:");
3092 3085
       CONFIG_ECHO_START();
3093
-      SERIAL_ECHOPAIR("  M907 X", stepper.motor_current_setting[0]);
3094
-      SERIAL_ECHOPAIR(" Z", stepper.motor_current_setting[1]);
3095
-      SERIAL_ECHOPAIR(" E", stepper.motor_current_setting[2]);
3096
-      SERIAL_EOL();
3086
+      SERIAL_ECHOLNPAIR(
3087
+          "  M907 X", stepper.motor_current_setting[0]
3088
+        , " Z", stepper.motor_current_setting[1]
3089
+        , " E", stepper.motor_current_setting[2]
3090
+      );
3097 3091
     #endif
3098 3092
 
3099 3093
     /**
@@ -3101,39 +3095,21 @@ void MarlinSettings::reset() {
3101 3095
      */
3102 3096
     #if ENABLED(ADVANCED_PAUSE_FEATURE)
3103 3097
       CONFIG_ECHO_HEADING("Filament load/unload lengths:");
3104
-      CONFIG_ECHO_START();
3105 3098
       #if EXTRUDERS == 1
3106
-        say_M603();
3107
-        SERIAL_ECHOPAIR("L", LINEAR_UNIT(fc_settings[0].load_length));
3108
-        SERIAL_ECHOLNPAIR(" U", LINEAR_UNIT(fc_settings[0].unload_length));
3099
+        say_M603(forReplay);
3100
+        SERIAL_ECHOLNPAIR("L", LINEAR_UNIT(fc_settings[0].load_length), " U", LINEAR_UNIT(fc_settings[0].unload_length));
3109 3101
       #else
3110
-        say_M603();
3111
-        SERIAL_ECHOPAIR("T0 L", LINEAR_UNIT(fc_settings[0].load_length));
3112
-        SERIAL_ECHOLNPAIR(" U", LINEAR_UNIT(fc_settings[0].unload_length));
3113
-        CONFIG_ECHO_START();
3114
-        say_M603();
3115
-        SERIAL_ECHOPAIR("T1 L", LINEAR_UNIT(fc_settings[1].load_length));
3116
-        SERIAL_ECHOLNPAIR(" U", LINEAR_UNIT(fc_settings[1].unload_length));
3102
+        #define _ECHO_603(N) do{ say_M603(forReplay); SERIAL_ECHOLNPAIR("T" STRINGIFY(N) " L", LINEAR_UNIT(fc_settings[N].load_length), " U", LINEAR_UNIT(fc_settings[N].unload_length)); }while(0)
3103
+        _ECHO_603(0);
3104
+        _ECHO_603(1);
3117 3105
         #if EXTRUDERS > 2
3118
-          CONFIG_ECHO_START();
3119
-          say_M603();
3120
-          SERIAL_ECHOPAIR("T2 L", LINEAR_UNIT(fc_settings[2].load_length));
3121
-          SERIAL_ECHOLNPAIR(" U", LINEAR_UNIT(fc_settings[2].unload_length));
3106
+          _ECHO_603(2);
3122 3107
           #if EXTRUDERS > 3
3123
-            CONFIG_ECHO_START();
3124
-            say_M603();
3125
-            SERIAL_ECHOPAIR("T3 L", LINEAR_UNIT(fc_settings[3].load_length));
3126
-            SERIAL_ECHOLNPAIR(" U", LINEAR_UNIT(fc_settings[3].unload_length));
3108
+            _ECHO_603(3);
3127 3109
             #if EXTRUDERS > 4
3128
-              CONFIG_ECHO_START();
3129
-              say_M603();
3130
-              SERIAL_ECHOPAIR("T4 L", LINEAR_UNIT(fc_settings[4].load_length));
3131
-              SERIAL_ECHOLNPAIR(" U", LINEAR_UNIT(fc_settings[4].unload_length));
3110
+              _ECHO_603(4);
3132 3111
               #if EXTRUDERS > 5
3133
-                CONFIG_ECHO_START();
3134
-                say_M603();
3135
-                SERIAL_ECHOPAIR("T5 L", LINEAR_UNIT(fc_settings[5].load_length));
3136
-                SERIAL_ECHOLNPAIR(" U", LINEAR_UNIT(fc_settings[5].unload_length));
3112
+                _ECHO_603(5);
3137 3113
               #endif // EXTRUDERS > 5
3138 3114
             #endif // EXTRUDERS > 4
3139 3115
           #endif // EXTRUDERS > 3

+ 11
- 30
Marlin/src/module/printcounter.cpp Переглянути файл

@@ -185,51 +185,32 @@ void PrintCounter::showStats() {
185 185
   char buffer[21];
186 186
 
187 187
   SERIAL_ECHOPGM(MSG_STATS);
188
+  SERIAL_ECHOLNPAIR(
189
+    "Prints: ", data.totalPrints,
190
+    ", Finished: ", data.finishedPrints,
191
+    ", Failed: ", data.totalPrints - data.finishedPrints
192
+                    - ((isRunning() || isPaused()) ? 1 : 0) // Remove 1 from failures with an active counter
193
+  );
188 194
 
189
-  SERIAL_ECHOPGM("Prints: ");
190
-  SERIAL_ECHO(data.totalPrints);
191
-
192
-  SERIAL_ECHOPGM(", Finished: ");
193
-  SERIAL_ECHO(data.finishedPrints);
194
-
195
-  SERIAL_ECHOPGM(", Failed: "); // Note: Removes 1 from failures with an active counter
196
-  SERIAL_ECHO(data.totalPrints - data.finishedPrints
197
-    - ((isRunning() || isPaused()) ? 1 : 0));
198
-
199
-  SERIAL_EOL();
200 195
   SERIAL_ECHOPGM(MSG_STATS);
201
-
202 196
   duration_t elapsed = data.printTime;
203 197
   elapsed.toString(buffer);
204
-
205
-  SERIAL_ECHOPGM("Total time: ");
206
-  SERIAL_ECHO(buffer);
207
-
198
+  SERIAL_ECHOPAIR("Total time: ", buffer);
208 199
   #if ENABLED(DEBUG_PRINTCOUNTER)
209
-    SERIAL_ECHOPGM(" (");
210
-    SERIAL_ECHO(data.printTime);
200
+    SERIAL_ECHOPAIR(" (", data.printTime);
211 201
     SERIAL_CHAR(')');
212 202
   #endif
213 203
 
214 204
   elapsed = data.longestPrint;
215 205
   elapsed.toString(buffer);
216
-
217
-  SERIAL_ECHOPGM(", Longest job: ");
218
-  SERIAL_ECHO(buffer);
219
-
206
+  SERIAL_ECHOPAIR(", Longest job: ", buffer);
220 207
   #if ENABLED(DEBUG_PRINTCOUNTER)
221
-    SERIAL_ECHOPGM(" (");
222
-    SERIAL_ECHO(data.longestPrint);
208
+    SERIAL_ECHOPAIR(" (", data.longestPrint);
223 209
     SERIAL_CHAR(')');
224 210
   #endif
225 211
 
226
-  SERIAL_EOL();
227
-  SERIAL_ECHOPGM(MSG_STATS);
228
-
229
-  SERIAL_ECHOPGM("Filament used: ");
230
-  SERIAL_ECHO(data.filamentUsed / 1000);
212
+  SERIAL_ECHOPAIR("\n" MSG_STATS "Filament used: ", data.filamentUsed / 1000);
231 213
   SERIAL_CHAR('m');
232
-
233 214
   SERIAL_EOL();
234 215
 
235 216
   #if SERVICE_INTERVAL_1 > 0

+ 12
- 25
Marlin/src/module/probe.cpp Переглянути файл

@@ -83,11 +83,7 @@ float zprobe_zoffset; // Initialized by settings.load()
83 83
    */
84 84
   static void dock_sled(bool stow) {
85 85
     #if ENABLED(DEBUG_LEVELING_FEATURE)
86
-      if (DEBUGGING(LEVELING)) {
87
-        SERIAL_ECHOPAIR("dock_sled(", stow);
88
-        SERIAL_CHAR(')');
89
-        SERIAL_EOL();
90
-      }
86
+      if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPAIR("dock_sled(", stow, ")");
91 87
     #endif
92 88
 
93 89
     // Dock sled a bit closer to ensure proper capturing
@@ -317,11 +313,7 @@ float zprobe_zoffset; // Initialized by settings.load()
317 313
     bltouch_command(deploy ? BLTOUCH_DEPLOY : BLTOUCH_STOW);
318 314
 
319 315
     #if ENABLED(DEBUG_LEVELING_FEATURE)
320
-      if (DEBUGGING(LEVELING)) {
321
-        SERIAL_ECHOPAIR("set_bltouch_deployed(", deploy);
322
-        SERIAL_CHAR(')');
323
-        SERIAL_EOL();
324
-      }
316
+      if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPAIR("set_bltouch_deployed(", deploy, ")");
325 317
     #endif
326 318
 
327 319
     return false;
@@ -334,11 +326,7 @@ float zprobe_zoffset; // Initialized by settings.load()
334 326
  */
335 327
 inline void do_probe_raise(const float z_raise) {
336 328
   #if ENABLED(DEBUG_LEVELING_FEATURE)
337
-    if (DEBUGGING(LEVELING)) {
338
-      SERIAL_ECHOPAIR("do_probe_raise(", z_raise);
339
-      SERIAL_CHAR(')');
340
-      SERIAL_EOL();
341
-    }
329
+    if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPAIR("do_probe_raise(", z_raise, ")");
342 330
   #endif
343 331
 
344 332
   float z_dest = z_raise;
@@ -707,10 +695,7 @@ static float run_z_probe() {
707 695
     const float z2 = current_position[Z_AXIS];
708 696
 
709 697
     #if ENABLED(DEBUG_LEVELING_FEATURE)
710
-      if (DEBUGGING(LEVELING)) {
711
-        SERIAL_ECHOPAIR("2nd Probe Z:", z2);
712
-        SERIAL_ECHOLNPAIR(" Discrepancy:", first_probe_z - z2);
713
-      }
698
+      if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPAIR("2nd Probe Z:", z2, " Discrepancy:", first_probe_z - z2);
714 699
     #endif
715 700
 
716 701
     // Return a weighted average of the fast and slow probes
@@ -742,12 +727,14 @@ static float run_z_probe() {
742 727
 float probe_pt(const float &rx, const float &ry, const ProbePtRaise raise_after/*=PROBE_PT_NONE*/, const uint8_t verbose_level/*=0*/, const bool probe_relative/*=true*/) {
743 728
   #if ENABLED(DEBUG_LEVELING_FEATURE)
744 729
     if (DEBUGGING(LEVELING)) {
745
-      SERIAL_ECHOPAIR(">>> probe_pt(", LOGICAL_X_POSITION(rx));
746
-      SERIAL_ECHOPAIR(", ", LOGICAL_Y_POSITION(ry));
747
-      SERIAL_ECHOPAIR(", ", raise_after == PROBE_PT_RAISE ? "raise" : raise_after == PROBE_PT_STOW ? "stow" : "none");
748
-      SERIAL_ECHOPAIR(", ", int(verbose_level));
749
-      SERIAL_ECHOPAIR(", ", probe_relative ? "probe" : "nozzle");
750
-      SERIAL_ECHOLNPGM("_relative)");
730
+      SERIAL_ECHOLNPAIR(
731
+        ">>> probe_pt(", LOGICAL_X_POSITION(rx),
732
+        ", ", LOGICAL_Y_POSITION(ry),
733
+        ", ", raise_after == PROBE_PT_RAISE ? "raise" : raise_after == PROBE_PT_STOW ? "stow" : "none",
734
+        ", ", int(verbose_level),
735
+        ", ", probe_relative ? "probe" : "nozzle",
736
+        "_relative)"
737
+      );
751 738
       DEBUG_POS("", current_position);
752 739
     }
753 740
   #endif

+ 13
- 20
Marlin/src/module/scara.cpp Переглянути файл

@@ -45,8 +45,7 @@ void scara_set_axis_is_at_home(const AxisEnum axis) {
45 45
     float homeposition[XYZ];
46 46
     LOOP_XYZ(i) homeposition[i] = base_home_pos((AxisEnum)i);
47 47
 
48
-    // SERIAL_ECHOPAIR("homeposition X:", homeposition[X_AXIS]);
49
-    // SERIAL_ECHOLNPAIR(" Y:", homeposition[Y_AXIS]);
48
+    // SERIAL_ECHOLNPAIR("homeposition X:", homeposition[X_AXIS], " Y:", homeposition[Y_AXIS]);
50 49
 
51 50
     /**
52 51
      * Get Home position SCARA arm angles using inverse kinematics,
@@ -55,8 +54,7 @@ void scara_set_axis_is_at_home(const AxisEnum axis) {
55 54
     inverse_kinematics(homeposition);
56 55
     forward_kinematics_SCARA(delta[A_AXIS], delta[B_AXIS]);
57 56
 
58
-    // SERIAL_ECHOPAIR("Cartesian X:", cartes[X_AXIS]);
59
-    // SERIAL_ECHOLNPAIR(" Y:", cartes[Y_AXIS]);
57
+    // SERIAL_ECHOLNPAIR("Cartesian X:", cartes[X_AXIS], " Y:", cartes[Y_AXIS]);
60 58
 
61 59
     current_position[axis] = cartes[axis];
62 60
 
@@ -80,14 +78,15 @@ void forward_kinematics_SCARA(const float &a, const float &b) {
80 78
   cartes[Y_AXIS] = a_sin + b_sin + SCARA_OFFSET_Y;  //theta+phi
81 79
 
82 80
   /*
83
-    SERIAL_ECHOPAIR("SCARA FK Angle a=", a);
84
-    SERIAL_ECHOPAIR(" b=", b);
85
-    SERIAL_ECHOPAIR(" a_sin=", a_sin);
86
-    SERIAL_ECHOPAIR(" a_cos=", a_cos);
87
-    SERIAL_ECHOPAIR(" b_sin=", b_sin);
88
-    SERIAL_ECHOLNPAIR(" b_cos=", b_cos);
89
-    SERIAL_ECHOPAIR(" cartes[X_AXIS]=", cartes[X_AXIS]);
90
-    SERIAL_ECHOLNPAIR(" cartes[Y_AXIS]=", cartes[Y_AXIS]);
81
+    SERIAL_ECHOLNPAIR(
82
+      "SCARA FK Angle a=", a,
83
+      " b=", b,
84
+      " a_sin=", a_sin,
85
+      " a_cos=", a_cos,
86
+      " b_sin=", b_sin,
87
+      " b_cos=", b_cos
88
+    );
89
+    SERIAL_ECHOLNPAIR(" cartes (X,Y) = "(cartes[X_AXIS], ", ", cartes[Y_AXIS], ")");
91 90
   //*/
92 91
 }
93 92
 
@@ -132,18 +131,12 @@ void inverse_kinematics(const float (&raw)[XYZ]) {
132 131
   /*
133 132
     DEBUG_POS("SCARA IK", raw);
134 133
     DEBUG_POS("SCARA IK", delta);
135
-    SERIAL_ECHOPAIR("  SCARA (x,y) ", sx);
136
-    SERIAL_ECHOPAIR(",", sy);
137
-    SERIAL_ECHOPAIR(" C2=", C2);
138
-    SERIAL_ECHOPAIR(" S2=", S2);
139
-    SERIAL_ECHOPAIR(" Theta=", THETA);
140
-    SERIAL_ECHOLNPAIR(" Phi=", PHI);
134
+    SERIAL_ECHOLNPAIR("  SCARA (x,y) ", sx, ",", sy, " C2=", C2, " S2=", S2, " Theta=", THETA, " Phi=", PHI);
141 135
   //*/
142 136
 }
143 137
 
144 138
 void scara_report_positions() {
145
-  SERIAL_ECHOPAIR("SCARA Theta:", planner.get_axis_position_degrees(A_AXIS));
146
-  SERIAL_ECHOLNPAIR("   Psi+Theta:", planner.get_axis_position_degrees(B_AXIS));
139
+  SERIAL_ECHOLNPAIR("SCARA Theta:", planner.get_axis_position_degrees(A_AXIS), "  Psi+Theta:", planner.get_axis_position_degrees(B_AXIS));
147 140
   SERIAL_EOL();
148 141
 }
149 142
 

+ 27
- 36
Marlin/src/module/temperature.cpp Переглянути файл

@@ -456,37 +456,26 @@ uint8_t Temperature::soft_pwm_amount[HOTENDS];
456 456
               bias = constrain(bias, 20, max_pow - 20);
457 457
               d = (bias > max_pow >> 1) ? max_pow - 1 - bias : bias;
458 458
 
459
-              SERIAL_ECHOPAIR(MSG_BIAS, bias);
460
-              SERIAL_ECHOPAIR(MSG_D, d);
461
-              SERIAL_ECHOPAIR(MSG_T_MIN, min);
462
-              SERIAL_ECHOPAIR(MSG_T_MAX, max);
459
+              SERIAL_ECHOPAIR(MSG_BIAS, bias, MSG_D, d, MSG_T_MIN, min, MSG_T_MAX, max);
463 460
               if (cycles > 2) {
464 461
                 float Ku = (4.0f * d) / (float(M_PI) * (max - min) * 0.5f),
465 462
                       Tu = ((float)(t_low + t_high) * 0.001f);
466
-                SERIAL_ECHOPAIR(MSG_KU, Ku);
467
-                SERIAL_ECHOPAIR(MSG_TU, Tu);
468 463
                 tune_pid.Kp = 0.6f * Ku;
469 464
                 tune_pid.Ki = 2 * tune_pid.Kp / Tu;
470 465
                 tune_pid.Kd = tune_pid.Kp * Tu * 0.125f;
466
+                SERIAL_ECHOPAIR(MSG_KU, Ku, MSG_TU, Tu);
471 467
                 SERIAL_ECHOLNPGM("\n" MSG_CLASSIC_PID);
472
-                SERIAL_ECHOPAIR(MSG_KP, tune_pid.Kp);
473
-                SERIAL_ECHOPAIR(MSG_KI, tune_pid.Ki);
474
-                SERIAL_ECHOLNPAIR(MSG_KD, tune_pid.Kd);
468
+                SERIAL_ECHOLNPAIR(MSG_KP, tune_pid.Kp, MSG_KI, tune_pid.Ki, MSG_KD, tune_pid.Kd);
475 469
                 /**
476 470
                 tune_pid.Kp = 0.33*Ku;
477 471
                 tune_pid.Ki = tune_pid.Kp/Tu;
478 472
                 tune_pid.Kd = tune_pid.Kp*Tu/3;
479 473
                 SERIAL_ECHOLNPGM(" Some overshoot");
480
-                SERIAL_ECHOPAIR(" Kp: ", tune_pid.Kp);
481
-                SERIAL_ECHOPAIR(" Ki: ", tune_pid.Ki);
482
-                SERIAL_ECHOPAIR(" Kd: ", tune_pid.Kd);
474
+                SERIAL_ECHOLNPAIR(" Kp: ", tune_pid.Kp, " Ki: ", tune_pid.Ki, " Kd: ", tune_pid.Kd, " No overshoot");
483 475
                 tune_pid.Kp = 0.2*Ku;
484 476
                 tune_pid.Ki = 2*tune_pid.Kp/Tu;
485 477
                 tune_pid.Kd = tune_pid.Kp*Tu/3;
486
-                SERIAL_ECHOLNPGM(" No overshoot");
487
-                SERIAL_ECHOPAIR(" Kp: ", tune_pid.Kp);
488
-                SERIAL_ECHOPAIR(" Ki: ", tune_pid.Ki);
489
-                SERIAL_ECHOPAIR(" Kd: ", tune_pid.Kd);
478
+                SERIAL_ECHOPAIR(" Kp: ", tune_pid.Kp, " Ki: ", tune_pid.Ki, " Kd: ", tune_pid.Kd);
490 479
                 */
491 480
               }
492 481
             }
@@ -807,16 +796,20 @@ float Temperature::get_pid_output(const int8_t e) {
807 796
 
808 797
     #if ENABLED(PID_DEBUG)
809 798
       SERIAL_ECHO_START();
810
-      SERIAL_ECHOPAIR(MSG_PID_DEBUG, HOTEND_INDEX);
811
-      SERIAL_ECHOPAIR(MSG_PID_DEBUG_INPUT, current_temperature[HOTEND_INDEX]);
812
-      SERIAL_ECHOPAIR(MSG_PID_DEBUG_OUTPUT, pid_output);
799
+      SERIAL_ECHOPAIR(
800
+        MSG_PID_DEBUG, HOTEND_INDEX,
801
+        MSG_PID_DEBUG_INPUT, current_temperature[HOTEND_INDEX],
802
+        MSG_PID_DEBUG_OUTPUT, pid_output
803
+      );
813 804
       #if DISABLED(PID_OPENLOOP)
814
-        SERIAL_ECHOPAIR(MSG_PID_DEBUG_PTERM, work_pid[HOTEND_INDEX].Kp);
815
-        SERIAL_ECHOPAIR(MSG_PID_DEBUG_ITERM, work_pid[HOTEND_INDEX].Ki);
816
-        SERIAL_ECHOPAIR(MSG_PID_DEBUG_DTERM, work_pid[HOTEND_INDEX].Kd);
817
-        #if ENABLED(PID_EXTRUSION_SCALING)
818
-          SERIAL_ECHOPAIR(MSG_PID_DEBUG_CTERM, work_pid[HOTEND_INDEX].Kc);
819
-        #endif
805
+        SERIAL_ECHOPAIR(
806
+          MSG_PID_DEBUG_PTERM, work_pid[HOTEND_INDEX].Kp,
807
+          MSG_PID_DEBUG_ITERM, work_pid[HOTEND_INDEX].Ki,
808
+          MSG_PID_DEBUG_DTERM, work_pid[HOTEND_INDEX].Kd
809
+          #if ENABLED(PID_EXTRUSION_SCALING),
810
+            MSG_PID_DEBUG_CTERM, work_pid[HOTEND_INDEX].Kc
811
+          #endif
812
+        );
820 813
       #endif
821 814
       SERIAL_EOL();
822 815
     #endif // PID_DEBUG
@@ -869,13 +862,14 @@ float Temperature::get_pid_output(const int8_t e) {
869 862
 
870 863
     #if ENABLED(PID_BED_DEBUG)
871 864
       SERIAL_ECHO_START();
872
-      SERIAL_ECHOPAIR(" PID_BED_DEBUG : Input ", current_temperature_bed);
873
-      SERIAL_ECHOPAIR(" Output ", pid_output);
874
-      #if DISABLED(PID_OPENLOOP)
875
-        SERIAL_ECHOPAIR(MSG_PID_DEBUG_PTERM, work_pid.Kp);
876
-        SERIAL_ECHOPAIR(MSG_PID_DEBUG_ITERM, work_pid.Ki);
877
-        SERIAL_ECHOLNPAIR(MSG_PID_DEBUG_DTERM, work_pid.Kd);
878
-      #endif
865
+      SERIAL_ECHOLNPAIR(
866
+        " PID_BED_DEBUG : Input ", current_temperature_bed, " Output ", pid_output,
867
+        #if DISABLED(PID_OPENLOOP)
868
+          MSG_PID_DEBUG_PTERM, work_pid.Kp,
869
+          MSG_PID_DEBUG_ITERM, work_pid.Ki,
870
+          MSG_PID_DEBUG_DTERM, work_pid.Kd,
871
+        #endif
872
+      );
879 873
     #endif
880 874
 
881 875
     return pid_output;
@@ -1622,10 +1616,7 @@ void Temperature::init() {
1622 1616
         SERIAL_ECHO_START();
1623 1617
         SERIAL_ECHOPGM("Thermal Thermal Runaway Running. Heater ID: ");
1624 1618
         if (heater_id < 0) SERIAL_ECHOPGM("bed"); else SERIAL_ECHO(heater_id);
1625
-        SERIAL_ECHOPAIR(" ;  State:", *state);
1626
-        SERIAL_ECHOPAIR(" ;  Timer:", *timer);
1627
-        SERIAL_ECHOPAIR(" ;  Temperature:", current);
1628
-        SERIAL_ECHOPAIR(" ;  Target Temp:", target);
1619
+        SERIAL_ECHOPAIR(" ;  State:", *state, " ;  Timer:", *timer, " ;  Temperature:", current, " ;  Target Temp:", target);
1629 1620
         if (heater_id >= 0)
1630 1621
           SERIAL_ECHOPAIR(" ;  Idle Timeout:", heater_idle_timeout_exceeded[heater_id]);
1631 1622
         else

+ 2
- 6
Marlin/src/module/tool_change.cpp Переглянути файл

@@ -804,12 +804,8 @@ void tool_change(const uint8_t tmp_extruder, const float fr_mm_s/*=0.0*/, bool n
804 804
       #endif
805 805
 
806 806
       #if ENABLED(DEBUG_LEVELING_FEATURE)
807
-        if (DEBUGGING(LEVELING)) {
808
-          SERIAL_ECHOPAIR("Offset Tool XY by { ", xdiff);
809
-          SERIAL_ECHOPAIR(", ", ydiff);
810
-          SERIAL_ECHOPAIR(", ", zdiff);
811
-          SERIAL_ECHOLNPGM(" }");
812
-        }
807
+        if (DEBUGGING(LEVELING))
808
+          SERIAL_ECHOLNPAIR("Offset Tool XY by { ", xdiff, ", ", ydiff, ", ", zdiff, " }");
813 809
       #endif
814 810
 
815 811
       // The newly-selected extruder XY is actually at...

+ 11
- 27
Marlin/src/sd/cardreader.cpp Переглянути файл

@@ -438,9 +438,7 @@ void CardReader::openFile(char * const path, const bool read, const bool subcall
438 438
       filespos[file_subcall_ctr] = sdpos;
439 439
 
440 440
       SERIAL_ECHO_START();
441
-      SERIAL_ECHOPAIR("SUBROUTINE CALL target:\"", path);
442
-      SERIAL_ECHOPAIR("\" parent:\"", proc_filenames[file_subcall_ctr]);
443
-      SERIAL_ECHOLNPAIR("\" pos", sdpos);
441
+      SERIAL_ECHOLNPAIR("SUBROUTINE CALL target:\"", path, "\" parent:\"", proc_filenames[file_subcall_ctr], "\" pos", sdpos);
444 442
       file_subcall_ctr++;
445 443
     }
446 444
     else
@@ -470,8 +468,7 @@ void CardReader::openFile(char * const path, const bool read, const bool subcall
470 468
     if (file.open(curDir, fname, O_READ)) {
471 469
       filesize = file.fileSize();
472 470
       sdpos = 0;
473
-      SERIAL_ECHOPAIR(MSG_SD_FILE_OPENED, fname);
474
-      SERIAL_ECHOLNPAIR(MSG_SD_SIZE, filesize);
471
+      SERIAL_ECHOLNPAIR(MSG_SD_FILE_OPENED, fname, MSG_SD_SIZE, filesize);
475 472
       SERIAL_ECHOLNPGM(MSG_SD_FILE_SELECTED);
476 473
 
477 474
       getfilename(0, fname);
@@ -480,18 +477,12 @@ void CardReader::openFile(char * const path, const bool read, const bool subcall
480 477
       //  SERIAL_ECHOPAIR(MSG_SD_FILE_LONG_NAME, longFilename);
481 478
       //}
482 479
     }
483
-    else {
484
-      SERIAL_ECHOPAIR(MSG_SD_OPEN_FILE_FAIL, fname);
485
-      SERIAL_CHAR('.');
486
-      SERIAL_EOL();
487
-    }
480
+    else
481
+      SERIAL_ECHOLNPAIR(MSG_SD_OPEN_FILE_FAIL, fname, ".");
488 482
   }
489 483
   else { //write
490
-    if (!file.open(curDir, fname, O_CREAT | O_APPEND | O_WRITE | O_TRUNC)) {
491
-      SERIAL_ECHOPAIR(MSG_SD_OPEN_FILE_FAIL, fname);
492
-      SERIAL_CHAR('.');
493
-      SERIAL_EOL();
494
-    }
484
+    if (!file.open(curDir, fname, O_CREAT | O_APPEND | O_WRITE | O_TRUNC))
485
+      SERIAL_ECHOLNPAIR(MSG_SD_OPEN_FILE_FAIL, fname, ".");
495 486
     else {
496 487
       flag.saving = true;
497 488
       getfilename(0, fname);
@@ -520,10 +511,8 @@ void CardReader::removeFile(const char * const name) {
520 511
       presort();
521 512
     #endif
522 513
   }
523
-  else {
524
-    SERIAL_ECHOPAIR("Deletion failed, File: ", fname);
525
-    SERIAL_CHAR('.');
526
-  }
514
+  else
515
+    SERIAL_ECHOLNPAIR("Deletion failed, File: ", fname, ".");
527 516
 }
528 517
 
529 518
 void CardReader::report_status() {
@@ -669,9 +658,7 @@ const char* CardReader::diveToFile(SdFile*& curDir, const char * const path, con
669 658
     if (echo) SERIAL_ECHOLN(dosSubdirname);
670 659
 
671 660
     if (!myDir.open(curDir, dosSubdirname, O_READ)) {
672
-      SERIAL_ECHOPAIR(MSG_SD_OPEN_FILE_FAIL, dosSubdirname);
673
-      SERIAL_CHAR('.');
674
-      SERIAL_EOL();
661
+      SERIAL_ECHOLNPAIR(MSG_SD_OPEN_FILE_FAIL, dosSubdirname, ".");
675 662
       return NULL;
676 663
     }
677 664
     curDir = &myDir;
@@ -1030,11 +1017,8 @@ void CardReader::printingHasFinished() {
1030 1017
   void CardReader::openJobRecoveryFile(const bool read) {
1031 1018
     if (!isDetected()) return;
1032 1019
     if (recovery.file.isOpen()) return;
1033
-    if (!recovery.file.open(&root, job_recovery_file_name, read ? O_READ : O_CREAT | O_WRITE | O_TRUNC | O_SYNC)) {
1034
-      SERIAL_ECHOPAIR(MSG_SD_OPEN_FILE_FAIL, job_recovery_file_name);
1035
-      SERIAL_CHAR('.');
1036
-      SERIAL_EOL();
1037
-    }
1020
+    if (!recovery.file.open(&root, job_recovery_file_name, read ? O_READ : O_CREAT | O_WRITE | O_TRUNC | O_SYNC))
1021
+      SERIAL_ECHOLNPAIR(MSG_SD_OPEN_FILE_FAIL, job_recovery_file_name, ".");
1038 1022
     else if (!read)
1039 1023
       SERIAL_ECHOLNPAIR(MSG_SD_WRITE_TO_FILE, job_recovery_file_name);
1040 1024
   }

Завантаження…
Відмінити
Зберегти