Browse Source

Patch some serial macros

Scott Lahteine 7 years ago
parent
commit
e94f79ccea

+ 3
- 3
Marlin/G26_Mesh_Validation_Tool.cpp View File

288
           SERIAL_ECHOPAIR("   Doing circle at: (xi=", xi);
288
           SERIAL_ECHOPAIR("   Doing circle at: (xi=", xi);
289
           SERIAL_ECHOPAIR(", yi=", yi);
289
           SERIAL_ECHOPAIR(", yi=", yi);
290
           SERIAL_CHAR(')');
290
           SERIAL_CHAR(')');
291
-          SERIAL_EOL;
291
+          SERIAL_EOL();
292
         }
292
         }
293
 
293
 
294
         start_angle = 0.0;    // assume it is going to be a full circle
294
         start_angle = 0.0;    // assume it is going to be a full circle
467
                   SERIAL_ECHOPAIR(") -> (ex=", ex);
467
                   SERIAL_ECHOPAIR(") -> (ex=", ex);
468
                   SERIAL_ECHOPAIR(", ey=", ey);
468
                   SERIAL_ECHOPAIR(", ey=", ey);
469
                   SERIAL_CHAR(')');
469
                   SERIAL_CHAR(')');
470
-                  SERIAL_EOL;
470
+                  SERIAL_EOL();
471
                   //debug_current_and_destination(PSTR("Connecting horizontal line."));
471
                   //debug_current_and_destination(PSTR("Connecting horizontal line."));
472
                 }
472
                 }
473
 
473
 
501
                     SERIAL_ECHOPAIR(") -> (ex=", ex);
501
                     SERIAL_ECHOPAIR(") -> (ex=", ex);
502
                     SERIAL_ECHOPAIR(", ey=", ey);
502
                     SERIAL_ECHOPAIR(", ey=", ey);
503
                     SERIAL_CHAR(')');
503
                     SERIAL_CHAR(')');
504
-                    SERIAL_EOL;
504
+                    SERIAL_EOL();
505
                     debug_current_and_destination(PSTR("Connecting vertical line."));
505
                     debug_current_and_destination(PSTR("Connecting vertical line."));
506
                   }
506
                   }
507
                   print_line_from_here_to_there(LOGICAL_X_POSITION(sx), LOGICAL_Y_POSITION(sy), g26_layer_height, LOGICAL_X_POSITION(ex), LOGICAL_Y_POSITION(ey), g26_layer_height);
507
                   print_line_from_here_to_there(LOGICAL_X_POSITION(sx), LOGICAL_Y_POSITION(sy), g26_layer_height, LOGICAL_X_POSITION(ex), LOGICAL_Y_POSITION(ey), g26_layer_height);

+ 1
- 1
Marlin/I2CPositionEncoder.cpp View File

736
       char c;
736
       char c;
737
       while (Wire.available() > 0 && (c = (char)Wire.read()) > 0)
737
       while (Wire.available() > 0 && (c = (char)Wire.read()) > 0)
738
         SERIAL_ECHO(c);
738
         SERIAL_ECHO(c);
739
-      SERIAL_EOL;
739
+      SERIAL_EOL();
740
     }
740
     }
741
 
741
 
742
     // Set module back to normal (distance) mode
742
     // Set module back to normal (distance) mode

+ 4
- 4
Marlin/M100_Free_Mem_Chk.cpp View File

130
         }
130
         }
131
         SERIAL_CHAR(ccc);
131
         SERIAL_CHAR(ccc);
132
       }
132
       }
133
-      SERIAL_EOL;
133
+      SERIAL_EOL();
134
       ptr += 16;
134
       ptr += 16;
135
       safe_delay(25);
135
       safe_delay(25);
136
       idle();
136
       idle();
200
         *addr = i;
200
         *addr = i;
201
         SERIAL_ECHOPAIR("\nCorrupting address: ", hex_address(addr));
201
         SERIAL_ECHOPAIR("\nCorrupting address: ", hex_address(addr));
202
       }
202
       }
203
-      SERIAL_EOL;
203
+      SERIAL_EOL();
204
     }
204
     }
205
   }
205
   }
206
 #endif // M100_FREE_MEMORY_CORRUPTOR
206
 #endif // M100_FREE_MEMORY_CORRUPTOR
229
     if (ptr[i] != TEST_BYTE) {
229
     if (ptr[i] != TEST_BYTE) {
230
       SERIAL_ECHOPAIR("? address : ", hex_address(ptr + i));
230
       SERIAL_ECHOPAIR("? address : ", hex_address(ptr + i));
231
       SERIAL_ECHOLNPAIR("=", hex_byte(ptr[i]));
231
       SERIAL_ECHOLNPAIR("=", hex_byte(ptr[i]));
232
-      SERIAL_EOL;
232
+      SERIAL_EOL();
233
     }
233
     }
234
   }
234
   }
235
 }
235
 }
323
   SERIAL_ECHOPGM(" return=");
323
   SERIAL_ECHOPGM(" return=");
324
   if (block_cnt == 1) {
324
   if (block_cnt == 1) {
325
     SERIAL_CHAR('0');       // if the block_cnt is 1, nothing has broken up the free memory
325
     SERIAL_CHAR('0');       // if the block_cnt is 1, nothing has broken up the free memory
326
-    SERIAL_EOL;             // area and it is appropriate to say 'no corruption'.
326
+    SERIAL_EOL();             // area and it is appropriate to say 'no corruption'.
327
     return 0;
327
     return 0;
328
   }
328
   }
329
   SERIAL_ECHOLNPGM("true");
329
   SERIAL_ECHOLNPGM("true");

+ 128
- 128
Marlin/Marlin_main.cpp
File diff suppressed because it is too large
View File


+ 16
- 16
Marlin/cardreader.cpp View File

109
       SdFile dir;
109
       SdFile dir;
110
       if (!dir.open(parent, lfilename, O_READ)) {
110
       if (!dir.open(parent, lfilename, O_READ)) {
111
         if (lsAction == LS_SerialPrint) {
111
         if (lsAction == LS_SerialPrint) {
112
-          SERIAL_ECHO_START;
112
+          SERIAL_ECHO_START();
113
           SERIAL_ECHOPGM(MSG_SD_CANT_OPEN_SUBDIR);
113
           SERIAL_ECHOPGM(MSG_SD_CANT_OPEN_SUBDIR);
114
           SERIAL_ECHOLN(lfilename);
114
           SERIAL_ECHOLN(lfilename);
115
         }
115
         }
208
       // Open the sub-item as the new dive parent
208
       // Open the sub-item as the new dive parent
209
       SdFile dir;
209
       SdFile dir;
210
       if (!dir.open(diveDir, segment, O_READ)) {
210
       if (!dir.open(diveDir, segment, O_READ)) {
211
-        SERIAL_EOL;
212
-        SERIAL_ECHO_START;
211
+        SERIAL_EOL();
212
+        SERIAL_ECHO_START();
213
         SERIAL_ECHOPGM(MSG_SD_CANT_OPEN_SUBDIR);
213
         SERIAL_ECHOPGM(MSG_SD_CANT_OPEN_SUBDIR);
214
         SERIAL_ECHO(segment);
214
         SERIAL_ECHO(segment);
215
         break;
215
         break;
220
 
220
 
221
     } // while i<pathLen
221
     } // while i<pathLen
222
 
222
 
223
-    SERIAL_EOL;
223
+    SERIAL_EOL();
224
   }
224
   }
225
 
225
 
226
 #endif // LONG_FILENAME_HOST_SUPPORT
226
 #endif // LONG_FILENAME_HOST_SUPPORT
239
     #endif
239
     #endif
240
   ) {
240
   ) {
241
     //if (!card.init(SPI_HALF_SPEED,SDSS))
241
     //if (!card.init(SPI_HALF_SPEED,SDSS))
242
-    SERIAL_ECHO_START;
242
+    SERIAL_ECHO_START();
243
     SERIAL_ECHOLNPGM(MSG_SD_INIT_FAIL);
243
     SERIAL_ECHOLNPGM(MSG_SD_INIT_FAIL);
244
   }
244
   }
245
   else if (!volume.init(&card)) {
245
   else if (!volume.init(&card)) {
246
-    SERIAL_ERROR_START;
246
+    SERIAL_ERROR_START();
247
     SERIAL_ERRORLNPGM(MSG_SD_VOL_INIT_FAIL);
247
     SERIAL_ERRORLNPGM(MSG_SD_VOL_INIT_FAIL);
248
   }
248
   }
249
   else if (!root.openRoot(&volume)) {
249
   else if (!root.openRoot(&volume)) {
250
-    SERIAL_ERROR_START;
250
+    SERIAL_ERROR_START();
251
     SERIAL_ERRORLNPGM(MSG_SD_OPENROOT_FAIL);
251
     SERIAL_ERRORLNPGM(MSG_SD_OPENROOT_FAIL);
252
   }
252
   }
253
   else {
253
   else {
254
     cardOK = true;
254
     cardOK = true;
255
-    SERIAL_ECHO_START;
255
+    SERIAL_ECHO_START();
256
     SERIAL_ECHOLNPGM(MSG_SD_CARD_OK);
256
     SERIAL_ECHOLNPGM(MSG_SD_CARD_OK);
257
   }
257
   }
258
   workDir = root;
258
   workDir = root;
