mirror of
https://github.com/MarlinFirmware/Marlin.git
synced 2024-11-30 07:17:59 +00:00
Extend SERIAL_CHAR to take multiple arguments
This commit is contained in:
parent
5beca89412
commit
95046c9047
@ -234,8 +234,7 @@ static void print_is_also_tied() { SERIAL_ECHOPGM(" is also tied to this pin");
|
||||
void com_print(uint8_t N, uint8_t Z) {
|
||||
const uint8_t *TCCRA = (uint8_t*)TCCR_A(N);
|
||||
SERIAL_ECHOPGM(" COM");
|
||||
SERIAL_CHAR('0' + N);
|
||||
SERIAL_CHAR('A' + Z);
|
||||
SERIAL_CHAR('0' + N, 'A' + Z);
|
||||
SERIAL_ECHOPAIR(": ", int((*TCCRA >> (6 - Z * 2)) & 0x03));
|
||||
}
|
||||
|
||||
@ -247,8 +246,7 @@ void timer_prefix(uint8_t T, char L, uint8_t N) { // T - timer L - pwm N -
|
||||
if (N == 4) WGM |= ((*TCCRB & _BV(WGM_3)) >> 1);
|
||||
|
||||
SERIAL_ECHOPGM(" TIMER");
|
||||
SERIAL_CHAR(T + '0');
|
||||
SERIAL_CHAR(L);
|
||||
SERIAL_CHAR(T + '0', L);
|
||||
SERIAL_ECHO_SP(3);
|
||||
|
||||
if (N == 3) {
|
||||
|
@ -35,7 +35,7 @@ static bool UnwReportOut(void* ctx, const UnwReport* bte) {
|
||||
|
||||
(*p)++;
|
||||
|
||||
SERIAL_CHAR('#'); SERIAL_PRINT(*p,DEC); SERIAL_ECHOPGM(" : ");
|
||||
SERIAL_CHAR('#'); SERIAL_PRINT(*p, DEC); SERIAL_ECHOPGM(" : ");
|
||||
SERIAL_ECHOPGM(bte->name ? bte->name : "unknown"); SERIAL_ECHOPGM("@0x"); SERIAL_PRINT(bte->function, HEX);
|
||||
SERIAL_CHAR('+'); SERIAL_PRINT(bte->address - bte->function,DEC);
|
||||
SERIAL_ECHOPGM(" PC:"); SERIAL_PRINT(bte->address,HEX); SERIAL_CHAR('\n');
|
||||
|
@ -66,7 +66,6 @@ extern uint8_t marlin_debug_flags;
|
||||
#define PORT_REDIRECT(p) _PORT_REDIRECT(1,p)
|
||||
#define PORT_RESTORE() _PORT_RESTORE(1)
|
||||
|
||||
#define SERIAL_CHAR(x) SERIAL_OUT(write, x)
|
||||
#define SERIAL_ECHO(x) SERIAL_OUT(print, x)
|
||||
#define SERIAL_ECHO_F(V...) SERIAL_OUT(print, V)
|
||||
#define SERIAL_ECHOLN(x) SERIAL_OUT(println, x)
|
||||
@ -83,6 +82,22 @@ extern uint8_t marlin_debug_flags;
|
||||
#define SERIAL_FLUSHTX()
|
||||
#endif
|
||||
|
||||
// Print up to 10 chars from a list
|
||||
#define __CHAR_N(N,V...) _CHAR_##N(V)
|
||||
#define _CHAR_N(N,V...) __CHAR_N(N,V)
|
||||
#define _CHAR_1(c) SERIAL_OUT(write, c)
|
||||
#define _CHAR_2(a,b) do{ _CHAR_1(a); _CHAR_1(b); }while(0)
|
||||
#define _CHAR_3(a,V...) do{ _CHAR_1(a); _CHAR_2(V); }while(0)
|
||||
#define _CHAR_4(a,V...) do{ _CHAR_1(a); _CHAR_3(V); }while(0)
|
||||
#define _CHAR_5(a,V...) do{ _CHAR_1(a); _CHAR_4(V); }while(0)
|
||||
#define _CHAR_6(a,V...) do{ _CHAR_1(a); _CHAR_5(V); }while(0)
|
||||
#define _CHAR_7(a,V...) do{ _CHAR_1(a); _CHAR_6(V); }while(0)
|
||||
#define _CHAR_8(a,V...) do{ _CHAR_1(a); _CHAR_7(V); }while(0)
|
||||
#define _CHAR_9(a,V...) do{ _CHAR_1(a); _CHAR_8(V); }while(0)
|
||||
#define _CHAR_10(a,V...) do{ _CHAR_1(a); _CHAR_9(V); }while(0)
|
||||
|
||||
#define SERIAL_CHAR(V...) _CHAR_N(NUM_ARGS(V),V)
|
||||
|
||||
// Print up to 12 pairs of values. Odd elements auto-wrapped in PSTR().
|
||||
#define __SEP_N(N,V...) _SEP_##N(V)
|
||||
#define _SEP_N(N,V...) __SEP_N(N,V)
|
||||
|
@ -148,8 +148,7 @@ void safe_delay(millis_t ms) {
|
||||
SERIAL_ECHOPGM("ABL Adjustment X");
|
||||
LOOP_XYZ(a) {
|
||||
float v = planner.get_axis_position_mm(AxisEnum(a)) - current_position[a];
|
||||
SERIAL_CHAR(' ');
|
||||
SERIAL_CHAR('X' + char(a));
|
||||
SERIAL_CHAR(' ', 'X' + char(a));
|
||||
if (v > 0) SERIAL_CHAR('+');
|
||||
SERIAL_ECHO(v);
|
||||
}
|
||||
|
@ -207,8 +207,7 @@ void reset_bed_level() {
|
||||
#endif
|
||||
}
|
||||
#ifdef SCAD_MESH_OUTPUT
|
||||
SERIAL_CHAR(' ');
|
||||
SERIAL_CHAR(']'); // close sub-array
|
||||
SERIAL_CHAR(' ', ']'); // close sub-array
|
||||
if (y < sy - 1) SERIAL_CHAR(',');
|
||||
#endif
|
||||
SERIAL_EOL();
|
||||
|
@ -213,7 +213,7 @@ class FilamentSensorBase {
|
||||
if (change) {
|
||||
SERIAL_ECHOPGM("Motion detected:");
|
||||
for (uint8_t e = 0; e < NUM_RUNOUT_SENSORS; e++)
|
||||
if (TEST(change, e)) { SERIAL_CHAR(' '); SERIAL_CHAR('0' + e); }
|
||||
if (TEST(change, e)) SERIAL_CHAR(' ', '0' + e);
|
||||
SERIAL_EOL();
|
||||
}
|
||||
#endif
|
||||
|
@ -242,7 +242,7 @@ inline int check_for_free_memory_corruption(PGM_P const title) {
|
||||
|
||||
SERIAL_ECHOPGM(" return=");
|
||||
if (block_cnt == 1) {
|
||||
SERIAL_CHAR('0'); // if the block_cnt is 1, nothing has broken up the free memory
|
||||
SERIAL_CHAR('0'); // If the block_cnt is 1, nothing has broken up the free memory
|
||||
SERIAL_EOL(); // area and it is appropriate to say 'no corruption'.
|
||||
return 0;
|
||||
}
|
||||
|
@ -75,8 +75,7 @@ void GcodeSuite::M425() {
|
||||
SERIAL_ECHOLNPAIR(" Correction Amount/Fade-out: F", backlash.get_correction(), " (F1.0 = full, F0.0 = none)");
|
||||
SERIAL_ECHOPGM(" Backlash Distance (mm): ");
|
||||
LOOP_XYZ(a) {
|
||||
SERIAL_CHAR(' ');
|
||||
SERIAL_CHAR(axis_codes[a]);
|
||||
SERIAL_CHAR(' ', axis_codes[a]);
|
||||
SERIAL_ECHO(backlash.distance_mm[a]);
|
||||
SERIAL_EOL();
|
||||
}
|
||||
@ -89,8 +88,7 @@ void GcodeSuite::M425() {
|
||||
SERIAL_ECHOPGM(" Average measured backlash (mm):");
|
||||
if (backlash.has_any_measurement()) {
|
||||
LOOP_XYZ(a) if (backlash.has_measurement(AxisEnum(a))) {
|
||||
SERIAL_CHAR(' ');
|
||||
SERIAL_CHAR(axis_codes[a]);
|
||||
SERIAL_CHAR(' ', axis_codes[a]);
|
||||
SERIAL_ECHO(backlash.get_measurement(AxisEnum(a)));
|
||||
}
|
||||
}
|
||||
|
@ -39,8 +39,7 @@ void GcodeSuite::M221() {
|
||||
}
|
||||
else {
|
||||
SERIAL_ECHO_START();
|
||||
SERIAL_CHAR('E');
|
||||
SERIAL_CHAR('0' + target_extruder);
|
||||
SERIAL_CHAR('E', '0' + target_extruder);
|
||||
SERIAL_ECHOPAIR(" Flow: ", planner.flow_percentage[target_extruder]);
|
||||
SERIAL_CHAR('%');
|
||||
SERIAL_EOL();
|
||||
|
@ -39,9 +39,7 @@
|
||||
void report_xyze(const xyze_pos_t &pos, const uint8_t n=4, const uint8_t precision=3) {
|
||||
char str[12];
|
||||
for (uint8_t a = 0; a < n; a++) {
|
||||
SERIAL_CHAR(' ');
|
||||
SERIAL_CHAR(axis_codes[a]);
|
||||
SERIAL_CHAR(':');
|
||||
SERIAL_CHAR(' ', axis_codes[a], ':');
|
||||
SERIAL_ECHO(dtostrf(pos[a], 1, precision, str));
|
||||
}
|
||||
SERIAL_EOL();
|
||||
@ -50,9 +48,7 @@
|
||||
void report_xyz(const xyz_pos_t &pos, const uint8_t precision=3) {
|
||||
char str[12];
|
||||
for (uint8_t a = X_AXIS; a <= Z_AXIS; a++) {
|
||||
SERIAL_CHAR(' ');
|
||||
SERIAL_CHAR(axis_codes[a]);
|
||||
SERIAL_CHAR(':');
|
||||
SERIAL_CHAR(' ', axis_codes[a], ':');
|
||||
SERIAL_ECHO(dtostrf(pos[a], 1, precision, str));
|
||||
}
|
||||
SERIAL_EOL();
|
||||
@ -150,9 +146,7 @@
|
||||
|
||||
SERIAL_ECHOPGM("Stepper:");
|
||||
LOOP_XYZE(i) {
|
||||
SERIAL_CHAR(' ');
|
||||
SERIAL_CHAR(axis_codes[i]);
|
||||
SERIAL_CHAR(':');
|
||||
SERIAL_CHAR(' ', axis_codes[i], ':');
|
||||
SERIAL_ECHO(stepper.position((AxisEnum)i));
|
||||
}
|
||||
SERIAL_EOL();
|
||||
|
@ -346,7 +346,7 @@ void GCodeParser::unknown_command_error() {
|
||||
SERIAL_ECHOLNPGM(")");
|
||||
#if ENABLED(FASTER_GCODE_PARSER)
|
||||
SERIAL_ECHOPGM(" args: { ");
|
||||
for (char c = 'A'; c <= 'Z'; ++c) if (seen(c)) { SERIAL_CHAR(c); SERIAL_CHAR(' '); }
|
||||
for (char c = 'A'; c <= 'Z'; ++c) if (seen(c)) SERIAL_CHAR(c, ' ');
|
||||
SERIAL_CHAR('}');
|
||||
#else
|
||||
SERIAL_ECHOPAIR(" args: { ", command_args, " }");
|
||||
|
@ -539,10 +539,7 @@ bool L6470_Marlin::get_user_input(uint8_t &driver_count, uint8_t axis_index[3],
|
||||
|
||||
void L6470_Marlin::say_axis(const uint8_t axis, const bool label/*=true*/) {
|
||||
if (label) SERIAL_ECHOPGM("AXIS:");
|
||||
SERIAL_CHAR(' ');
|
||||
SERIAL_CHAR(index_to_axis[axis][0]);
|
||||
SERIAL_CHAR(index_to_axis[axis][1]);
|
||||
SERIAL_CHAR(' ');
|
||||
SERIAL_CHAR(' ', index_to_axis[axis][0], index_to_axis[axis][1], ' ');
|
||||
}
|
||||
|
||||
void L6470_Marlin::error_status_decode(const uint16_t status, const uint8_t axis) { // assumes status bits have been inverted
|
||||
|
@ -471,7 +471,7 @@ void _O2 Endstops::report_states() {
|
||||
#endif
|
||||
}
|
||||
SERIAL_ECHOPGM(MSG_FILAMENT_RUNOUT_SENSOR);
|
||||
if (i > 1) { SERIAL_CHAR(' '); SERIAL_CHAR('0' + i); }
|
||||
if (i > 1) SERIAL_CHAR(' ', '0' + i);
|
||||
print_es_state(extDigitalRead(pin) != FIL_RUNOUT_INVERTING);
|
||||
}
|
||||
#endif
|
||||
|
@ -2932,77 +2932,78 @@ void Stepper::report_positions() {
|
||||
}
|
||||
|
||||
void Stepper::microstep_readings() {
|
||||
SERIAL_ECHOPGM("MS1,MS2,MS3 Pins\nX: ");
|
||||
SERIAL_ECHOLNPGM("MS1|MS2|MS3 Pins");
|
||||
#if HAS_X_MICROSTEPS
|
||||
SERIAL_CHAR('0' + READ(X_MS1_PIN));
|
||||
SERIAL_CHAR('0' + READ(X_MS2_PIN));
|
||||
SERIAL_ECHOPGM("X: ");
|
||||
SERIAL_CHAR('0' + READ(X_MS1_PIN), '0' + READ(X_MS2_PIN)
|
||||
#if PIN_EXISTS(X_MS3)
|
||||
SERIAL_ECHOLN((int)READ(X_MS3_PIN));
|
||||
, '0' + READ(X_MS3_PIN)
|
||||
#endif
|
||||
);
|
||||
#endif
|
||||
#if HAS_Y_MICROSTEPS
|
||||
SERIAL_ECHOPGM("Y: ");
|
||||
SERIAL_CHAR('0' + READ(Y_MS1_PIN));
|
||||
SERIAL_CHAR('0' + READ(Y_MS2_PIN));
|
||||
SERIAL_CHAR('0' + READ(Y_MS1_PIN), '0' + READ(Y_MS2_PIN)
|
||||
#if PIN_EXISTS(Y_MS3)
|
||||
SERIAL_ECHOLN((int)READ(Y_MS3_PIN));
|
||||
, '0' + READ(Y_MS3_PIN)
|
||||
#endif
|
||||
);
|
||||
#endif
|
||||
#if HAS_Z_MICROSTEPS
|
||||
SERIAL_ECHOPGM("Z: ");
|
||||
SERIAL_CHAR('0' + READ(Z_MS1_PIN));
|
||||
SERIAL_CHAR('0' + READ(Z_MS2_PIN));
|
||||
SERIAL_CHAR('0' + READ(Z_MS1_PIN), '0' + READ(Z_MS2_PIN)
|
||||
#if PIN_EXISTS(Z_MS3)
|
||||
SERIAL_ECHOLN((int)READ(Z_MS3_PIN));
|
||||
, '0' + READ(Z_MS3_PIN)
|
||||
#endif
|
||||
);
|
||||
#endif
|
||||
#if HAS_E0_MICROSTEPS
|
||||
SERIAL_ECHOPGM("E0: ");
|
||||
SERIAL_CHAR('0' + READ(E0_MS1_PIN));
|
||||
SERIAL_CHAR('0' + READ(E0_MS2_PIN));
|
||||
SERIAL_CHAR('0' + READ(E0_MS1_PIN), '0' + READ(E0_MS2_PIN)
|
||||
#if PIN_EXISTS(E0_MS3)
|
||||
SERIAL_ECHOLN((int)READ(E0_MS3_PIN));
|
||||
, '0' + READ(E0_MS3_PIN)
|
||||
#endif
|
||||
);
|
||||
#endif
|
||||
#if HAS_E1_MICROSTEPS
|
||||
SERIAL_ECHOPGM("E1: ");
|
||||
SERIAL_CHAR('0' + READ(E1_MS1_PIN));
|
||||
SERIAL_CHAR('0' + READ(E1_MS2_PIN));
|
||||
SERIAL_CHAR('0' + READ(E1_MS1_PIN), '0' + READ(E1_MS2_PIN)
|
||||
#if PIN_EXISTS(E1_MS3)
|
||||
SERIAL_ECHOLN((int)READ(E1_MS3_PIN));
|
||||
, '0' + READ(E1_MS3_PIN)
|
||||
#endif
|
||||
);
|
||||
#endif
|
||||
#if HAS_E2_MICROSTEPS
|
||||
SERIAL_ECHOPGM("E2: ");
|
||||
SERIAL_CHAR('0' + READ(E2_MS1_PIN));
|
||||
SERIAL_CHAR('0' + READ(E2_MS2_PIN));
|
||||
SERIAL_CHAR('0' + READ(E2_MS1_PIN), '0' + READ(E2_MS2_PIN)
|
||||
#if PIN_EXISTS(E2_MS3)
|
||||
SERIAL_ECHOLN((int)READ(E2_MS3_PIN));
|
||||
, '0' + READ(E2_MS3_PIN)
|
||||
#endif
|
||||
);
|
||||
#endif
|
||||
#if HAS_E3_MICROSTEPS
|
||||
SERIAL_ECHOPGM("E3: ");
|
||||
SERIAL_CHAR('0' + READ(E3_MS1_PIN));
|
||||
SERIAL_CHAR('0' + READ(E3_MS2_PIN));
|
||||
SERIAL_CHAR('0' + READ(E3_MS1_PIN), '0' + READ(E3_MS2_PIN)
|
||||
#if PIN_EXISTS(E3_MS3)
|
||||
SERIAL_ECHOLN((int)READ(E3_MS3_PIN));
|
||||
, '0' + READ(E3_MS3_PIN)
|
||||
#endif
|
||||
);
|
||||
#endif
|
||||
#if HAS_E4_MICROSTEPS
|
||||
SERIAL_ECHOPGM("E4: ");
|
||||
SERIAL_CHAR('0' + READ(E4_MS1_PIN));
|
||||
SERIAL_CHAR('0' + READ(E4_MS2_PIN));
|
||||
SERIAL_CHAR('0' + READ(E4_MS1_PIN), '0' + READ(E4_MS2_PIN)
|
||||
#if PIN_EXISTS(E4_MS3)
|
||||
SERIAL_ECHOLN((int)READ(E4_MS3_PIN));
|
||||
, '0' + READ(E4_MS3_PIN)
|
||||
#endif
|
||||
);
|
||||
#endif
|
||||
#if HAS_E5_MICROSTEPS
|
||||
SERIAL_ECHOPGM("E5: ");
|
||||
SERIAL_CHAR('0' + READ(E5_MS1_PIN));
|
||||
SERIAL_ECHOLN((int)READ(E5_MS2_PIN));
|
||||
SERIAL_CHAR('0' + READ(E5_MS1_PIN), '0' + READ(E5_MS2_PIN)
|
||||
#if PIN_EXISTS(E5_MS3)
|
||||
SERIAL_ECHOLN((int)READ(E5_MS3_PIN));
|
||||
, '0' + READ(E5_MS3_PIN)
|
||||
#endif
|
||||
);
|
||||
#endif
|
||||
}
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user