Serial refactor. Default 8-bit ECHO to int, not char (#20985)
Co-authored-by: Scott Lahteine <thinkyhead@users.noreply.github.com>
This commit is contained in:
@ -321,6 +321,12 @@
|
||||
namespace Private {
|
||||
template<bool, typename _Tp = void> struct enable_if { };
|
||||
template<typename _Tp> struct enable_if<true, _Tp> { typedef _Tp type; };
|
||||
|
||||
template<typename T, typename U> struct is_same { enum { value = false }; };
|
||||
template<typename T> struct is_same<T, T> { enum { value = true }; };
|
||||
|
||||
template <typename T, typename ... Args> struct first_type_of { typedef T type; };
|
||||
template <typename T> struct first_type_of<T> { typedef T type; };
|
||||
}
|
||||
// C++11 solution using SFINAE to detect the existance of a member in a class at compile time.
|
||||
// It creates a HasMember<Type> structure containing 'value' set to true if the member exists
|
||||
|
@ -59,12 +59,14 @@ void serialprintPGM(PGM_P str) {
|
||||
void serial_echo_start() { static PGMSTR(echomagic, "echo:"); serialprintPGM(echomagic); }
|
||||
void serial_error_start() { static PGMSTR(errormagic, "Error:"); serialprintPGM(errormagic); }
|
||||
|
||||
void serial_echopair_PGM(PGM_P const s_P, serial_char_t v) { serialprintPGM(s_P); SERIAL_CHAR(v.c); }
|
||||
void serial_echopair_PGM(PGM_P const s_P, const char *v) { serialprintPGM(s_P); SERIAL_ECHO(v); }
|
||||
void serial_echopair_PGM(PGM_P const s_P, char v) { serialprintPGM(s_P); SERIAL_CHAR(v); }
|
||||
void serial_echopair_PGM(PGM_P const s_P, char v) { serialprintPGM(s_P); SERIAL_ECHO(v); }
|
||||
void serial_echopair_PGM(PGM_P const s_P, int v) { serialprintPGM(s_P); SERIAL_ECHO(v); }
|
||||
void serial_echopair_PGM(PGM_P const s_P, long v) { serialprintPGM(s_P); SERIAL_ECHO(v); }
|
||||
void serial_echopair_PGM(PGM_P const s_P, float v) { serialprintPGM(s_P); SERIAL_DECIMAL(v); }
|
||||
void serial_echopair_PGM(PGM_P const s_P, double v) { serialprintPGM(s_P); SERIAL_DECIMAL(v); }
|
||||
void serial_echopair_PGM(PGM_P const s_P, unsigned char v) { serialprintPGM(s_P); SERIAL_ECHO(v); }
|
||||
void serial_echopair_PGM(PGM_P const s_P, unsigned int v) { serialprintPGM(s_P); SERIAL_ECHO(v); }
|
||||
void serial_echopair_PGM(PGM_P const s_P, unsigned long v) { serialprintPGM(s_P); SERIAL_ECHO(v); }
|
||||
|
||||
|
@ -81,37 +81,49 @@ typedef int8_t serial_index_t;
|
||||
#define PORT_REDIRECT(p) _PORT_REDIRECT(1,p)
|
||||
#define SERIAL_PORTMASK(P) _BV(P)
|
||||
|
||||
#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)
|
||||
#define SERIAL_PRINT(x,b) SERIAL_OUT(print, x, b)
|
||||
#define SERIAL_PRINTLN(x,b) SERIAL_OUT(println, x, b)
|
||||
#define SERIAL_FLUSH() SERIAL_OUT(flush)
|
||||
//
|
||||
// SERIAL_CHAR - Print one or more individual chars
|
||||
//
|
||||
inline void SERIAL_CHAR(char a) { SERIAL_IMPL.write(a); }
|
||||
template <typename ... Args>
|
||||
void SERIAL_CHAR(char a, Args ... args) { SERIAL_IMPL.write(a); SERIAL_CHAR(args ...); }
|
||||
|
||||
#ifdef ARDUINO_ARCH_STM32
|
||||
#define SERIAL_FLUSHTX() SERIAL_OUT(flush)
|
||||
#elif TX_BUFFER_SIZE > 0
|
||||
#define SERIAL_FLUSHTX() SERIAL_OUT(flushTX)
|
||||
#else
|
||||
#define SERIAL_FLUSHTX()
|
||||
#endif
|
||||
/**
|
||||
* SERIAL_ECHO - Print a single string or value.
|
||||
* Any numeric parameter (including char) is printed as a base-10 number.
|
||||
* A string pointer or literal will be output as a string.
|
||||
*
|
||||
* NOTE: Use SERIAL_CHAR to print char as a single character.
|
||||
*/
|
||||
template <typename T>
|
||||
void SERIAL_ECHO(T x) { SERIAL_IMPL.print(x); }
|
||||
|
||||
// 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)
|
||||
// Wrapper for ECHO commands to interpret a char
|
||||
typedef struct SerialChar { char c; SerialChar(char n) : c(n) { } } serial_char_t;
|
||||
inline void SERIAL_ECHO(serial_char_t x) { SERIAL_IMPL.write(x.c); }
|
||||
#define AS_CHAR(C) serial_char_t(C)
|
||||
|
||||
#define SERIAL_CHAR(V...) _CHAR_N(NUM_ARGS(V),V)
|
||||
// SERIAL_ECHO_F prints a floating point value with optional precision
|
||||
inline void SERIAL_ECHO_F(EnsureDouble x, int digit = 2) { SERIAL_IMPL.print(x, digit); }
|
||||
|
||||
template <typename T>
|
||||
void SERIAL_ECHOLN(T x) { SERIAL_IMPL.println(x); }
|
||||
|
||||
// SERIAL_PRINT works like SERIAL_ECHO but allow to specify the encoding base of the number printed
|
||||
template <typename T, typename U>
|
||||
void SERIAL_PRINT(T x, U y) { SERIAL_IMPL.print(x, y); }
|
||||
|
||||
template <typename T, typename U>
|
||||
void SERIAL_PRINTLN(T x, U y) { SERIAL_IMPL.println(x, y); }
|
||||
|
||||
// Flush the serial port
|
||||
inline void SERIAL_FLUSH() { SERIAL_IMPL.flush(); }
|
||||
inline void SERIAL_FLUSHTX() { SERIAL_IMPL.flushTX(); }
|
||||
|
||||
// Print a single PROGMEM string to serial
|
||||
void serialprintPGM(PGM_P str);
|
||||
|
||||
// SERIAL_ECHOPAIR / SERIAL_ECHOPAIR_P is used to output a key value pair. The key must be a string and the value can be anything
|
||||
// Print up to 12 pairs of values. Odd elements auto-wrapped in PSTR().
|
||||
#define __SEP_N(N,V...) _SEP_##N(V)
|
||||
#define _SEP_N(N,V...) __SEP_N(N,V)
|
||||
@ -170,6 +182,7 @@ typedef int8_t serial_index_t;
|
||||
#define _SEP_23_P(a,b,V...) do{ _SEP_2_P(a,b); _SEP_21_P(V); }while(0)
|
||||
#define _SEP_24_P(a,b,V...) do{ _SEP_2_P(a,b); _SEP_22_P(V); }while(0)
|
||||
|
||||
// SERIAL_ECHOPAIR_P is used to output a key value pair. Unlike SERIAL_ECHOPAIR, the key must be a PGM string already and the value can be anything
|
||||
#define SERIAL_ECHOPAIR_P(V...) _SEP_N_P(NUM_ARGS(V),V)
|
||||
|
||||
// Print up to 12 pairs of values followed by newline
|
||||
@ -244,32 +257,39 @@ typedef int8_t serial_index_t;
|
||||
|
||||
#define SERIAL_ECHOLNPAIR_P(V...) _SELP_N_P(NUM_ARGS(V),V)
|
||||
|
||||
// Print up to 20 comma-separated pairs of values
|
||||
#define __SLST_N(N,V...) _SLST_##N(V)
|
||||
#define _SLST_N(N,V...) __SLST_N(N,V)
|
||||
#define _SLST_1(a) SERIAL_ECHO(a)
|
||||
#define _SLST_2(a,b) do{ SERIAL_ECHO(a); SERIAL_ECHOPAIR(", ",b); }while(0)
|
||||
#define _SLST_3(a,b,c) do{ SERIAL_ECHO(a); _SEP_2(", ",b); _SLST_1(c); }while(0)
|
||||
#define _SLST_4(a,b,V...) do{ SERIAL_ECHO(a); _SEP_2(", ",b); _SLST_2(V); }while(0)
|
||||
#define _SLST_5(a,b,V...) do{ SERIAL_ECHO(a); _SEP_2(", ",b); _SLST_3(V); }while(0)
|
||||
#define _SLST_6(a,b,V...) do{ SERIAL_ECHO(a); _SEP_2(", ",b); _SLST_4(V); }while(0)
|
||||
#define _SLST_7(a,b,V...) do{ SERIAL_ECHO(a); _SEP_2(", ",b); _SLST_5(V); }while(0)
|
||||
#define _SLST_8(a,b,V...) do{ SERIAL_ECHO(a); _SEP_2(", ",b); _SLST_6(V); }while(0)
|
||||
#define _SLST_9(a,b,V...) do{ SERIAL_ECHO(a); _SEP_2(", ",b); _SLST_7(V); }while(0)
|
||||
#define _SLST_10(a,b,V...) do{ SERIAL_ECHO(a); _SEP_2(", ",b); _SLST_8(V); }while(0)
|
||||
#define _SLST_11(a,b,V...) do{ SERIAL_ECHO(a); _SEP_2(", ",b); _SLST_9(V); }while(0)
|
||||
#define _SLST_12(a,b,V...) do{ SERIAL_ECHO(a); _SEP_2(", ",b); _SLST_10(V); }while(0)
|
||||
#define _SLST_13(a,b,V...) do{ SERIAL_ECHO(a); _SEP_2(", ",b); _SLST_11(V); }while(0)
|
||||
#define _SLST_14(a,b,V...) do{ SERIAL_ECHO(a); _SEP_2(", ",b); _SLST_12(V); }while(0)
|
||||
#define _SLST_15(a,b,V...) do{ SERIAL_ECHO(a); _SEP_2(", ",b); _SLST_13(V); }while(0)
|
||||
#define _SLST_16(a,b,V...) do{ SERIAL_ECHO(a); _SEP_2(", ",b); _SLST_14(V); }while(0)
|
||||
#define _SLST_17(a,b,V...) do{ SERIAL_ECHO(a); _SEP_2(", ",b); _SLST_15(V); }while(0)
|
||||
#define _SLST_18(a,b,V...) do{ SERIAL_ECHO(a); _SEP_2(", ",b); _SLST_16(V); }while(0)
|
||||
#define _SLST_19(a,b,V...) do{ SERIAL_ECHO(a); _SEP_2(", ",b); _SLST_17(V); }while(0)
|
||||
#define _SLST_20(a,b,V...) do{ SERIAL_ECHO(a); _SEP_2(", ",b); _SLST_18(V); }while(0) // Eat two args, pass the rest up
|
||||
#ifdef AllowDifferentTypeInList
|
||||
|
||||
#define SERIAL_ECHOLIST(pre,V...) do{ SERIAL_ECHOPGM(pre); _SLST_N(NUM_ARGS(V),V); }while(0)
|
||||
#define SERIAL_ECHOLIST_N(N,V...) _SLST_N(N,LIST_N(N,V))
|
||||
inline void SERIAL_ECHOLIST_IMPL() {}
|
||||
template <typename T>
|
||||
void SERIAL_ECHOLIST_IMPL(T && t) { SERIAL_IMPL.print(t); }
|
||||
|
||||
template <typename T, typename ... Args>
|
||||
void SERIAL_ECHOLIST_IMPL(T && t, Args && ... args) {
|
||||
SERIAL_IMPL.print(t);
|
||||
serialprintPGM(PSTR(", "));
|
||||
SERIAL_ECHOLIST_IMPL(args...);
|
||||
}
|
||||
|
||||
template <typename ... Args>
|
||||
void SERIAL_ECHOLIST(PGM_P const str, Args && ... args) {
|
||||
SERIAL_IMPL.print(str);
|
||||
SERIAL_ECHOLIST_IMPL(args...);
|
||||
}
|
||||
|
||||
#else // Optimization if the listed type are all the same (seems to be the case in the codebase so use that instead)
|
||||
|
||||
template <typename ... Args>
|
||||
void SERIAL_ECHOLIST(PGM_P const str, Args && ... args) {
|
||||
serialprintPGM(str);
|
||||
typename Private::first_type_of<Args...>::type values[] = { args... };
|
||||
constexpr size_t argsSize = sizeof...(args);
|
||||
for (size_t i = 0; i < argsSize; i++) {
|
||||
if (i) serialprintPGM(PSTR(", "));
|
||||
SERIAL_IMPL.print(values[i]);
|
||||
}
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
#define SERIAL_ECHOPGM_P(P) (serialprintPGM(P))
|
||||
#define SERIAL_ECHOLNPGM_P(P) (serialprintPGM(P "\n"))
|
||||
@ -303,19 +323,19 @@ typedef int8_t serial_index_t;
|
||||
//
|
||||
// Functions for serial printing from PROGMEM. (Saves loads of SRAM.)
|
||||
//
|
||||
void serial_echopair_PGM(PGM_P const s_P, serial_char_t v);
|
||||
void serial_echopair_PGM(PGM_P const s_P, const char *v);
|
||||
void serial_echopair_PGM(PGM_P const s_P, char v);
|
||||
void serial_echopair_PGM(PGM_P const s_P, int v);
|
||||
void serial_echopair_PGM(PGM_P const s_P, unsigned int v);
|
||||
void serial_echopair_PGM(PGM_P const s_P, long v);
|
||||
void serial_echopair_PGM(PGM_P const s_P, unsigned long v);
|
||||
void serial_echopair_PGM(PGM_P const s_P, float v);
|
||||
void serial_echopair_PGM(PGM_P const s_P, double v);
|
||||
inline void serial_echopair_PGM(PGM_P const s_P, uint8_t v) { serial_echopair_PGM(s_P, (int)v); }
|
||||
void serial_echopair_PGM(PGM_P const s_P, unsigned char v);
|
||||
void serial_echopair_PGM(PGM_P const s_P, unsigned int v);
|
||||
void serial_echopair_PGM(PGM_P const s_P, unsigned long v);
|
||||
inline void serial_echopair_PGM(PGM_P const s_P, bool v) { serial_echopair_PGM(s_P, (int)v); }
|
||||
inline void serial_echopair_PGM(PGM_P const s_P, void *v) { serial_echopair_PGM(s_P, (uintptr_t)v); }
|
||||
|
||||
void serialprintPGM(PGM_P str);
|
||||
void serial_echo_start();
|
||||
void serial_error_start();
|
||||
void serial_ternary(const bool onoff, PGM_P const pre, PGM_P const on, PGM_P const off, PGM_P const post=nullptr);
|
||||
|
@ -22,25 +22,41 @@
|
||||
#pragma once
|
||||
|
||||
#include "../inc/MarlinConfigPre.h"
|
||||
#include "macros.h"
|
||||
|
||||
#if ENABLED(EMERGENCY_PARSER)
|
||||
#include "../feature/e_parser.h"
|
||||
#endif
|
||||
|
||||
#ifndef DEC
|
||||
#define DEC 10
|
||||
#define HEX 16
|
||||
#define OCT 8
|
||||
#define BIN 2
|
||||
#endif
|
||||
|
||||
// flushTX is not implemented in all HAL, so use SFINAE to call the method where it is.
|
||||
CALL_IF_EXISTS_IMPL(void, flushTX );
|
||||
CALL_IF_EXISTS_IMPL(bool, connected, true);
|
||||
|
||||
// In order to catch usage errors in code, we make the base to encode number explicit
|
||||
// If given a number (and not this enum), the compiler will reject the overload, falling back to the (double, digit) version
|
||||
// We don't want hidden conversion of the first parameter to double, so it has to be as hard to do for the compiler as creating this enum
|
||||
enum class PrintBase {
|
||||
Dec = 10,
|
||||
Hex = 16,
|
||||
Oct = 8,
|
||||
Bin = 2
|
||||
};
|
||||
|
||||
// A simple forward struct that prevent the compiler to select print(double, int) as a default overload for any type different than
|
||||
// double or float. For double or float, a conversion exists so the call will be transparent
|
||||
struct EnsureDouble {
|
||||
double a;
|
||||
FORCE_INLINE operator double() { return a; }
|
||||
// If the compiler breaks on ambiguity here, it's likely because you're calling print(X, base) with X not a double or a float, and a
|
||||
// base that's not one of PrintBase's value. This exact code is made to detect such error, you NEED to set a base explicitely like this:
|
||||
// SERIAL_PRINT(v, PrintBase::Hex)
|
||||
FORCE_INLINE EnsureDouble(double a) : a(a) {}
|
||||
FORCE_INLINE EnsureDouble(float a) : a(a) {}
|
||||
};
|
||||
|
||||
// Using Curiously Recurring Template Pattern here to avoid virtual table cost when compiling.
|
||||
// Since the real serial class is known at compile time, this results in compiler writing a completely
|
||||
// efficient code
|
||||
// Since the real serial class is known at compile time, this results in the compiler writing
|
||||
// a completely efficient code.
|
||||
template <class Child>
|
||||
struct SerialBase {
|
||||
#if ENABLED(EMERGENCY_PARSER)
|
||||
@ -78,39 +94,47 @@ struct SerialBase {
|
||||
FORCE_INLINE void write(const char* str) { while (*str) write(*str++); }
|
||||
FORCE_INLINE void write(const uint8_t* buffer, size_t size) { while (size--) write(*buffer++); }
|
||||
FORCE_INLINE void print(const char* str) { write(str); }
|
||||
NO_INLINE void print(char c, int base = 0) { print((long)c, base); }
|
||||
NO_INLINE void print(unsigned char c, int base = 0) { print((unsigned long)c, base); }
|
||||
NO_INLINE void print(int c, int base = DEC) { print((long)c, base); }
|
||||
NO_INLINE void print(unsigned int c, int base = DEC) { print((unsigned long)c, base); }
|
||||
void print(unsigned long c, int base = DEC) { printNumber(c, base); }
|
||||
void print(double c, int digits = 2) { printFloat(c, digits); }
|
||||
void print(long c, int base = DEC) {
|
||||
if (!base) {
|
||||
write(c);
|
||||
return;
|
||||
}
|
||||
if (base == DEC && c < 0) {
|
||||
write((uint8_t)'-'); c = -c;
|
||||
}
|
||||
printNumber(c, base);
|
||||
}
|
||||
// No default argument to avoid ambiguity
|
||||
NO_INLINE void print(char c, PrintBase base) { printNumber((signed long)c, (uint8_t)base); }
|
||||
NO_INLINE void print(unsigned char c, PrintBase base) { printNumber((unsigned long)c, (uint8_t)base); }
|
||||
NO_INLINE void print(int c, PrintBase base) { printNumber((signed long)c, (uint8_t)base); }
|
||||
NO_INLINE void print(unsigned int c, PrintBase base) { printNumber((unsigned long)c, (uint8_t)base); }
|
||||
void print(unsigned long c, PrintBase base) { printNumber((unsigned long)c, (uint8_t)base); }
|
||||
void print(long c, PrintBase base) { printNumber((signed long)c, (uint8_t)base); }
|
||||
void print(EnsureDouble c, int digits) { printFloat(c, digits); }
|
||||
|
||||
NO_INLINE void println(const char s[]) { print(s); println(); }
|
||||
NO_INLINE void println(char c, int base = 0) { print(c, base); println(); }
|
||||
NO_INLINE void println(unsigned char c, int base = 0) { print(c, base); println(); }
|
||||
NO_INLINE void println(int c, int base = DEC) { print(c, base); println(); }
|
||||
NO_INLINE void println(unsigned int c, int base = DEC) { print(c, base); println(); }
|
||||
NO_INLINE void println(long c, int base = DEC) { print(c, base); println(); }
|
||||
NO_INLINE void println(unsigned long c, int base = DEC) { print(c, base); println(); }
|
||||
NO_INLINE void println(double c, int digits = 2) { print(c, digits); println(); }
|
||||
NO_INLINE void println() { write('\r'); write('\n'); }
|
||||
// Forward the call to the former's method
|
||||
FORCE_INLINE void print(char c) { print(c, PrintBase::Dec); }
|
||||
FORCE_INLINE void print(unsigned char c) { print(c, PrintBase::Dec); }
|
||||
FORCE_INLINE void print(int c) { print(c, PrintBase::Dec); }
|
||||
FORCE_INLINE void print(unsigned int c) { print(c, PrintBase::Dec); }
|
||||
FORCE_INLINE void print(unsigned long c) { print(c, PrintBase::Dec); }
|
||||
FORCE_INLINE void print(long c) { print(c, PrintBase::Dec); }
|
||||
FORCE_INLINE void print(double c) { print(c, 2); }
|
||||
|
||||
FORCE_INLINE void println(const char s[]) { print(s); println(); }
|
||||
FORCE_INLINE void println(char c, PrintBase base) { print(c, base); println(); }
|
||||
FORCE_INLINE void println(unsigned char c, PrintBase base) { print(c, base); println(); }
|
||||
FORCE_INLINE void println(int c, PrintBase base) { print(c, base); println(); }
|
||||
FORCE_INLINE void println(unsigned int c, PrintBase base) { print(c, base); println(); }
|
||||
FORCE_INLINE void println(long c, PrintBase base) { print(c, base); println(); }
|
||||
FORCE_INLINE void println(unsigned long c, PrintBase base) { print(c, base); println(); }
|
||||
FORCE_INLINE void println(double c, int digits) { print(c, digits); println(); }
|
||||
FORCE_INLINE void println() { write('\r'); write('\n'); }
|
||||
|
||||
// Forward the call to the former's method
|
||||
FORCE_INLINE void println(char c) { println(c, PrintBase::Dec); }
|
||||
FORCE_INLINE void println(unsigned char c) { println(c, PrintBase::Dec); }
|
||||
FORCE_INLINE void println(int c) { println(c, PrintBase::Dec); }
|
||||
FORCE_INLINE void println(unsigned int c) { println(c, PrintBase::Dec); }
|
||||
FORCE_INLINE void println(unsigned long c) { println(c, PrintBase::Dec); }
|
||||
FORCE_INLINE void println(long c) { println(c, PrintBase::Dec); }
|
||||
FORCE_INLINE void println(double c) { println(c, 2); }
|
||||
|
||||
// Print a number with the given base
|
||||
void printNumber(unsigned long n, const uint8_t base) {
|
||||
if (!base) {
|
||||
write((uint8_t)n);
|
||||
return;
|
||||
}
|
||||
NO_INLINE void printNumber(unsigned long n, const uint8_t base) {
|
||||
if (!base) return; // Hopefully, this should raise visible bug immediately
|
||||
|
||||
if (n) {
|
||||
unsigned char buf[8 * sizeof(long)]; // Enough space for base 2
|
||||
int8_t i = 0;
|
||||
@ -122,9 +146,19 @@ struct SerialBase {
|
||||
}
|
||||
else write('0');
|
||||
}
|
||||
void printNumber(signed long n, const uint8_t base) {
|
||||
if (base == 10 && n < 0) {
|
||||
n = -n; // This works because all platforms Marlin's builds on are using 2-complement encoding for negative number
|
||||
// On such CPU, changing the sign of a number is done by inverting the bits and adding one, so if n = 0x80000000 = -2147483648 then
|
||||
// -n = 0x7FFFFFFF + 1 => 0x80000000 = 2147483648 (if interpreted as unsigned) or -2147483648 if interpreted as signed.
|
||||
// On non 2-complement CPU, there would be no possible representation for 2147483648.
|
||||
write('-');
|
||||
}
|
||||
printNumber((unsigned long)n , base);
|
||||
}
|
||||
|
||||
// Print a decimal number
|
||||
void printFloat(double number, uint8_t digits) {
|
||||
NO_INLINE void printFloat(double number, uint8_t digits) {
|
||||
// Handle negative numbers
|
||||
if (number < 0.0) {
|
||||
write('-');
|
||||
@ -147,7 +181,7 @@ struct SerialBase {
|
||||
// Extract digits from the remainder one at a time
|
||||
while (digits--) {
|
||||
remainder *= 10.0;
|
||||
int toPrint = int(remainder);
|
||||
unsigned long toPrint = (unsigned long)remainder;
|
||||
printNumber(toPrint, 10);
|
||||
remainder -= toPrint;
|
||||
}
|
||||
@ -155,5 +189,5 @@ struct SerialBase {
|
||||
}
|
||||
};
|
||||
|
||||
// All serial instances will be built by chaining the features required for the function in a form of a template
|
||||
// type definition
|
||||
// All serial instances will be built by chaining the features required
|
||||
// for the function in the form of a template type definition.
|
||||
|
@ -21,6 +21,7 @@
|
||||
*/
|
||||
#pragma once
|
||||
|
||||
#include "macros.h"
|
||||
#include "serial_base.h"
|
||||
|
||||
// The most basic serial class: it dispatch to the base serial class with no hook whatsoever. This will compile to nothing but the base serial class
|
||||
@ -37,6 +38,8 @@ struct BaseSerial : public SerialBase< BaseSerial<SerialT> >, public SerialT {
|
||||
bool available(uint8_t index) { return index == 0 && SerialT::available(); }
|
||||
int read(uint8_t index) { return index == 0 ? SerialT::read() : -1; }
|
||||
bool connected() { return CALL_IF_EXISTS(bool, static_cast<SerialT*>(this), connected);; }
|
||||
void flushTX() { CALL_IF_EXISTS(void, static_cast<SerialT*>(this), flushTX); }
|
||||
|
||||
// We have 2 implementation of the same method in both base class, let's say which one we want
|
||||
using SerialT::available;
|
||||
using SerialT::read;
|
||||
@ -68,6 +71,7 @@ struct ConditionalSerial : public SerialBase< ConditionalSerial<SerialT> > {
|
||||
|
||||
void msgDone() {}
|
||||
bool connected() { return CALL_IF_EXISTS(bool, &out, connected); }
|
||||
void flushTX() { CALL_IF_EXISTS(void, &out, flushTX); }
|
||||
|
||||
bool available(uint8_t index) { return index == 0 && out.available(); }
|
||||
int read(uint8_t index) { return index == 0 ? out.read() : -1; }
|
||||
@ -91,6 +95,7 @@ struct ForwardSerial : public SerialBase< ForwardSerial<SerialT> > {
|
||||
void msgDone() {}
|
||||
// Existing instances implement Arduino's operator bool, so use that if it's available
|
||||
bool connected() { return Private::HasMember_connected<SerialT>::value ? CALL_IF_EXISTS(bool, &out, connected) : (bool)out; }
|
||||
void flushTX() { CALL_IF_EXISTS(void, &out, flushTX); }
|
||||
|
||||
bool available(uint8_t index) { return index == 0 && out.available(); }
|
||||
int read(uint8_t index) { return index == 0 ? out.read() : -1; }
|
||||
@ -131,11 +136,11 @@ struct RuntimeSerial : public SerialBase< RuntimeSerial<SerialT> >, public Seria
|
||||
using BaseClassT::print;
|
||||
using BaseClassT::println;
|
||||
|
||||
|
||||
// Underlying implementation might use Arduino's bool operator
|
||||
bool connected() {
|
||||
return Private::HasMember_connected<SerialT>::value ? CALL_IF_EXISTS(bool, static_cast<SerialT*>(this), connected) : static_cast<SerialT*>(this)->operator bool();
|
||||
}
|
||||
void flushTX() { CALL_IF_EXISTS(void, static_cast<SerialT*>(this), flushTX); }
|
||||
|
||||
void setHook(WriteHook writeHook = 0, EndOfMessageHook eofHook = 0, void * userPointer = 0) {
|
||||
// Order is important here as serial code can be called inside interrupts
|
||||
|
Reference in New Issue
Block a user