331
   if (isFileOpen()) { //replacing current file by new file, or subfile call
331
   if (isFileOpen()) { //replacing current file by new file, or subfile call
332
     if (push_current) {
332
     if (push_current) {
333
       if (file_subcall_ctr > SD_PROCEDURE_DEPTH - 1) {
333
       if (file_subcall_ctr > SD_PROCEDURE_DEPTH - 1) {
334
-        SERIAL_ERROR_START;
334
+        SERIAL_ERROR_START();
335
         SERIAL_ERRORPGM("trying to call sub-gcode files with too many levels. MAX level is:");
335
         SERIAL_ERRORPGM("trying to call sub-gcode files with too many levels. MAX level is:");
336
         SERIAL_ERRORLN(SD_PROCEDURE_DEPTH);
336
         SERIAL_ERRORLN(SD_PROCEDURE_DEPTH);
337
         kill(PSTR(MSG_KILLED));
337
         kill(PSTR(MSG_KILLED));
341
       // Store current filename and position
341
       // Store current filename and position
342
       getAbsFilename(proc_filenames[file_subcall_ctr]);
342
       getAbsFilename(proc_filenames[file_subcall_ctr]);
343
 
343
 
344
-      SERIAL_ECHO_START;
344
+      SERIAL_ECHO_START();
345
       SERIAL_ECHOPAIR("SUBROUTINE CALL target:\"", name);
345
       SERIAL_ECHOPAIR("SUBROUTINE CALL target:\"", name);
346
       SERIAL_ECHOPAIR("\" parent:\"", proc_filenames[file_subcall_ctr]);
346
       SERIAL_ECHOPAIR("\" parent:\"", proc_filenames[file_subcall_ctr]);
347
       SERIAL_ECHOLNPAIR("\" pos", sdpos);
347
       SERIAL_ECHOLNPAIR("\" pos", sdpos);
358
   }
358
   }
359
 
359
 
360
   if (doing) {
360
   if (doing) {
361
-    SERIAL_ECHO_START;
361
+    SERIAL_ECHO_START();
362
     SERIAL_ECHOPGM("Now ");
362
     SERIAL_ECHOPGM("Now ");
363
     SERIAL_ECHO(doing == 1 ? "doing" : "fresh");
363
     SERIAL_ECHO(doing == 1 ? "doing" : "fresh");
364
     SERIAL_ECHOLNPAIR(" file: ", name);
364
     SERIAL_ECHOLNPAIR(" file: ", name);
421
     else {
421
     else {
422
       SERIAL_PROTOCOLPAIR(MSG_SD_OPEN_FILE_FAIL, fname);
422
       SERIAL_PROTOCOLPAIR(MSG_SD_OPEN_FILE_FAIL, fname);
423
       SERIAL_PROTOCOLCHAR('.');
423
       SERIAL_PROTOCOLCHAR('.');
424
-      SERIAL_EOL;
424
+      SERIAL_EOL();
425
     }
425
     }
426
   }
426
   }
427
   else { //write
427
   else { //write
428
     if (!file.open(curDir, fname, O_CREAT | O_APPEND | O_WRITE | O_TRUNC)) {
428
     if (!file.open(curDir, fname, O_CREAT | O_APPEND | O_WRITE | O_TRUNC)) {
429
       SERIAL_PROTOCOLPAIR(MSG_SD_OPEN_FILE_FAIL, fname);
429
       SERIAL_PROTOCOLPAIR(MSG_SD_OPEN_FILE_FAIL, fname);
430
       SERIAL_PROTOCOLCHAR('.');
430
       SERIAL_PROTOCOLCHAR('.');
431
-      SERIAL_EOL;
431
+      SERIAL_EOL();
432
     }
432
     }
433
     else {
433
     else {
434
       saving = true;
434
       saving = true;
462
         if (!myDir.open(curDir, subdirname, O_READ)) {
462
         if (!myDir.open(curDir, subdirname, O_READ)) {
463
           SERIAL_PROTOCOLPAIR("open failed, File: ", subdirname);
463
           SERIAL_PROTOCOLPAIR("open failed, File: ", subdirname);
464
           SERIAL_PROTOCOLCHAR('.');
464
           SERIAL_PROTOCOLCHAR('.');
465
-          SERIAL_EOL;
465
+          SERIAL_EOL();
466
           return;
466
           return;
467
         }
467
         }
468
         else {
468
         else {
526
   end[3] = '\0';
526
   end[3] = '\0';
527
   file.write(begin);
527
   file.write(begin);
528
   if (file.writeError) {
528
   if (file.writeError) {
529
-    SERIAL_ERROR_START;
529
+    SERIAL_ERROR_START();
530
     SERIAL_ERRORLNPGM(MSG_SD_ERR_WRITE_TO_FILE);
530
     SERIAL_ERRORLNPGM(MSG_SD_ERR_WRITE_TO_FILE);
531
   }
531
   }
532
 }
532
 }
617
   if (workDir.isOpen()) parent = &workDir;
617
   if (workDir.isOpen()) parent = &workDir;
618
 
618
 
619
   if (!newfile.open(*parent, relpath, O_READ)) {
619
   if (!newfile.open(*parent, relpath, O_READ)) {
620
-    SERIAL_ECHO_START;
620
+    SERIAL_ECHO_START();
621
     SERIAL_ECHOPGM(MSG_SD_CANT_ENTER_SUBDIR);
621
     SERIAL_ECHOPGM(MSG_SD_CANT_ENTER_SUBDIR);
622
     SERIAL_ECHOLN(relpath);
622
     SERIAL_ECHOLN(relpath);
623
   }
623
   }

+ 33
- 33
Marlin/configuration_store.cpp View File

247
   #define EEPROM_SKIP(VAR) eeprom_index += sizeof(VAR)
247
   #define EEPROM_SKIP(VAR) eeprom_index += sizeof(VAR)
248
   #define EEPROM_WRITE(VAR) write_data(eeprom_index, (uint8_t*)&VAR, sizeof(VAR), &working_crc)
248
   #define EEPROM_WRITE(VAR) write_data(eeprom_index, (uint8_t*)&VAR, sizeof(VAR), &working_crc)
249
   #define EEPROM_READ(VAR) read_data(eeprom_index, (uint8_t*)&VAR, sizeof(VAR), &working_crc)
249
   #define EEPROM_READ(VAR) read_data(eeprom_index, (uint8_t*)&VAR, sizeof(VAR), &working_crc)
250
-  #define EEPROM_ASSERT(TST,ERR) if (!(TST)) do{ SERIAL_ERROR_START; SERIAL_ERRORLNPGM(ERR); eeprom_read_error = true; }while(0)
250
+  #define EEPROM_ASSERT(TST,ERR) if (!(TST)) do{ SERIAL_ERROR_START(); SERIAL_ERRORLNPGM(ERR); eeprom_read_error = true; }while(0)
251
 
251
 
252
   const char version[4] = EEPROM_VERSION;
252
   const char version[4] = EEPROM_VERSION;
253
 
253
 
267
       if (v != eeprom_read_byte(p)) {
267
       if (v != eeprom_read_byte(p)) {
268
         eeprom_write_byte(p, v);
268
         eeprom_write_byte(p, v);
269
         if (eeprom_read_byte(p) != v) {
269
         if (eeprom_read_byte(p) != v) {
270
-          SERIAL_ECHO_START;
270
+          SERIAL_ECHO_START();
271
           SERIAL_ECHOLNPGM(MSG_ERR_EEPROM_WRITE);
271
           SERIAL_ECHOLNPGM(MSG_ERR_EEPROM_WRITE);
272
           eeprom_error = true;
272
           eeprom_error = true;
273
           return;
273
           return;
638
       EEPROM_WRITE(final_crc);
638
       EEPROM_WRITE(final_crc);
639
 
639
 
640
       // Report storage size
640
       // Report storage size
641
-      SERIAL_ECHO_START;
641
+      SERIAL_ECHO_START();
642
       SERIAL_ECHOPAIR("Settings Stored (", eeprom_size - (EEPROM_OFFSET));
642
       SERIAL_ECHOPAIR("Settings Stored (", eeprom_size - (EEPROM_OFFSET));
643
       SERIAL_ECHOPAIR(" bytes; crc ", final_crc);
643
       SERIAL_ECHOPAIR(" bytes; crc ", final_crc);
644
       SERIAL_ECHOLNPGM(")");
644
       SERIAL_ECHOLNPGM(")");
672
         stored_ver[0] = '?';
672
         stored_ver[0] = '?';
673
         stored_ver[1] = '\0';
673
         stored_ver[1] = '\0';
674
       }
674
       }
675
-      SERIAL_ECHO_START;
675
+      SERIAL_ECHO_START();
676
       SERIAL_ECHOPGM("EEPROM version mismatch ");
676
       SERIAL_ECHOPGM("EEPROM version mismatch ");
677
       SERIAL_ECHOPAIR("(EEPROM=", stored_ver);
677
       SERIAL_ECHOPAIR("(EEPROM=", stored_ver);
678
       SERIAL_ECHOLNPGM(" Marlin=" EEPROM_VERSION ")");
678
       SERIAL_ECHOLNPGM(" Marlin=" EEPROM_VERSION ")");
981
 
981
 
982
       if (working_crc == stored_crc) {
982
       if (working_crc == stored_crc) {
983
           postprocess();
983
           postprocess();
984
-          SERIAL_ECHO_START;
984
+          SERIAL_ECHO_START();
985
           SERIAL_ECHO(version);
985
           SERIAL_ECHO(version);
986
           SERIAL_ECHOPAIR(" stored settings retrieved (", eeprom_index - (EEPROM_OFFSET));
986
           SERIAL_ECHOPAIR(" stored settings retrieved (", eeprom_index - (EEPROM_OFFSET));
987
           SERIAL_ECHOPAIR(" bytes; crc ", working_crc);
987
           SERIAL_ECHOPAIR(" bytes; crc ", working_crc);
988
           SERIAL_ECHOLNPGM(")");
988
           SERIAL_ECHOLNPGM(")");
989
       }
989
       }
990
       else {
990
       else {
991
-        SERIAL_ERROR_START;
991
+        SERIAL_ERROR_START();
992
         SERIAL_ERRORPGM("EEPROM CRC mismatch - (stored) ");
992
         SERIAL_ERRORPGM("EEPROM CRC mismatch - (stored) ");
993
         SERIAL_ERROR(stored_crc);
993
         SERIAL_ERROR(stored_crc);
994
         SERIAL_ERRORPGM(" != ");
994
         SERIAL_ERRORPGM(" != ");
1004
         ubl.report_state();
1004
         ubl.report_state();
1005
 
1005
 
1006
         if (!ubl.sanity_check()) {
1006
         if (!ubl.sanity_check()) {
1007
-          SERIAL_EOL;
1007
+          SERIAL_EOL();
1008
           ubl.echo_name();
1008
           ubl.echo_name();
1009
           SERIAL_ECHOLNPGM(" initialized.\n");
1009
           SERIAL_ECHOLNPGM(" initialized.\n");
1010
         }
1010
         }
1059
           SERIAL_PROTOCOLPAIR("E2END=", E2END);
1059
           SERIAL_PROTOCOLPAIR("E2END=", E2END);
1060
           SERIAL_PROTOCOLPAIR(" meshes_end=", meshes_end);
1060
           SERIAL_PROTOCOLPAIR(" meshes_end=", meshes_end);
1061
           SERIAL_PROTOCOLLNPAIR(" slot=", slot);
1061
           SERIAL_PROTOCOLLNPAIR(" slot=", slot);
1062
-          SERIAL_EOL;
1062
+          SERIAL_EOL();
1063
           return;
1063
           return;
1064
         }
1064
         }
1065
 
1065
 
1114
 #else // !EEPROM_SETTINGS
1114
 #else // !EEPROM_SETTINGS
1115
 
1115
 
1116
   bool MarlinSettings::save() {
1116
   bool MarlinSettings::save() {
1117
-    SERIAL_ERROR_START;
1117
+    SERIAL_ERROR_START();
1118
     SERIAL_ERRORLNPGM("EEPROM disabled");
1118
     SERIAL_ERRORLNPGM("EEPROM disabled");
1119
     return false;
1119
     return false;
1120
   }
1120
   }
1315
 
1315
 
1316
   postprocess();
1316
   postprocess();
1317
 
1317
 
1318
-  SERIAL_ECHO_START;
1318
+  SERIAL_ECHO_START();
1319
   SERIAL_ECHOLNPGM("Hardcoded Default Settings Loaded");
1319
   SERIAL_ECHOLNPGM("Hardcoded Default Settings Loaded");
1320
 }
1320
 }
1321
 
1321
 
1322
 #if DISABLED(DISABLE_M503)
1322
 #if DISABLED(DISABLE_M503)
1323
 
1323
 
1324
-  #define CONFIG_ECHO_START do{ if (!forReplay) SERIAL_ECHO_START; }while(0)
1324
+  #define CONFIG_ECHO_START do{ if (!forReplay) SERIAL_ECHO_START(); }while(0)
1325
 
1325
 
1326
   /**
1326
   /**
1327
    * M503 - Report current settings in RAM
1327
    * M503 - Report current settings in RAM
1365
 
1365
 
1366
     #endif
1366
     #endif
1367
 
1367
 
1368
-    SERIAL_EOL;
1368
+    SERIAL_EOL();
1369
 
1369
 
1370
     /**
1370
     /**
1371
      * Volumetric extrusion M200
1371
      * Volumetric extrusion M200
1374
       CONFIG_ECHO_START;
1374
       CONFIG_ECHO_START;
1375
       SERIAL_ECHOPGM("Filament settings:");
1375
       SERIAL_ECHOPGM("Filament settings:");
1376
       if (volumetric_enabled)
1376
       if (volumetric_enabled)
1377
-        SERIAL_EOL;
1377
+        SERIAL_EOL();
1378
       else
1378
       else
1379
         SERIAL_ECHOLNPGM(" Disabled");
1379
         SERIAL_ECHOLNPGM(" Disabled");
1380
     }
1380
     }
1381
 
1381
 
1382
     CONFIG_ECHO_START;
1382
     CONFIG_ECHO_START;
1383
     SERIAL_ECHOPAIR("  M200 D", filament_size[0]);
1383
     SERIAL_ECHOPAIR("  M200 D", filament_size[0]);
1384
-    SERIAL_EOL;
1384
+    SERIAL_EOL();
1385
     #if EXTRUDERS > 1
1385
     #if EXTRUDERS > 1
1386
       CONFIG_ECHO_START;
1386
       CONFIG_ECHO_START;
1387
       SERIAL_ECHOPAIR("  M200 T1 D", filament_size[1]);
1387
       SERIAL_ECHOPAIR("  M200 T1 D", filament_size[1]);
1388
-      SERIAL_EOL;
1388
+      SERIAL_EOL();
1389
       #if EXTRUDERS > 2
1389
       #if EXTRUDERS > 2
1390
         CONFIG_ECHO_START;
1390
         CONFIG_ECHO_START;
1391
         SERIAL_ECHOPAIR("  M200 T2 D", filament_size[2]);
1391
         SERIAL_ECHOPAIR("  M200 T2 D", filament_size[2]);
1392
-        SERIAL_EOL;
1392
+        SERIAL_EOL();
1393
         #if EXTRUDERS > 3
1393
         #if EXTRUDERS > 3
1394
           CONFIG_ECHO_START;
1394
           CONFIG_ECHO_START;
1395
           SERIAL_ECHOPAIR("  M200 T3 D", filament_size[3]);
1395
           SERIAL_ECHOPAIR("  M200 T3 D", filament_size[3]);
1396
-          SERIAL_EOL;
1396
+          SERIAL_EOL();
1397
           #if EXTRUDERS > 4
1397
           #if EXTRUDERS > 4
1398
             CONFIG_ECHO_START;
1398
             CONFIG_ECHO_START;
1399
             SERIAL_ECHOPAIR("  M200 T4 D", filament_size[4]);
1399
             SERIAL_ECHOPAIR("  M200 T4 D", filament_size[4]);
1400
-            SERIAL_EOL;
1400
+            SERIAL_EOL();
1401
           #endif // EXTRUDERS > 4
1401
           #endif // EXTRUDERS > 4
1402
         #endif // EXTRUDERS > 3
1402
         #endif // EXTRUDERS > 3
1403
       #endif // EXTRUDERS > 2
1403
       #endif // EXTRUDERS > 2
1419
     #if DISABLED(DISTINCT_E_FACTORS)
1419
     #if DISABLED(DISTINCT_E_FACTORS)
1420
       SERIAL_ECHOPAIR(" E", VOLUMETRIC_UNIT(planner.axis_steps_per_mm[E_AXIS]));
1420
       SERIAL_ECHOPAIR(" E", VOLUMETRIC_UNIT(planner.axis_steps_per_mm[E_AXIS]));
1421
     #endif
1421
     #endif
1422
-    SERIAL_EOL;
1422
+    SERIAL_EOL();
1423
     #if ENABLED(DISTINCT_E_FACTORS)
1423
     #if ENABLED(DISTINCT_E_FACTORS)
1424
       CONFIG_ECHO_START;
1424
       CONFIG_ECHO_START;
1425
       for (uint8_t i = 0; i < E_STEPPERS; i++) {
1425
       for (uint8_t i = 0; i < E_STEPPERS; i++) {
1439
     #if DISABLED(DISTINCT_E_FACTORS)
1439
     #if DISABLED(DISTINCT_E_FACTORS)
1440
       SERIAL_ECHOPAIR(" E", VOLUMETRIC_UNIT(planner.max_feedrate_mm_s[E_AXIS]));
1440
       SERIAL_ECHOPAIR(" E", VOLUMETRIC_UNIT(planner.max_feedrate_mm_s[E_AXIS]));
1441
     #endif
1441
     #endif
1442
-    SERIAL_EOL;
1442
+    SERIAL_EOL();
1443
     #if ENABLED(DISTINCT_E_FACTORS)
1443
     #if ENABLED(DISTINCT_E_FACTORS)
1444
       CONFIG_ECHO_START;
1444
       CONFIG_ECHO_START;
1445
       for (uint8_t i = 0; i < E_STEPPERS; i++) {
1445
       for (uint8_t i = 0; i < E_STEPPERS; i++) {
1459
     #if DISABLED(DISTINCT_E_FACTORS)
1459
     #if DISABLED(DISTINCT_E_FACTORS)
1460
       SERIAL_ECHOPAIR(" E", VOLUMETRIC_UNIT(planner.max_acceleration_mm_per_s2[E_AXIS]));
1460
       SERIAL_ECHOPAIR(" E", VOLUMETRIC_UNIT(planner.max_acceleration_mm_per_s2[E_AXIS]));
1461
     #endif
1461
     #endif
1462
-    SERIAL_EOL;
1462
+    SERIAL_EOL();
1463
     #if ENABLED(DISTINCT_E_FACTORS)
1463
     #if ENABLED(DISTINCT_E_FACTORS)
1464
       CONFIG_ECHO_START;
1464
       CONFIG_ECHO_START;
1465
       for (uint8_t i = 0; i < E_STEPPERS; i++) {
1465
       for (uint8_t i = 0; i < E_STEPPERS; i++) {
1514
         #if ENABLED(DUAL_X_CARRIAGE) || ENABLED(SWITCHING_NOZZLE)
1514
         #if ENABLED(DUAL_X_CARRIAGE) || ENABLED(SWITCHING_NOZZLE)
1515
           SERIAL_ECHOPAIR(" Z", LINEAR_UNIT(hotend_offset[Z_AXIS][e]));
1515
           SERIAL_ECHOPAIR(" Z", LINEAR_UNIT(hotend_offset[Z_AXIS][e]));
1516
         #endif
1516
         #endif
1517
-        SERIAL_EOL;
1517
+        SERIAL_EOL();
1518
       }
1518
       }
1519
     #endif
1519
     #endif
1520
 
1520
 
1529
       #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT)
1529
       #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT)
1530
         SERIAL_ECHOPAIR(" Z", LINEAR_UNIT(planner.z_fade_height));
1530
         SERIAL_ECHOPAIR(" Z", LINEAR_UNIT(planner.z_fade_height));
1531
       #endif
1531
       #endif
1532
-      SERIAL_EOL;
1532
+      SERIAL_EOL();
1533
       for (uint8_t py = 0; py < GRID_MAX_POINTS_Y; py++) {
1533
       for (uint8_t py = 0; py < GRID_MAX_POINTS_Y; py++) {
1534
         for (uint8_t px = 0; px < GRID_MAX_POINTS_X; px++) {
1534
         for (uint8_t px = 0; px < GRID_MAX_POINTS_X; px++) {
1535
           CONFIG_ECHO_START;
1535
           CONFIG_ECHO_START;
1537
           SERIAL_ECHOPAIR(" Y", (int)py + 1);
1537
           SERIAL_ECHOPAIR(" Y", (int)py + 1);
1538
           SERIAL_ECHOPGM(" Z");
1538
           SERIAL_ECHOPGM(" Z");
1539
           SERIAL_PROTOCOL_F(LINEAR_UNIT(mbl.z_values[px][py]), 5);
1539
           SERIAL_PROTOCOL_F(LINEAR_UNIT(mbl.z_values[px][py]), 5);
1540
-          SERIAL_EOL;
1540
+          SERIAL_EOL();
1541
         }
1541
         }
1542
       }
1542
       }
1543
 
1543
 
1553
       #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT)
1553
       #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT)
1554
         SERIAL_ECHOPAIR(" Z", planner.z_fade_height);
1554
         SERIAL_ECHOPAIR(" Z", planner.z_fade_height);
1555
       #endif
1555
       #endif
1556
-      SERIAL_EOL;
1556
+      SERIAL_EOL();
1557
 
1557
 
1558
       if (!forReplay) {
1558
       if (!forReplay) {
1559
-        SERIAL_EOL;
1559
+        SERIAL_EOL();
1560
         ubl.report_state();
1560
         ubl.report_state();
1561
 
1561
 
1562
         SERIAL_ECHOLNPAIR("\nActive Mesh Slot: ", ubl.state.storage_slot);
1562
         SERIAL_ECHOLNPAIR("\nActive Mesh Slot: ", ubl.state.storage_slot);
1563
 
1563
 
1564
         SERIAL_ECHOPGM("z_offset: ");
1564
         SERIAL_ECHOPGM("z_offset: ");
1565
         SERIAL_ECHO_F(ubl.state.z_offset, 6);
1565
         SERIAL_ECHO_F(ubl.state.z_offset, 6);
1566
-        SERIAL_EOL;
1566
+        SERIAL_EOL();
1567
 
1567
 
1568
         SERIAL_ECHOPAIR("EEPROM can hold ", calc_num_meshes());
1568
         SERIAL_ECHOPAIR("EEPROM can hold ", calc_num_meshes());
1569
         SERIAL_ECHOLNPGM(" meshes.\n");
1569
         SERIAL_ECHOLNPGM(" meshes.\n");
1580
       #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT)
1580
       #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT)
1581
         SERIAL_ECHOPAIR(" Z", LINEAR_UNIT(planner.z_fade_height));
1581
         SERIAL_ECHOPAIR(" Z", LINEAR_UNIT(planner.z_fade_height));
1582
       #endif
1582
       #endif
1583
-      SERIAL_EOL;
1583
+      SERIAL_EOL();
1584
 
1584
 
1585
     #endif
1585
     #endif
1586
 
1586
 
1606
       SERIAL_ECHOPAIR(" X", LINEAR_UNIT(delta_tower_angle_trim[A_AXIS]));
1606
       SERIAL_ECHOPAIR(" X", LINEAR_UNIT(delta_tower_angle_trim[A_AXIS]));
1607
       SERIAL_ECHOPAIR(" Y", LINEAR_UNIT(delta_tower_angle_trim[B_AXIS]));
1607
       SERIAL_ECHOPAIR(" Y", LINEAR_UNIT(delta_tower_angle_trim[B_AXIS]));
1608
       SERIAL_ECHOPAIR(" Z", 0.00);
1608
       SERIAL_ECHOPAIR(" Z", 0.00);
1609
-      SERIAL_EOL;
1609
+      SERIAL_EOL();
1610
     #elif ENABLED(Z_DUAL_ENDSTOPS)
1610
     #elif ENABLED(Z_DUAL_ENDSTOPS)
1611
       if (!forReplay) {
1611
       if (!forReplay) {
1612
         CONFIG_ECHO_START;
1612
         CONFIG_ECHO_START;
1649
                 SERIAL_ECHOPAIR(" C", PID_PARAM(Kc, e));
1649
                 SERIAL_ECHOPAIR(" C", PID_PARAM(Kc, e));
1650
                 if (e == 0) SERIAL_ECHOPAIR(" L", lpq_len);
1650
                 if (e == 0) SERIAL_ECHOPAIR(" L", lpq_len);
1651
               #endif
1651
               #endif
1652
-              SERIAL_EOL;
1652
+              SERIAL_EOL();
1653
             }
1653
             }
1654
           }
1654
           }
1655
           else
1655
           else
1664
             SERIAL_ECHOPAIR(" C", PID_PARAM(Kc, 0));
1664
             SERIAL_ECHOPAIR(" C", PID_PARAM(Kc, 0));
1665
             SERIAL_ECHOPAIR(" L", lpq_len);
1665
             SERIAL_ECHOPAIR(" L", lpq_len);
1666
           #endif
1666
           #endif
1667
-          SERIAL_EOL;
1667
+          SERIAL_EOL();
1668
         }
1668
         }
1669
       #endif // PIDTEMP
1669
       #endif // PIDTEMP
1670
 
1670
 
1673
         SERIAL_ECHOPAIR("  M304 P", thermalManager.bedKp);
1673
         SERIAL_ECHOPAIR("  M304 P", thermalManager.bedKp);
1674
         SERIAL_ECHOPAIR(" I", unscalePID_i(thermalManager.bedKi));
1674
         SERIAL_ECHOPAIR(" I", unscalePID_i(thermalManager.bedKi));
1675
         SERIAL_ECHOPAIR(" D", unscalePID_d(thermalManager.bedKd));
1675
         SERIAL_ECHOPAIR(" D", unscalePID_d(thermalManager.bedKd));
1676
-        SERIAL_EOL;
1676
+        SERIAL_EOL();
1677
       #endif
1677
       #endif
1678
 
1678
 
1679
     #endif // PIDTEMP || PIDTEMPBED
1679
     #endif // PIDTEMP || PIDTEMPBED
1773
       #if ENABLED(E3_IS_TMC2130)
1773
       #if ENABLED(E3_IS_TMC2130)
1774
         SERIAL_ECHOPAIR(" E3", stepperE3.getCurrent());
1774
         SERIAL_ECHOPAIR(" E3", stepperE3.getCurrent());
1775
       #endif
1775
       #endif
1776
-      SERIAL_EOL;
1776
+      SERIAL_EOL();
1777
     #endif
1777
     #endif
1778
 
1778
 
1779
     /**
1779
     /**

+ 2
- 2
Marlin/endstops.cpp View File

161
     #define ENDSTOP_HIT_TEST_Y() _ENDSTOP_HIT_TEST(Y,'Y')
161
     #define ENDSTOP_HIT_TEST_Y() _ENDSTOP_HIT_TEST(Y,'Y')
162
     #define ENDSTOP_HIT_TEST_Z() _ENDSTOP_HIT_TEST(Z,'Z')
162
     #define ENDSTOP_HIT_TEST_Z() _ENDSTOP_HIT_TEST(Z,'Z')
163
 
163
 
164
-    SERIAL_ECHO_START;
164
+    SERIAL_ECHO_START();
165
     SERIAL_ECHOPGM(MSG_ENDSTOPS_HIT);
165
     SERIAL_ECHOPGM(MSG_ENDSTOPS_HIT);
166
     ENDSTOP_HIT_TEST_X();
166
     ENDSTOP_HIT_TEST_X();
167
     ENDSTOP_HIT_TEST_Y();
167
     ENDSTOP_HIT_TEST_Y();
171
       #define P_AXIS Z_AXIS
171
       #define P_AXIS Z_AXIS
172
       if (TEST(endstop_hit_bits, Z_MIN_PROBE)) _ENDSTOP_HIT_ECHO(P, 'P');
172
       if (TEST(endstop_hit_bits, Z_MIN_PROBE)) _ENDSTOP_HIT_ECHO(P, 'P');
173
     #endif
173
     #endif
174
-    SERIAL_EOL;
174
+    SERIAL_EOL();
175
 
175
 
176
     #if ENABLED(ULTRA_LCD)
176
     #if ENABLED(ULTRA_LCD)
177
       lcd_status_printf_P(0, PSTR(MSG_LCD_ENDSTOPS " %c %c %c %c"), chrX, chrY, chrZ, chrP);
177
       lcd_status_printf_P(0, PSTR(MSG_LCD_ENDSTOPS " %c %c %c %c"), chrX, chrY, chrZ, chrP);

+ 3
- 3
Marlin/gcode.cpp View File

203
       }
203
       }
204
 
204
 
205
       #if ENABLED(DEBUG_GCODE_PARSER)
205
       #if ENABLED(DEBUG_GCODE_PARSER)
206
-        if (debug) SERIAL_EOL;
206
+        if (debug) SERIAL_EOL();
207
       #endif
207
       #endif
208
 
208
 
209
       #if ENABLED(FASTER_GCODE_PARSER)
209
       #if ENABLED(FASTER_GCODE_PARSER)
229
 }
229
 }
230
 
230
 
231
 void GCodeParser::unknown_command_error() {
231
 void GCodeParser::unknown_command_error() {
232
-  SERIAL_ECHO_START;
232
+  SERIAL_ECHO_START();
233
   SERIAL_ECHOPAIR(MSG_UNKNOWN_COMMAND, command_ptr);
233
   SERIAL_ECHOPAIR(MSG_UNKNOWN_COMMAND, command_ptr);
234
   SERIAL_CHAR('"');
234
   SERIAL_CHAR('"');
235
-  SERIAL_EOL;
235
+  SERIAL_EOL();
236
 }
236
 }
237
 
237
 
238
 #if ENABLED(DEBUG_GCODE_PARSER)
238
 #if ENABLED(DEBUG_GCODE_PARSER)

+ 2
- 2
Marlin/pinsDebug.h View File

452
         }
452
         }
453
         if (!multi_name_pin && extended) pwm_details(pin);  // report PWM capabilities only on the first pass & only if doing an extended report
453
         if (!multi_name_pin && extended) pwm_details(pin);  // report PWM capabilities only on the first pass & only if doing an extended report
454
       }
454
       }
455
-      SERIAL_EOL;
455
+      SERIAL_EOL();
456
     }  // end of IF
456
     }  // end of IF
457
   } // end of for loop
457
   } // end of for loop
458
 
458
 
483
     }
483
     }
484
     //if (!pwm_status(pin)) SERIAL_CHAR(' ');    // add padding if it's not a PWM pin
484
     //if (!pwm_status(pin)) SERIAL_CHAR(' ');    // add padding if it's not a PWM pin
485
     if (extended) pwm_details(pin);  // report PWM capabilities only if doing an extended report
485
     if (extended) pwm_details(pin);  // report PWM capabilities only if doing an extended report
486
-    SERIAL_EOL;
486
+    SERIAL_EOL();
487
   }
487
   }
488
 }
488
 }
489
 
489
 

+ 4
- 4
Marlin/planner.cpp View File

740
   #endif
740
   #endif
741
   SERIAL_ECHOPAIR(" (", dc);
741
   SERIAL_ECHOPAIR(" (", dc);
742
   SERIAL_CHAR(')');
742
   SERIAL_CHAR(')');
743
-  SERIAL_EOL;
743
+  SERIAL_EOL();
744
   //*/
744
   //*/
745
 
745
 
746
   // DRYRUN ignores all temperature constraints and assures that the extruder is instantly satisfied
746
   // DRYRUN ignores all temperature constraints and assures that the extruder is instantly satisfied
766
           position_float[E_AXIS] = e;
766
           position_float[E_AXIS] = e;
767
           de_float = 0;
767
           de_float = 0;
768
         #endif
768
         #endif
769
-        SERIAL_ECHO_START;
769
+        SERIAL_ECHO_START();
770
         SERIAL_ECHOLNPGM(MSG_ERR_COLD_EXTRUDE_STOP);
770
         SERIAL_ECHOLNPGM(MSG_ERR_COLD_EXTRUDE_STOP);
771
       }
771
       }
772
       #if ENABLED(PREVENT_LENGTHY_EXTRUDE)
772
       #if ENABLED(PREVENT_LENGTHY_EXTRUDE)
777
             position_float[E_AXIS] = e;
777
             position_float[E_AXIS] = e;
778
             de_float = 0;
778
             de_float = 0;
779
           #endif
779
           #endif
780
-          SERIAL_ECHO_START;
780
+          SERIAL_ECHO_START();
781
           SERIAL_ECHOLNPGM(MSG_ERR_LONG_EXTRUDE_STOP);
781
           SERIAL_ECHOLNPGM(MSG_ERR_LONG_EXTRUDE_STOP);
782
         }
782
         }
783
       #endif
783
       #endif
1420
       block->advance_rate = block->advance = 0;
1420
       block->advance_rate = block->advance = 0;
1421
 
1421
 
1422
     /**
1422
     /**
1423
-     SERIAL_ECHO_START;
1423
+     SERIAL_ECHO_START();
1424
      SERIAL_ECHOPGM("advance :");
1424
      SERIAL_ECHOPGM("advance :");
1425
      SERIAL_ECHO(block->advance/256.0);
1425
      SERIAL_ECHO(block->advance/256.0);
1426
      SERIAL_ECHOPGM("advance rate :");
1426
      SERIAL_ECHOPGM("advance rate :");

+ 3
- 3
Marlin/printcounter.cpp View File

108
   SERIAL_ECHO(this->data.totalPrints - this->data.finishedPrints
108
   SERIAL_ECHO(this->data.totalPrints - this->data.finishedPrints
109
     - ((this->isRunning() || this->isPaused()) ? 1 : 0));
109
     - ((this->isRunning() || this->isPaused()) ? 1 : 0));
110
 
110
 
111
-  SERIAL_EOL;
111
+  SERIAL_EOL();
112
   SERIAL_PROTOCOLPGM(MSG_STATS);
112
   SERIAL_PROTOCOLPGM(MSG_STATS);
113
 
113
 
114
   elapsed = this->data.printTime;
114
   elapsed = this->data.printTime;
135
     SERIAL_CHAR(')');
135
     SERIAL_CHAR(')');
136
   #endif
136
   #endif
137
 
137
 
138
-  SERIAL_EOL;
138
+  SERIAL_EOL();
139
   SERIAL_PROTOCOLPGM(MSG_STATS);
139
   SERIAL_PROTOCOLPGM(MSG_STATS);
140
 
140
 
141
   SERIAL_ECHOPGM("Filament used: ");
141
   SERIAL_ECHOPGM("Filament used: ");
142
   SERIAL_ECHO(this->data.filamentUsed / 1000);
142
   SERIAL_ECHO(this->data.filamentUsed / 1000);
143
   SERIAL_ECHOPGM("m");
143
   SERIAL_ECHOPGM("m");
144
 
144
 
145
-  SERIAL_EOL;
145
+  SERIAL_EOL();
146
 }
146
 }
147
 
147
 
148
 void PrintCounter::tick() {
148
 void PrintCounter::tick() {

+ 5
- 5
Marlin/serial.h View File

41
 extern const char errormagic[] PROGMEM;
41
 extern const char errormagic[] PROGMEM;
42
 
42
 
43
 #define SERIAL_CHAR(x) (MYSERIAL.write(x))
43
 #define SERIAL_CHAR(x) (MYSERIAL.write(x))
44
-#define SERIAL_EOL SERIAL_CHAR('\n')
44
+#define SERIAL_EOL() SERIAL_CHAR('\n')
45
 
45
 
46
 #define SERIAL_PROTOCOLCHAR(x)              SERIAL_CHAR(x)
46
 #define SERIAL_PROTOCOLCHAR(x)              SERIAL_CHAR(x)
47
 #define SERIAL_PROTOCOL(x)                  (MYSERIAL.print(x))
47
 #define SERIAL_PROTOCOL(x)                  (MYSERIAL.print(x))
48
 #define SERIAL_PROTOCOL_F(x,y)              (MYSERIAL.print(x,y))
48
 #define SERIAL_PROTOCOL_F(x,y)              (MYSERIAL.print(x,y))
49
 #define SERIAL_PROTOCOLPGM(x)               (serialprintPGM(PSTR(x)))
49
 #define SERIAL_PROTOCOLPGM(x)               (serialprintPGM(PSTR(x)))
50
-#define SERIAL_PROTOCOLLN(x)                do{ MYSERIAL.print(x); SERIAL_EOL; }while(0)
50
+#define SERIAL_PROTOCOLLN(x)                do{ MYSERIAL.print(x); SERIAL_EOL(); }while(0)
51
 #define SERIAL_PROTOCOLLNPGM(x)             (serialprintPGM(PSTR(x "\n")))
51
 #define SERIAL_PROTOCOLLNPGM(x)             (serialprintPGM(PSTR(x "\n")))
52
 #define SERIAL_PROTOCOLPAIR(name, value)    (serial_echopair_P(PSTR(name),(value)))
52
 #define SERIAL_PROTOCOLPAIR(name, value)    (serial_echopair_P(PSTR(name),(value)))
53
-#define SERIAL_PROTOCOLLNPAIR(name, value)  do{ SERIAL_PROTOCOLPAIR(name, value); SERIAL_EOL; }while(0)
53
+#define SERIAL_PROTOCOLLNPAIR(name, value)  do{ SERIAL_PROTOCOLPAIR(name, value); SERIAL_EOL(); }while(0)
54
 
54
 
55
-#define SERIAL_ECHO_START             (serialprintPGM(echomagic))
55
+#define SERIAL_ECHO_START()            (serialprintPGM(echomagic))
56
 #define SERIAL_ECHO(x)                 SERIAL_PROTOCOL(x)
56
 #define SERIAL_ECHO(x)                 SERIAL_PROTOCOL(x)
57
 #define SERIAL_ECHOPGM(x)              SERIAL_PROTOCOLPGM(x)
57
 #define SERIAL_ECHOPGM(x)              SERIAL_PROTOCOLPGM(x)
58
 #define SERIAL_ECHOLN(x)               SERIAL_PROTOCOLLN(x)
58
 #define SERIAL_ECHOLN(x)               SERIAL_PROTOCOLLN(x)
61
 #define SERIAL_ECHOLNPAIR(name, value) SERIAL_PROTOCOLLNPAIR(name, value)
61
 #define SERIAL_ECHOLNPAIR(name, value) SERIAL_PROTOCOLLNPAIR(name, value)
62
 #define SERIAL_ECHO_F(x,y)             SERIAL_PROTOCOL_F(x,y)
62
 #define SERIAL_ECHO_F(x,y)             SERIAL_PROTOCOL_F(x,y)
63
 
63
 
64
-#define SERIAL_ERROR_START            (serialprintPGM(errormagic))
64
+#define SERIAL_ERROR_START()           (serialprintPGM(errormagic))
65
 #define SERIAL_ERROR(x)                SERIAL_PROTOCOL(x)
65
 #define SERIAL_ERROR(x)                SERIAL_PROTOCOL(x)
66
 #define SERIAL_ERRORPGM(x)             SERIAL_PROTOCOLPGM(x)
66
 #define SERIAL_ERRORPGM(x)             SERIAL_PROTOCOLPGM(x)
67
 #define SERIAL_ERRORLN(x)              SERIAL_PROTOCOLLN(x)
67
 #define SERIAL_ERRORLN(x)              SERIAL_PROTOCOLLN(x)

+ 1
- 1
Marlin/stepper.cpp View File

1305
   #endif
1305
   #endif
1306
   SERIAL_PROTOCOL(zpos);
1306
   SERIAL_PROTOCOL(zpos);
1307
 
1307
 
1308
-  SERIAL_EOL;
1308
+  SERIAL_EOL();
1309
 }
1309
 }
1310
 
1310
 
1311
 #if ENABLED(BABYSTEPPING)
1311
 #if ENABLED(BABYSTEPPING)

+ 1
- 1
Marlin/stepper.h View File

369
         }
369
         }
370
       #endif
370
       #endif
371
 
371
 
372
-      // SERIAL_ECHO_START;
372
+      // SERIAL_ECHO_START();
373
       // SERIAL_ECHOPGM("advance :");
373
       // SERIAL_ECHOPGM("advance :");
374
       // SERIAL_ECHO(current_block->advance/256.0);
374
       // SERIAL_ECHO(current_block->advance/256.0);
375
       // SERIAL_ECHOPGM("advance rate :");
375
       // SERIAL_ECHOPGM("advance rate :");

+ 2
- 2
Marlin/stepper_dac.cpp View File

103
   void dac_print_values() {
103
   void dac_print_values() {
104
     if (!dac_present) return;
104
     if (!dac_present) return;
105
 
105
 
106
-    SERIAL_ECHO_START;
106
+    SERIAL_ECHO_START();
107
     SERIAL_ECHOLNPGM("Stepper current values in % (Amps):");
107
     SERIAL_ECHOLNPGM("Stepper current values in % (Amps):");
108
-    SERIAL_ECHO_START;
108
+    SERIAL_ECHO_START();
109
     SERIAL_ECHOPAIR(" X:",  dac_perc(X_AXIS));
109
     SERIAL_ECHOPAIR(" X:",  dac_perc(X_AXIS));
110
     SERIAL_ECHOPAIR(" (",   dac_amps(X_AXIS));
110
     SERIAL_ECHOPAIR(" (",   dac_amps(X_AXIS));
111
     SERIAL_ECHOPAIR(") Y:", dac_perc(Y_AXIS));
111
     SERIAL_ECHOPAIR(") Y:", dac_perc(Y_AXIS));

+ 18
- 18
Marlin/temperature.cpp View File

389
       if (ELAPSED(ms, temp_ms + 2000UL)) {
389
       if (ELAPSED(ms, temp_ms + 2000UL)) {
390
         #if HAS_TEMP_HOTEND || HAS_TEMP_BED
390
         #if HAS_TEMP_HOTEND || HAS_TEMP_BED
391
           print_heaterstates();
391
           print_heaterstates();
392
-          SERIAL_EOL;
392
+          SERIAL_EOL();
393
         #endif
393
         #endif
394
 
394
 
395
         temp_ms = ms;
395
         temp_ms = ms;
404
 
404
 
405
         #if HAS_PID_FOR_BOTH
405
         #if HAS_PID_FOR_BOTH
406
           const char* estring = hotend < 0 ? "bed" : "";
406
           const char* estring = hotend < 0 ? "bed" : "";
407
-          SERIAL_PROTOCOLPAIR("#define  DEFAULT_", estring); SERIAL_PROTOCOLPAIR("Kp ", workKp); SERIAL_EOL;
408
-          SERIAL_PROTOCOLPAIR("#define  DEFAULT_", estring); SERIAL_PROTOCOLPAIR("Ki ", workKi); SERIAL_EOL;
409
-          SERIAL_PROTOCOLPAIR("#define  DEFAULT_", estring); SERIAL_PROTOCOLPAIR("Kd ", workKd); SERIAL_EOL;
407
+          SERIAL_PROTOCOLPAIR("#define  DEFAULT_", estring); SERIAL_PROTOCOLPAIR("Kp ", workKp); SERIAL_EOL();
408
+          SERIAL_PROTOCOLPAIR("#define  DEFAULT_", estring); SERIAL_PROTOCOLPAIR("Ki ", workKi); SERIAL_EOL();
409
+          SERIAL_PROTOCOLPAIR("#define  DEFAULT_", estring); SERIAL_PROTOCOLPAIR("Kd ", workKd); SERIAL_EOL();
410
         #elif ENABLED(PIDTEMP)
410
         #elif ENABLED(PIDTEMP)
411
-          SERIAL_PROTOCOLPAIR("#define  DEFAULT_Kp ", workKp); SERIAL_EOL;
412
-          SERIAL_PROTOCOLPAIR("#define  DEFAULT_Ki ", workKi); SERIAL_EOL;
413
-          SERIAL_PROTOCOLPAIR("#define  DEFAULT_Kd ", workKd); SERIAL_EOL;
411
+          SERIAL_PROTOCOLPAIR("#define  DEFAULT_Kp ", workKp); SERIAL_EOL();
412
+          SERIAL_PROTOCOLPAIR("#define  DEFAULT_Ki ", workKi); SERIAL_EOL();
413
+          SERIAL_PROTOCOLPAIR("#define  DEFAULT_Kd ", workKd); SERIAL_EOL();
414
         #else
414
         #else
415
-          SERIAL_PROTOCOLPAIR("#define  DEFAULT_bedKp ", workKp); SERIAL_EOL;
416
-          SERIAL_PROTOCOLPAIR("#define  DEFAULT_bedKi ", workKi); SERIAL_EOL;
417
-          SERIAL_PROTOCOLPAIR("#define  DEFAULT_bedKd ", workKd); SERIAL_EOL;
415
+          SERIAL_PROTOCOLPAIR("#define  DEFAULT_bedKp ", workKp); SERIAL_EOL();
416
+          SERIAL_PROTOCOLPAIR("#define  DEFAULT_bedKi ", workKi); SERIAL_EOL();
417
+          SERIAL_PROTOCOLPAIR("#define  DEFAULT_bedKd ", workKd); SERIAL_EOL();
418
         #endif
418
         #endif
419
 
419
 
420
         #define _SET_BED_PID() do { \
420
         #define _SET_BED_PID() do { \
508
 void Temperature::_temp_error(int e, const char* serial_msg, const char* lcd_msg) {
508
 void Temperature::_temp_error(int e, const char* serial_msg, const char* lcd_msg) {
509
   static bool killed = false;
509
   static bool killed = false;
510
   if (IsRunning()) {
510
   if (IsRunning()) {
511
-    SERIAL_ERROR_START;
511
+    SERIAL_ERROR_START();
512
     serialprintPGM(serial_msg);
512
     serialprintPGM(serial_msg);
513
     SERIAL_ERRORPGM(MSG_STOPPED_HEATER);
513
     SERIAL_ERRORPGM(MSG_STOPPED_HEATER);
514
     if (e >= 0) SERIAL_ERRORLN((int)e); else SERIAL_ERRORLNPGM(MSG_HEATER_BED);
514
     if (e >= 0) SERIAL_ERRORLN((int)e); else SERIAL_ERRORLNPGM(MSG_HEATER_BED);
619
     #endif // PID_OPENLOOP
619
     #endif // PID_OPENLOOP
620
 
620
 
621
     #if ENABLED(PID_DEBUG)
621
     #if ENABLED(PID_DEBUG)
622
-      SERIAL_ECHO_START;
622
+      SERIAL_ECHO_START();
623
       SERIAL_ECHOPAIR(MSG_PID_DEBUG, HOTEND_INDEX);
623
       SERIAL_ECHOPAIR(MSG_PID_DEBUG, HOTEND_INDEX);
624
       SERIAL_ECHOPAIR(MSG_PID_DEBUG_INPUT, current_temperature[HOTEND_INDEX]);
624
       SERIAL_ECHOPAIR(MSG_PID_DEBUG_INPUT, current_temperature[HOTEND_INDEX]);
625
       SERIAL_ECHOPAIR(MSG_PID_DEBUG_OUTPUT, pid_output);
625
       SERIAL_ECHOPAIR(MSG_PID_DEBUG_OUTPUT, pid_output);
629
       #if ENABLED(PID_EXTRUSION_SCALING)
629
       #if ENABLED(PID_EXTRUSION_SCALING)
630
         SERIAL_ECHOPAIR(MSG_PID_DEBUG_CTERM, cTerm[HOTEND_INDEX]);
630
         SERIAL_ECHOPAIR(MSG_PID_DEBUG_CTERM, cTerm[HOTEND_INDEX]);
631
       #endif
631
       #endif
632
-      SERIAL_EOL;
632
+      SERIAL_EOL();
633
     #endif // PID_DEBUG
633
     #endif // PID_DEBUG
634
 
634
 
635
   #else /* PID off */
635
   #else /* PID off */
670
     #endif // PID_OPENLOOP
670
     #endif // PID_OPENLOOP
671
 
671
 
672
     #if ENABLED(PID_BED_DEBUG)
672
     #if ENABLED(PID_BED_DEBUG)
673
-      SERIAL_ECHO_START;
673
+      SERIAL_ECHO_START();
674
       SERIAL_ECHOPGM(" PID_BED_DEBUG ");
674
       SERIAL_ECHOPGM(" PID_BED_DEBUG ");
675
       SERIAL_ECHOPGM(": Input ");
675
       SERIAL_ECHOPGM(": Input ");
676
       SERIAL_ECHO(current_temperature_bed);
676
       SERIAL_ECHO(current_temperature_bed);
854
     if (e >= HOTENDS)
854
     if (e >= HOTENDS)
855
   #endif
855
   #endif
856
     {
856
     {
857
-      SERIAL_ERROR_START;
857
+      SERIAL_ERROR_START();
858
       SERIAL_ERROR((int)e);
858
       SERIAL_ERROR((int)e);
859
       SERIAL_ERRORLNPGM(MSG_INVALID_EXTRUDER_NUM);
859
       SERIAL_ERRORLNPGM(MSG_INVALID_EXTRUDER_NUM);
860
       kill(PSTR(MSG_KILLED));
860
       kill(PSTR(MSG_KILLED));
1278
     static float tr_target_temperature[HOTENDS + 1] = { 0.0 };
1278
     static float tr_target_temperature[HOTENDS + 1] = { 0.0 };
1279
 
1279
 
1280
     /**
1280
     /**
1281
-        SERIAL_ECHO_START;
1281
+        SERIAL_ECHO_START();
1282
         SERIAL_ECHOPGM("Thermal Thermal Runaway Running. Heater ID: ");
1282
         SERIAL_ECHOPGM("Thermal Thermal Runaway Running. Heater ID: ");
1283
         if (heater_id < 0) SERIAL_ECHOPGM("bed"); else SERIAL_ECHO(heater_id);
1283
         if (heater_id < 0) SERIAL_ECHOPGM("bed"); else SERIAL_ECHO(heater_id);
1284
         SERIAL_ECHOPAIR(" ;  State:", *state);
1284
         SERIAL_ECHOPAIR(" ;  State:", *state);
1289
           SERIAL_ECHOPAIR(" ;  Idle Timeout:", heater_idle_timeout_exceeded[heater_id]);
1289
           SERIAL_ECHOPAIR(" ;  Idle Timeout:", heater_idle_timeout_exceeded[heater_id]);
1290
         else
1290
         else
1291
           SERIAL_ECHOPAIR(" ;  Idle Timeout:", bed_idle_timeout_exceeded);
1291
           SERIAL_ECHOPAIR(" ;  Idle Timeout:", bed_idle_timeout_exceeded);
1292
-        SERIAL_EOL;
1292
+        SERIAL_EOL();
1293
     */
1293
     */
1294
 
1294
 
1295
     int heater_index = heater_id >= 0 ? heater_id : HOTENDS;
1295
     int heater_index = heater_id >= 0 ? heater_id : HOTENDS;
1457
     WRITE(MAX6675_SS, 1); // disable TT_MAX6675
1457
     WRITE(MAX6675_SS, 1); // disable TT_MAX6675
1458
 
1458
 
1459
     if (max6675_temp & MAX6675_ERROR_MASK) {
1459
     if (max6675_temp & MAX6675_ERROR_MASK) {
1460
-      SERIAL_ERROR_START;
1460
+      SERIAL_ERROR_START();
1461
       SERIAL_ERRORPGM("Temp measurement error! ");
1461
       SERIAL_ERRORPGM("Temp measurement error! ");
1462
       #if MAX6675_ERROR_MASK == 7
1462
       #if MAX6675_ERROR_MASK == 7
1463
         SERIAL_ERRORPGM("MAX31855 ");
1463
         SERIAL_ERRORPGM("MAX31855 ");

+ 4
- 4
Marlin/twibus.cpp View File

43
 
43
 
44
 void TWIBus::address(const uint8_t adr) {
44
 void TWIBus::address(const uint8_t adr) {
45
   if (!WITHIN(adr, 8, 127)) {
45
   if (!WITHIN(adr, 8, 127)) {
46
-    SERIAL_ECHO_START;
46
+    SERIAL_ECHO_START();
47
     SERIAL_ECHOLNPGM("Bad I2C address (8-127)");
47
     SERIAL_ECHOLNPGM("Bad I2C address (8-127)");
48
   }
48
   }
49
 
49
 
90
 
90
 
91
 // static
91
 // static
92
 void TWIBus::echoprefix(uint8_t bytes, const char prefix[], uint8_t adr) {
92
 void TWIBus::echoprefix(uint8_t bytes, const char prefix[], uint8_t adr) {
93
-  SERIAL_ECHO_START;
93
+  SERIAL_ECHO_START();
94
   serialprintPGM(prefix);
94
   serialprintPGM(prefix);
95
   SERIAL_ECHOPAIR(": from:", adr);
95
   SERIAL_ECHOPAIR(": from:", adr);
96
   SERIAL_ECHOPAIR(" bytes:", bytes);
96
   SERIAL_ECHOPAIR(" bytes:", bytes);
101
 void TWIBus::echodata(uint8_t bytes, const char prefix[], uint8_t adr) {
101
 void TWIBus::echodata(uint8_t bytes, const char prefix[], uint8_t adr) {
102
   echoprefix(bytes, prefix, adr);
102
   echoprefix(bytes, prefix, adr);
103
   while (bytes-- && Wire.available()) SERIAL_CHAR(Wire.read());
103
   while (bytes-- && Wire.available()) SERIAL_CHAR(Wire.read());
104
-  SERIAL_EOL;
104
+  SERIAL_EOL();
105
 }
105
 }
106
 
106
 
107
 void TWIBus::echobuffer(const char prefix[], uint8_t adr) {
107
 void TWIBus::echobuffer(const char prefix[], uint8_t adr) {
108
   echoprefix(this->buffer_s, prefix, adr);
108
   echoprefix(this->buffer_s, prefix, adr);
109
   for (uint8_t i = 0; i < this->buffer_s; i++) SERIAL_CHAR(this->buffer[i]);
109
   for (uint8_t i = 0; i < this->buffer_s; i++) SERIAL_CHAR(this->buffer[i]);
110
-  SERIAL_EOL;
110
+  SERIAL_EOL();
111
 }
111
 }
112
 
112
 
113
 bool TWIBus::request(const uint8_t bytes) {
113
 bool TWIBus::request(const uint8_t bytes) {

+ 6
- 6
Marlin/ubl.cpp View File

116
       serial_echo_xy(0, GRID_MAX_POINTS_Y - 1);
116
       serial_echo_xy(0, GRID_MAX_POINTS_Y - 1);
117
       SERIAL_ECHO_SP(spaces + 3);
117
       SERIAL_ECHO_SP(spaces + 3);
118
       serial_echo_xy(GRID_MAX_POINTS_X - 1, GRID_MAX_POINTS_Y - 1);
118
       serial_echo_xy(GRID_MAX_POINTS_X - 1, GRID_MAX_POINTS_Y - 1);
119
-      SERIAL_EOL;
119
+      SERIAL_EOL();
120
       serial_echo_xy(UBL_MESH_MIN_X, UBL_MESH_MAX_Y);
120
       serial_echo_xy(UBL_MESH_MIN_X, UBL_MESH_MAX_Y);
121
       SERIAL_ECHO_SP(spaces);
121
       SERIAL_ECHO_SP(spaces);
122
       serial_echo_xy(UBL_MESH_MAX_X, UBL_MESH_MAX_Y);
122
       serial_echo_xy(UBL_MESH_MAX_X, UBL_MESH_MAX_Y);
123
-      SERIAL_EOL;
123
+      SERIAL_EOL();
124
     }
124
     }
125
 
125
 
126
     const float current_xi = get_cell_index_x(current_position[X_AXIS] + (MESH_X_DIST) / 2.0),
126
     const float current_xi = get_cell_index_x(current_position[X_AXIS] + (MESH_X_DIST) / 2.0),
154
           SERIAL_CHAR(' ');
154
           SERIAL_CHAR(' ');
155
         }
155
         }
156
       }
156
       }
157
-      SERIAL_EOL;
157
+      SERIAL_EOL();
158
       if (j && map0) { // we want the (0,0) up tight against the block of numbers
158
       if (j && map0) { // we want the (0,0) up tight against the block of numbers
159
         SERIAL_CHAR(' ');
159
         SERIAL_CHAR(' ');
160
-        SERIAL_EOL;
160
+        SERIAL_EOL();
161
       }
161
       }
162
     }
162
     }
163
 
163
 
165
       serial_echo_xy(UBL_MESH_MIN_X, UBL_MESH_MIN_Y);
165
       serial_echo_xy(UBL_MESH_MIN_X, UBL_MESH_MIN_Y);
166
       SERIAL_ECHO_SP(spaces + 4);
166
       SERIAL_ECHO_SP(spaces + 4);
167
       serial_echo_xy(UBL_MESH_MAX_X, UBL_MESH_MIN_Y);
167
       serial_echo_xy(UBL_MESH_MAX_X, UBL_MESH_MIN_Y);
168
-      SERIAL_EOL;
168
+      SERIAL_EOL();
169
       serial_echo_xy(0, 0);
169
       serial_echo_xy(0, 0);
170
       SERIAL_ECHO_SP(spaces + 5);
170
       SERIAL_ECHO_SP(spaces + 5);
171
       serial_echo_xy(GRID_MAX_POINTS_X - 1, 0);
171
       serial_echo_xy(GRID_MAX_POINTS_X - 1, 0);
172
-      SERIAL_EOL;
172
+      SERIAL_EOL();
173
     }
173
     }
174
   }
174
   }
175
 
175
 

+ 5
- 5
Marlin/ubl.h View File

256
           SERIAL_ECHOPAIR(",x1_i=", x1_i);
256
           SERIAL_ECHOPAIR(",x1_i=", x1_i);
257
           SERIAL_ECHOPAIR(",yi=", yi);
257
           SERIAL_ECHOPAIR(",yi=", yi);
258
           SERIAL_CHAR(')');
258
           SERIAL_CHAR(')');
259
-          SERIAL_EOL;
259
+          SERIAL_EOL();
260
           return NAN;
260
           return NAN;
261
         }
261
         }
262
 
262
 
276
           SERIAL_ECHOPAIR(", xi=", xi);
276
           SERIAL_ECHOPAIR(", xi=", xi);
277
           SERIAL_ECHOPAIR(", y1_i=", y1_i);
277
           SERIAL_ECHOPAIR(", y1_i=", y1_i);
278
           SERIAL_CHAR(')');
278
           SERIAL_CHAR(')');
279
-          SERIAL_EOL;
279
+          SERIAL_EOL();
280
           return NAN;
280
           return NAN;
281
         }
281
         }
282
 
282
 
301
           SERIAL_ECHOPAIR("? in get_z_correction(lx0=", lx0);
301
           SERIAL_ECHOPAIR("? in get_z_correction(lx0=", lx0);
302
           SERIAL_ECHOPAIR(", ly0=", ly0);
302
           SERIAL_ECHOPAIR(", ly0=", ly0);
303
           SERIAL_CHAR(')');
303
           SERIAL_CHAR(')');
304
-          SERIAL_EOL;
304
+          SERIAL_EOL();
305
 
305
 
306
           #if ENABLED(ULTRA_LCD)
306
           #if ENABLED(ULTRA_LCD)
307
             strcpy(lcd_status_message, "get_z_correction() indexes out of range.");
307
             strcpy(lcd_status_message, "get_z_correction() indexes out of range.");
336
           if (DEBUGGING(MESH_ADJUST)) {
336
           if (DEBUGGING(MESH_ADJUST)) {
337
             SERIAL_ECHOPGM(" >>>---> ");
337
             SERIAL_ECHOPGM(" >>>---> ");
338
             SERIAL_ECHO_F(z0, 6);
338
             SERIAL_ECHO_F(z0, 6);
339
-            SERIAL_EOL;
339
+            SERIAL_EOL();
340
           }
340
           }
341
         #endif
341
         #endif
342
 
342
 
352
               SERIAL_CHAR(',');
352
               SERIAL_CHAR(',');
353
               SERIAL_ECHO(ly0);
353
               SERIAL_ECHO(ly0);
354
               SERIAL_CHAR(')');
354
               SERIAL_CHAR(')');
355
-              SERIAL_EOL;
355
+              SERIAL_EOL();
356
             }
356
             }
357
           #endif
357
           #endif
358
         }
358
         }

+ 25
- 25
Marlin/ubl_G29.cpp View File

406
         }
406
         }
407
 
407
 
408
         if (isnan(z1) || isnan(z2) || isnan(z3)) { // probe_pt will return NAN if unreachable
408
         if (isnan(z1) || isnan(z2) || isnan(z3)) { // probe_pt will return NAN if unreachable
409
-          SERIAL_ERROR_START;
409
+          SERIAL_ERROR_START();
410
           SERIAL_ERRORLNPGM("Attempt to probe off the bed.");
410
           SERIAL_ERRORLNPGM("Attempt to probe off the bed.");
411
           goto LEAVE;
411
           goto LEAVE;
412
         }
412
         }
643
               SERIAL_ECHO_F(z_values[x][y], 6);
643
               SERIAL_ECHO_F(z_values[x][y], 6);
644
               SERIAL_ECHOPAIR(" ; X ", LOGICAL_X_POSITION(mesh_index_to_xpos(x)));
644
               SERIAL_ECHOPAIR(" ; X ", LOGICAL_X_POSITION(mesh_index_to_xpos(x)));
645
               SERIAL_ECHOPAIR(", Y ", LOGICAL_Y_POSITION(mesh_index_to_ypos(y)));
645
               SERIAL_ECHOPAIR(", Y ", LOGICAL_Y_POSITION(mesh_index_to_ypos(y)));
646
-              SERIAL_EOL;
646
+              SERIAL_EOL();
647
             }
647
             }
648
         return;
648
         return;
649
       }
649
       }
766
     SERIAL_ECHOLNPAIR("# of samples: ", n);
766
     SERIAL_ECHOLNPAIR("# of samples: ", n);
767
     SERIAL_ECHOPGM("Mean Mesh Height: ");
767
     SERIAL_ECHOPGM("Mean Mesh Height: ");
768
     SERIAL_ECHO_F(mean, 6);
768
     SERIAL_ECHO_F(mean, 6);
769
-    SERIAL_EOL;
769
+    SERIAL_EOL();
770
 
770
 
771
     const float sigma = sqrt(sum_of_diff_squared / (n + 1));
771
     const float sigma = sqrt(sum_of_diff_squared / (n + 1));
772
     SERIAL_ECHOPGM("Standard Deviation: ");
772
     SERIAL_ECHOPGM("Standard Deviation: ");
773
     SERIAL_ECHO_F(sigma, 6);
773
     SERIAL_ECHO_F(sigma, 6);
774
-    SERIAL_EOL;
774
+    SERIAL_EOL();
775
 
775
 
776
     if (g29_c_flag)
776
     if (g29_c_flag)
777
       for (uint8_t x = 0; x < GRID_MAX_POINTS_X; x++)
777
       for (uint8_t x = 0; x < GRID_MAX_POINTS_X; x++)
892
       if (DEBUGGING(LEVELING)) {
892
       if (DEBUGGING(LEVELING)) {
893
         SERIAL_ECHOPGM("d from 1st point: ");
893
         SERIAL_ECHOPGM("d from 1st point: ");
894
         SERIAL_ECHO_F(d, 6);
894
         SERIAL_ECHO_F(d, 6);
895
-        SERIAL_EOL;
895
+        SERIAL_EOL();
896
         t = normal.x * (UBL_PROBE_PT_2_X) + normal.y * (UBL_PROBE_PT_2_Y);
896
         t = normal.x * (UBL_PROBE_PT_2_X) + normal.y * (UBL_PROBE_PT_2_Y);
897
         d = t + normal.z * z2;
897
         d = t + normal.z * z2;
898
         SERIAL_ECHOPGM("d from 2nd point: ");
898
         SERIAL_ECHOPGM("d from 2nd point: ");
899
         SERIAL_ECHO_F(d, 6);
899
         SERIAL_ECHO_F(d, 6);
900
-        SERIAL_EOL;
900
+        SERIAL_EOL();
901
         t = normal.x * (UBL_PROBE_PT_3_X) + normal.y * (UBL_PROBE_PT_3_Y);
901
         t = normal.x * (UBL_PROBE_PT_3_X) + normal.y * (UBL_PROBE_PT_3_Y);
902
         d = t + normal.z * z3;
902
         d = t + normal.z * z3;
903
         SERIAL_ECHOPGM("d from 3rd point: ");
903
         SERIAL_ECHOPGM("d from 3rd point: ");
904
         SERIAL_ECHO_F(d, 6);
904
         SERIAL_ECHO_F(d, 6);
905
-        SERIAL_EOL;
905
+        SERIAL_EOL();
906
       }
906
       }
907
     #endif
907
     #endif
908
 
908
 
1080
         if (g29_verbose_level > 2) {
1080
         if (g29_verbose_level > 2) {
1081
           SERIAL_PROTOCOLPGM("Mesh Point Measured at: ");
1081
           SERIAL_PROTOCOLPGM("Mesh Point Measured at: ");
1082
           SERIAL_PROTOCOL_F(z_values[location.x_index][location.y_index], 6);
1082
           SERIAL_PROTOCOL_F(z_values[location.x_index][location.y_index], 6);
1083
-          SERIAL_EOL;
1083
+          SERIAL_EOL();
1084
         }
1084
         }
1085
       } while (location.x_index >= 0 && location.y_index >= 0);
1085
       } while (location.x_index >= 0 && location.y_index >= 0);
1086
 
1086
 
1244
       SERIAL_PROTOCOLPAIR("Mesh ", state.storage_slot);
1244
       SERIAL_PROTOCOLPAIR("Mesh ", state.storage_slot);
1245
       SERIAL_PROTOCOLPGM(" Loaded.");
1245
       SERIAL_PROTOCOLPGM(" Loaded.");
1246
     }
1246
     }
1247
-    SERIAL_EOL;
1247
+    SERIAL_EOL();
1248
     safe_delay(50);
1248
     safe_delay(50);
1249
 
1249
 
1250
     SERIAL_PROTOCOLLNPAIR("UBL object count: ", (int)ubl_cnt);
1250
     SERIAL_PROTOCOLLNPAIR("UBL object count: ", (int)ubl_cnt);
1252
     #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT)
1252
     #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT)
1253
       SERIAL_PROTOCOL("planner.z_fade_height : ");
1253
       SERIAL_PROTOCOL("planner.z_fade_height : ");
1254
       SERIAL_PROTOCOL_F(planner.z_fade_height, 4);
1254
       SERIAL_PROTOCOL_F(planner.z_fade_height, 4);
1255
-      SERIAL_EOL;
1255
+      SERIAL_EOL();
1256
     #endif
1256
     #endif
1257
 
1257
 
1258
     #if HAS_BED_PROBE
1258
     #if HAS_BED_PROBE
1259
       SERIAL_PROTOCOLPGM("zprobe_zoffset: ");
1259
       SERIAL_PROTOCOLPGM("zprobe_zoffset: ");
1260
       SERIAL_PROTOCOL_F(zprobe_zoffset, 7);
1260
       SERIAL_PROTOCOL_F(zprobe_zoffset, 7);
1261
-      SERIAL_EOL;
1261
+      SERIAL_EOL();
1262
     #endif
1262
     #endif
1263
 
1263
 
1264
     SERIAL_ECHOLNPAIR("UBL_MESH_MIN_X  " STRINGIFY(UBL_MESH_MIN_X) "=", UBL_MESH_MIN_X);
1264
     SERIAL_ECHOLNPAIR("UBL_MESH_MIN_X  " STRINGIFY(UBL_MESH_MIN_X) "=", UBL_MESH_MIN_X);
1280
       SERIAL_PROTOCOLPGM("  ");
1280
       SERIAL_PROTOCOLPGM("  ");
1281
       safe_delay(25);
1281
       safe_delay(25);
1282
     }
1282
     }
1283
-    SERIAL_EOL;
1283
+    SERIAL_EOL();
1284
 
1284
 
1285
     SERIAL_PROTOCOLPGM("Y-Axis Mesh Points at: ");
1285
     SERIAL_PROTOCOLPGM("Y-Axis Mesh Points at: ");
1286
     for (uint8_t i = 0; i < GRID_MAX_POINTS_Y; i++) {
1286
     for (uint8_t i = 0; i < GRID_MAX_POINTS_Y; i++) {
1288
       SERIAL_PROTOCOLPGM("  ");
1288
       SERIAL_PROTOCOLPGM("  ");
1289
       safe_delay(25);
1289
       safe_delay(25);
1290
     }
1290
     }
1291
-    SERIAL_EOL;
1291
+    SERIAL_EOL();
1292
 
1292
 
1293
     #if HAS_KILL
1293
     #if HAS_KILL
1294
       SERIAL_PROTOCOLPAIR("Kill pin on :", KILL_PIN);
1294
       SERIAL_PROTOCOLPAIR("Kill pin on :", KILL_PIN);
1295
       SERIAL_PROTOCOLLNPAIR("  state:", READ(KILL_PIN));
1295
       SERIAL_PROTOCOLLNPAIR("  state:", READ(KILL_PIN));
1296
     #endif
1296
     #endif
1297
-    SERIAL_EOL;
1297
+    SERIAL_EOL();
1298
     safe_delay(50);
1298
     safe_delay(50);
1299
 
1299
 
1300
     SERIAL_PROTOCOLLNPAIR("ubl_state_at_invocation :", ubl_state_at_invocation);
1300
     SERIAL_PROTOCOLLNPAIR("ubl_state_at_invocation :", ubl_state_at_invocation);
1301
-    SERIAL_EOL;
1301
+    SERIAL_EOL();
1302
     SERIAL_PROTOCOLLNPAIR("ubl_state_recursion_chk :", ubl_state_recursion_chk);
1302
     SERIAL_PROTOCOLLNPAIR("ubl_state_recursion_chk :", ubl_state_recursion_chk);
1303
-    SERIAL_EOL;
1303
+    SERIAL_EOL();
1304
     safe_delay(50);
1304
     safe_delay(50);
1305
 
1305
 
1306
     SERIAL_PROTOCOLPAIR("Meshes go from ", hex_address((void*)settings.get_start_of_meshes()));
1306
     SERIAL_PROTOCOLPAIR("Meshes go from ", hex_address((void*)settings.get_start_of_meshes()));
1308
     safe_delay(50);
1308
     safe_delay(50);
1309
 
1309
 
1310
     SERIAL_PROTOCOLLNPAIR("sizeof(ubl) :  ", (int)sizeof(ubl));
1310
     SERIAL_PROTOCOLLNPAIR("sizeof(ubl) :  ", (int)sizeof(ubl));
1311
-    SERIAL_EOL;
1311
+    SERIAL_EOL();
1312
     SERIAL_PROTOCOLLNPAIR("z_value[][] size: ", (int)sizeof(z_values));
1312
     SERIAL_PROTOCOLLNPAIR("z_value[][] size: ", (int)sizeof(z_values));
1313
-    SERIAL_EOL;
1313
+    SERIAL_EOL();
1314
     safe_delay(25);
1314
     safe_delay(25);
1315
 
1315
 
1316
     SERIAL_PROTOCOLLNPAIR("EEPROM free for UBL: ", hex_address((void*)(settings.get_end_of_meshes() - settings.get_start_of_meshes())));
1316
     SERIAL_PROTOCOLLNPAIR("EEPROM free for UBL: ", hex_address((void*)(settings.get_end_of_meshes() - settings.get_start_of_meshes())));
1334
     unsigned char cccc;
1334
     unsigned char cccc;
1335
     uint16_t kkkk;
1335
     uint16_t kkkk;
1336
 
1336
 
1337
-    SERIAL_ECHO_START;
1337
+    SERIAL_ECHO_START();
1338
     SERIAL_ECHOLNPGM("EEPROM Dump:");
1338
     SERIAL_ECHOLNPGM("EEPROM Dump:");
1339
     for (uint16_t i = 0; i < E2END + 1; i += 16) {
1339
     for (uint16_t i = 0; i < E2END + 1; i += 16) {
1340
       if (!(i & 0x3)) idle();
1340
       if (!(i & 0x3)) idle();
1346
         print_hex_byte(cccc);
1346
         print_hex_byte(cccc);
1347
         SERIAL_ECHO(' ');
1347
         SERIAL_ECHO(' ');
1348
       }
1348
       }
1349
-      SERIAL_EOL;
1349
+      SERIAL_EOL();
1350
     }
1350
     }
1351
-    SERIAL_EOL;
1351
+    SERIAL_EOL();
1352
   }
1352
   }
1353
 
1353
 
1354
   /**
1354
   /**
1667
           if (DEBUGGING(LEVELING)) {
1667
           if (DEBUGGING(LEVELING)) {
1668
             SERIAL_ECHOPGM("   final >>>---> ");
1668
             SERIAL_ECHOPGM("   final >>>---> ");
1669
             SERIAL_PROTOCOL_F(measured_z, 7);
1669
             SERIAL_PROTOCOL_F(measured_z, 7);
1670
-            SERIAL_EOL;
1670
+            SERIAL_EOL();
1671
           }
1671
           }
1672
         #endif
1672
         #endif
1673
 
1673
 
1689
       SERIAL_PROTOCOL_F(lsf_results.B, 7);
1689
       SERIAL_PROTOCOL_F(lsf_results.B, 7);
1690
       SERIAL_ECHOPGM("  D=");
1690
       SERIAL_ECHOPGM("  D=");
1691
       SERIAL_PROTOCOL_F(lsf_results.D, 7);
1691
       SERIAL_PROTOCOL_F(lsf_results.D, 7);
1692
-      SERIAL_EOL;
1692
+      SERIAL_EOL();
1693
     }
1693
     }
1694
 
1694
 
1695
     vector_3 normal = vector_3(lsf_results.A, lsf_results.B, 1.0000).get_normal();
1695
     vector_3 normal = vector_3(lsf_results.A, lsf_results.B, 1.0000).get_normal();
1753
         SERIAL_PROTOCOL_F(lsf_results.B, 7);
1753
         SERIAL_PROTOCOL_F(lsf_results.B, 7);
1754
         SERIAL_ECHOPGM("  D=");
1754
         SERIAL_ECHOPGM("  D=");
1755
         SERIAL_PROTOCOL_F(lsf_results.D, 7);
1755
         SERIAL_PROTOCOL_F(lsf_results.D, 7);
1756
-        SERIAL_EOL;
1756
+        SERIAL_EOL();
1757
         safe_delay(55);
1757
         safe_delay(55);
1758
 
1758
 
1759
         SERIAL_ECHOPGM("bed plane normal = [");
1759
         SERIAL_ECHOPGM("bed plane normal = [");
1763
         SERIAL_PROTOCOLCHAR(',');
1763
         SERIAL_PROTOCOLCHAR(',');
1764
         SERIAL_PROTOCOL_F(normal.z, 7);
1764
         SERIAL_PROTOCOL_F(normal.z, 7);
1765
         SERIAL_ECHOPGM("]\n");
1765
         SERIAL_ECHOPGM("]\n");
1766
-        SERIAL_EOL;
1766
+        SERIAL_EOL();
1767
       }
1767
       }
1768
     #endif
1768
     #endif
1769
 
1769
 

+ 2
- 2
Marlin/ubl_motion.cpp View File

97
     debug_echo_axis(E_AXIS);
97
     debug_echo_axis(E_AXIS);
98
     SERIAL_ECHOPGM(" )   ");
98
     SERIAL_ECHOPGM(" )   ");
99
     SERIAL_ECHO(title);
99
     SERIAL_ECHO(title);
100
-    SERIAL_EOL;
100
+    SERIAL_EOL();
101
 
101
 
102
   }
102
   }
103
 
103
 
131
       SERIAL_ECHOPAIR(", ze=", end[Z_AXIS]);
131
       SERIAL_ECHOPAIR(", ze=", end[Z_AXIS]);
132
       SERIAL_ECHOPAIR(", ee=", end[E_AXIS]);
132
       SERIAL_ECHOPAIR(", ee=", end[E_AXIS]);
133
       SERIAL_CHAR(')');
133
       SERIAL_CHAR(')');
134
-      SERIAL_EOL;
134
+      SERIAL_EOL();
135
       debug_current_and_destination(PSTR("Start of ubl.line_to_destination()"));
135
       debug_current_and_destination(PSTR("Start of ubl.line_to_destination()"));
136
     }
136
     }
137
 
137
 

+ 2
- 2
Marlin/ultralcd.cpp View File

4043
                 else if (encoderStepRate >= ENCODER_10X_STEPS_PER_SEC) encoderMultiplier = 10;
4043
                 else if (encoderStepRate >= ENCODER_10X_STEPS_PER_SEC) encoderMultiplier = 10;
4044
 
4044
 
4045
                 #if ENABLED(ENCODER_RATE_MULTIPLIER_DEBUG)
4045
                 #if ENABLED(ENCODER_RATE_MULTIPLIER_DEBUG)
4046
-                  SERIAL_ECHO_START;
4046
+                  SERIAL_ECHO_START();
4047
                   SERIAL_ECHOPAIR("Enc Step Rate: ", encoderStepRate);
4047
                   SERIAL_ECHOPAIR("Enc Step Rate: ", encoderStepRate);
4048
                   SERIAL_ECHOPAIR("  Multiplier: ", encoderMultiplier);
4048
                   SERIAL_ECHOPAIR("  Multiplier: ", encoderMultiplier);
4049
                   SERIAL_ECHOPAIR("  ENCODER_10X_STEPS_PER_SEC: ", ENCODER_10X_STEPS_PER_SEC);
4049
                   SERIAL_ECHOPAIR("  ENCODER_10X_STEPS_PER_SEC: ", ENCODER_10X_STEPS_PER_SEC);
4050
                   SERIAL_ECHOPAIR("  ENCODER_100X_STEPS_PER_SEC: ", ENCODER_100X_STEPS_PER_SEC);
4050
                   SERIAL_ECHOPAIR("  ENCODER_100X_STEPS_PER_SEC: ", ENCODER_100X_STEPS_PER_SEC);
4051
-                  SERIAL_EOL;
4051
+                  SERIAL_EOL();
4052
                 #endif // ENCODER_RATE_MULTIPLIER_DEBUG
4052
                 #endif // ENCODER_RATE_MULTIPLIER_DEBUG
4053
               }
4053
               }
4054
 
4054
 

+ 2
- 2
Marlin/vector_3.cpp View File

89
   SERIAL_PROTOCOL_F(y, 6);
89
   SERIAL_PROTOCOL_F(y, 6);
90
   SERIAL_PROTOCOLPGM(" z: ");
90
   SERIAL_PROTOCOLPGM(" z: ");
91
   SERIAL_PROTOCOL_F(z, 6);
91
   SERIAL_PROTOCOL_F(z, 6);
92
-  SERIAL_EOL;
92
+  SERIAL_EOL();
93
 }
93
 }
94
 
94
 
95
 void apply_rotation_xyz(matrix_3x3 matrix, float &x, float &y, float &z) {
95
 void apply_rotation_xyz(matrix_3x3 matrix, float &x, float &y, float &z) {
152
       SERIAL_PROTOCOLCHAR(' ');
152
       SERIAL_PROTOCOLCHAR(' ');
153
       count++;
153
       count++;
154
     }
154
     }
155
-    SERIAL_EOL;
155
+    SERIAL_EOL();
156
   }
156
   }
157
 }
157
 }
158
 
158
 

+ 1
- 1
Marlin/watchdog.cpp View File

46
 // Watchdog timer interrupt, called if main program blocks >4sec and manual reset is enabled.
46
 // Watchdog timer interrupt, called if main program blocks >4sec and manual reset is enabled.
47
 #if ENABLED(WATCHDOG_RESET_MANUAL)
47
 #if ENABLED(WATCHDOG_RESET_MANUAL)
48
   ISR(WDT_vect) {
48
   ISR(WDT_vect) {
49
-    SERIAL_ERROR_START;
49
+    SERIAL_ERROR_START();
50
     SERIAL_ERRORLNPGM("Something is wrong, please turn off the printer.");
50
     SERIAL_ERRORLNPGM("Something is wrong, please turn off the printer.");
51
     kill(PSTR("ERR:Please Reset")); //kill blocks //16 characters so it fits on a 16x2 display
51
     kill(PSTR("ERR:Please Reset")); //kill blocks //16 characters so it fits on a 16x2 display
52
     while (1); //wait for user or serial reset
52
     while (1); //wait for user or serial reset

Loading…
Cancel
Save