Browse Source

Merge branch '2.1.x' into vanilla_fb_2.1.x

FB4S_WIFI
Sergey Terentiev 2 years ago
parent
commit
b4f15d867f
  1. 2
      .github/contributing.md
  2. 7
      Marlin/Configuration.h
  3. 13
      Marlin/Configuration_adv.h
  4. 2
      Marlin/Makefile
  5. 202
      Marlin/src/HAL/AVR/Servo.cpp
  6. 138
      Marlin/src/HAL/DUE/Servo.cpp
  7. 2
      Marlin/src/HAL/DUE/ServoTimers.h
  8. 11
      Marlin/src/HAL/DUE/timers.cpp
  9. 3
      Marlin/src/HAL/DUE/timers.h
  10. 2
      Marlin/src/HAL/DUE/usb/compiler.h
  11. 50
      Marlin/src/HAL/ESP32/HAL.cpp
  12. 11
      Marlin/src/HAL/ESP32/HAL.h
  13. 20
      Marlin/src/HAL/ESP32/i2s.cpp
  14. 7
      Marlin/src/HAL/ESP32/inc/Conditionals_adv.h
  15. 4
      Marlin/src/HAL/ESP32/inc/SanityCheck.h
  16. 16
      Marlin/src/HAL/LINUX/eeprom.cpp
  17. 4
      Marlin/src/HAL/LINUX/hardware/Heater.h
  18. 45
      Marlin/src/HAL/SAMD51/Servo.cpp
  19. 16
      Marlin/src/HAL/STM32/tft/gt911.cpp
  20. 2
      Marlin/src/HAL/STM32/tft/gt911.h
  21. 16
      Marlin/src/HAL/STM32F1/Servo.cpp
  22. 4
      Marlin/src/HAL/shared/backtrace/unwarmbytab.cpp
  23. 13
      Marlin/src/HAL/shared/servo.cpp
  24. 12
      Marlin/src/HAL/shared/servo_private.h
  25. 4
      Marlin/src/MarlinCore.cpp
  26. 2
      Marlin/src/core/boards.h
  27. 5
      Marlin/src/core/macros.h
  28. 4
      Marlin/src/core/serial.cpp
  29. 8
      Marlin/src/core/types.h
  30. 18
      Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp
  31. 2
      Marlin/src/feature/bltouch.cpp
  32. 113
      Marlin/src/feature/max7219.cpp
  33. 79
      Marlin/src/feature/max7219.h
  34. 10
      Marlin/src/feature/pause.cpp
  35. 6
      Marlin/src/feature/power_monitor.cpp
  36. 2
      Marlin/src/feature/power_monitor.h
  37. 4
      Marlin/src/feature/spindle_laser.cpp
  38. 4
      Marlin/src/gcode/calibrate/G28.cpp
  39. 2
      Marlin/src/gcode/calibrate/G33.cpp
  40. 8
      Marlin/src/gcode/config/M43.cpp
  41. 6
      Marlin/src/gcode/control/M280.cpp
  42. 2
      Marlin/src/gcode/control/M282.cpp
  43. 18
      Marlin/src/gcode/feature/trinamic/M919.cpp
  44. 4
      Marlin/src/gcode/gcode.cpp
  45. 197
      Marlin/src/gcode/motion/G2_G3.cpp
  46. 2
      Marlin/src/gcode/motion/G6.cpp
  47. 5
      Marlin/src/gcode/queue.cpp
  48. 3
      Marlin/src/gcode/queue.h
  49. 4
      Marlin/src/gcode/temp/M106_M107.cpp
  50. 6
      Marlin/src/gcode/units/M149.cpp
  51. 11
      Marlin/src/inc/Conditionals_LCD.h
  52. 8
      Marlin/src/inc/Conditionals_adv.h
  53. 10
      Marlin/src/inc/SanityCheck.h
  54. 12
      Marlin/src/lcd/HD44780/lcdprint_hd44780.cpp
  55. 138
      Marlin/src/lcd/HD44780/marlinui_HD44780.cpp
  56. 12
      Marlin/src/lcd/TFTGLCD/lcdprint_TFTGLCD.cpp
  57. 18
      Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp
  58. 2
      Marlin/src/lcd/dogm/HAL_LCD_com_defines.h
  59. 2
      Marlin/src/lcd/dogm/lcdprint_u8g.cpp
  60. 36
      Marlin/src/lcd/dogm/marlinui_DOGM.cpp
  61. 44
      Marlin/src/lcd/dogm/status_screen_DOGM.cpp
  62. 26
      Marlin/src/lcd/dogm/u8g_fontutf8.cpp
  63. 2
      Marlin/src/lcd/dogm/u8g_fontutf8.h
  64. 2
      Marlin/src/lcd/e3v2/README.md
  65. 10
      Marlin/src/lcd/e3v2/common/dwin_api.h
  66. 10
      Marlin/src/lcd/e3v2/creality/dwin.cpp
  67. 2
      Marlin/src/lcd/e3v2/jyersui/README.md
  68. 18
      Marlin/src/lcd/e3v2/jyersui/dwin.cpp
  69. 26
      Marlin/src/lcd/e3v2/marlinui/dwin_string.cpp
  70. 8
      Marlin/src/lcd/e3v2/marlinui/dwin_string.h
  71. 10
      Marlin/src/lcd/e3v2/marlinui/lcdprint_dwin.cpp
  72. 23
      Marlin/src/lcd/e3v2/marlinui/ui_common.cpp
  73. 20
      Marlin/src/lcd/e3v2/marlinui/ui_status_480x272.cpp
  74. 5
      Marlin/src/lcd/e3v2/proui/gcode_preview.cpp
  75. 13
      Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp
  76. 4
      Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.h
  77. 33
      Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp
  78. 22
      Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/printing_dialog_box.cpp
  79. 6
      Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/status_screen.cpp
  80. 4
      Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h
  81. 10
      Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.cpp
  82. 10
      Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.cpp
  83. 5
      Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/dialog_box_base_class.cpp
  84. 7
      Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/dialog_box_base_class.h
  85. 12
      Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/status_screen.cpp
  86. 16
      Marlin/src/lcd/extui/mks_ui/mks_hardware.cpp
  87. 2
      Marlin/src/lcd/extui/mks_ui/wifi_module.cpp
  88. 20
      Marlin/src/lcd/extui/ui_api.cpp
  89. 6
      Marlin/src/lcd/fontutils.cpp
  90. 27
      Marlin/src/lcd/fontutils.h
  91. 2
      Marlin/src/lcd/language/language_cz.h
  92. 2
      Marlin/src/lcd/language/language_de.h
  93. 4
      Marlin/src/lcd/language/language_en.h
  94. 2
      Marlin/src/lcd/language/language_es.h
  95. 1
      Marlin/src/lcd/language/language_eu.h
  96. 2
      Marlin/src/lcd/language/language_fr.h
  97. 2
      Marlin/src/lcd/language/language_gl.h
  98. 2
      Marlin/src/lcd/language/language_hu.h
  99. 83
      Marlin/src/lcd/language/language_it.h
  100. 2
      Marlin/src/lcd/language/language_nl.h

2
.github/contributing.md

@ -116,7 +116,7 @@ Unsure where to begin contributing to Marlin? You can start by looking through t
### Pull Requests
Pull Requests should always be targeted to working branches (e.g., `bugfix-2.0.x` and/or `bugfix-1.1.x`) and never to release branches (e.g., `2.0.x` and/or `1.1.x`). If this is your first Pull Request, please read our [Guide to Pull Requests](https://marlinfw.org/docs/development/getting_started_pull_requests.html) and Github's [Pull Request](https://help.github.com/articles/creating-a-pull-request/) documentation.
Pull Requests should always be targeted to working branches (e.g., `bugfix-2.1.x` and/or `bugfix-1.1.x`) and never to release branches (e.g., `2.0.x` and/or `1.1.x`). If this is your first Pull Request, please read our [Guide to Pull Requests](https://marlinfw.org/docs/development/getting_started_pull_requests.html) and Github's [Pull Request](https://help.github.com/articles/creating-a-pull-request/) documentation.
* Fill in [the required template](pull_request_template.md).
* Don't include issue numbers in the PR title.

7
Marlin/Configuration.h

@ -864,6 +864,13 @@
#define POLAR_SEGMENTS_PER_SECOND 5
#endif
// Enable for an articulated robot (robot arm). Joints are directly mapped to axes (no kinematics).
//#define ARTICULATED_ROBOT_ARM
// For a hot wire cutter with parallel horizontal axes (X, I) where the heights of the two wire
// ends are controlled by parallel axes (Y, J). Joints are directly mapped to axes (no kinematics).
//#define FOAMCUTTER_XYUV
//===========================================================================
//============================== Endstop Settings ===========================
//===========================================================================

13
Marlin/Configuration_adv.h

@ -3592,6 +3592,9 @@
#if ENABLED(SPINDLE_LASER_USE_PWM)
#define SPINDLE_LASER_PWM_INVERT false // Set to "true" if the speed/power goes up when you want it to go slower
#define SPINDLE_LASER_FREQUENCY 2500 // (Hz) Spindle/laser frequency (only on supported HALs: AVR, ESP32, and LPC)
// ESP32: If SPINDLE_LASER_PWM_PIN is onboard then <=78125Hz. For I2S expander
// the frequency determines the PWM resolution. 2500Hz = 0-100, 977Hz = 0-255, ...
// (250000 / SPINDLE_LASER_FREQUENCY) = max value.
#endif
//#define AIR_EVACUATION // Cutter Vacuum / Laser Blower motor control with G-codes M10-M11
@ -4286,7 +4289,8 @@
#define MAX7219_NUMBER_UNITS 1 // Number of Max7219 units in chain.
#define MAX7219_ROTATE 0 // Rotate the display clockwise (in multiples of +/- 90°)
// connector at: right=0 bottom=-90 top=90 left=180
//#define MAX7219_REVERSE_ORDER // The individual LED matrix units may be in reversed order
//#define MAX7219_REVERSE_ORDER // The order of the LED matrix units may be reversed
//#define MAX7219_REVERSE_EACH // The LEDs in each matrix unit row may be reversed
//#define MAX7219_SIDE_BY_SIDE // Big chip+matrix boards can be chained side-by-side
/**
@ -4294,12 +4298,15 @@
* If you add more debug displays, be careful to avoid conflicts!
*/
#define MAX7219_DEBUG_PRINTER_ALIVE // Blink corner LED of 8x8 matrix to show that the firmware is functioning
#define MAX7219_DEBUG_PLANNER_HEAD 3 // Show the planner queue head position on this and the next LED matrix row
#define MAX7219_DEBUG_PLANNER_TAIL 5 // Show the planner queue tail position on this and the next LED matrix row
#define MAX7219_DEBUG_PLANNER_HEAD 2 // Show the planner queue head position on this and the next LED matrix row
#define MAX7219_DEBUG_PLANNER_TAIL 4 // Show the planner queue tail position on this and the next LED matrix row
#define MAX7219_DEBUG_PLANNER_QUEUE 0 // Show the current planner queue depth on this and the next LED matrix row
// If you experience stuttering, reboots, etc. this option can reveal how
// tweaks made to the configuration are affecting the printer in real-time.
#define MAX7219_DEBUG_PROFILE 6 // Display the fraction of CPU time spent in profiled code on this LED matrix
// row. By default idle() is profiled so this shows how "idle" the processor is.
// See class CodeProfiler.
#endif
/**

2
Marlin/Makefile

@ -109,7 +109,7 @@ LIQUID_TWI2 ?= 0
# This defines if Wire is needed
WIRE ?= 0
# This defines if Tone is needed (i.e SPEAKER is defined in Configuration.h)
# This defines if Tone is needed (i.e., SPEAKER is defined in Configuration.h)
# Disabling this (and SPEAKER) saves approximately 350 bytes of memory.
TONE ?= 1

202
Marlin/src/HAL/AVR/Servo.cpp

@ -66,27 +66,26 @@ static volatile int8_t Channel[_Nbr_16timers]; // counter for the s
/************ static functions common to all instances ***********************/
static inline void handle_interrupts(timer16_Sequence_t timer, volatile uint16_t* TCNTn, volatile uint16_t* OCRnA) {
if (Channel[timer] < 0)
*TCNTn = 0; // channel set to -1 indicated that refresh interval completed so reset the timer
else {
if (SERVO_INDEX(timer, Channel[timer]) < ServoCount && SERVO(timer, Channel[timer]).Pin.isActive)
extDigitalWrite(SERVO(timer, Channel[timer]).Pin.nbr, LOW); // pulse this channel low if activated
}
Channel[timer]++; // increment to the next channel
if (SERVO_INDEX(timer, Channel[timer]) < ServoCount && Channel[timer] < SERVOS_PER_TIMER) {
*OCRnA = *TCNTn + SERVO(timer, Channel[timer]).ticks;
if (SERVO(timer, Channel[timer]).Pin.isActive) // check if activated
extDigitalWrite(SERVO(timer, Channel[timer]).Pin.nbr, HIGH); // it's an active channel so pulse it high
static inline void handle_interrupts(const timer16_Sequence_t timer, volatile uint16_t* TCNTn, volatile uint16_t* OCRnA) {
int8_t cho = Channel[timer]; // Handle the prior Channel[timer] first
if (cho < 0) // Channel -1 indicates the refresh interval completed...
*TCNTn = 0; // ...so reset the timer
else if (SERVO_INDEX(timer, cho) < ServoCount) // prior channel handled?
extDigitalWrite(SERVO(timer, cho).Pin.nbr, LOW); // pulse the prior channel LOW
Channel[timer] = ++cho; // Handle the next channel (or 0)
if (cho < SERVOS_PER_TIMER && SERVO_INDEX(timer, cho) < ServoCount) {
*OCRnA = *TCNTn + SERVO(timer, cho).ticks; // set compare to current ticks plus duration
if (SERVO(timer, cho).Pin.isActive) // activated?
extDigitalWrite(SERVO(timer, cho).Pin.nbr, HIGH); // yes: pulse HIGH
}
else {
// finished all channels so wait for the refresh period to expire before starting over
if (((unsigned)*TCNTn) + 4 < usToTicks(REFRESH_INTERVAL)) // allow a few ticks to ensure the next OCR1A not missed
*OCRnA = (unsigned int)usToTicks(REFRESH_INTERVAL);
else
*OCRnA = *TCNTn + 4; // at least REFRESH_INTERVAL has elapsed
Channel[timer] = -1; // this will get incremented at the end of the refresh period to start again at the first channel
const unsigned int cval = ((unsigned)*TCNTn) + 32 / (SERVO_TIMER_PRESCALER), // allow 32 cycles to ensure the next OCR1A not missed
ival = (unsigned int)usToTicks(REFRESH_INTERVAL); // at least REFRESH_INTERVAL has elapsed
*OCRnA = max(cval, ival);
Channel[timer] = -1; // reset the timer counter to 0 on the next call
}
}
@ -123,91 +122,102 @@ static inline void handle_interrupts(timer16_Sequence_t timer, volatile uint16_t
/****************** end of static functions ******************************/
void initISR(timer16_Sequence_t timer) {
#ifdef _useTimer1
if (timer == _timer1) {
TCCR1A = 0; // normal counting mode
TCCR1B = _BV(CS11); // set prescaler of 8
TCNT1 = 0; // clear the timer count
#if defined(__AVR_ATmega8__) || defined(__AVR_ATmega128__)
SBI(TIFR, OCF1A); // clear any pending interrupts;
SBI(TIMSK, OCIE1A); // enable the output compare interrupt
#else
// here if not ATmega8 or ATmega128
SBI(TIFR1, OCF1A); // clear any pending interrupts;
SBI(TIMSK1, OCIE1A); // enable the output compare interrupt
#endif
#ifdef WIRING
timerAttach(TIMER1OUTCOMPAREA_INT, Timer1Service);
#endif
}
#endif
#ifdef _useTimer3
if (timer == _timer3) {
TCCR3A = 0; // normal counting mode
TCCR3B = _BV(CS31); // set prescaler of 8
TCNT3 = 0; // clear the timer count
#ifdef __AVR_ATmega128__
SBI(TIFR, OCF3A); // clear any pending interrupts;
SBI(ETIMSK, OCIE3A); // enable the output compare interrupt
#else
SBI(TIFR3, OCF3A); // clear any pending interrupts;
SBI(TIMSK3, OCIE3A); // enable the output compare interrupt
#endif
#ifdef WIRING
timerAttach(TIMER3OUTCOMPAREA_INT, Timer3Service); // for Wiring platform only
#endif
}
#endif
#ifdef _useTimer4
if (timer == _timer4) {
TCCR4A = 0; // normal counting mode
TCCR4B = _BV(CS41); // set prescaler of 8
TCNT4 = 0; // clear the timer count
TIFR4 = _BV(OCF4A); // clear any pending interrupts;
TIMSK4 = _BV(OCIE4A); // enable the output compare interrupt
}
#endif
#ifdef _useTimer5
if (timer == _timer5) {
TCCR5A = 0; // normal counting mode
TCCR5B = _BV(CS51); // set prescaler of 8
TCNT5 = 0; // clear the timer count
TIFR5 = _BV(OCF5A); // clear any pending interrupts;
TIMSK5 = _BV(OCIE5A); // enable the output compare interrupt
}
#endif
}
void finISR(timer16_Sequence_t timer) {
// Disable use of the given timer
#ifdef WIRING
if (timer == _timer1) {
CBI(
#if defined(__AVR_ATmega1281__) || defined(__AVR_ATmega2561__)
TIMSK1
void initISR(const timer16_Sequence_t timer_index) {
switch (timer_index) {
default: break;
#ifdef _useTimer1
case _timer1:
TCCR1A = 0; // normal counting mode
TCCR1B = _BV(CS11); // set prescaler of 8
TCNT1 = 0; // clear the timer count
#if defined(__AVR_ATmega8__) || defined(__AVR_ATmega128__)
SBI(TIFR, OCF1A); // clear any pending interrupts;
SBI(TIMSK, OCIE1A); // enable the output compare interrupt
#else
TIMSK
// here if not ATmega8 or ATmega128
SBI(TIFR1, OCF1A); // clear any pending interrupts;
SBI(TIMSK1, OCIE1A); // enable the output compare interrupt
#endif
, OCIE1A); // disable timer 1 output compare interrupt
timerDetach(TIMER1OUTCOMPAREA_INT);
}
else if (timer == _timer3) {
CBI(
#if defined(__AVR_ATmega1281__) || defined(__AVR_ATmega2561__)
TIMSK3
#ifdef WIRING
timerAttach(TIMER1OUTCOMPAREA_INT, Timer1Service);
#endif
break;
#endif
#ifdef _useTimer3
case _timer3:
TCCR3A = 0; // normal counting mode
TCCR3B = _BV(CS31); // set prescaler of 8
TCNT3 = 0; // clear the timer count
#ifdef __AVR_ATmega128__
SBI(TIFR, OCF3A); // clear any pending interrupts;
SBI(ETIMSK, OCIE3A); // enable the output compare interrupt
#else
ETIMSK
SBI(TIFR3, OCF3A); // clear any pending interrupts;
SBI(TIMSK3, OCIE3A); // enable the output compare interrupt
#endif
#ifdef WIRING
timerAttach(TIMER3OUTCOMPAREA_INT, Timer3Service); // for Wiring platform only
#endif
, OCIE3A); // disable the timer3 output compare A interrupt
timerDetach(TIMER3OUTCOMPAREA_INT);
break;
#endif
#ifdef _useTimer4
case _timer4:
TCCR4A = 0; // normal counting mode
TCCR4B = _BV(CS41); // set prescaler of 8
TCNT4 = 0; // clear the timer count
TIFR4 = _BV(OCF4A); // clear any pending interrupts;
TIMSK4 = _BV(OCIE4A); // enable the output compare interrupt
break;
#endif
#ifdef _useTimer5
case _timer5:
TCCR5A = 0; // normal counting mode
TCCR5B = _BV(CS51); // set prescaler of 8
TCNT5 = 0; // clear the timer count
TIFR5 = _BV(OCF5A); // clear any pending interrupts;
TIMSK5 = _BV(OCIE5A); // enable the output compare interrupt
break;
#endif
}
}
void finISR(const timer16_Sequence_t timer_index) {
// Disable use of the given timer
#ifdef WIRING
switch (timer_index) {
default: break;
case _timer1:
CBI(
#if defined(__AVR_ATmega1281__) || defined(__AVR_ATmega2561__)
TIMSK1
#else
TIMSK
#endif
, OCIE1A // disable timer 1 output compare interrupt
);
timerDetach(TIMER1OUTCOMPAREA_INT);
break;
case _timer3:
CBI(
#if defined(__AVR_ATmega1281__) || defined(__AVR_ATmega2561__)
TIMSK3
#else
ETIMSK
#endif
, OCIE3A // disable the timer3 output compare A interrupt
);
timerDetach(TIMER3OUTCOMPAREA_INT);
break;
}
#else // !WIRING
// For arduino - in future: call here to a currently undefined function to reset the timer
UNUSED(timer);
UNUSED(timer_index);
#endif
}

138
Marlin/src/HAL/DUE/Servo.cpp

@ -47,12 +47,12 @@
#include "../shared/servo.h"
#include "../shared/servo_private.h"
static volatile int8_t Channel[_Nbr_16timers]; // counter for the servo being pulsed for each timer (or -1 if refresh interval)
static Flags<_Nbr_16timers> DisablePending; // ISR should disable the timer at the next timer reset
// ------------------------
/// Interrupt handler for the TC0 channel 1.
// ------------------------
void Servo_Handler(timer16_Sequence_t timer, Tc *pTc, uint8_t channel);
void Servo_Handler(const timer16_Sequence_t, Tc*, const uint8_t);
#ifdef _useTimer1
void HANDLER_FOR_TIMER1() { Servo_Handler(_timer1, TC_FOR_TIMER1, CHANNEL_FOR_TIMER1); }
@ -70,88 +70,92 @@ void Servo_Handler(timer16_Sequence_t timer, Tc *pTc, uint8_t channel);
void HANDLER_FOR_TIMER5() { Servo_Handler(_timer5, TC_FOR_TIMER5, CHANNEL_FOR_TIMER5); }
#endif
void Servo_Handler(timer16_Sequence_t timer, Tc *tc, uint8_t channel) {
// clear interrupt
tc->TC_CHANNEL[channel].TC_SR;
if (Channel[timer] < 0)
tc->TC_CHANNEL[channel].TC_CCR |= TC_CCR_SWTRG; // channel set to -1 indicated that refresh interval completed so reset the timer
else if (SERVO_INDEX(timer, Channel[timer]) < ServoCount && SERVO(timer, Channel[timer]).Pin.isActive)
extDigitalWrite(SERVO(timer, Channel[timer]).Pin.nbr, LOW); // pulse this channel low if activated
Channel[timer]++; // increment to the next channel
if (SERVO_INDEX(timer, Channel[timer]) < ServoCount && Channel[timer] < SERVOS_PER_TIMER) {
tc->TC_CHANNEL[channel].TC_RA = tc->TC_CHANNEL[channel].TC_CV + SERVO(timer,Channel[timer]).ticks;
if (SERVO(timer,Channel[timer]).Pin.isActive) // check if activated
extDigitalWrite(SERVO(timer, Channel[timer]).Pin.nbr, HIGH); // its an active channel so pulse it high
void Servo_Handler(const timer16_Sequence_t timer, Tc *tc, const uint8_t channel) {
static int8_t Channel[_Nbr_16timers]; // Servo counters to pulse (or -1 for refresh interval)
int8_t cho = Channel[timer]; // Handle the prior Channel[timer] first
if (cho < 0) { // Channel -1 indicates the refresh interval completed...
tc->TC_CHANNEL[channel].TC_CCR |= TC_CCR_SWTRG; // ...so reset the timer
if (DisablePending[timer]) {
// Disabling only after the full servo period expires prevents
// pulses being too close together if immediately re-enabled.
DisablePending.clear(timer);
TC_Stop(tc, channel);
tc->TC_CHANNEL[channel].TC_SR; // clear interrupt
return;
}
}
else if (SERVO_INDEX(timer, cho) < ServoCount) // prior channel handled?
extDigitalWrite(SERVO(timer, cho).Pin.nbr, LOW); // pulse the prior channel LOW
Channel[timer] = ++cho; // go to the next channel (or 0)
if (cho < SERVOS_PER_TIMER && SERVO_INDEX(timer, cho) < ServoCount) {
tc->TC_CHANNEL[channel].TC_RA = tc->TC_CHANNEL[channel].TC_CV + SERVO(timer, cho).ticks;
if (SERVO(timer, cho).Pin.isActive) // activated?
extDigitalWrite(SERVO(timer, cho).Pin.nbr, HIGH); // yes: pulse HIGH
}
else {
// finished all channels so wait for the refresh period to expire before starting over
tc->TC_CHANNEL[channel].TC_RA =
tc->TC_CHANNEL[channel].TC_CV < usToTicks(REFRESH_INTERVAL) - 4
? (unsigned int)usToTicks(REFRESH_INTERVAL) // allow a few ticks to ensure the next OCR1A not missed
: tc->TC_CHANNEL[channel].TC_CV + 4; // at least REFRESH_INTERVAL has elapsed
Channel[timer] = -1; // this will get incremented at the end of the refresh period to start again at the first channel
const unsigned int cval = tc->TC_CHANNEL[channel].TC_CV + 128 / (SERVO_TIMER_PRESCALER), // allow 128 cycles to ensure the next CV not missed
ival = (unsigned int)usToTicks(REFRESH_INTERVAL); // at least REFRESH_INTERVAL has elapsed
tc->TC_CHANNEL[channel].TC_RA = max(cval, ival);
Channel[timer] = -1; // reset the timer CCR on the next call
}
tc->TC_CHANNEL[channel].TC_SR; // clear interrupt
}
static void _initISR(Tc *tc, uint32_t channel, uint32_t id, IRQn_Type irqn) {
pmc_enable_periph_clk(id);
TC_Configure(tc, channel,
TC_CMR_TCCLKS_TIMER_CLOCK3 | // MCK/32
TC_CMR_WAVE | // Waveform mode
TC_CMR_WAVSEL_UP_RC ); // Counter running up and reset when equals to RC
/* 84MHz, MCK/32, for 1.5ms: 3937 */
TC_SetRA(tc, channel, 2625); // 1ms
/* Configure and enable interrupt */
TC_CMR_WAVE // Waveform mode
| TC_CMR_WAVSEL_UP_RC // Counter running up and reset when equal to RC
| (SERVO_TIMER_PRESCALER == 2 ? TC_CMR_TCCLKS_TIMER_CLOCK1 : 0) // MCK/2
| (SERVO_TIMER_PRESCALER == 8 ? TC_CMR_TCCLKS_TIMER_CLOCK2 : 0) // MCK/8
| (SERVO_TIMER_PRESCALER == 32 ? TC_CMR_TCCLKS_TIMER_CLOCK3 : 0) // MCK/32
| (SERVO_TIMER_PRESCALER == 128 ? TC_CMR_TCCLKS_TIMER_CLOCK4 : 0) // MCK/128
);
// Wait 1ms before the first ISR
TC_SetRA(tc, channel, (F_CPU) / (SERVO_TIMER_PRESCALER) / 1000UL); // 1ms
// Configure and enable interrupt
NVIC_EnableIRQ(irqn);
// TC_IER_CPAS: RA Compare
tc->TC_CHANNEL[channel].TC_IER = TC_IER_CPAS;
tc->TC_CHANNEL[channel].TC_IER = TC_IER_CPAS; // TC_IER_CPAS: RA Compare
// Enables the timer clock and performs a software reset to start the counting
TC_Start(tc, channel);
}
void initISR(timer16_Sequence_t timer) {
#ifdef _useTimer1
if (timer == _timer1)
_initISR(TC_FOR_TIMER1, CHANNEL_FOR_TIMER1, ID_TC_FOR_TIMER1, IRQn_FOR_TIMER1);
#endif
#ifdef _useTimer2
if (timer == _timer2)
_initISR(TC_FOR_TIMER2, CHANNEL_FOR_TIMER2, ID_TC_FOR_TIMER2, IRQn_FOR_TIMER2);
#endif
#ifdef _useTimer3
if (timer == _timer3)
_initISR(TC_FOR_TIMER3, CHANNEL_FOR_TIMER3, ID_TC_FOR_TIMER3, IRQn_FOR_TIMER3);
#endif
#ifdef _useTimer4
if (timer == _timer4)
_initISR(TC_FOR_TIMER4, CHANNEL_FOR_TIMER4, ID_TC_FOR_TIMER4, IRQn_FOR_TIMER4);
#endif
#ifdef _useTimer5
if (timer == _timer5)
_initISR(TC_FOR_TIMER5, CHANNEL_FOR_TIMER5, ID_TC_FOR_TIMER5, IRQn_FOR_TIMER5);
#endif
void initISR(const timer16_Sequence_t timer_index) {
CRITICAL_SECTION_START();
const bool disable_soon = DisablePending[timer_index];
DisablePending.clear(timer_index);
CRITICAL_SECTION_END();
if (!disable_soon) switch (timer_index) {
default: break;
#ifdef _useTimer1
case _timer1: return _initISR(TC_FOR_TIMER1, CHANNEL_FOR_TIMER1, ID_TC_FOR_TIMER1, IRQn_FOR_TIMER1);
#endif
#ifdef _useTimer2
case _timer2: return _initISR(TC_FOR_TIMER2, CHANNEL_FOR_TIMER2, ID_TC_FOR_TIMER2, IRQn_FOR_TIMER2);
#endif
#ifdef _useTimer3
case _timer3: return _initISR(TC_FOR_TIMER3, CHANNEL_FOR_TIMER3, ID_TC_FOR_TIMER3, IRQn_FOR_TIMER3);
#endif
#ifdef _useTimer4
case _timer4: return _initISR(TC_FOR_TIMER4, CHANNEL_FOR_TIMER4, ID_TC_FOR_TIMER4, IRQn_FOR_TIMER4);
#endif
#ifdef _useTimer5
case _timer5: return _initISR(TC_FOR_TIMER5, CHANNEL_FOR_TIMER5, ID_TC_FOR_TIMER5, IRQn_FOR_TIMER5);
#endif
}
}
void finISR(timer16_Sequence_t) {
#ifdef _useTimer1
TC_Stop(TC_FOR_TIMER1, CHANNEL_FOR_TIMER1);
#endif
#ifdef _useTimer2
TC_Stop(TC_FOR_TIMER2, CHANNEL_FOR_TIMER2);
#endif
#ifdef _useTimer3
TC_Stop(TC_FOR_TIMER3, CHANNEL_FOR_TIMER3);
#endif
#ifdef _useTimer4
TC_Stop(TC_FOR_TIMER4, CHANNEL_FOR_TIMER4);
#endif
#ifdef _useTimer5
TC_Stop(TC_FOR_TIMER5, CHANNEL_FOR_TIMER5);
#endif
void finISR(const timer16_Sequence_t timer_index) {
// Timer is disabled from the ISR, to ensure proper final pulse length.
DisablePending.set(timer_index);
}
#endif // HAS_SERVOS

2
Marlin/src/HAL/DUE/ServoTimers.h

@ -37,7 +37,7 @@
#define _useTimer5
#define TRIM_DURATION 2 // compensation ticks to trim adjust for digitalWrite delays
#define SERVO_TIMER_PRESCALER 32 // timer prescaler
#define SERVO_TIMER_PRESCALER 2 // timer prescaler
/*
TC0, chan 0 => TC0_Handler

11
Marlin/src/HAL/DUE/timers.cpp

@ -89,10 +89,17 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) {
NVIC_SetPriority(irq, timer_config[timer_num].priority);
// wave mode, reset counter on match with RC,
TC_Configure(tc, channel, TC_CMR_WAVE | TC_CMR_WAVSEL_UP_RC | TC_CMR_TCCLKS_TIMER_CLOCK1);
TC_Configure(tc, channel,
TC_CMR_WAVE
| TC_CMR_WAVSEL_UP_RC
| (HAL_TIMER_PRESCALER == 2 ? TC_CMR_TCCLKS_TIMER_CLOCK1 : 0)
| (HAL_TIMER_PRESCALER == 8 ? TC_CMR_TCCLKS_TIMER_CLOCK2 : 0)
| (HAL_TIMER_PRESCALER == 32 ? TC_CMR_TCCLKS_TIMER_CLOCK3 : 0)
| (HAL_TIMER_PRESCALER == 128 ? TC_CMR_TCCLKS_TIMER_CLOCK4 : 0)
);
// Set compare value
TC_SetRC(tc, channel, VARIANT_MCK / 2 / frequency);
TC_SetRC(tc, channel, VARIANT_MCK / (HAL_TIMER_PRESCALER) / frequency);
// And start timer
TC_Start(tc, channel);

3
Marlin/src/HAL/DUE/timers.h

@ -35,7 +35,8 @@
typedef uint32_t hal_timer_t;
#define HAL_TIMER_TYPE_MAX 0xFFFFFFFF
#define HAL_TIMER_RATE ((F_CPU) / 2) // frequency of timers peripherals
#define HAL_TIMER_PRESCALER 2
#define HAL_TIMER_RATE ((F_CPU) / (HAL_TIMER_PRESCALER)) // frequency of timers peripherals
#ifndef MF_TIMER_STEP
#define MF_TIMER_STEP 2 // Timer Index for Stepper

2
Marlin/src/HAL/DUE/usb/compiler.h

@ -1059,7 +1059,7 @@ static inline void convert_64_bit_to_byte_array(uint64_t value, uint8_t *data)
while (val_index < 8)
{
data[val_index++] = value & 0xFF;
value = value >> 8;
value >>= 8;
}
}

50
Marlin/src/HAL/ESP32/HAL.cpp

@ -65,6 +65,7 @@ portMUX_TYPE MarlinHAL::spinlock = portMUX_INITIALIZER_UNLOCKED;
// ------------------------
uint16_t MarlinHAL::adc_result;
pwm_pin_t MarlinHAL::pwm_pin_data[MAX_EXPANDER_BITS];
// ------------------------
// Private Variables
@ -330,21 +331,46 @@ int8_t get_pwm_channel(const pin_t pin, const uint32_t freq, const uint16_t res)
}
void MarlinHAL::set_pwm_duty(const pin_t pin, const uint16_t v, const uint16_t v_size/*=_BV(PWM_RESOLUTION)-1*/, const bool invert/*=false*/) {
const int8_t cid = get_pwm_channel(pin, PWM_FREQUENCY, PWM_RESOLUTION);
if (cid >= 0) {
uint32_t duty = map(invert ? v_size - v : v, 0, v_size, 0, _BV(PWM_RESOLUTION)-1);
ledcWrite(cid, duty);
}
#if ENABLED(I2S_STEPPER_STREAM)
if (pin > 127) {
const uint8_t pinlo = pin & 0x7F;
pwm_pin_t &pindata = pwm_pin_data[pinlo];
const uint32_t duty = map(invert ? v_size - v : v, 0, v_size, 0, pindata.pwm_cycle_ticks);
if (duty == 0 || duty == pindata.pwm_cycle_ticks) { // max or min (i.e., on/off)
pindata.pwm_duty_ticks = 0; // turn off PWM for this pin
duty ? SBI32(i2s_port_data, pinlo) : CBI32(i2s_port_data, pinlo); // set pin level
}
else
pindata.pwm_duty_ticks = duty; // PWM duty count = # of 4µs ticks per full PWM cycle
}
else
#endif
{
const int8_t cid = get_pwm_channel(pin, PWM_FREQUENCY, PWM_RESOLUTION);
if (cid >= 0) {
const uint32_t duty = map(invert ? v_size - v : v, 0, v_size, 0, _BV(PWM_RESOLUTION)-1);
ledcWrite(cid, duty);
}
}
}
int8_t MarlinHAL::set_pwm_frequency(const pin_t pin, const uint32_t f_desired) {
const int8_t cid = channel_for_pin(pin);
if (cid >= 0) {
if (f_desired == ledcReadFreq(cid)) return cid; // no freq change
ledcDetachPin(chan_pin[cid]);
chan_pin[cid] = 0; // remove old freq channel
}
return get_pwm_channel(pin, f_desired, PWM_RESOLUTION); // try for new one
#if ENABLED(I2S_STEPPER_STREAM)
if (pin > 127) {
pwm_pin_data[pin & 0x7F].pwm_cycle_ticks = 1000000UL / f_desired / 4; // # of 4µs ticks per full PWM cycle
return 0;
}
else
#endif
{
const int8_t cid = channel_for_pin(pin);
if (cid >= 0) {
if (f_desired == ledcReadFreq(cid)) return cid; // no freq change
ledcDetachPin(chan_pin[cid]);
chan_pin[cid] = 0; // remove old freq channel
}
return get_pwm_channel(pin, f_desired, PWM_RESOLUTION); // try for new one
}
}
// use hardware PWM if avail, if not then ISR

11
Marlin/src/HAL/ESP32/HAL.h

@ -68,6 +68,9 @@
#define PWM_RESOLUTION 10u // Default PWM bit resolution
#define CHANNEL_MAX_NUM 15u // max PWM channel # to allocate (7 to only use low speed, 15 to use low & high)
#define MAX_PWM_IOPIN 33u // hardware pwm pins < 34
#ifndef MAX_EXPANDER_BITS
#define MAX_EXPANDER_BITS 32 // I2S expander bit width (max 32)
#endif
// ------------------------
// Types
@ -76,6 +79,12 @@
typedef double isr_float_t; // FPU ops are used for single-precision, so use double for ISRs.
typedef int16_t pin_t;
typedef struct pwm_pin {
uint32_t pwm_cycle_ticks = 1000000UL / (PWM_FREQUENCY) / 4; // # ticks per pwm cycle
uint32_t pwm_tick_count = 0; // current tick count
uint32_t pwm_duty_ticks = 0; // # of ticks for current duty cycle
} pwm_pin_t;
class Servo;
typedef Servo hal_servo_t;
@ -197,6 +206,8 @@ public:
// Free SRAM
static int freeMemory();
static pwm_pin_t pwm_pin_data[MAX_EXPANDER_BITS];
//
// ADC Methods
//

20
Marlin/src/HAL/ESP32/i2s.cpp

@ -337,6 +337,26 @@ uint8_t i2s_state(uint8_t pin) {
}
void i2s_push_sample() {
// Every 4µs (when space in DMA buffer) toggle each expander PWM output using
// the current duty cycle/frequency so they sync with any steps (once
// through the DMA/FIFO buffers). PWM signal inversion handled by other functions
LOOP_L_N(p, MAX_EXPANDER_BITS) {
if (hal.pwm_pin_data[p].pwm_duty_ticks > 0) { // pin has active pwm?
if (hal.pwm_pin_data[p].pwm_tick_count == 0) {
if (TEST32(i2s_port_data, p)) { // hi->lo
CBI32(i2s_port_data, p);
hal.pwm_pin_data[p].pwm_tick_count = hal.pwm_pin_data[p].pwm_cycle_ticks - hal.pwm_pin_data[p].pwm_duty_ticks;
}
else { // lo->hi
SBI32(i2s_port_data, p);
hal.pwm_pin_data[p].pwm_tick_count = hal.pwm_pin_data[p].pwm_duty_ticks;
}
}
else
hal.pwm_pin_data[p].pwm_tick_count--;
}
}
dma.current[dma.rw_pos++] = i2s_port_data;
}

7
Marlin/src/HAL/ESP32/inc/Conditionals_adv.h

@ -20,3 +20,10 @@
*
*/
#pragma once
//
// Board-specific options need to be defined before HAL.h
//
#if MB(MKS_TINYBEE)
#define MAX_EXPANDER_BITS 24 // TinyBee has 3 x HC595
#endif

4
Marlin/src/HAL/ESP32/inc/SanityCheck.h

@ -48,3 +48,7 @@
#if USING_PULLDOWNS
#error "PULLDOWN pin mode is not available on ESP32 boards."
#endif
#if BOTH(I2S_STEPPER_STREAM, LIN_ADVANCE)
#error "I2S stream is currently incompatible with LIN_ADVANCE."
#endif

16
Marlin/src/HAL/LINUX/eeprom.cpp

@ -69,12 +69,12 @@ bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, ui
std::size_t bytes_written = 0;
for (std::size_t i = 0; i < size; i++) {
buffer[pos+i] = value[i];
bytes_written ++;
buffer[pos + i] = value[i];
bytes_written++;
}
crc16(crc, value, size);
pos = pos + size;
pos += size;
return (bytes_written != size); // return true for any error
}
@ -82,21 +82,21 @@ bool PersistentStore::read_data(int &pos, uint8_t *value, const size_t size, uin
std::size_t bytes_read = 0;
if (writing) {
for (std::size_t i = 0; i < size; i++) {
value[i] = buffer[pos+i];
bytes_read ++;
value[i] = buffer[pos + i];
bytes_read++;
}
crc16(crc, value, size);
}
else {
uint8_t temp[size];
for (std::size_t i = 0; i < size; i++) {
temp[i] = buffer[pos+i];
bytes_read ++;
temp[i] = buffer[pos + i];
bytes_read++;
}
crc16(crc, temp, size);
}
pos = pos + size;
pos += size;
return bytes_read != size; // return true for any error
}

4
Marlin/src/HAL/LINUX/hardware/Heater.h

@ -26,8 +26,8 @@
struct LowpassFilter {
uint64_t data_delay = 0;
uint16_t update(uint16_t value) {
data_delay = data_delay - (data_delay >> 6) + value;
return (uint16_t)(data_delay >> 6);
data_delay += value - (data_delay >> 6);
return uint16_t(data_delay >> 6);
}
};

45
Marlin/src/HAL/SAMD51/Servo.cpp

@ -77,7 +77,8 @@ HAL_SERVO_TIMER_ISR() {
;
const uint8_t tcChannel = TIMER_TCCHANNEL(timer);
if (currentServoIndex[timer] < 0) {
int8_t cho = currentServoIndex[timer]; // Handle the prior servo first
if (cho < 0) { // Servo -1 indicates the refresh interval completed...
#if defined(_useTimer1) && defined(_useTimer2)
if (currentServoIndex[timer ^ 1] >= 0) {
// Wait for both channels
@ -86,45 +87,37 @@ HAL_SERVO_TIMER_ISR() {
return;
}
#endif
tc->COUNT16.COUNT.reg = TC_COUNTER_START_VAL;
tc->COUNT16.COUNT.reg = TC_COUNTER_START_VAL; // ...so reset the timer
SYNC(tc->COUNT16.SYNCBUSY.bit.COUNT);
}
else if (SERVO_INDEX(timer, currentServoIndex[timer]) < ServoCount && SERVO(timer, currentServoIndex[timer]).Pin.isActive)
digitalWrite(SERVO(timer, currentServoIndex[timer]).Pin.nbr, LOW); // pulse this channel low if activated
// Select the next servo controlled by this timer
currentServoIndex[timer]++;
else if (SERVO_INDEX(timer, cho) < ServoCount) // prior channel handled?
digitalWrite(SERVO(timer, cho).Pin.nbr, LOW); // pulse the prior channel LOW
if (SERVO_INDEX(timer, currentServoIndex[timer]) < ServoCount && currentServoIndex[timer] < SERVOS_PER_TIMER) {
if (SERVO(timer, currentServoIndex[timer]).Pin.isActive) // check if activated
digitalWrite(SERVO(timer, currentServoIndex[timer]).Pin.nbr, HIGH); // it's an active channel so pulse it high
currentServoIndex[timer] = ++cho; // go to the next channel (or 0)
if (cho < SERVOS_PER_TIMER && SERVO_INDEX(timer, cho) < ServoCount) {
if (SERVO(timer, cho).Pin.isActive) // activated?
digitalWrite(SERVO(timer, cho).Pin.nbr, HIGH); // yes: pulse HIGH
tc->COUNT16.CC[tcChannel].reg = getTimerCount() - (uint16_t)SERVO(timer, currentServoIndex[timer]).ticks;
tc->COUNT16.CC[tcChannel].reg = getTimerCount() - (uint16_t)SERVO(timer, cho).ticks;
}
else {
// finished all channels so wait for the refresh period to expire before starting over
currentServoIndex[timer] = -1; // this will get incremented at the end of the refresh period to start again at the first channel
const uint16_t tcCounterValue = getTimerCount();
if ((TC_COUNTER_START_VAL - tcCounterValue) + 4UL < usToTicks(REFRESH_INTERVAL)) // allow a few ticks to ensure the next OCR1A not missed
tc->COUNT16.CC[tcChannel].reg = TC_COUNTER_START_VAL - (uint16_t)usToTicks(REFRESH_INTERVAL);
else
tc->COUNT16.CC[tcChannel].reg = (uint16_t)(tcCounterValue - 4UL); // at least REFRESH_INTERVAL has elapsed
currentServoIndex[timer] = -1; // reset the timer COUNT.reg on the next call
const uint16_t cval = getTimerCount() - 256 / (SERVO_TIMER_PRESCALER), // allow 256 cycles to ensure the next CV not missed
ival = (TC_COUNTER_START_VAL) - (uint16_t)usToTicks(REFRESH_INTERVAL); // at least REFRESH_INTERVAL has elapsed
tc->COUNT16.CC[tcChannel].reg = min(cval, ival);
}
if (tcChannel == 0) {
SYNC(tc->COUNT16.SYNCBUSY.bit.CC0);
// Clear the interrupt
tc->COUNT16.INTFLAG.reg = TC_INTFLAG_MC0;
tc->COUNT16.INTFLAG.reg = TC_INTFLAG_MC0; // Clear the interrupt
}
else {
SYNC(tc->COUNT16.SYNCBUSY.bit.CC1);
// Clear the interrupt
tc->COUNT16.INTFLAG.reg = TC_INTFLAG_MC1;
tc->COUNT16.INTFLAG.reg = TC_INTFLAG_MC1; // Clear the interrupt
}
}
void initISR(timer16_Sequence_t timer) {
void initISR(const timer16_Sequence_t timer) {
Tc * const tc = timer_config[SERVO_TC].pTc;
const uint8_t tcChannel = TIMER_TCCHANNEL(timer);
@ -201,9 +194,9 @@ void initISR(timer16_Sequence_t timer) {
}
}
void finISR(timer16_Sequence_t timer) {
void finISR(const timer16_Sequence_t timer_index) {
Tc * const tc = timer_config[SERVO_TC].pTc;
const uint8_t tcChannel = TIMER_TCCHANNEL(timer);
const uint8_t tcChannel = TIMER_TCCHANNEL(timer_index);
// Disable the match channel interrupt request
tc->COUNT16.INTENCLR.reg = (tcChannel == 0) ? TC_INTENCLR_MC0 : TC_INTENCLR_MC1;

16
Marlin/src/HAL/STM32/tft/gt911.cpp

@ -159,24 +159,28 @@ void GT911::read_reg(uint16_t reg, uint8_t reg_len, uint8_t* r_data, uint8_t r_l
void GT911::Init() {
OUT_WRITE(GT911_RST_PIN, LOW);
OUT_WRITE(GT911_INT_PIN, LOW);
delay(20);
delay(11);
WRITE(GT911_INT_PIN, HIGH);
delayMicroseconds(110);
WRITE(GT911_RST_PIN, HIGH);
delay(6);
WRITE(GT911_INT_PIN, LOW);
delay(55);
SET_INPUT(GT911_INT_PIN);
sw_iic.init();
uint8_t clear_reg = 0x0000;
write_reg(0x814E, 2, &clear_reg, 2); // Reset to 0 for start
uint8_t clear_reg = 0x00;
write_reg(0x814E, 2, &clear_reg, 1); // Reset to 0 for start
}
bool GT911::getFirstTouchPoint(int16_t *x, int16_t *y) {
read_reg(0x814E, 2, &reg.REG.status, 1);
if (reg.REG.status & 0x80) {
if (reg.REG.status >= 0x80 && reg.REG.status <= 0x85) {
read_reg(0x8150, 2, reg.map + 2, 38);
uint8_t clear_reg = 0x00;
write_reg(0x814E, 2, &clear_reg, 1); // Reset to 0 for start
read_reg(0x8150, 2, reg.map + 2, 8 * (reg.REG.status & 0x0F));
// First touch point
*x = ((reg.REG.point[0].xh & 0x0F) << 8) | reg.REG.point[0].xl;
*y = ((reg.REG.point[0].yh & 0x0F) << 8) | reg.REG.point[0].yl;

2
Marlin/src/HAL/STM32/tft/gt911.h

@ -23,7 +23,7 @@
#include "../../../inc/MarlinConfig.h"
#define GT911_SLAVE_ADDRESS 0xBA
#define GT911_SLAVE_ADDRESS 0x28
#if !PIN_EXISTS(GT911_RST)
#error "GT911_RST_PIN is not defined."

16
Marlin/src/HAL/STM32F1/Servo.cpp

@ -147,17 +147,17 @@ void libServo::move(const int32_t value) {
uint16_t SR = timer_get_status(tdev);
if (SR & TIMER_SR_CC1IF) { // channel 1 off
#ifdef SERVO0_PWM_OD
OUT_WRITE_OD(SERVO0_PIN, 1); // off
OUT_WRITE_OD(SERVO0_PIN, HIGH); // off
#else
OUT_WRITE(SERVO0_PIN, 0);
OUT_WRITE(SERVO0_PIN, LOW);
#endif
timer_reset_status_bit(tdev, TIMER_SR_CC1IF_BIT);
}
if (SR & TIMER_SR_CC2IF) { // channel 2 resume
#ifdef SERVO0_PWM_OD
OUT_WRITE_OD(SERVO0_PIN, 0); // on
OUT_WRITE_OD(SERVO0_PIN, LOW); // on
#else
OUT_WRITE(SERVO0_PIN, 1);
OUT_WRITE(SERVO0_PIN, HIGH);
#endif
timer_reset_status_bit(tdev, TIMER_SR_CC2IF_BIT);
}
@ -167,9 +167,9 @@ void libServo::move(const int32_t value) {
timer_dev *tdev = HAL_get_timer_dev(MF_TIMER_SERVO0);
if (!tdev) return false;
#ifdef SERVO0_PWM_OD
OUT_WRITE_OD(inPin, 1);
OUT_WRITE_OD(inPin, HIGH);
#else
OUT_WRITE(inPin, 0);
OUT_WRITE(inPin, LOW);
#endif
timer_pause(tdev);
@ -200,9 +200,9 @@ void libServo::move(const int32_t value) {
timer_disable_irq(tdev, 1);
timer_disable_irq(tdev, 2);
#ifdef SERVO0_PWM_OD
OUT_WRITE_OD(pin, 1); // off
OUT_WRITE_OD(pin, HIGH); // off
#else
OUT_WRITE(pin, 0);
OUT_WRITE(pin, LOW);
#endif
}
}

4
Marlin/src/HAL/shared/backtrace/unwarmbytab.cpp

@ -135,11 +135,11 @@ static UnwResult UnwTabExecuteInstructions(const UnwindCallbacks *cb, UnwTabStat
while ((instruction = UnwTabGetNextInstruction(cb, ucb)) != -1) {
if ((instruction & 0xC0) == 0x00) { // ARM_EXIDX_CMD_DATA_POP
/* vsp = vsp + (xxxxxx << 2) + 4 */
/* vsp += (xxxxxx << 2) + 4 */
ucb->vrs[13] += ((instruction & 0x3F) << 2) + 4;
}
else if ((instruction & 0xC0) == 0x40) { // ARM_EXIDX_CMD_DATA_PUSH
/* vsp = vsp - (xxxxxx << 2) - 4 */
/* vsp -= (xxxxxx << 2) - 4 */
ucb->vrs[13] -= ((instruction & 0x3F) << 2) - 4;
}
else if ((instruction & 0xF0) == 0x80) {

13
Marlin/src/HAL/shared/servo.cpp

@ -65,7 +65,7 @@ uint8_t ServoCount = 0; // the total number of attached
/************ static functions common to all instances ***********************/
static boolean isTimerActive(timer16_Sequence_t timer) {
static bool anyTimerChannelActive(const timer16_Sequence_t timer) {
// returns true if any servo is active on this timer
LOOP_L_N(channel, SERVOS_PER_TIMER) {
if (SERVO(timer, channel).Pin.isActive)
@ -101,17 +101,18 @@ int8_t Servo::attach(const int inPin, const int inMin, const int inMax) {
max = (MAX_PULSE_WIDTH - inMax) / 4;
// initialize the timer if it has not already been initialized
timer16_Sequence_t timer = SERVO_INDEX_TO_TIMER(servoIndex);
if (!isTimerActive(timer)) initISR(timer);
servo_info[servoIndex].Pin.isActive = true; // this must be set after the check for isTimerActive
const timer16_Sequence_t timer = SERVO_INDEX_TO_TIMER(servoIndex);
if (!anyTimerChannelActive(timer)) initISR(timer);
servo_info[servoIndex].Pin.isActive = true; // this must be set after the check for anyTimerChannelActive
return servoIndex;
}
void Servo::detach() {
servo_info[servoIndex].Pin.isActive = false;
timer16_Sequence_t timer = SERVO_INDEX_TO_TIMER(servoIndex);
if (!isTimerActive(timer)) finISR(timer);
const timer16_Sequence_t timer = SERVO_INDEX_TO_TIMER(servoIndex);
if (!anyTimerChannelActive(timer)) finISR(timer);
//pinMode(servo_info[servoIndex].Pin.nbr, INPUT); // set servo pin to input
}
void Servo::write(int value) {

12
Marlin/src/HAL/shared/servo_private.h

@ -70,10 +70,10 @@
#define ticksToUs(_ticks) (unsigned(_ticks) * (SERVO_TIMER_PRESCALER) / clockCyclesPerMicrosecond())
// convenience macros
#define SERVO_INDEX_TO_TIMER(_servo_nbr) ((timer16_Sequence_t)(_servo_nbr / (SERVOS_PER_TIMER))) // returns the timer controlling this servo
#define SERVO_INDEX_TO_CHANNEL(_servo_nbr) (_servo_nbr % (SERVOS_PER_TIMER)) // returns the index of the servo on this timer
#define SERVO_INDEX(_timer,_channel) ((_timer*(SERVOS_PER_TIMER)) + _channel) // macro to access servo index by timer and channel
#define SERVO(_timer,_channel) (servo_info[SERVO_INDEX(_timer,_channel)]) // macro to access servo class by timer and channel
#define SERVO_INDEX_TO_TIMER(_servo_nbr) timer16_Sequence_t(_servo_nbr / (SERVOS_PER_TIMER)) // the timer controlling this servo
#define SERVO_INDEX_TO_CHANNEL(_servo_nbr) (_servo_nbr % (SERVOS_PER_TIMER)) // the index of the servo on this timer
#define SERVO_INDEX(_timer,_channel) ((_timer*(SERVOS_PER_TIMER)) + _channel) // servo index by timer and channel
#define SERVO(_timer,_channel) servo_info[SERVO_INDEX(_timer,_channel)] // servo class by timer and channel
// Types
@ -94,5 +94,5 @@ extern ServoInfo_t servo_info[MAX_SERVOS];
// Public functions
extern void initISR(timer16_Sequence_t timer);
extern void finISR(timer16_Sequence_t timer);
void initISR(const timer16_Sequence_t timer_index);
void finISR(const timer16_Sequence_t timer_index);

4
Marlin/src/MarlinCore.cpp

@ -776,6 +776,10 @@ inline void manage_inactivity(const bool no_stepper_sleep=false) {
* - Handle Joystick jogging
*/
void idle(bool no_stepper_sleep/*=false*/) {
#ifdef MAX7219_DEBUG_PROFILE
CodeProfiler idle_profiler;
#endif
#if ENABLED(MARLIN_DEV_MODE)
static uint16_t idle_depth = 0;
if (++idle_depth > 5) SERIAL_ECHOLNPGM("idle() call depth: ", idle_depth);

2
Marlin/src/core/boards.h

@ -413,7 +413,7 @@
#define BOARD_ANET_ET4P 4232 // ANET ET4P V1.x (STM32F407VG)
#define BOARD_FYSETC_CHEETAH_V20 4233 // FYSETC Cheetah V2.0
#define BOARD_TH3D_EZBOARD_V2 4234 // TH3D EZBoard v2.0
#define BOARD_INDEX_REV03 4235 // Index PnP Controller REV03 (STM32F407VE/VG)
#define BOARD_OPULO_LUMEN_REV3 4235 // Opulo Lumen PnP Controller REV3 (STM32F407VE/VG)
#define BOARD_MKS_ROBIN_NANO_V1_3_F4 4236 // MKS Robin Nano V1.3 and MKS Robin Nano-S V1.3 (STM32F407VE)
#define BOARD_MKS_EAGLE 4237 // MKS Eagle (STM32F407VE)
#define BOARD_ARTILLERY_RUBY 4238 // Artillery Ruby (STM32F401RC)

5
Marlin/src/core/macros.h

@ -644,8 +644,8 @@
#define IS_PROBE(V...) SECOND(V, 0) // Get the second item passed, or 0
#define PROBE() ~, 1 // Second item will be 1 if this is passed
#define _NOT_0 PROBE()
#define NOT(x) IS_PROBE(_CAT(_NOT_, x)) // NOT('0') gets '1'. Anything else gets '0'.
#define _BOOL(x) NOT(NOT(x)) // NOT('0') gets '0'. Anything else gets '1'.
#define NOT(x) IS_PROBE(_CAT(_NOT_, x)) // NOT('0') gets '1'. Anything else gets '0'.
#define _BOOL(x) NOT(NOT(x)) // _BOOL('0') gets '0'. Anything else gets '1'.
#define IF_ELSE(TF) _IF_ELSE(_BOOL(TF))
#define _IF_ELSE(TF) _CAT(_IF_, TF)
@ -659,7 +659,6 @@
#define HAS_ARGS(V...) _BOOL(FIRST(_END_OF_ARGUMENTS_ V)())
#define _END_OF_ARGUMENTS_() 0
// Simple Inline IF Macros, friendly to use in other macro definitions
#define IF(O, A, B) ((O) ? (A) : (B))
#define IF_0(O, A) IF(O, A, 0)

4
Marlin/src/core/serial.cpp

@ -72,8 +72,8 @@ void serial_print_P(PGM_P str) {
while (const char c = pgm_read_byte(str++)) SERIAL_CHAR(c);
}
void serial_echo_start() { static PGMSTR(echomagic, "echo:"); serial_print_P(echomagic); }
void serial_error_start() { static PGMSTR(errormagic, "Error:"); serial_print_P(errormagic); }
void serial_echo_start() { serial_print(F("echo:")); }
void serial_error_start() { serial_print(F("Error:")); }
void serial_spaces(uint8_t count) { count *= (PROPORTIONAL_FONT_RATIO); while (count--) SERIAL_CHAR(' '); }

8
Marlin/src/core/types.h

@ -99,8 +99,8 @@ struct Flags {
void set(const int n) { b |= (bits_t)_BV(n); }
void clear(const int n) { b &= ~(bits_t)_BV(n); }
bool test(const int n) const { return TEST(b, n); }
bool operator[](const int n) { return test(n); }
bool operator[](const int n) const { return test(n); }
const bool operator[](const int n) { return test(n); }
const bool operator[](const int n) const { return test(n); }
int size() const { return sizeof(b); }
};
@ -113,8 +113,8 @@ struct Flags<1> {
void set(const int) { b = true; }
void clear(const int) { b = false; }
bool test(const int) const { return b; }
bool operator[](const int) { return b; }
bool operator[](const int) const { return b; }
bool& operator[](const int) { return b; }
bool operator[](const int) const { return b; }
int size() const { return sizeof(b); }
};

18
Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp

@ -36,8 +36,18 @@
#include "../../../MarlinCore.h"
#include <math.h>
//#define DEBUG_UBL_MOTION
#define DEBUG_OUT ENABLED(DEBUG_UBL_MOTION)
#include "../../../core/debug_out.h"
#if !UBL_SEGMENTED
// TODO: The first and last parts of a move might result in very short segment(s)
// after getting split on the cell boundary, so moves like that should not
// get split. This will be most common for moves that start/end near the
// corners of cells. To fix the issue, simply check if the start/end of the line
// is very close to a cell boundary in advance and don't split the line there.
void unified_bed_leveling::line_to_destination_cartesian(const_feedRate_t scaled_fr_mm_s, const uint8_t extruder) {
/**
* Much of the nozzle movement will be within the same cell. So we will do as little computation
@ -176,7 +186,9 @@
dest.z += z0;
planner.buffer_segment(dest, scaled_fr_mm_s, extruder);
} //else printf("FIRST MOVE PRUNED ");
}
else
DEBUG_ECHOLNPGM("[ubl] skip Y segment");
}
// At the final destination? Usually not, but when on a Y Mesh Line it's completed.
@ -225,7 +237,9 @@
dest.z += z0;
if (!planner.buffer_segment(dest, scaled_fr_mm_s, extruder)) break;
} //else printf("FIRST MOVE PRUNED ");
}
else
DEBUG_ECHOLNPGM("[ubl] skip Y segment");
}
if (xy_pos_t(current_position) != xy_pos_t(end))

2
Marlin/src/feature/bltouch.cpp

@ -45,7 +45,7 @@ void stop();
bool BLTouch::command(const BLTCommand cmd, const millis_t &ms) {
if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("BLTouch Command :", cmd);
MOVE_SERVO(Z_PROBE_SERVO_NR, cmd);
servo[Z_PROBE_SERVO_NR].move(cmd);
safe_delay(_MAX(ms, (uint32_t)BLTOUCH_DELAY)); // BLTOUCH_DELAY is also the *minimum* delay
return triggered();
}

113
Marlin/src/feature/max7219.cpp

@ -52,6 +52,7 @@
#define HAS_SIDE_BY_SIDE 1
#endif
#define _ROT ((MAX7219_ROTATE + 360) % 360)
#if _ROT == 0 || _ROT == 180
#define MAX7219_X_LEDS TERN(HAS_SIDE_BY_SIDE, 8, MAX7219_LINES)
#define MAX7219_Y_LEDS TERN(HAS_SIDE_BY_SIDE, MAX7219_LINES, 8)
@ -62,6 +63,15 @@
#error "MAX7219_ROTATE must be a multiple of +/- 90°."
#endif
#ifdef MAX7219_DEBUG_PROFILE
CodeProfiler::Mode CodeProfiler::mode = ACCUMULATE_AVERAGE;
uint8_t CodeProfiler::instance_count = 0;
uint32_t CodeProfiler::last_calc_time = micros();
uint8_t CodeProfiler::time_fraction = 0;
uint32_t CodeProfiler::total_time = 0;
uint16_t CodeProfiler::call_count = 0;
#endif
Max7219 max7219;
uint8_t Max7219::led_line[MAX7219_LINES]; // = { 0 };
@ -69,7 +79,7 @@ uint8_t Max7219::suspended; // = 0;
#define LINE_REG(Q) (max7219_reg_digit0 + ((Q) & 0x7))
#if _ROT == 0 || _ROT == 270
#if (_ROT == 0 || _ROT == 270) == DISABLED(MAX7219_REVERSE_EACH)
#define _LED_BIT(Q) (7 - ((Q) & 0x7))
#else
#define _LED_BIT(Q) ((Q) & 0x7)
@ -266,26 +276,27 @@ void Max7219::set(const uint8_t line, const uint8_t bits) {
#endif // MAX7219_NUMERIC
// Modify a single LED bit and send the changed line
void Max7219::led_set(const uint8_t x, const uint8_t y, const bool on) {
void Max7219::led_set(const uint8_t x, const uint8_t y, const bool on, uint8_t * const rcm/*=nullptr*/) {
if (x >= MAX7219_X_LEDS || y >= MAX7219_Y_LEDS) return error(F("led_set"), x, y);
if (BIT_7219(x, y) == on) return;
XOR_7219(x, y);
refresh_unit_line(LED_IND(x, y));
if (rcm != nullptr) *rcm |= _BV(LED_IND(x, y) & 0x07);
}
void Max7219::led_on(const uint8_t x, const uint8_t y) {
void Max7219::led_on(const uint8_t x, const uint8_t y, uint8_t * const rcm/*=nullptr*/) {
if (x >= MAX7219_X_LEDS || y >= MAX7219_Y_LEDS) return error(F("led_on"), x, y);
led_set(x, y, true);
led_set(x, y, true, rcm);
}
void Max7219::led_off(const uint8_t x, const uint8_t y) {
void Max7219::led_off(const uint8_t x, const uint8_t y, uint8_t * const rcm/*=nullptr*/) {
if (x >= MAX7219_X_LEDS || y >= MAX7219_Y_LEDS) return error(F("led_off"), x, y);
led_set(x, y, false);
led_set(x, y, false, rcm);
}
void Max7219::led_toggle(const uint8_t x, const uint8_t y) {
void Max7219::led_toggle(const uint8_t x, const uint8_t y, uint8_t * const rcm/*=nullptr*/) {
if (x >= MAX7219_X_LEDS || y >= MAX7219_Y_LEDS) return error(F("led_toggle"), x, y);
led_set(x, y, !BIT_7219(x, y));
led_set(x, y, !BIT_7219(x, y), rcm);
}
void Max7219::send_row(const uint8_t row) {
@ -448,7 +459,7 @@ void Max7219::register_setup() {
pulse_load(); // Tell the chips to load the clocked out data
}
#ifdef MAX7219_INIT_TEST
#if MAX7219_INIT_TEST
uint8_t test_mode = 0;
millis_t next_patt_ms;
@ -536,13 +547,9 @@ void Max7219::init() {
register_setup();
LOOP_LE_N(i, 7) { // Empty registers to turn all LEDs off
led_line[i] = 0x00;
send(max7219_reg_digit0 + i, 0);
pulse_load(); // Tell the chips to load the clocked out data
}
clear();
#ifdef MAX7219_INIT_TEST
#if MAX7219_INIT_TEST
start_test_pattern();
#endif
}
@ -554,41 +561,55 @@ void Max7219::init() {
*/
// Apply changes to update a marker
void Max7219::mark16(const uint8_t pos, const uint8_t v1, const uint8_t v2) {
void Max7219::mark16(const uint8_t pos, const uint8_t v1, const uint8_t v2, uint8_t * const rcm/*=nullptr*/) {
#if MAX7219_X_LEDS > 8 // At least 16 LEDs on the X-Axis. Use single line.
led_off(v1 & 0xF, pos);
led_on(v2 & 0xF, pos);
led_off(v1 & 0xF, pos, rcm);
led_on(v2 & 0xF, pos, rcm);
#elif MAX7219_Y_LEDS > 8 // At least 16 LEDs on the Y-Axis. Use a single column.
led_off(pos, v1 & 0xF);
led_on(pos, v2 & 0xF);
led_off(pos, v1 & 0xF, rcm);
led_on(pos, v2 & 0xF, rcm);
#else // Single 8x8 LED matrix. Use two lines to get 16 LEDs.
led_off(v1 & 0x7, pos + (v1 >= 8));
led_on(v2 & 0x7, pos + (v2 >= 8));
led_off(v1 & 0x7, pos + (v1 >= 8), rcm);
led_on(v2 & 0x7, pos + (v2 >= 8), rcm);
#endif
}
// Apply changes to update a tail-to-head range
void Max7219::range16(const uint8_t y, const uint8_t ot, const uint8_t nt, const uint8_t oh, const uint8_t nh) {
void Max7219::range16(const uint8_t y, const uint8_t ot, const uint8_t nt, const uint8_t oh,
const uint8_t nh, uint8_t * const rcm/*=nullptr*/) {
#if MAX7219_X_LEDS > 8 // At least 16 LEDs on the X-Axis. Use single line.
if (ot != nt) for (uint8_t n = ot & 0xF; n != (nt & 0xF) && n != (nh & 0xF); n = (n + 1) & 0xF)
led_off(n & 0xF, y);
led_off(n & 0xF, y, rcm);
if (oh != nh) for (uint8_t n = (oh + 1) & 0xF; n != ((nh + 1) & 0xF); n = (n + 1) & 0xF)
led_on(n & 0xF, y);
led_on(n & 0xF, y, rcm);
#elif MAX7219_Y_LEDS > 8 // At least 16 LEDs on the Y-Axis. Use a single column.
if (ot != nt) for (uint8_t n = ot & 0xF; n != (nt & 0xF) && n != (nh & 0xF); n = (n + 1) & 0xF)
led_off(y, n & 0xF);
led_off(y, n & 0xF, rcm);
if (oh != nh) for (uint8_t n = (oh + 1) & 0xF; n != ((nh + 1) & 0xF); n = (n + 1) & 0xF)
led_on(y, n & 0xF);
led_on(y, n & 0xF, rcm);
#else // Single 8x8 LED matrix. Use two lines to get 16 LEDs.
if (ot != nt) for (uint8_t n = ot & 0xF; n != (nt & 0xF) && n != (nh & 0xF); n = (n + 1) & 0xF)
led_off(n & 0x7, y + (n >= 8));
led_off(n & 0x7, y + (n >= 8), rcm);
if (oh != nh) for (uint8_t n = (oh + 1) & 0xF; n != ((nh + 1) & 0xF); n = (n + 1) & 0xF)
led_on(n & 0x7, y + (n >= 8));
led_on(n & 0x7, y + (n >= 8), rcm);
#endif
}
// Apply changes to update a quantity
void Max7219::quantity16(const uint8_t pos, const uint8_t ov, const uint8_t nv) {
void Max7219::quantity(const uint8_t pos, const uint8_t ov, const uint8_t nv, uint8_t * const rcm/*=nullptr*/) {
for (uint8_t i = _MIN(nv, ov); i < _MAX(nv, ov); i++)
led_set(
#if MAX7219_X_LEDS >= MAX7219_Y_LEDS
i, pos // Single matrix or multiple matrices in Landscape
#else
pos, i // Multiple matrices in Portrait
#endif
, nv >= ov
, rcm
);
}
void Max7219::quantity16(const uint8_t pos, const uint8_t ov, const uint8_t nv, uint8_t * const rcm/*=nullptr*/) {
for (uint8_t i = _MIN(nv, ov); i < _MAX(nv, ov); i++)
led_set(
#if MAX7219_X_LEDS > 8 // At least 16 LEDs on the X-Axis. Use single line.
@ -599,6 +620,7 @@ void Max7219::quantity16(const uint8_t pos, const uint8_t ov, const uint8_t nv)
i >> 1, pos + (i & 1)
#endif
, nv >= ov
, rcm
);
}
@ -636,16 +658,20 @@ void Max7219::idle_tasks() {
register_setup();
}
#ifdef MAX7219_INIT_TEST
#if MAX7219_INIT_TEST
if (test_mode) {
run_test_pattern();
return;
}
#endif
// suspend updates and record which lines have changed for batching later
suspended++;
uint8_t row_change_mask = 0x00;
#if ENABLED(MAX7219_DEBUG_PRINTER_ALIVE)
if (do_blink) {
led_toggle(MAX7219_X_LEDS - 1, MAX7219_Y_LEDS - 1);
led_toggle(MAX7219_X_LEDS - 1, MAX7219_Y_LEDS - 1, &row_change_mask);
next_blink = ms + 1000;
}
#endif
@ -655,7 +681,7 @@ void Max7219::idle_tasks() {
static int16_t last_head_cnt = 0xF, last_tail_cnt = 0xF;
if (last_head_cnt != head || last_tail_cnt != tail) {
range16(MAX7219_DEBUG_PLANNER_HEAD, last_tail_cnt, tail, last_head_cnt, head);
range16(MAX7219_DEBUG_PLANNER_HEAD, last_tail_cnt, tail, last_head_cnt, head, &row_change_mask);
last_head_cnt = head;
last_tail_cnt = tail;
}
@ -665,7 +691,7 @@ void Max7219::idle_tasks() {
#ifdef MAX7219_DEBUG_PLANNER_HEAD
static int16_t last_head_cnt = 0x1;
if (last_head_cnt != head) {
mark16(MAX7219_DEBUG_PLANNER_HEAD, last_head_cnt, head);
mark16(MAX7219_DEBUG_PLANNER_HEAD, last_head_cnt, head, &row_change_mask);
last_head_cnt = head;
}
#endif
@ -673,7 +699,7 @@ void Max7219::idle_tasks() {
#ifdef MAX7219_DEBUG_PLANNER_TAIL
static int16_t last_tail_cnt = 0x1;
if (last_tail_cnt != tail) {
mark16(MAX7219_DEBUG_PLANNER_TAIL, last_tail_cnt, tail);
mark16(MAX7219_DEBUG_PLANNER_TAIL, last_tail_cnt, tail, &row_change_mask);
last_tail_cnt = tail;
}
#endif
@ -684,11 +710,26 @@ void Max7219::idle_tasks() {
static int16_t last_depth = 0;
const int16_t current_depth = (head - tail + BLOCK_BUFFER_SIZE) & (BLOCK_BUFFER_SIZE - 1) & 0xF;
if (current_depth != last_depth) {
quantity16(MAX7219_DEBUG_PLANNER_QUEUE, last_depth, current_depth);
quantity16(MAX7219_DEBUG_PLANNER_QUEUE, last_depth, current_depth, &row_change_mask);
last_depth = current_depth;
}
#endif
#ifdef MAX7219_DEBUG_PROFILE
static uint8_t last_time_fraction = 0;
const uint8_t current_time_fraction = (uint16_t(CodeProfiler::get_time_fraction()) * MAX7219_NUMBER_UNITS + 8) / 16;
if (current_time_fraction != last_time_fraction) {
quantity(MAX7219_DEBUG_PROFILE, last_time_fraction, current_time_fraction, &row_change_mask);
last_time_fraction = current_time_fraction;
}
#endif
// batch line updates
suspended--;
if (!suspended)
LOOP_L_N(i, 8) if (row_change_mask & _BV(i))
refresh_line(i);
// After resume() automatically do a refresh()
if (suspended == 0x80) {
suspended = 0;

79
Marlin/src/feature/max7219.h

@ -47,7 +47,6 @@
#ifndef MAX7219_ROTATE
#define MAX7219_ROTATE 0
#endif
#define _ROT ((MAX7219_ROTATE + 360) % 360)
#ifndef MAX7219_NUMBER_UNITS
#define MAX7219_NUMBER_UNITS 1
@ -73,6 +72,67 @@
#define max7219_reg_shutdown 0x0C
#define max7219_reg_displayTest 0x0F
#ifdef MAX7219_DEBUG_PROFILE
// This class sums up the amount of time for which its instances exist.
// By default there is one instantiated for the duration of the idle()
// function. But an instance can be created in any code block to measure
// the time spent from the point of instantiation until the CPU leaves
// block. Be careful about having multiple instances of CodeProfiler as
// it does not guard against double counting. In general mixing ISR and
// non-ISR use will require critical sections but note that mode setting
// is atomic so the total or average times can safely be read if you set
// mode to FREEZE first.
class CodeProfiler {
public:
enum Mode : uint8_t { ACCUMULATE_AVERAGE, ACCUMULATE_TOTAL, FREEZE };
private:
static Mode mode;
static uint8_t instance_count;
static uint32_t last_calc_time;
static uint32_t total_time;
static uint8_t time_fraction;
static uint16_t call_count;
uint32_t start_time;
public:
CodeProfiler() : start_time(micros()) { instance_count++; }
~CodeProfiler() {
instance_count--;
if (mode == FREEZE) return;
call_count++;
const uint32_t now = micros();
total_time += now - start_time;
if (mode == ACCUMULATE_TOTAL) return;
// update time_fraction every hundred milliseconds
if (instance_count == 0 && ELAPSED(now, last_calc_time + 100000)) {
time_fraction = total_time * 128 / (now - last_calc_time);
last_calc_time = now;
total_time = 0;
}
}
static void set_mode(Mode _mode) { mode = _mode; }
static void reset() {
time_fraction = 0;
last_calc_time = micros();
total_time = 0;
call_count = 0;
}
// returns fraction of total time which was measured, scaled from 0 to 128
static uint8_t get_time_fraction() { return time_fraction; }
// returns total time in microseconds
static uint32_t get_total_time() { return total_time; }
static uint16_t get_call_count() { return call_count; }
};
#endif
class Max7219 {
public:
static uint8_t led_line[MAX7219_LINES];
@ -110,10 +170,10 @@ public:
#endif
// Set a single LED by XY coordinate
static void led_set(const uint8_t x, const uint8_t y, const bool on);
static void led_on(const uint8_t x, const uint8_t y);
static void led_off(const uint8_t x, const uint8_t y);
static void led_toggle(const uint8_t x, const uint8_t y);
static void led_set(const uint8_t x, const uint8_t y, const bool on, uint8_t * const rcm=nullptr);
static void led_on(const uint8_t x, const uint8_t y, uint8_t * const rcm=nullptr);
static void led_off(const uint8_t x, const uint8_t y, uint8_t * const rcm=nullptr);
static void led_toggle(const uint8_t x, const uint8_t y, uint8_t * const rcm=nullptr);
// Set all LEDs in a single column
static void set_column(const uint8_t col, const uint32_t val);
@ -147,11 +207,12 @@ private:
static void set(const uint8_t line, const uint8_t bits);
static void send_row(const uint8_t row);
static void send_column(const uint8_t col);
static void mark16(const uint8_t y, const uint8_t v1, const uint8_t v2);
static void range16(const uint8_t y, const uint8_t ot, const uint8_t nt, const uint8_t oh, const uint8_t nh);
static void quantity16(const uint8_t y, const uint8_t ov, const uint8_t nv);
static void mark16(const uint8_t y, const uint8_t v1, const uint8_t v2, uint8_t * const rcm=nullptr);
static void range16(const uint8_t y, const uint8_t ot, const uint8_t nt, const uint8_t oh, const uint8_t nh, uint8_t * const rcm=nullptr);
static void quantity(const uint8_t y, const uint8_t ov, const uint8_t nv, uint8_t * const rcm=nullptr);
static void quantity16(const uint8_t y, const uint8_t ov, const uint8_t nv, uint8_t * const rcm=nullptr);
#ifdef MAX7219_INIT_TEST
#if MAX7219_INIT_TEST
static void test_pattern();
static void run_test_pattern();
static void start_test_pattern();

10
Marlin/src/feature/pause.cpp

@ -711,9 +711,13 @@ void resume_print(const_float_t slow_load_length/*=0*/, const_float_t fast_load_
TERN_(HAS_FILAMENT_SENSOR, runout.reset());
TERN(DWIN_LCD_PROUI, DWIN_Print_Resume(), ui.reset_status());
TERN_(HAS_MARLINUI_MENU, ui.return_to_status());
TERN_(DWIN_LCD_PROUI, HMI_ReturnScreen());
#if ENABLED(DWIN_LCD_PROUI)
DWIN_Print_Resume();
HMI_ReturnScreen();
#else
ui.reset_status();
ui.return_to_status();
#endif
}
#endif // ADVANCED_PAUSE_FEATURE

6
Marlin/src/feature/power_monitor.cpp

@ -53,7 +53,7 @@ PowerMonitor power_monitor; // Single instance - this calls the constructor
void PowerMonitor::draw_current() {
const float amps = getAmps();
lcd_put_u8str(amps < 100 ? ftostr31ns(amps) : ui16tostr4rj((uint16_t)amps));
lcd_put_wchar('A');
lcd_put_lchar('A');
}
#endif
@ -61,7 +61,7 @@ PowerMonitor power_monitor; // Single instance - this calls the constructor
void PowerMonitor::draw_voltage() {
const float volts = getVolts();
lcd_put_u8str(volts < 100 ? ftostr31ns(volts) : ui16tostr4rj((uint16_t)volts));
lcd_put_wchar('V');
lcd_put_lchar('V');
}
#endif
@ -69,7 +69,7 @@ PowerMonitor power_monitor; // Single instance - this calls the constructor
void PowerMonitor::draw_power() {
const float power = getPower();
lcd_put_u8str(power < 100 ? ftostr31ns(power) : ui16tostr4rj((uint16_t)power));
lcd_put_wchar('W');
lcd_put_lchar('W');
}
#endif

2
Marlin/src/feature/power_monitor.h

@ -32,7 +32,7 @@ struct pm_lpf_t {
uint32_t filter_buf;
float value;
void add_sample(const uint16_t sample) {
filter_buf = filter_buf - (filter_buf >> K_VALUE) + (uint32_t(sample) << K_SCALE);
filter_buf += (uint32_t(sample) << K_SCALE) - (filter_buf >> K_VALUE);
}
void capture() {
value = filter_buf * (SCALE * (1.0f / (1UL << (PM_K_VALUE + PM_K_SCALE))));

4
Marlin/src/feature/spindle_laser.cpp

@ -58,7 +58,7 @@ cutter_power_t SpindleLaser::menuPower, // Power s
*/
void SpindleLaser::init() {
#if ENABLED(SPINDLE_SERVO)
MOVE_SERVO(SPINDLE_SERVO_NR, SPINDLE_SERVO_MIN);
servo[SPINDLE_SERVO_NR].move(SPINDLE_SERVO_MIN);
#else
OUT_WRITE(SPINDLE_LASER_ENA_PIN, !SPINDLE_LASER_ACTIVE_STATE); // Init spindle to off
#endif
@ -131,7 +131,7 @@ void SpindleLaser::apply_power(const uint8_t opwr) {
isReady = false;
}
#elif ENABLED(SPINDLE_SERVO)
MOVE_SERVO(SPINDLE_SERVO_NR, power);
servo[SPINDLE_SERVO_NR].move(power);
#else
WRITE(SPINDLE_LASER_ENA_PIN, enabled() ? SPINDLE_LASER_ACTIVE_STATE : !SPINDLE_LASER_ACTIVE_STATE);
isReady = true;

4
Marlin/src/gcode/calibrate/G28.cpp

@ -169,7 +169,7 @@
motion_state.jerk_state = planner.max_jerk;
planner.max_jerk.set(0, 0 OPTARG(DELTA, 0));
#endif
planner.reset_acceleration_rates();
planner.refresh_acceleration_rates();
return motion_state;
}
@ -178,7 +178,7 @@
planner.settings.max_acceleration_mm_per_s2[Y_AXIS] = motion_state.acceleration.y;
TERN_(DELTA, planner.settings.max_acceleration_mm_per_s2[Z_AXIS] = motion_state.acceleration.z);
TERN_(HAS_CLASSIC_JERK, planner.max_jerk = motion_state.jerk_state);
planner.reset_acceleration_rates();
planner.refresh_acceleration_rates();
}
#endif // IMPROVE_HOMING_RELIABILITY

2
Marlin/src/gcode/calibrate/G33.cpp

@ -437,7 +437,7 @@ void GcodeSuite::G33() {
const bool stow_after_each = parser.seen_test('E');
#if HAS_DELTA_SENSORLESS_PROBING
probe.test_sensitivity.set(!parser.seen_test('X'), !parser.seen_test('Y'), !parser.seen_test('Z'));
probe.test_sensitivity = { !parser.seen_test('X'), !parser.seen_test('Y'), !parser.seen_test('Z') };
const bool do_save_offset_adj = parser.seen_test('S');
#endif

8
Marlin/src/gcode/config/M43.cpp

@ -198,10 +198,10 @@ inline void servo_probe_test() {
uint8_t i = 0;
SERIAL_ECHOLNPGM(". Deploy & stow 4 times");
do {
MOVE_SERVO(probe_index, servo_angles[Z_PROBE_SERVO_NR][0]); // Deploy
servo[probe_index].move(servo_angles[Z_PROBE_SERVO_NR][0]); // Deploy
safe_delay(500);
deploy_state = READ(PROBE_TEST_PIN);
MOVE_SERVO(probe_index, servo_angles[Z_PROBE_SERVO_NR][1]); // Stow
servo[probe_index].move(servo_angles[Z_PROBE_SERVO_NR][1]); // Stow
safe_delay(500);
stow_state = READ(PROBE_TEST_PIN);
} while (++i < 4);
@ -226,7 +226,7 @@ inline void servo_probe_test() {
}
// Ask the user for a trigger event and measure the pulse width.
MOVE_SERVO(probe_index, servo_angles[Z_PROBE_SERVO_NR][0]); // Deploy
servo[probe_index].move(servo_angles[Z_PROBE_SERVO_NR][0]); // Deploy
safe_delay(500);
SERIAL_ECHOLNPGM("** Please trigger probe within 30 sec **");
uint16_t probe_counter = 0;
@ -256,7 +256,7 @@ inline void servo_probe_test() {
}
else SERIAL_ECHOLNPGM("FAIL: Noise detected - please re-run test");
MOVE_SERVO(probe_index, servo_angles[Z_PROBE_SERVO_NR][1]); // Stow
servo[probe_index].move(servo_angles[Z_PROBE_SERVO_NR][1]); // Stow
return;
}
}

6
Marlin/src/gcode/control/M280.cpp

@ -56,14 +56,14 @@ void GcodeSuite::M280() {
while (PENDING(now, end)) {
safe_delay(50);
now = _MIN(millis(), end);
MOVE_SERVO(servo_index, LROUND(aold + (anew - aold) * (float(now - start) / t)));
servo[servo_index].move(LROUND(aold + (anew - aold) * (float(now - start) / t)));
}
}
#endif // POLARGRAPH
MOVE_SERVO(servo_index, anew);
servo[servo_index].move(anew);
}
else
DETACH_SERVO(servo_index);
servo[servo_index].detach();
}
else
SERIAL_ECHO_MSG(" Servo ", servo_index, ": ", servo[servo_index].read());

2
Marlin/src/gcode/control/M282.cpp

@ -36,7 +36,7 @@ void GcodeSuite::M282() {
const int servo_index = parser.value_int();
if (WITHIN(servo_index, 0, NUM_SERVOS - 1))
DETACH_SERVO(servo_index);
servo[servo_index].detach();
else
SERIAL_ECHO_MSG("Servo ", servo_index, " out of range");

18
Marlin/src/gcode/feature/trinamic/M919.cpp

@ -169,6 +169,15 @@ void GcodeSuite::M919() {
#if AXIS_IS_TMC(K)
case K_AXIS: TMC_SET_CHOPPER_TIME(K); break;
#endif
#if AXIS_IS_TMC(U)
case U_AXIS: TMC_SET_CHOPPER_TIME(U); break;
#endif
#if AXIS_IS_TMC(V)
case V_AXIS: TMC_SET_CHOPPER_TIME(V); break;
#endif
#if AXIS_IS_TMC(W)
case W_AXIS: TMC_SET_CHOPPER_TIME(W); break;
#endif
#if HAS_E_CHOPPER
case E_AXIS: {
@ -236,6 +245,15 @@ void GcodeSuite::M919() {
#if AXIS_IS_TMC(K)
TMC_SAY_CHOPPER_TIME(K);
#endif
#if AXIS_IS_TMC(U)
TMC_SAY_CHOPPER_TIME(U);
#endif
#if AXIS_IS_TMC(V)
TMC_SAY_CHOPPER_TIME(V);
#endif
#if AXIS_IS_TMC(W)
TMC_SAY_CHOPPER_TIME(W);
#endif
#if AXIS_IS_TMC(E0)
TMC_SAY_CHOPPER_TIME(E0);
#endif

4
Marlin/src/gcode/gcode.cpp

@ -848,6 +848,10 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) {
case 421: M421(); break; // M421: Set a Mesh Bed Leveling Z coordinate
#endif
#if ENABLED(X_AXIS_TWIST_COMPENSATION)
case 423: M423(); break; // M423: Reset, modify, or report X-Twist Compensation data
#endif
#if ENABLED(BACKLASH_GCODE)
case 425: M425(); break; // M425: Tune backlash compensation
#endif

197
Marlin/src/gcode/motion/G2_G3.cpp

@ -197,8 +197,8 @@ void plan_arc(
// Feedrate for the move, scaled by the feedrate multiplier
const feedRate_t scaled_fr_mm_s = MMS_SCALED(feedrate_mm_s);
// Get the nominal segment length based on settings
const float nominal_segment_mm = (
// Get the ideal segment length for the move based on settings
const float ideal_segment_mm = (
#if ARC_SEGMENTS_PER_SEC // Length based on segments per second and feedrate
constrain(scaled_fr_mm_s * RECIPROCAL(ARC_SEGMENTS_PER_SEC), MIN_ARC_SEGMENT_MM, MAX_ARC_SEGMENT_MM)
#else
@ -206,19 +206,18 @@ void plan_arc(
#endif
);
// Number of whole segments based on the nominal segment length
const float nominal_segments = _MAX(FLOOR(flat_mm / nominal_segment_mm), min_segments);
// Number of whole segments based on the ideal segment length
const float nominal_segments = _MAX(FLOOR(flat_mm / ideal_segment_mm), min_segments),
nominal_segment_mm = flat_mm / nominal_segments;
// A new segment length based on the required minimum
const float segment_mm = constrain(flat_mm / nominal_segments, MIN_ARC_SEGMENT_MM, MAX_ARC_SEGMENT_MM);
// The number of whole segments in the arc, with best attempt to honor MIN_ARC_SEGMENT_MM and MAX_ARC_SEGMENT_MM
const uint16_t segments = nominal_segment_mm > (MAX_ARC_SEGMENT_MM) ? CEIL(flat_mm / (MAX_ARC_SEGMENT_MM)) :
nominal_segment_mm < (MIN_ARC_SEGMENT_MM) ? _MAX(1, FLOOR(flat_mm / (MIN_ARC_SEGMENT_MM))) :
nominal_segments;
// The number of whole segments in the arc, ignoring the remainder
uint16_t segments = FLOOR(flat_mm / segment_mm);
// Are the segments now too few to reach the destination?
const float segmented_length = segment_mm * segments;
const bool tooshort = segmented_length < flat_mm - 0.0001f;
const float proportion = tooshort ? segmented_length / flat_mm : 1.0f;
#if ENABLED(SCARA_FEEDRATE_SCALING)
const float inv_duration = (scaled_fr_mm_s / flat_mm) * segments;
#endif
/**
* Vector rotation by transformation matrix: r is the original vector, r_T is the rotated vector,
@ -246,108 +245,106 @@ void plan_arc(
* a correction, the planner should have caught up to the lag caused by the initial plan_arc overhead.
* This is important when there are successive arc motions.
*/
// Vector rotation matrix values
xyze_pos_t raw;
const float theta_per_segment = proportion * angular_travel / segments,
sq_theta_per_segment = sq(theta_per_segment),
sin_T = theta_per_segment - sq_theta_per_segment * theta_per_segment / 6,
cos_T = 1 - 0.5f * sq_theta_per_segment; // Small angle approximation
#if DISABLED(AUTO_BED_LEVELING_UBL)
ARC_LIJKUVW_CODE(
const float per_segment_L = proportion * travel_L / segments,
const float per_segment_I = proportion * travel_I / segments,
const float per_segment_J = proportion * travel_J / segments,
const float per_segment_K = proportion * travel_K / segments,
const float per_segment_U = proportion * travel_U / segments,
const float per_segment_V = proportion * travel_V / segments,
const float per_segment_W = proportion * travel_W / segments
);
#endif
CODE_ITEM_E(const float extruder_per_segment = proportion * travel_E / segments);
// For shortened segments, run all but the remainder in the loop
if (tooshort) segments++;
xyze_pos_t raw;
// Initialize all linear axes and E
ARC_LIJKUVWE_CODE(
raw[axis_l] = current_position[axis_l],
raw.i = current_position.i,
raw.j = current_position.j,
raw.k = current_position.k,
raw.u = current_position.u,
raw.v = current_position.v,
raw.w = current_position.w,
raw.e = current_position.e
);
// do not calculate rotation parameters for trivial single-segment arcs
if (segments > 1) {
// Vector rotation matrix values
const float theta_per_segment = angular_travel / segments,
sq_theta_per_segment = sq(theta_per_segment),
sin_T = theta_per_segment - sq_theta_per_segment * theta_per_segment / 6,
cos_T = 1 - 0.5f * sq_theta_per_segment; // Small angle approximation
#if DISABLED(AUTO_BED_LEVELING_UBL)
ARC_LIJKUVW_CODE(
const float per_segment_L = travel_L / segments,
const float per_segment_I = travel_I / segments,
const float per_segment_J = travel_J / segments,
const float per_segment_K = travel_K / segments,
const float per_segment_U = travel_U / segments,
const float per_segment_V = travel_V / segments,
const float per_segment_W = travel_W / segments
);
#endif
#if ENABLED(SCARA_FEEDRATE_SCALING)
const float inv_duration = scaled_fr_mm_s / segment_mm;
#endif
CODE_ITEM_E(const float extruder_per_segment = travel_E / segments);
millis_t next_idle_ms = millis() + 200UL;
// Initialize all linear axes and E
ARC_LIJKUVWE_CODE(
raw[axis_l] = current_position[axis_l],
raw.i = current_position.i,
raw.j = current_position.j,
raw.k = current_position.k,
raw.u = current_position.u,
raw.v = current_position.v,
raw.w = current_position.w,
raw.e = current_position.e
);
#if N_ARC_CORRECTION > 1
int8_t arc_recalc_count = N_ARC_CORRECTION;
#endif
millis_t next_idle_ms = millis() + 200UL;
for (uint16_t i = 1; i < segments; i++) { // Iterate (segments-1) times
#if N_ARC_CORRECTION > 1
int8_t arc_recalc_count = N_ARC_CORRECTION;
#endif
thermalManager.manage_heater();
const millis_t ms = millis();
if (ELAPSED(ms, next_idle_ms)) {
next_idle_ms = ms + 200UL;
idle();
}
for (uint16_t i = 1; i < segments; i++) { // Iterate (segments-1) times
#if N_ARC_CORRECTION > 1
if (--arc_recalc_count) {
// Apply vector rotation matrix to previous rvec.a / 1
const float r_new_Y = rvec.a * sin_T + rvec.b * cos_T;
rvec.a = rvec.a * cos_T - rvec.b * sin_T;
rvec.b = r_new_Y;
thermalManager.manage_heater();
const millis_t ms = millis();
if (ELAPSED(ms, next_idle_ms)) {
next_idle_ms = ms + 200UL;
idle();
}
else
#endif
{
#if N_ARC_CORRECTION > 1
arc_recalc_count = N_ARC_CORRECTION;
if (--arc_recalc_count) {
// Apply vector rotation matrix to previous rvec.a / 1
const float r_new_Y = rvec.a * sin_T + rvec.b * cos_T;
rvec.a = rvec.a * cos_T - rvec.b * sin_T;
rvec.b = r_new_Y;
}
else
#endif
{
#if N_ARC_CORRECTION > 1
arc_recalc_count = N_ARC_CORRECTION;
#endif
// Arc correction to radius vector. Computed only every N_ARC_CORRECTION increments.
// Compute exact location by applying transformation matrix from initial radius vector(=-offset).
// To reduce stuttering, the sin and cos could be computed at different times.
// For now, compute both at the same time.
const float Ti = i * theta_per_segment, cos_Ti = cos(Ti), sin_Ti = sin(Ti);
rvec.a = -offset[0] * cos_Ti + offset[1] * sin_Ti;
rvec.b = -offset[0] * sin_Ti - offset[1] * cos_Ti;
}
// Arc correction to radius vector. Computed only every N_ARC_CORRECTION increments.
// Compute exact location by applying transformation matrix from initial radius vector(=-offset).
// To reduce stuttering, the sin and cos could be computed at different times.
// For now, compute both at the same time.
const float cos_Ti = cos(i * theta_per_segment), sin_Ti = sin(i * theta_per_segment);
rvec.a = -offset[0] * cos_Ti + offset[1] * sin_Ti;
rvec.b = -offset[0] * sin_Ti - offset[1] * cos_Ti;
}
// Update raw location
raw[axis_p] = center_P + rvec.a;
raw[axis_q] = center_Q + rvec.b;
ARC_LIJKUVWE_CODE(
#if ENABLED(AUTO_BED_LEVELING_UBL)
raw[axis_l] = start_L,
raw.i = start_I, raw.j = start_J, raw.k = start_K,
raw.u = start_U, raw.v = start_V, raw.w = start_V
#else
raw[axis_l] += per_segment_L,
raw.i += per_segment_I, raw.j += per_segment_J, raw.k += per_segment_K,
raw.u += per_segment_U, raw.v += per_segment_V, raw.w += per_segment_W
#endif
, raw.e += extruder_per_segment
);
// Update raw location
raw[axis_p] = center_P + rvec.a;
raw[axis_q] = center_Q + rvec.b;
ARC_LIJKUVWE_CODE(
#if ENABLED(AUTO_BED_LEVELING_UBL)
raw[axis_l] = start_L,
raw.i = start_I, raw.j = start_J, raw.k = start_K,
raw.u = start_U, raw.v = start_V, raw.w = start_V
#else
raw[axis_l] += per_segment_L,
raw.i += per_segment_I, raw.j += per_segment_J, raw.k += per_segment_K,
raw.u += per_segment_U, raw.v += per_segment_V, raw.w += per_segment_W
#endif
, raw.e += extruder_per_segment
);
apply_motion_limits(raw);
apply_motion_limits(raw);
#if HAS_LEVELING && !PLANNER_LEVELING
planner.apply_leveling(raw);
#endif
#if HAS_LEVELING && !PLANNER_LEVELING
planner.apply_leveling(raw);
#endif
if (!planner.buffer_line(raw, scaled_fr_mm_s, active_extruder, 0 OPTARG(SCARA_FEEDRATE_SCALING, inv_duration)))
break;
if (!planner.buffer_line(raw, scaled_fr_mm_s, active_extruder, 0 OPTARG(SCARA_FEEDRATE_SCALING, inv_duration)))
break;
}
}
// Ensure last segment arrives at target location.

2
Marlin/src/gcode/motion/G6.cpp

@ -50,7 +50,7 @@ void GcodeSuite::G6() {
// No speed is set, can't schedule the move
if (!planner.last_page_step_rate) return;
const page_idx_t page_idx = (page_idx_t) parser.value_ulong();
const page_idx_t page_idx = (page_idx_t)parser.value_ulong();
uint16_t num_steps = DirectStepping::Config::TOTAL_STEPS;
if (parser.seen('S')) num_steps = parser.value_ushort();

5
Marlin/src/gcode/queue.cpp

@ -196,14 +196,15 @@ bool GCodeQueue::process_injected_command() {
* Never call this from a G-code handler!
*/
void GCodeQueue::enqueue_one_now(const char * const cmd) { while (!enqueue_one(cmd)) idle(); }
void GCodeQueue::enqueue_one_now(FSTR_P const fcmd) { while (!enqueue_one(fcmd)) idle(); }
/**
* Attempt to enqueue a single G-code command
* and return 'true' if successful.
*/
bool GCodeQueue::enqueue_one(FSTR_P const fgcode) {
bool GCodeQueue::enqueue_one(FSTR_P const fcmd) {
size_t i = 0;
PGM_P p = FTOP(fgcode);
PGM_P p = FTOP(fcmd);
char c;
while ((c = pgm_read_byte(&p[i])) && c != '\n') i++;
char cmd[i + 1];

3
Marlin/src/gcode/queue.h

@ -141,12 +141,13 @@ public:
* Enqueue and return only when commands are actually enqueued
*/
static void enqueue_one_now(const char * const cmd);
static void enqueue_one_now(FSTR_P const fcmd);
/**
* Attempt to enqueue a single G-code command
* and return 'true' if successful.
*/
static bool enqueue_one(FSTR_P const fgcode);
static bool enqueue_one(FSTR_P const fcmd);
/**
* Enqueue with Serial Echo

4
Marlin/src/gcode/temp/M106_M107.cpp

@ -90,7 +90,7 @@ void GcodeSuite::M106() {
// Set speed, with constraint
thermalManager.set_fan_speed(pfan, speed);
TERN_(LASER_SYNCHRONOUS_M106_M107, planner.buffer_sync_block(BLOCK_FLAG_SYNC_FANS));
TERN_(LASER_SYNCHRONOUS_M106_M107, planner.buffer_sync_block(BLOCK_BIT_SYNC_FANS));
if (TERN0(DUAL_X_CARRIAGE, idex_is_duplicating())) // pfan == 0 when duplicating
thermalManager.set_fan_speed(1 - pfan, speed);
@ -111,7 +111,7 @@ void GcodeSuite::M107() {
if (TERN0(DUAL_X_CARRIAGE, idex_is_duplicating())) // pfan == 0 when duplicating
thermalManager.set_fan_speed(1 - pfan, 0);
TERN_(LASER_SYNCHRONOUS_M106_M107, planner.buffer_sync_block(BLOCK_FLAG_SYNC_FANS));
TERN_(LASER_SYNCHRONOUS_M106_M107, planner.buffer_sync_block(BLOCK_BIT_SYNC_FANS));
}
#endif // HAS_FAN

6
Marlin/src/gcode/units/M149.cpp

@ -30,9 +30,9 @@
* M149: Set temperature units
*/
void GcodeSuite::M149() {
if (parser.seenval('C')) parser.set_input_temp_units(TEMPUNIT_C);
else if (parser.seenval('K')) parser.set_input_temp_units(TEMPUNIT_K);
else if (parser.seenval('F')) parser.set_input_temp_units(TEMPUNIT_F);
if (parser.seen('C')) parser.set_input_temp_units(TEMPUNIT_C);
else if (parser.seen('K')) parser.set_input_temp_units(TEMPUNIT_K);
else if (parser.seen('F')) parser.set_input_temp_units(TEMPUNIT_F);
else M149_report();
}

11
Marlin/src/inc/Conditionals_LCD.h

@ -513,7 +513,7 @@
#define HAS_LCDPRINT 1
#endif
#if ANY(HAS_DISPLAY, HAS_DWIN_E3V2)
#if HAS_DISPLAY || HAS_DWIN_E3V2
#define HAS_STATUS_MESSAGE 1
#endif
@ -669,9 +669,9 @@
* Number of Linear Axes (e.g., XYZIJKUVW)
* All the logical axes except for the tool (E) axis
*/
#ifdef LINEAR_AXES
#undef LINEAR_AXES
#define LINEAR_AXES_WARNING 1
#ifdef NUM_AXES
#undef NUM_AXES
#define NUM_AXES_WARNING 1
#endif
#ifdef W_DRIVER_TYPE
@ -1463,7 +1463,8 @@
#elif ENABLED(TFT_RES_1024x600)
#define TFT_WIDTH 1024
#define TFT_HEIGHT 600
#define GRAPHICAL_TFT_UPSCALE 4
#define GRAPHICAL_TFT_UPSCALE 6
#define TFT_PIXEL_OFFSET_X 120
#endif
// FSMC/SPI TFT Panels using standard HAL/tft/tft_(fsmc|spi|ltdc).h

8
Marlin/src/inc/Conditionals_adv.h

@ -1018,13 +1018,13 @@
* LCD_SERIAL_PORT must be defined ahead of HAL.h
*/
#ifndef LCD_SERIAL_PORT
#if HAS_DWIN_E3V2 || IS_DWIN_MARLINUI
#if HAS_DWIN_E3V2 || IS_DWIN_MARLINUI || HAS_DGUS_LCD
#if MB(BTT_SKR_MINI_E3_V1_0, BTT_SKR_MINI_E3_V1_2, BTT_SKR_MINI_E3_V2_0, BTT_SKR_MINI_E3_V3_0, BTT_SKR_E3_TURBO)
#define LCD_SERIAL_PORT 1
#elif MB(CREALITY_V24S1_301, CREALITY_V24S1_301F4, CREALITY_V423)
#define LCD_SERIAL_PORT 2 // Creality Ender3S1 board
#elif MB(CREALITY_V24S1_301, CREALITY_V24S1_301F4, CREALITY_V423, MKS_ROBIN)
#define LCD_SERIAL_PORT 2 // Creality Ender3S1, MKS Robin
#else
#define LCD_SERIAL_PORT 3 // Creality 4.x board
#define LCD_SERIAL_PORT 3 // Other boards
#endif
#endif
#ifdef LCD_SERIAL_PORT

10
Marlin/src/inc/SanityCheck.h

@ -619,6 +619,8 @@
#error "Z_STEPPER_ALIGN_KNOWN_STEPPER_POSITIONS is now just Z_STEPPER_ALIGN_STEPPER_XY."
#elif defined(DWIN_CREALITY_LCD_ENHANCED)
#error "DWIN_CREALITY_LCD_ENHANCED is now DWIN_LCD_PROUI."
#elif defined(LINEAR_AXES)
#error "LINEAR_AXES is now NUM_AXES (to account for rotational axes)."
#elif defined(X_DUAL_STEPPER_DRIVERS)
#error "X_DUAL_STEPPER_DRIVERS is no longer needed and should be removed."
#elif defined(Y_DUAL_STEPPER_DRIVERS)
@ -1565,8 +1567,8 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
/**
* Allow only one kinematic type to be defined
*/
#if MANY(DELTA, MORGAN_SCARA, MP_SCARA, AXEL_TPARA, COREXY, COREXZ, COREYZ, COREYX, COREZX, COREZY, MARKFORGED_XY, MARKFORGED_YX, FOAMCUTTER_XYUV)
#error "Please enable only one of DELTA, MORGAN_SCARA, MP_SCARA, AXEL_TPARA, COREXY, COREXZ, COREYZ, COREYX, COREZX, COREZY, MARKFORGED_XY, MARKFORGED_YX, or FOAMCUTTER_XYUV."
#if MANY(DELTA, MORGAN_SCARA, MP_SCARA, AXEL_TPARA, COREXY, COREXZ, COREYZ, COREYX, COREZX, COREZY, MARKFORGED_XY, MARKFORGED_YX, ARTICULATED_ROBOT_ARM, FOAMCUTTER_XYUV)
#error "Please enable only one of DELTA, MORGAN_SCARA, MP_SCARA, AXEL_TPARA, COREXY, COREXZ, COREYZ, COREYX, COREZX, COREZY, MARKFORGED_XY, MARKFORGED_YX, ARTICULATED_ROBOT_ARM, or FOAMCUTTER_XYUV."
#endif
/**
@ -2921,8 +2923,8 @@ static_assert(Y_MAX_LENGTH >= Y_BED_SIZE, "Movement bounds (Y_MIN_POS, Y_MAX_POS
#endif
#endif
#if defined(GRAPHICAL_TFT_UPSCALE) && !WITHIN(GRAPHICAL_TFT_UPSCALE, 2, 4)
#error "GRAPHICAL_TFT_UPSCALE must be 2, 3, or 4."
#if defined(GRAPHICAL_TFT_UPSCALE) && !WITHIN(GRAPHICAL_TFT_UPSCALE, 2, 6)
#error "GRAPHICAL_TFT_UPSCALE must be between 2 and 6."
#endif
#if BOTH(CHIRON_TFT_STANDARD, CHIRON_TFT_NEW)

12
Marlin/src/lcd/HD44780/lcdprint_hd44780.cpp

@ -50,7 +50,7 @@ extern LCD_CLASS lcd;
int lcd_glyph_height() { return 1; }
typedef struct _hd44780_charmap_t {
wchar_t uchar; // the unicode char
lchar_t uchar; // the unicode char
uint8_t idx; // the glyph of the char in the ROM
uint8_t idx2; // the char used to be combined with the idx to simulate a single char
} hd44780_charmap_t;
@ -992,7 +992,7 @@ void lcd_put_int(const int i) { lcd.print(i); }
// return < 0 on error
// return the advanced cols
int lcd_put_wchar_max(const wchar_t c, const pixel_len_t max_length) {
int lcd_put_lchar_max(const lchar_t &c, const pixel_len_t max_length) {
// find the HD44780 internal ROM first
int ret;
@ -1051,10 +1051,10 @@ static int lcd_put_u8str_max_cb(const char * utf8_str, read_byte_cb_t cb_read_by
pixel_len_t ret = 0;
const uint8_t *p = (uint8_t *)utf8_str;
while (ret < max_length) {
wchar_t ch = 0;
p = get_utf8_value_cb(p, cb_read_byte, &ch);
if (!ch) break;
ret += lcd_put_wchar_max(ch, max_length - ret);
lchar_t wc;
p = get_utf8_value_cb(p, cb_read_byte, wc);
if (!wc) break;
ret += lcd_put_lchar_max(wc, max_length - ret);
}
return (int)ret;
}

138
Marlin/src/lcd/HD44780/marlinui_HD44780.cpp

@ -405,7 +405,7 @@ void MarlinUI::clear_lcd() { lcd.clear(); }
void lcd_erase_line(const lcd_uint_t line) {
lcd_moveto(0, line);
for (uint8_t i = LCD_WIDTH + 1; --i;)
lcd_put_wchar(' ');
lcd_put_lchar(' ');
}
// Scroll the PSTR 'text' in a 'len' wide field for 'time' milliseconds at position col,line
@ -413,7 +413,7 @@ void MarlinUI::clear_lcd() { lcd.clear(); }
uint8_t slen = utf8_strlen(ftxt);
if (slen < len) {
lcd_put_u8str_max(col, line, ftxt, len);
for (; slen < len; ++slen) lcd_put_wchar(' ');
for (; slen < len; ++slen) lcd_put_lchar(' ');
safe_delay(time);
}
else {
@ -425,7 +425,7 @@ void MarlinUI::clear_lcd() { lcd.clear(); }
lcd_put_u8str_max_P(col, line, p, len);
// Fill with spaces
for (uint8_t ix = slen - i; ix < len; ++ix) lcd_put_wchar(' ');
for (uint8_t ix = slen - i; ix < len; ++ix) lcd_put_lchar(' ');
// Delay
safe_delay(dly);
@ -439,9 +439,9 @@ void MarlinUI::clear_lcd() { lcd.clear(); }
static void logo_lines(FSTR_P const extra) {
int16_t indent = (LCD_WIDTH - 8 - utf8_strlen(extra)) / 2;
lcd_put_wchar(indent, 0, '\x00'); lcd_put_u8str(F( "------" )); lcd_put_wchar('\x01');
lcd_put_lchar(indent, 0, '\x00'); lcd_put_u8str(F( "------" )); lcd_put_lchar('\x01');
lcd_put_u8str(indent, 1, F("|Marlin|")); lcd_put_u8str(extra);
lcd_put_wchar(indent, 2, '\x02'); lcd_put_u8str(F( "------" )); lcd_put_wchar('\x03');
lcd_put_lchar(indent, 2, '\x02'); lcd_put_u8str(F( "------" )); lcd_put_lchar('\x03');
}
void MarlinUI::show_bootscreen() {
@ -510,11 +510,11 @@ void MarlinUI::draw_kill_screen() {
// Homed and known, display constantly.
//
FORCE_INLINE void _draw_axis_value(const AxisEnum axis, const char *value, const bool blink) {
lcd_put_wchar('X' + uint8_t(axis));
lcd_put_lchar('X' + uint8_t(axis));
if (blink)
lcd_put_u8str(value);
else if (axis_should_home(axis))
while (const char c = *value++) lcd_put_wchar(c <= '.' ? c : '?');
while (const char c = *value++) lcd_put_lchar(c <= '.' ? c : '?');
else if (NONE(HOME_AFTER_DEACTIVATE, DISABLE_REDUCED_ACCURACY_WARNING) && !axis_is_trusted(axis))
lcd_put_u8str(axis == Z_AXIS ? F(" ") : F(" "));
else
@ -531,27 +531,27 @@ FORCE_INLINE void _draw_heater_status(const heater_id_t heater_id, const char pr
const celsius_t t1 = thermalManager.wholeDegHotend(heater_id), t2 = thermalManager.degTargetHotend(heater_id);
#endif
if (prefix >= 0) lcd_put_wchar(prefix);
if (prefix >= 0) lcd_put_lchar(prefix);
lcd_put_u8str(t1 < 0 ? "err" : i16tostr3rj(t1));
lcd_put_wchar('/');
lcd_put_lchar('/');
#if !HEATER_IDLE_HANDLER
UNUSED(blink);
#else
if (!blink && thermalManager.heater_idle[thermalManager.idle_index_for_id(heater_id)].timed_out) {
lcd_put_wchar(' ');
if (t2 >= 10) lcd_put_wchar(' ');
if (t2 >= 100) lcd_put_wchar(' ');
lcd_put_lchar(' ');
if (t2 >= 10) lcd_put_lchar(' ');
if (t2 >= 100) lcd_put_lchar(' ');
}
else
#endif
lcd_put_u8str(i16tostr3left(t2));
if (prefix >= 0) {
lcd_put_wchar(LCD_STR_DEGREE[0]);
lcd_put_wchar(' ');
if (t2 < 10) lcd_put_wchar(' ');
lcd_put_lchar(LCD_STR_DEGREE[0]);
lcd_put_lchar(' ');
if (t2 < 10) lcd_put_lchar(' ');
}
}
@ -559,27 +559,27 @@ FORCE_INLINE void _draw_heater_status(const heater_id_t heater_id, const char pr
FORCE_INLINE void _draw_cooler_status(const char prefix, const bool blink) {
const celsius_t t2 = thermalManager.degTargetCooler();
if (prefix >= 0) lcd_put_wchar(prefix);
if (prefix >= 0) lcd_put_lchar(prefix);
lcd_put_u8str(i16tostr3rj(thermalManager.wholeDegCooler()));
lcd_put_wchar('/');
lcd_put_lchar('/');
#if !HEATER_IDLE_HANDLER
UNUSED(blink);
#else
if (!blink && thermalManager.heater_idle[thermalManager.idle_index_for_id(heater_id)].timed_out) {
lcd_put_wchar(' ');
if (t2 >= 10) lcd_put_wchar(' ');
if (t2 >= 100) lcd_put_wchar(' ');
lcd_put_lchar(' ');
if (t2 >= 10) lcd_put_lchar(' ');
if (t2 >= 100) lcd_put_lchar(' ');
}
else
#endif
lcd_put_u8str(i16tostr3left(t2));
if (prefix >= 0) {
lcd_put_wchar(LCD_STR_DEGREE[0]);
lcd_put_wchar(' ');
if (t2 < 10) lcd_put_wchar(' ');
lcd_put_lchar(LCD_STR_DEGREE[0]);
lcd_put_lchar(' ');
if (t2 < 10) lcd_put_lchar(' ');
}
}
#endif
@ -588,7 +588,7 @@ FORCE_INLINE void _draw_cooler_status(const char prefix, const bool blink) {
FORCE_INLINE void _draw_flowmeter_status() {
lcd_put_u8str("~");
lcd_put_u8str(ftostr11ns(cooler.flowrate));
lcd_put_wchar('L');
lcd_put_lchar('L');
}
#endif
@ -602,7 +602,7 @@ FORCE_INLINE void _draw_cooler_status(const char prefix, const bool blink) {
}
else {
lcd_put_u8str(ftostr12ns(ammeter.current));
lcd_put_wchar('A');
lcd_put_lchar('A');
}
}
#endif
@ -620,7 +620,7 @@ FORCE_INLINE void _draw_bed_status(const bool blink) {
lcd_put_u8str(ui8tostr3rj(progress));
else
lcd_put_u8str(F("---"));
lcd_put_wchar('%');
lcd_put_lchar('%');
}
#endif
@ -667,7 +667,7 @@ void MarlinUI::draw_status_message(const bool blink) {
lcd_put_u8str(ftostr12ns(filwidth.measured_mm));
lcd_put_u8str(F(" V"));
lcd_put_u8str(i16tostr3rj(planner.volumetric_percent(parser.volumetric_enabled)));
lcd_put_wchar('%');
lcd_put_lchar('%');
return;
}
@ -686,7 +686,7 @@ void MarlinUI::draw_status_message(const bool blink) {
lcd_put_u8str(status_message);
// Fill the rest with spaces
while (slen < LCD_WIDTH) { lcd_put_wchar(' '); ++slen; }
while (slen < LCD_WIDTH) { lcd_put_lchar(' '); ++slen; }
}
else {
// String is larger than the available space in screen.
@ -700,11 +700,11 @@ void MarlinUI::draw_status_message(const bool blink) {
// If the remaining string doesn't completely fill the screen
if (rlen < LCD_WIDTH) {
uint8_t chars = LCD_WIDTH - rlen; // Amount of space left in characters
lcd_put_wchar(' '); // Always at 1+ spaces left, draw a space
lcd_put_lchar(' '); // Always at 1+ spaces left, draw a space
if (--chars) { // Draw a second space if there's room
lcd_put_wchar(' ');
lcd_put_lchar(' ');
if (--chars) { // Draw a third space if there's room
lcd_put_wchar(' ');
lcd_put_lchar(' ');
if (--chars)
lcd_put_u8str_max(status_message, chars); // Print a second copy of the message
}
@ -726,7 +726,7 @@ void MarlinUI::draw_status_message(const bool blink) {
// Fill the rest with spaces if there are missing spaces
while (slen < LCD_WIDTH) {
lcd_put_wchar(' ');
lcd_put_lchar(' ');
++slen;
}
#endif
@ -778,7 +778,7 @@ inline uint8_t draw_elapsed_or_remaining_time(uint8_t timepos, const bool blink)
duration_t remaining = (progress > 0) ? ((elapsed * 25600 / progress) >> 8) - elapsed : 0;
#endif
timepos -= remaining.toDigital(buffer);
lcd_put_wchar(timepos, 2, 'R');
lcd_put_lchar(timepos, 2, 'R');
}
#else
constexpr bool show_remain = false;
@ -787,7 +787,7 @@ inline uint8_t draw_elapsed_or_remaining_time(uint8_t timepos, const bool blink)
if (!show_remain) {
duration_t elapsed = print_job_timer.duration();
timepos -= elapsed.toDigital(buffer);
lcd_put_wchar(timepos, 2, LCD_STR_CLOCK[0]);
lcd_put_lchar(timepos, 2, LCD_STR_CLOCK[0]);
}
lcd_put_u8str(buffer);
return timepos;
@ -912,7 +912,7 @@ void MarlinUI::draw_status_screen() {
else {
const xy_pos_t lpos = current_position.asLogical();
_draw_axis_value(X_AXIS, ftostr4sign(lpos.x), blink);
lcd_put_wchar(' ');
lcd_put_lchar(' ');
_draw_axis_value(Y_AXIS, ftostr4sign(lpos.y), blink);
}
@ -926,7 +926,7 @@ void MarlinUI::draw_status_screen() {
_draw_axis_value(Z_AXIS, ftostr52sp(LOGICAL_Z_POSITION(current_position.z)), blink);
#if HAS_LEVELING && !HAS_HEATED_BED
lcd_put_wchar(planner.leveling_active || blink ? '_' : ' ');
lcd_put_lchar(planner.leveling_active || blink ? '_' : ' ');
#endif
#endif // LCD_HEIGHT > 2
@ -935,9 +935,9 @@ void MarlinUI::draw_status_screen() {
#if LCD_HEIGHT > 3
lcd_put_wchar(0, 2, LCD_STR_FEEDRATE[0]);
lcd_put_lchar(0, 2, LCD_STR_FEEDRATE[0]);
lcd_put_u8str(i16tostr3rj(feedrate_percentage));
lcd_put_wchar('%');
lcd_put_lchar('%');
const uint8_t timepos = draw_elapsed_or_remaining_time(LCD_WIDTH - 1, blink);
@ -969,9 +969,9 @@ void MarlinUI::draw_status_screen() {
per = planner.flow_percentage[0];
#endif
}
lcd_put_wchar(c);
lcd_put_lchar(c);
lcd_put_u8str(i16tostr3rj(per));
lcd_put_wchar('%');
lcd_put_lchar('%');
#endif
#endif
@ -993,7 +993,7 @@ void MarlinUI::draw_status_screen() {
_draw_axis_value(Z_AXIS, ftostr52sp(LOGICAL_Z_POSITION(current_position.z)), blink);
#if HAS_LEVELING && (HAS_MULTI_HOTEND || !HAS_HEATED_BED)
lcd_put_wchar(LCD_WIDTH - 1, 0, planner.leveling_active || blink ? '_' : ' ');
lcd_put_lchar(LCD_WIDTH - 1, 0, planner.leveling_active || blink ? '_' : ' ');
#endif
// ========== Line 2 ==========
@ -1008,9 +1008,9 @@ void MarlinUI::draw_status_screen() {
_draw_bed_status(blink);
#endif
lcd_put_wchar(LCD_WIDTH - 9, 1, LCD_STR_FEEDRATE[0]);
lcd_put_lchar(LCD_WIDTH - 9, 1, LCD_STR_FEEDRATE[0]);
lcd_put_u8str(i16tostr3rj(feedrate_percentage));
lcd_put_wchar('%');
lcd_put_lchar('%');
// ========== Line 3 ==========
@ -1075,29 +1075,29 @@ void MarlinUI::draw_status_screen() {
vlen = vstr ? utf8_strlen(vstr) : 0;
if (style & SS_CENTER) {
int8_t pad = (LCD_WIDTH - plen - vlen) / 2;
while (--pad >= 0) { lcd_put_wchar(' '); n--; }
while (--pad >= 0) { lcd_put_lchar(' '); n--; }
}
if (plen) n = lcd_put_u8str(fstr, itemIndex, itemStringC, itemStringF, n);
if (vlen) n -= lcd_put_u8str_max(vstr, n);
for (; n > 0; --n) lcd_put_wchar(' ');
for (; n > 0; --n) lcd_put_lchar(' ');
}
// Draw a generic menu item with pre_char (if selected) and post_char
void MenuItemBase::_draw(const bool sel, const uint8_t row, FSTR_P const ftpl, const char pre_char, const char post_char) {
lcd_put_wchar(0, row, sel ? pre_char : ' ');
lcd_put_lchar(0, row, sel ? pre_char : ' ');
uint8_t n = lcd_put_u8str(ftpl, itemIndex, itemStringC, itemStringF, LCD_WIDTH - 2);
for (; n; --n) lcd_put_wchar(' ');
lcd_put_wchar(post_char);
for (; n; --n) lcd_put_lchar(' ');
lcd_put_lchar(post_char);
}
// Draw a menu item with a (potentially) editable value
void MenuEditItemBase::draw(const bool sel, const uint8_t row, FSTR_P const ftpl, const char * const inStr, const bool pgm) {
const uint8_t vlen = inStr ? (pgm ? utf8_strlen_P(inStr) : utf8_strlen(inStr)) : 0;
lcd_put_wchar(0, row, sel ? LCD_STR_ARROW_RIGHT[0] : ' ');
lcd_put_lchar(0, row, sel ? LCD_STR_ARROW_RIGHT[0] : ' ');
uint8_t n = lcd_put_u8str(ftpl, itemIndex, itemStringC, itemStringF, LCD_WIDTH - 2 - vlen);
if (vlen) {
lcd_put_wchar(':');
for (; n; --n) lcd_put_wchar(' ');
lcd_put_lchar(':');
for (; n; --n) lcd_put_lchar(' ');
if (pgm) lcd_put_u8str_P(inStr); else lcd_put_u8str(inStr);
}
}
@ -1107,10 +1107,10 @@ void MarlinUI::draw_status_screen() {
ui.encoder_direction_normal();
uint8_t n = lcd_put_u8str(0, 1, ftpl, itemIndex, itemStringC, itemStringF, LCD_WIDTH - 1);
if (value) {
lcd_put_wchar(':'); n--;
lcd_put_lchar(':'); n--;
const uint8_t len = utf8_strlen(value) + 1; // Plus one for a leading space
const lcd_uint_t valrow = n < len ? 2 : 1; // Value on the next row if it won't fit
lcd_put_wchar(LCD_WIDTH - len, valrow, ' '); // Right-justified, padded, leading space
lcd_put_lchar(LCD_WIDTH - len, valrow, ' '); // Right-justified, padded, leading space
lcd_put_u8str(value);
}
}
@ -1120,22 +1120,22 @@ void MarlinUI::draw_status_screen() {
ui.draw_select_screen_prompt(pref, string, suff);
if (no) {
SETCURSOR(0, LCD_HEIGHT - 1);
lcd_put_wchar(yesno ? ' ' : '['); lcd_put_u8str(no); lcd_put_wchar(yesno ? ' ' : ']');
lcd_put_lchar(yesno ? ' ' : '['); lcd_put_u8str(no); lcd_put_lchar(yesno ? ' ' : ']');
}
if (yes) {
SETCURSOR_RJ(utf8_strlen(yes) + 2, LCD_HEIGHT - 1);
lcd_put_wchar(yesno ? '[' : ' '); lcd_put_u8str(yes); lcd_put_wchar(yesno ? ']' : ' ');
lcd_put_lchar(yesno ? '[' : ' '); lcd_put_u8str(yes); lcd_put_lchar(yesno ? ']' : ' ');
}
}
#if ENABLED(SDSUPPORT)
void MenuItem_sdbase::draw(const bool sel, const uint8_t row, FSTR_P const, CardReader &theCard, const bool isDir) {
lcd_put_wchar(0, row, sel ? LCD_STR_ARROW_RIGHT[0] : ' ');
lcd_put_lchar(0, row, sel ? LCD_STR_ARROW_RIGHT[0] : ' ');
constexpr uint8_t maxlen = LCD_WIDTH - 2;
uint8_t n = maxlen - lcd_put_u8str_max(ui.scrolled_filename(theCard, maxlen, row, sel), maxlen);
for (; n; --n) lcd_put_wchar(' ');
lcd_put_wchar(isDir ? LCD_STR_FOLDER[0] : ' ');
for (; n; --n) lcd_put_lchar(' ');
lcd_put_lchar(isDir ? LCD_STR_FOLDER[0] : ' ');
}
#endif
@ -1253,7 +1253,7 @@ void MarlinUI::draw_status_screen() {
void prep_and_put_map_char(custom_char &chrdata, const coordinate &ul, const coordinate &lr, const coordinate &brc, const uint8_t cl, const char c, const lcd_uint_t x, const lcd_uint_t y) {
add_edges_to_custom_char(chrdata, ul, lr, brc, cl);
lcd.createChar(c, (uint8_t*)&chrdata);
lcd_put_wchar(x, y, c);
lcd_put_lchar(x, y, c);
}
void MarlinUI::ubl_plot(const uint8_t x_plot, const uint8_t y_plot) {
@ -1270,7 +1270,7 @@ void MarlinUI::draw_status_screen() {
#define _LCD_W_POS 8
#define _PLOT_X 0
#define _MAP_X 1
#define _LABEL(X,Y,C) lcd_put_wchar(X, Y, C)
#define _LABEL(X,Y,C) lcd_put_lchar(X, Y, C)
#define _XLABEL(X,Y) _LABEL('X',X,Y)
#define _YLABEL(X,Y) _LABEL('Y',X,Y)
#define _ZLABEL(X,Y) _LABEL('Z',X,Y)
@ -1333,13 +1333,13 @@ void MarlinUI::draw_status_screen() {
n_cols = right_edge / (HD44780_CHAR_WIDTH) + 1;
for (i = 0; i < n_cols; i++) {
lcd_put_wchar(i, 0, CHAR_LINE_TOP); // Box Top line
lcd_put_wchar(i, n_rows - 1, CHAR_LINE_BOT); // Box Bottom line
lcd_put_lchar(i, 0, CHAR_LINE_TOP); // Box Top line
lcd_put_lchar(i, n_rows - 1, CHAR_LINE_BOT); // Box Bottom line
}
for (j = 0; j < n_rows; j++) {
lcd_put_wchar(0, j, CHAR_EDGE_L); // Box Left edge
lcd_put_wchar(n_cols - 1, j, CHAR_EDGE_R); // Box Right edge
lcd_put_lchar(0, j, CHAR_EDGE_L); // Box Left edge
lcd_put_lchar(n_cols - 1, j, CHAR_EDGE_R); // Box Right edge
}
/**
@ -1349,8 +1349,8 @@ void MarlinUI::draw_status_screen() {
k = pixels_per_y_mesh_pnt * (GRID_MAX_POINTS_Y) + 2;
l = (HD44780_CHAR_HEIGHT) * n_rows;
if (l > k && l - k >= (HD44780_CHAR_HEIGHT) / 2) {
lcd_put_wchar(0, n_rows - 1, ' '); // Box Left edge
lcd_put_wchar(n_cols - 1, n_rows - 1, ' '); // Box Right edge
lcd_put_lchar(0, n_rows - 1, ' '); // Box Left edge
lcd_put_lchar(n_cols - 1, n_rows - 1, ' '); // Box Right edge
}
clear_custom_char(&new_char);
@ -1464,11 +1464,11 @@ void MarlinUI::draw_status_screen() {
/**
* Print plot position
*/
lcd_put_wchar(_LCD_W_POS, 0, '(');
lcd_put_lchar(_LCD_W_POS, 0, '(');
lcd_put_u8str(ui8tostr3rj(x_plot));
lcd_put_wchar(',');
lcd_put_lchar(',');
lcd_put_u8str(ui8tostr3rj(y_plot));
lcd_put_wchar(')');
lcd_put_lchar(')');
#if LCD_HEIGHT <= 3 // 16x2 or 20x2 display

12
Marlin/src/lcd/TFTGLCD/lcdprint_TFTGLCD.cpp

@ -48,7 +48,7 @@
int lcd_glyph_height() { return 1; }
typedef struct _TFTGLCD_charmap_t {
wchar_t uchar; // the unicode char
lchar_t uchar; // the unicode char
uint8_t idx; // the glyph of the char in the ROM
uint8_t idx2; // the char used to be combined with the idx to simulate a single char
} TFTGLCD_charmap_t;
@ -991,7 +991,7 @@ void lcd_put_int(const int i) {
// return < 0 on error
// return the advanced cols
int lcd_put_wchar_max(const wchar_t c, const pixel_len_t max_length) {
int lcd_put_lchar_max(const lchar_t &c, const pixel_len_t max_length) {
// find the HD44780 internal ROM first
int ret;
@ -1049,10 +1049,10 @@ static int lcd_put_u8str_max_cb(const char * utf8_str, read_byte_cb_t cb_read_by
pixel_len_t ret = 0;
const uint8_t *p = (uint8_t *)utf8_str;
while (ret < max_length) {
wchar_t ch = 0;
p = get_utf8_value_cb(p, cb_read_byte, &ch);
if (!ch) break;
ret += lcd_put_wchar_max(ch, max_length - ret);
lchar_t wc;
p = get_utf8_value_cb(p, cb_read_byte, wc);
if (!wc) break;
ret += lcd_put_lchar_max(wc, max_length - ret);
}
return (int)ret;
}

18
Marlin/src/lcd/TFTGLCD/marlinui_TFTGLCD.cpp

@ -524,16 +524,16 @@ FORCE_INLINE void _draw_axis_value(const AxisEnum axis, const char *value, const
UNUSED(blink);
#else
if (!blink && thermalManager.heater_idle[thermalManager.idle_index_for_id(heater_id)].timed_out) {
lcd_put_wchar(' ');
if (t2 >= 10) lcd_put_wchar(' ');
if (t2 >= 100) lcd_put_wchar(' ');
lcd_put_lchar(' ');
if (t2 >= 10) lcd_put_lchar(' ');
if (t2 >= 100) lcd_put_lchar(' ');
}
else
#endif
lcd_put_u8str(i16tostr3left(t2));
lcd_put_wchar(' ');
if (t2 < 10) lcd_put_wchar(' ');
lcd_put_lchar(' ');
if (t2 < 10) lcd_put_lchar(' ');
if (t2) picBits |= ICON_TEMP1;
else picBits &= ~ICON_TEMP1;
@ -545,7 +545,7 @@ FORCE_INLINE void _draw_axis_value(const AxisEnum axis, const char *value, const
FORCE_INLINE void _draw_flowmeter_status() {
lcd_moveto(5, 5); lcd_put_u8str(F("FLOW"));
lcd_moveto(7, 6); lcd_put_wchar('L');
lcd_moveto(7, 6); lcd_put_lchar('L');
lcd_moveto(6, 7); lcd_put_u8str(ftostr11ns(cooler.flowrate));
if (cooler.flowrate) picBits |= ICON_FAN;
@ -564,7 +564,7 @@ FORCE_INLINE void _draw_axis_value(const AxisEnum axis, const char *value, const
{
lcd_put_u8str("mA");
lcd_moveto(10, 7);
lcd_put_wchar(' '); lcd_put_u8str(ui16tostr3rj(uint16_t(ammeter.current * 1000 + 0.5f)));
lcd_put_lchar(' '); lcd_put_u8str(ui16tostr3rj(uint16_t(ammeter.current * 1000 + 0.5f)));
}
else {
lcd_put_u8str(" A");
@ -585,9 +585,9 @@ FORCE_INLINE void _draw_axis_value(const AxisEnum axis, const char *value, const
#if CUTTER_UNIT_IS(RPM)
lcd_moveto(16, 6); lcd_put_u8str(F("RPM"));
lcd_moveto(15, 7); lcd_put_u8str(ftostr31ns(float(cutter.unitPower) / 1000));
lcd_put_wchar('K');
lcd_put_lchar('K');
#elif CUTTER_UNIT_IS(PERCENT)
lcd_moveto(17, 6); lcd_put_wchar('%');
lcd_moveto(17, 6); lcd_put_lchar('%');
lcd_moveto(18, 7); lcd_put_u8str(cutter_power2str(cutter.unitPower));
#else
lcd_moveto(17, 7); lcd_put_u8str(cutter_power2str(cutter.unitPower));

2
Marlin/src/lcd/dogm/HAL_LCD_com_defines.h

@ -124,7 +124,7 @@
#ifndef U8G_COM_SSD_I2C_HAL
#define U8G_COM_SSD_I2C_HAL u8g_com_null_fn
#endif
#if HAS_FSMC_GRAPHICAL_TFT || HAS_SPI_GRAPHICAL_TFT
#if HAS_FSMC_GRAPHICAL_TFT || HAS_SPI_GRAPHICAL_TFT || HAS_LTDC_GRAPHICAL_TFT
uint8_t u8g_com_hal_tft_fn(u8g_t *u8g, uint8_t msg, uint8_t arg_val, void *arg_ptr);
#define U8G_COM_HAL_TFT_FN u8g_com_hal_tft_fn
#else

2
Marlin/src/lcd/dogm/lcdprint_u8g.cpp

@ -28,7 +28,7 @@ void lcd_put_int(const int i) { u8g.print(i); }
// return < 0 on error
// return the advanced pixels
int lcd_put_wchar_max(const wchar_t c, const pixel_len_t max_length) {
int lcd_put_lchar_max(const lchar_t &c, const pixel_len_t max_length) {
if (c < 256) {
u8g.print((char)c);
return u8g_GetFontBBXWidth(u8g.getU8g());

36
Marlin/src/lcd/dogm/marlinui_DOGM.cpp

@ -371,11 +371,11 @@ void MarlinUI::clear_lcd() { } // Automatically cleared by Picture Loop
if (!PAGE_CONTAINS(y1 + 1, y2 + 2)) return;
lcd_put_wchar(LCD_PIXEL_WIDTH - 11 * (MENU_FONT_WIDTH), y2, 'E');
lcd_put_wchar((char)('1' + extruder));
lcd_put_wchar(' ');
lcd_put_lchar(LCD_PIXEL_WIDTH - 11 * (MENU_FONT_WIDTH), y2, 'E');
lcd_put_lchar((char)('1' + extruder));
lcd_put_lchar(' ');
lcd_put_u8str(i16tostr3rj(thermalManager.wholeDegHotend(extruder)));
lcd_put_wchar('/');
lcd_put_lchar('/');
if (get_blink() || !thermalManager.heater_idle[extruder].timed_out)
lcd_put_u8str(i16tostr3rj(thermalManager.degTargetHotend(extruder)));
@ -421,12 +421,12 @@ void MarlinUI::clear_lcd() { } // Automatically cleared by Picture Loop
vlen = vstr ? utf8_strlen(vstr) : 0;
if (style & SS_CENTER) {
int pad = (LCD_PIXEL_WIDTH - plen - vlen * MENU_FONT_WIDTH) / MENU_FONT_WIDTH / 2;
while (--pad >= 0) n -= lcd_put_wchar(' ');
while (--pad >= 0) n -= lcd_put_lchar(' ');
}
if (plen) n = lcd_put_u8str(ftpl, itemIndex, itemStringC, itemStringF, n / (MENU_FONT_WIDTH)) * (MENU_FONT_WIDTH);
if (vlen) n -= lcd_put_u8str_max(vstr, n);
while (n > MENU_FONT_WIDTH) n -= lcd_put_wchar(' ');
while (n > MENU_FONT_WIDTH) n -= lcd_put_lchar(' ');
}
}
@ -434,9 +434,9 @@ void MarlinUI::clear_lcd() { } // Automatically cleared by Picture Loop
void MenuItemBase::_draw(const bool sel, const uint8_t row, FSTR_P const ftpl, const char, const char post_char) {
if (mark_as_selected(row, sel)) {
pixel_len_t n = lcd_put_u8str(ftpl, itemIndex, itemStringC, itemStringF, LCD_WIDTH - 1) * (MENU_FONT_WIDTH);
while (n > MENU_FONT_WIDTH) n -= lcd_put_wchar(' ');
lcd_put_wchar(LCD_PIXEL_WIDTH - (MENU_FONT_WIDTH), row_y2, post_char);
lcd_put_wchar(' ');
while (n > MENU_FONT_WIDTH) n -= lcd_put_lchar(' ');
lcd_put_lchar(LCD_PIXEL_WIDTH - (MENU_FONT_WIDTH), row_y2, post_char);
lcd_put_lchar(' ');
}
}
@ -449,8 +449,8 @@ void MarlinUI::clear_lcd() { } // Automatically cleared by Picture Loop
pixel_len_t n = lcd_put_u8str(ftpl, itemIndex, itemStringC, itemStringF, LCD_WIDTH - 2 - vallen * prop) * (MENU_FONT_WIDTH);
if (vallen) {
lcd_put_wchar(':');
while (n > MENU_FONT_WIDTH) n -= lcd_put_wchar(' ');
lcd_put_lchar(':');
while (n > MENU_FONT_WIDTH) n -= lcd_put_lchar(' ');
lcd_moveto(LCD_PIXEL_WIDTH - _MAX((MENU_FONT_WIDTH) * vallen, pixelwidth + 2), row_y2);
if (pgm) lcd_put_u8str_P(inStr); else lcd_put_u8str(inStr);
}
@ -494,14 +494,14 @@ void MarlinUI::clear_lcd() { } // Automatically cleared by Picture Loop
// If a value is included, print a colon, then print the value right-justified
if (value) {
lcd_put_wchar(':');
lcd_put_lchar(':');
if (extra_row) {
// Assume that value is numeric (with no descender)
baseline += EDIT_FONT_ASCENT + 2;
onpage = PAGE_CONTAINS(baseline - (EDIT_FONT_ASCENT - 1), baseline);
}
if (onpage) {
lcd_put_wchar(((lcd_chr_fit - 1) - (vallen * prop + 1)) * one_chr_width, baseline, ' '); // Right-justified, padded, add a leading space
lcd_put_lchar(((lcd_chr_fit - 1) - (vallen * prop + 1)) * one_chr_width, baseline, ' '); // Right-justified, padded, add a leading space
lcd_put_u8str(value);
}
}
@ -533,10 +533,10 @@ void MarlinUI::clear_lcd() { } // Automatically cleared by Picture Loop
void MenuItem_sdbase::draw(const bool sel, const uint8_t row, FSTR_P const, CardReader &theCard, const bool isDir) {
if (mark_as_selected(row, sel)) {
const uint8_t maxlen = LCD_WIDTH - isDir;
if (isDir) lcd_put_wchar(LCD_STR_FOLDER[0]);
if (isDir) lcd_put_lchar(LCD_STR_FOLDER[0]);
const pixel_len_t pixw = maxlen * (MENU_FONT_WIDTH);
pixel_len_t n = pixw - lcd_put_u8str_max(ui.scrolled_filename(theCard, maxlen, row, sel), pixw);
while (n > MENU_FONT_WIDTH) n -= lcd_put_wchar(' ');
while (n > MENU_FONT_WIDTH) n -= lcd_put_lchar(' ');
}
}
@ -611,11 +611,11 @@ void MarlinUI::clear_lcd() { } // Automatically cleared by Picture Loop
// Print plot position
if (PAGE_CONTAINS(LCD_PIXEL_HEIGHT - (INFO_FONT_HEIGHT - 1), LCD_PIXEL_HEIGHT)) {
lcd_put_wchar(5, LCD_PIXEL_HEIGHT, '(');
lcd_put_lchar(5, LCD_PIXEL_HEIGHT, '(');
u8g.print(x_plot);
lcd_put_wchar(',');
lcd_put_lchar(',');
u8g.print(y_plot);
lcd_put_wchar(')');
lcd_put_lchar(')');
// Show the location value
lcd_put_u8str_P(74, LCD_PIXEL_HEIGHT, Z_LBL);

44
Marlin/src/lcd/dogm/status_screen_DOGM.cpp

@ -200,7 +200,7 @@ FORCE_INLINE void _draw_centered_temp(const celsius_t temp, const uint8_t tx, co
const char *str = i16tostr3rj(temp);
const uint8_t len = str[0] != ' ' ? 3 : str[1] != ' ' ? 2 : 1;
lcd_put_u8str(tx - len * (INFO_FONT_WIDTH) / 2 + 1, ty, &str[3-len]);
lcd_put_wchar(LCD_STR_DEGREE[0]);
lcd_put_lchar(LCD_STR_DEGREE[0]);
}
}
@ -432,13 +432,13 @@ FORCE_INLINE void _draw_axis_value(const AxisEnum axis, const char *value, const
const bool is_inch = parser.using_inch_units();
const AxisEnum a = TERN(LCD_SHOW_E_TOTAL, axis == E_AXIS ? X_AXIS : axis, axis);
const uint8_t offs = a * (is_inch ? XYZ_SPACING_IN : XYZ_SPACING);
lcd_put_wchar((is_inch ? X_LABEL_POS_IN : X_LABEL_POS) + offs, XYZ_BASELINE, AXIS_CHAR(axis));
lcd_put_lchar((is_inch ? X_LABEL_POS_IN : X_LABEL_POS) + offs, XYZ_BASELINE, AXIS_CHAR(axis));
lcd_moveto((is_inch ? X_VALUE_POS_IN : X_VALUE_POS) + offs, XYZ_BASELINE);
if (blink)
lcd_put_u8str(value);
else if (axis_should_home(axis))
while (const char c = *value++) lcd_put_wchar(c <= '.' ? c : '?');
while (const char c = *value++) lcd_put_lchar(c <= '.' ? c : '?');
else if (NONE(HOME_AFTER_DEACTIVATE, DISABLE_REDUCED_ACCURACY_WARNING) && !axis_is_trusted(axis))
lcd_put_u8str(axis == Z_AXIS ? F(" ") : F(" "));
else
@ -675,7 +675,7 @@ void MarlinUI::draw_status_screen() {
lcd_put_u8str(STATUS_CUTTER_TEXT_X, STATUS_CUTTER_TEXT_Y, cutter_power2str(cutter.unitPower));
#elif CUTTER_UNIT_IS(RPM)
lcd_put_u8str(STATUS_CUTTER_TEXT_X - 2, STATUS_CUTTER_TEXT_Y, ftostr61rj(float(cutter.unitPower) / 1000));
lcd_put_wchar('K');
lcd_put_lchar('K');
#else
lcd_put_u8str(STATUS_CUTTER_TEXT_X, STATUS_CUTTER_TEXT_Y, cutter_power2str(cutter.unitPower));
#endif
@ -734,7 +734,7 @@ void MarlinUI::draw_status_screen() {
}
#endif
lcd_put_u8str(STATUS_FAN_TEXT_X, STATUS_FAN_TEXT_Y, i16tostr3rj(thermalManager.pwmToPercent(spd)));
lcd_put_wchar(c);
lcd_put_lchar(c);
}
}
#endif
@ -783,7 +783,7 @@ void MarlinUI::draw_status_screen() {
if (progress_state == 0) {
if (progress_string[0]) {
lcd_put_u8str(progress_x_pos, EXTRAS_BASELINE, progress_string);
lcd_put_wchar('%');
lcd_put_lchar('%');
}
}
else if (progress_state == 2 && estimation_string[0]) {
@ -804,7 +804,7 @@ void MarlinUI::draw_status_screen() {
#if ENABLED(SHOW_SD_PERCENT)
if (progress_string[0]) {
lcd_put_u8str(55, EXTRAS_BASELINE, progress_string); // Percent complete
lcd_put_wchar('%');
lcd_put_lchar('%');
}
#endif
@ -814,7 +814,7 @@ void MarlinUI::draw_status_screen() {
#if ENABLED(SHOW_REMAINING_TIME)
if (blink && estimation_string[0]) {
lcd_put_wchar(estimation_x_pos, EXTRAS_BASELINE, 'R');
lcd_put_lchar(estimation_x_pos, EXTRAS_BASELINE, 'R');
lcd_put_u8str(estimation_string);
}
else
@ -912,11 +912,11 @@ void MarlinUI::draw_status_screen() {
if (PAGE_CONTAINS(EXTRAS_2_BASELINE - INFO_FONT_ASCENT, EXTRAS_2_BASELINE - 1)) {
set_font(FONT_MENU);
lcd_put_wchar(3, EXTRAS_2_BASELINE, LCD_STR_FEEDRATE[0]);
lcd_put_lchar(3, EXTRAS_2_BASELINE, LCD_STR_FEEDRATE[0]);
set_font(FONT_STATUSMENU);
lcd_put_u8str(12, EXTRAS_2_BASELINE, i16tostr3rj(feedrate_percentage));
lcd_put_wchar('%');
lcd_put_lchar('%');
//
// Filament sensor display if SD is disabled
@ -924,10 +924,10 @@ void MarlinUI::draw_status_screen() {
#if ENABLED(FILAMENT_LCD_DISPLAY) && DISABLED(SDSUPPORT)
lcd_put_u8str(56, EXTRAS_2_BASELINE, wstring);
lcd_put_u8str(102, EXTRAS_2_BASELINE, mstring);
lcd_put_wchar('%');
lcd_put_lchar('%');
set_font(FONT_MENU);
lcd_put_wchar(47, EXTRAS_2_BASELINE, LCD_STR_FILAM_DIA[0]); // lcd_put_u8str(F(LCD_STR_FILAM_DIA));
lcd_put_wchar(93, EXTRAS_2_BASELINE, LCD_STR_FILAM_MUL[0]);
lcd_put_lchar(47, EXTRAS_2_BASELINE, LCD_STR_FILAM_DIA[0]); // lcd_put_u8str(F(LCD_STR_FILAM_DIA));
lcd_put_lchar(93, EXTRAS_2_BASELINE, LCD_STR_FILAM_MUL[0]);
#endif
}
@ -941,12 +941,12 @@ void MarlinUI::draw_status_screen() {
// Alternate Status message and Filament display
if (ELAPSED(millis(), next_filament_display)) {
lcd_put_u8str(F(LCD_STR_FILAM_DIA));
lcd_put_wchar(':');
lcd_put_lchar(':');
lcd_put_u8str(wstring);
lcd_put_u8str(F(" " LCD_STR_FILAM_MUL));
lcd_put_wchar(':');
lcd_put_lchar(':');
lcd_put_u8str(mstring);
lcd_put_wchar('%');
lcd_put_lchar('%');
return;
}
#endif
@ -979,7 +979,7 @@ void MarlinUI::draw_status_message(const bool blink) {
if (slen <= lcd_width) {
// The string fits within the line. Print with no scrolling
lcd_put_u8str(status_message);
while (slen < lcd_width) { lcd_put_wchar(' '); ++slen; }
while (slen < lcd_width) { lcd_put_lchar(' '); ++slen; }
}
else {
// String is longer than the available space
@ -997,14 +997,14 @@ void MarlinUI::draw_status_message(const bool blink) {
// If the remaining string doesn't completely fill the screen
if (rlen < lcd_width) {
uint8_t chars = lcd_width - rlen; // Amount of space left in characters
lcd_put_wchar(' '); // Always at 1+ spaces left, draw a space
lcd_put_lchar(' '); // Always at 1+ spaces left, draw a space
if (--chars) { // Draw a second space if there's room
lcd_put_wchar(' ');
lcd_put_lchar(' ');
if (--chars) { // Draw a third space if there's room
lcd_put_wchar(' ');
lcd_put_lchar(' ');
if (--chars) { // Print a second copy of the message
lcd_put_u8str_max(status_message, pixel_width - (rlen + 2) * (MENU_FONT_WIDTH));
lcd_put_wchar(' ');
lcd_put_lchar(' ');
}
}
}
@ -1019,7 +1019,7 @@ void MarlinUI::draw_status_message(const bool blink) {
lcd_put_u8str_max(status_message, pixel_width);
// Fill the rest with spaces
for (; slen < lcd_width; ++slen) lcd_put_wchar(' ');
for (; slen < lcd_width; ++slen) lcd_put_lchar(' ');
#endif // !STATUS_MESSAGE_SCROLLING

26
Marlin/src/lcd/dogm/u8g_fontutf8.cpp

@ -60,11 +60,11 @@ static int fontgroup_init(font_group_t * root, const uxg_fontinfo_t * fntinfo, i
return 0;
}
static const font_t* fontgroup_find(font_group_t * root, wchar_t val) {
uxg_fontinfo_t vcmp = {(uint16_t)(val / 128), (uint8_t)(val % 128 + 128), (uint8_t)(val % 128 + 128), 0, 0};
size_t idx = 0;
static const font_t* fontgroup_find(font_group_t * root, const lchar_t &val) {
if (val <= 0xFF) return nullptr;
if (val < 256) return nullptr;
uxg_fontinfo_t vcmp = { uint16_t(val >> 7), uint8_t((val & 0x7F) + 0x80), uint8_t((val & 0x7F) + 0x80), 0, 0 };
size_t idx = 0;
if (pf_bsearch_r((void*)root->m_fntifo, root->m_fntinfo_num, pf_bsearch_cb_comp_fntifo_pgm, (void*)&vcmp, &idx) < 0)
return nullptr;
@ -73,7 +73,7 @@ static const font_t* fontgroup_find(font_group_t * root, wchar_t val) {
return vcmp.fntdata;
}
static void fontgroup_drawwchar(font_group_t *group, const font_t *fnt_default, wchar_t val, void * userdata, fontgroup_cb_draw_t cb_draw_ram) {
static void fontgroup_drawwchar(font_group_t *group, const font_t *fnt_default, const lchar_t &val, void * userdata, fontgroup_cb_draw_t cb_draw_ram) {
uint8_t buf[2] = {0, 0};
const font_t * fntpqm = (font_t*)fontgroup_find(group, val);
if (!fntpqm) {
@ -106,10 +106,10 @@ static void fontgroup_drawwchar(font_group_t *group, const font_t *fnt_default,
static void fontgroup_drawstring(font_group_t *group, const font_t *fnt_default, const char *utf8_msg, read_byte_cb_t cb_read_byte, void * userdata, fontgroup_cb_draw_t cb_draw_ram) {
const uint8_t *p = (uint8_t*)utf8_msg;
for (;;) {
wchar_t val = 0;
p = get_utf8_value_cb(p, cb_read_byte, &val);
if (!val) break;
fontgroup_drawwchar(group, fnt_default, val, userdata, cb_draw_ram);
lchar_t wc;
p = get_utf8_value_cb(p, cb_read_byte, wc);
if (!wc) break;
fontgroup_drawwchar(group, fnt_default, wc, userdata, cb_draw_ram);
}
}
@ -149,19 +149,19 @@ static int fontgroup_cb_draw_u8g(void *userdata, const font_t *fnt_current, cons
}
/**
* @brief Draw a wchar_t at the specified position
* @brief Draw a lchar_t at the specified position
*
* @param pu8g : U8G pointer
* @param x : position x axis
* @param y : position y axis
* @param ch : the wchar_t
* @param wc : the lchar_t
* @param max_width : the pixel width of the string allowed
*
* @return number of pixels advanced
*
* Draw a UTF-8 string at the specified position
*/
unsigned int uxg_DrawWchar(u8g_t *pu8g, unsigned int x, unsigned int y, wchar_t ch, pixel_len_t max_width) {
unsigned int uxg_DrawWchar(u8g_t *pu8g, unsigned int x, unsigned int y, const lchar_t &wc, pixel_len_t max_width) {
struct _uxg_drawu8_data_t data;
font_group_t *group = &g_fontgroup_root;
const font_t *fnt_default = uxg_GetFont(pu8g);
@ -176,7 +176,7 @@ unsigned int uxg_DrawWchar(u8g_t *pu8g, unsigned int x, unsigned int y, wchar_t
data.adv = 0;
data.max_width = max_width;
data.fnt_prev = nullptr;
fontgroup_drawwchar(group, fnt_default, ch, (void*)&data, fontgroup_cb_draw_u8g);
fontgroup_drawwchar(group, fnt_default, wc, (void*)&data, fontgroup_cb_draw_u8g);
u8g_SetFont(pu8g, (const u8g_fntpgm_uint8_t*)fnt_default);
return data.adv;

2
Marlin/src/lcd/dogm/u8g_fontutf8.h

@ -26,7 +26,7 @@ typedef struct _uxg_fontinfo_t {
int uxg_SetUtf8Fonts(const uxg_fontinfo_t * fntinfo, int number); // fntinfo is type of PROGMEM
unsigned int uxg_DrawWchar(u8g_t *pu8g, unsigned int x, unsigned int y, wchar_t ch, const pixel_len_t max_length);
unsigned int uxg_DrawWchar(u8g_t *pu8g, unsigned int x, unsigned int y, const lchar_t &ch, const pixel_len_t max_length);
unsigned int uxg_DrawUtf8Str(u8g_t *pu8g, unsigned int x, unsigned int y, const char *utf8_msg, const pixel_len_t max_length);
unsigned int uxg_DrawUtf8StrP(u8g_t *pu8g, unsigned int x, unsigned int y, PGM_P utf8_msg, const pixel_len_t max_length);

2
Marlin/src/lcd/e3v2/README.md

@ -1,6 +1,6 @@
# DWIN for Creality Ender 3 v2
Marlin's Ender 3 v2 support requires the `DWIN_SET` included with the Ender 3 V2 [example configuration](https://github.com/MarlinFirmware/Configurations/tree/bugfix-2.0.x/config/examples/Creality/Ender-3%20V2).
Marlin's Ender 3 v2 support requires the `DWIN_SET` included with the Ender 3 V2 [example configuration](https://github.com/MarlinFirmware/Configurations/tree/bugfix-2.1.x/config/examples/Creality/Ender-3%20V2).
## Easy Install

10
Marlin/src/lcd/e3v2/common/dwin_api.h

@ -176,9 +176,13 @@ void DWIN_Frame_AreaMove(uint8_t mode, uint8_t dir, uint16_t dis,
void DWIN_Draw_String(bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t x, uint16_t y, const char * const string, uint16_t rlimit=0xFFFF);
inline void DWIN_Draw_String(bool bShow, uint8_t size, uint16_t color, uint16_t bColor, uint16_t x, uint16_t y, FSTR_P const ftitle) {
char ctitle[strlen_P(FTOP(ftitle)) + 1];
strcpy_P(ctitle, FTOP(ftitle));
DWIN_Draw_String(bShow, size, color, bColor, x, y, ctitle);
#ifdef __AVR__
char ctitle[strlen_P(FTOP(ftitle)) + 1];
strcpy_P(ctitle, FTOP(ftitle));
DWIN_Draw_String(bShow, size, color, bColor, x, y, ctitle);
#else
DWIN_Draw_String(bShow, size, color, bColor, x, y, FTOP(ftitle));
#endif
}
// Draw a positive integer

10
Marlin/src/lcd/e3v2/creality/dwin.cpp

@ -4307,9 +4307,13 @@ void DWIN_StatusChanged(const char * const cstr/*=nullptr*/) {
}
void DWIN_StatusChanged(FSTR_P const fstr) {
char str[strlen_P(FTOP(fstr)) + 1];
strcpy_P(str, FTOP(fstr));
DWIN_StatusChanged(str);
#ifdef __AVR__
char str[strlen_P(FTOP(fstr)) + 1];
strcpy_P(str, FTOP(fstr));
DWIN_StatusChanged(str);
#else
DWIN_StatusChanged(FTOP(fstr));
#endif
}
#endif // DWIN_CREALITY_LCD

2
Marlin/src/lcd/e3v2/jyersui/README.md

@ -1,6 +1,6 @@
# DWIN for Creality Ender 3 v2
Marlin's Ender 3 v2 support requires the `DWIN_SET` included with the Ender 3 V2 [example configuration](https://github.com/MarlinFirmware/Configurations/tree/bugfix-2.0.x/config/examples/Creality/Ender-3%20V2).
Marlin's Ender 3 v2 support requires the `DWIN_SET` included with the Ender 3 V2 [example configuration](https://github.com/MarlinFirmware/Configurations/tree/bugfix-2.1.x/config/examples/Creality/Ender-3%20V2).
## Easy Install

18
Marlin/src/lcd/e3v2/jyersui/dwin.cpp

@ -283,7 +283,7 @@ CrealityDWINClass CrealityDWIN;
#endif
void manual_move(bool zmove=false) {
void manual_mesh_move(const bool zmove=false) {
if (zmove) {
planner.synchronize();
current_position.z = goto_mesh_value ? bedlevel.z_values[mesh_x][mesh_y] : Z_CLEARANCE_BETWEEN_PROBES;
@ -3035,7 +3035,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/
mesh_conf.goto_mesh_value = true;
mesh_conf.mesh_x = mesh_conf.mesh_y = 0;
Popup_Handler(MoveWait);
mesh_conf.manual_move();
mesh_conf.manual_mesh_move();
Draw_Menu(UBLMesh);
#endif
#elif HAS_BED_PROBE
@ -3091,7 +3091,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/
TERN_(HAS_HEATED_BED, thermalManager.wait_for_bed_heating());
#endif
Popup_Handler(MoveWait);
mesh_conf.manual_move();
mesh_conf.manual_mesh_move();
Draw_Menu(LevelManual);
}
break;
@ -3328,7 +3328,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/
mesh_conf.mesh_x++;
else
mesh_conf.mesh_x--;
mesh_conf.manual_move();
mesh_conf.manual_mesh_move();
}
}
break;
@ -3375,7 +3375,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/
else {
mesh_conf.goto_mesh_value = !mesh_conf.goto_mesh_value;
current_position.z = 0;
mesh_conf.manual_move(true);
mesh_conf.manual_mesh_move(true);
Draw_Checkbox(row, mesh_conf.goto_mesh_value);
}
break;
@ -3428,7 +3428,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/
mesh_conf.mesh_x++;
else
mesh_conf.mesh_x--;
mesh_conf.manual_move();
mesh_conf.manual_mesh_move();
}
else {
gcode.process_subcommands_now(F("G29 S"));
@ -3449,7 +3449,7 @@ void CrealityDWINClass::Menu_Item_Handler(uint8_t menu, uint8_t item, bool draw/
mesh_conf.mesh_x--;
else
mesh_conf.mesh_x++;
mesh_conf.manual_move();
mesh_conf.manual_mesh_move();
}
}
break;
@ -4109,8 +4109,8 @@ void CrealityDWINClass::Value_Control() {
planner.buffer_line(current_position, homing_feedrate(Z_AXIS), active_extruder);
planner.synchronize();
break;
case UBLMesh: mesh_conf.manual_move(true); break;
case LevelManual: mesh_conf.manual_move(selection == LEVELING_M_OFFSET); break;
case UBLMesh: mesh_conf.manual_mesh_move(true); break;
case LevelManual: mesh_conf.manual_mesh_move(selection == LEVELING_M_OFFSET); break;
#endif
}
if (valuepointer == &planner.flow_percentage[0])

26
Marlin/src/lcd/e3v2/marlinui/dwin_string.cpp

@ -50,12 +50,12 @@ uint8_t read_byte(const uint8_t *byte) { return *byte; }
* @ displays an axis name such as XYZUVW, or E for an extruder
*/
void DWIN_String::add(const char *tpl, const int8_t index, const char *cstr/*=nullptr*/, FSTR_P const fstr/*=nullptr*/) {
wchar_t wchar;
lchar_t wc;
while (*tpl) {
tpl = get_utf8_value_cb(tpl, read_byte, &wchar);
if (wchar > 255) wchar |= 0x0080;
const uint8_t ch = uint8_t(wchar & 0x00FF);
tpl = get_utf8_value_cb(tpl, read_byte, wc);
if (wc > 255) wc |= 0x0080;
const uint8_t ch = uint8_t(wc & 0x00FF);
if (ch == '=' || ch == '~' || ch == '*') {
if (index >= 0) {
@ -80,32 +80,32 @@ void DWIN_String::add(const char *tpl, const int8_t index, const char *cstr/*=nu
}
void DWIN_String::add(const char *cstr, uint8_t max_len/*=MAX_STRING_LENGTH*/) {
wchar_t wchar;
lchar_t wc;
while (*cstr && max_len) {
cstr = get_utf8_value_cb(cstr, read_byte, &wchar);
cstr = get_utf8_value_cb(cstr, read_byte, wc);
/*
if (wchar > 255) wchar |= 0x0080;
uint8_t ch = uint8_t(wchar & 0x00FF);
if (wc > 255) wc |= 0x0080;
const uint8_t ch = uint8_t(wc & 0x00FF);
add_character(ch);
*/
add(wchar);
add(wc);
max_len--;
}
eol();
}
void DWIN_String::add(const wchar_t character) {
void DWIN_String::add(const lchar_t &wc) {
int ret;
size_t idx = 0;
dwin_charmap_t pinval;
dwin_charmap_t *copy_address = nullptr;
pinval.uchar = character;
pinval.uchar = wc;
pinval.idx = -1;
// For 8-bit ASCII just print the single character
char str[] = { '?', 0 };
if (character < 255) {
str[0] = (char)character;
if (wc < 255) {
str[0] = (char)wc;
}
else {
copy_address = nullptr;

8
Marlin/src/lcd/e3v2/marlinui/dwin_string.h

@ -29,7 +29,7 @@
#include <stdint.h>
typedef struct _dwin_charmap_t {
wchar_t uchar; // the unicode char
lchar_t uchar; // the unicode char
uint8_t idx; // the glyph of the char in the ROM
uint8_t idx2; // the char used to be combined with the idx to simulate a single char
} dwin_charmap_t;
@ -69,10 +69,10 @@ class DWIN_String {
/**
* @brief Append a UTF-8 character
*
* @param character The UTF-8 character
* @param wc The UTF-8 character
*/
static void add(wchar_t character);
static void set(wchar_t character) { set(); add(character); }
static void add(const lchar_t &wc);
static void set(const lchar_t &wc) { set(); add(wc); }
/**
* @brief Append / Set C-string

10
Marlin/src/lcd/e3v2/marlinui/lcdprint_dwin.cpp

@ -63,7 +63,7 @@ int lcd_put_dwin_string() {
// return < 0 on error
// return the advanced cols
int lcd_put_wchar_max(const wchar_t c, const pixel_len_t max_length) {
int lcd_put_lchar_max(const lchar_t &c, const pixel_len_t max_length) {
dwin_string.set(c);
dwin_string.truncate(max_length);
// Draw the char(s) at the cursor and advance the cursor
@ -87,10 +87,10 @@ static int lcd_put_u8str_max_cb(const char * utf8_str, read_byte_cb_t cb_read_by
const uint8_t *p = (uint8_t *)utf8_str;
dwin_string.set();
while (dwin_string.length < max_length) {
wchar_t ch = 0;
p = get_utf8_value_cb(p, cb_read_byte, &ch);
if (!ch) break;
dwin_string.add(ch);
lchar_t wc;
p = get_utf8_value_cb(p, cb_read_byte, wc);
if (!wc) break;
dwin_string.add(wc);
}
DWIN_Draw_String(dwin_font.solid, dwin_font.index, dwin_font.fg, dwin_font.bg, cursor.x, cursor.y, dwin_string.string());
lcd_advance_cursor(dwin_string.length);

23
Marlin/src/lcd/e3v2/marlinui/ui_common.cpp

@ -213,7 +213,7 @@ void MarlinUI::draw_status_message(const bool blink) {
lcd_put_u8str(status_message);
// Fill the rest with spaces
while (slen < max_status_chars) { lcd_put_wchar(' '); ++slen; }
while (slen < max_status_chars) { lcd_put_lchar(' '); ++slen; }
}
}
else {
@ -227,10 +227,10 @@ void MarlinUI::draw_status_message(const bool blink) {
// If the string doesn't completely fill the line...
if (rlen < max_status_chars) {
lcd_put_wchar('.'); // Always at 1+ spaces left, draw a dot
lcd_put_lchar('.'); // Always at 1+ spaces left, draw a dot
uint8_t chars = max_status_chars - rlen; // Amount of space left in characters
if (--chars) { // Draw a second dot if there's space
lcd_put_wchar('.');
lcd_put_lchar('.');
if (--chars)
lcd_put_u8str_max(status_message, chars); // Print a second copy of the message
}
@ -254,7 +254,7 @@ void MarlinUI::draw_status_message(const bool blink) {
lcd_put_u8str_max(status_message, max_status_chars);
// Fill the rest with spaces if there are missing spaces
while (slen < max_status_chars) { lcd_put_wchar(' '); ++slen; }
while (slen < max_status_chars) { lcd_put_lchar(' '); ++slen; }
}
#endif
@ -274,7 +274,7 @@ void MarlinUI::draw_status_message(const bool blink) {
dwin_font.solid = false;
dwin_font.fg = Color_White;
dwin_string.set("E");
dwin_string.set('E');
dwin_string.add('1' + extruder);
dwin_string.add(' ');
dwin_string.add(i16tostr3rj(thermalManager.degHotend(extruder)));
@ -282,7 +282,7 @@ void MarlinUI::draw_status_message(const bool blink) {
if (get_blink() || !thermalManager.heater_idle[thermalManager.idle_index_for_id(extruder)].timed_out)
dwin_string.add(i16tostr3rj(thermalManager.degTargetHotend(extruder)));
else
dwin_string.add(PSTR(" "));
dwin_string.add(F(" "));
lcd_moveto(LCD_WIDTH - dwin_string.length, row);
lcd_put_dwin_string();
@ -410,8 +410,7 @@ void MarlinUI::draw_status_message(const bool blink) {
const dwin_coord_t by = (row * MENU_LINE_HEIGHT) + MENU_FONT_HEIGHT + EXTRA_ROW_HEIGHT / 2;
DWIN_Draw_String(true, font16x32, Color_Yellow, Color_Bg_Black, (LCD_PIXEL_WIDTH - vallen * 16) / 2, by, S(dwin_string.string()));
extern screenFunc_t _manual_move_func_ptr;
if (ui.currentScreen != _manual_move_func_ptr && !ui.external_control) {
if (ui.can_show_slider()) {
const dwin_coord_t slider_length = LCD_PIXEL_WIDTH - TERN(DWIN_MARLINUI_LANDSCAPE, 120, 20),
slider_height = 16,
@ -540,11 +539,11 @@ void MarlinUI::draw_status_message(const bool blink) {
lcd_put_u8str(ftostr52(lpos.y));
// Print plot position
dwin_string.set("(");
dwin_string.set('(');
dwin_string.add(i8tostr3rj(x_plot));
dwin_string.add(",");
dwin_string.add(',');
dwin_string.add(i8tostr3rj(y_plot));
dwin_string.add(")");
dwin_string.add(')');
lcd_moveto(
TERN(DWIN_MARLINUI_LANDSCAPE, ((x_offset + x_map_pixels) / MENU_FONT_WIDTH) + 2, LCD_WIDTH - dwin_string.length),
TERN(DWIN_MARLINUI_LANDSCAPE, LCD_HEIGHT - 2, ((y_offset + y_map_pixels) / MENU_LINE_HEIGHT) + 1)
@ -556,7 +555,7 @@ void MarlinUI::draw_status_message(const bool blink) {
if (!isnan(bedlevel.z_values[x_plot][y_plot]))
dwin_string.add(ftostr43sign(bedlevel.z_values[x_plot][y_plot]));
else
dwin_string.add(PSTR(" -----"));
dwin_string.add(F(" -----"));
lcd_moveto(
TERN(DWIN_MARLINUI_LANDSCAPE, ((x_offset + x_map_pixels) / MENU_FONT_WIDTH) + 2, LCD_WIDTH - dwin_string.length),
TERN(DWIN_MARLINUI_LANDSCAPE, LCD_HEIGHT - 1, ((y_offset + y_map_pixels) / MENU_LINE_HEIGHT) + 2)

20
Marlin/src/lcd/e3v2/marlinui/ui_status_480x272.cpp

@ -88,7 +88,7 @@ FORCE_INLINE void _draw_axis_value(const AxisEnum axis, const char *value, const
// For E_TOTAL there may be some characters to cover up
if (BOTH(DWIN_MARLINUI_PORTRAIT, LCD_SHOW_E_TOTAL) && axis == X_AXIS)
dwin_string.add(" ");
dwin_string.add(F(" "));
DWIN_Draw_String(true, font14x28, Color_White, Color_Bg_Black, x, y + 32, S(dwin_string.string()));
@ -117,7 +117,7 @@ FORCE_INLINE void _draw_axis_value(const AxisEnum axis, const char *value, const
// For E_TOTAL there may be some characters to cover up
if (ENABLED(LCD_SHOW_E_TOTAL) && (!ui.did_first_redraw || ui.old_is_printing != print_job_timer.isRunning()) && axis == X_AXIS)
dwin_string.add(" ");
dwin_string.add(F(" "));
DWIN_Draw_String(true, font14x28, Color_White, Color_Bg_Black, x + 32, y + 4, S(dwin_string.string()));
@ -133,7 +133,7 @@ FORCE_INLINE void _draw_axis_value(const AxisEnum axis, const char *value, const
if (!ui.did_first_redraw) {
// Extra spaces to erase previous value
dwin_string.set("E ");
dwin_string.set(F("E "));
DWIN_Draw_String(true, font16x32, Color_IconBlue, Color_Bg_Black, x + (4 * 14 / 2) - 7, y + 2, S(dwin_string.string()));
}
@ -146,7 +146,7 @@ FORCE_INLINE void _draw_axis_value(const AxisEnum axis, const char *value, const
#else // !DWIN_MARLINUI_PORTRAIT
if (!ui.did_first_redraw || ui.old_is_printing != print_job_timer.isRunning()) {
dwin_string.set("E ");
dwin_string.set(F("E "));
DWIN_Draw_String(true, font16x32, Color_IconBlue, Color_Bg_Black, x, y, S(dwin_string.string()));
}
@ -176,7 +176,7 @@ FORCE_INLINE void _draw_fan_status(const uint16_t x, const uint16_t y) {
else {
DWIN_ICON_AnimationControl(0x0000); // disable all icon animations (this is the only one)
DWIN_ICON_Show(ICON, ICON_Fan0, x + fanx, y);
dwin_string.set(PSTR(" "));
dwin_string.set(F(" "));
DWIN_Draw_String(true, font14x28, Color_White, Color_Bg_Black, x, y + STATUS_FAN_HEIGHT, S(dwin_string.string()));
}
}
@ -289,7 +289,7 @@ FORCE_INLINE void _draw_feedrate_status(const char *value, uint16_t x, uint16_t
}
dwin_string.set(value);
dwin_string.add(PSTR("%"));
dwin_string.add('%');
DWIN_Draw_String(true, font14x28, Color_White, Color_Bg_Black, x + 14, y, S(dwin_string.string()));
}
@ -396,7 +396,7 @@ void MarlinUI::draw_status_screen() {
// landscape mode shows both elapsed and remaining (if SHOW_REMAINING_TIME)
time = print_job_timer.duration();
time.toDigital(buffer);
dwin_string.set(" ");
dwin_string.set(' ');
dwin_string.add(buffer);
DWIN_Draw_String(true, font14x28, Color_White, Color_Bg_Black, 230, 170, S(dwin_string.string()));
@ -405,7 +405,7 @@ void MarlinUI::draw_status_screen() {
time = get_remaining_time();
DWIN_Draw_String(true, font14x28, Color_IconBlue, Color_Bg_Black, 336, 170, S(" R "));
if (print_job_timer.isPaused() && blink)
dwin_string.set(" ");
dwin_string.set(F(" "));
else {
time.toDigital(buffer);
dwin_string.set(buffer);
@ -413,7 +413,7 @@ void MarlinUI::draw_status_screen() {
DWIN_Draw_String(true, font14x28, Color_White, Color_Bg_Black, 378, 170, S(dwin_string.string()));
}
else if (!ui.did_first_redraw || ui.old_is_printing != print_job_timer.isRunning()) {
dwin_string.set(" ");
dwin_string.set(F(" "));
DWIN_Draw_String(true, font14x28, Color_IconBlue, Color_Bg_Black, 336, 170, S(dwin_string.string()));
}
#endif
@ -449,7 +449,7 @@ void MarlinUI::draw_status_screen() {
#if ENABLED(SHOW_SD_PERCENT)
dwin_string.set(TERN(PRINT_PROGRESS_SHOW_DECIMALS, permyriadtostr4(progress), ui8tostr3rj(progress / (PROGRESS_SCALE))));
dwin_string.add(PSTR("%"));
dwin_string.add('%');
DWIN_Draw_String(
false, font16x32, Percent_Color, Color_Bg_Black,
pb_left + (pb_width - dwin_string.length * 16) / 2,

5
Marlin/src/lcd/e3v2/proui/gcode_preview.cpp

@ -42,6 +42,9 @@
* For commercial applications additional licenses can be requested
*/
#include "../../../inc/MarlinConfigPre.h"
#if ENABLED(DWIN_LCD_PROUI)
#include "dwin_defines.h"
#if HAS_GCODE_PREVIEW
@ -49,6 +52,7 @@
#include "../../../core/types.h"
#include "../../marlinui.h"
#include "../../../sd/cardreader.h"
#include "../../../MarlinCore.h" // for wait_for_user
#include "dwin_lcd.h"
#include "dwinui.h"
#include "dwin.h"
@ -251,3 +255,4 @@ void Preview_Reset() {
}
#endif // HAS_GCODE_PREVIEW
#endif // DWIN_LCD_PROUI

13
Marlin/src/lcd/extui/dgus/DGUSScreenHandler.cpp

@ -474,13 +474,8 @@ void DGUSScreenHandler::HandleManualExtrude(DGUS_VP_Variable &var, void *val_ptr
void DGUSScreenHandler::HandleMotorLockUnlock(DGUS_VP_Variable &var, void *val_ptr) {
DEBUG_ECHOLNPGM("HandleMotorLockUnlock");
char buf[4];
const int16_t lock = swap16(*(uint16_t*)val_ptr);
strcpy_P(buf, lock ? PSTR("M18") : PSTR("M17"));
//DEBUG_ECHOPGM(" ", buf);
queue.enqueue_one_now(buf);
queue.enqueue_one_now(lock ? F("M18") : F("M17"));
}
void DGUSScreenHandler::HandleSettings(DGUS_VP_Variable &var, void *val_ptr) {
@ -552,23 +547,23 @@ void DGUSScreenHandler::HandleStepPerMMExtruderChanged(DGUS_VP_Variable &var, vo
#if HAS_HOTEND
case VP_PID_AUTOTUNE_E0: // Autotune Extruder 0
sprintf_P(buf, PSTR("M303 E%d C5 S210 U1"), ExtUI::extruder_t::E0);
queue.enqueue_one_now(buf);
break;
#endif
#if HAS_MULTI_HOTEND
case VP_PID_AUTOTUNE_E1:
sprintf_P(buf, PSTR("M303 E%d C5 S210 U1"), ExtUI::extruder_t::E1);
queue.enqueue_one_now(buf);
break;
#endif
#endif
#if ENABLED(PIDTEMPBED)
case VP_PID_AUTOTUNE_BED:
strcpy_P(buf, PSTR("M303 E-1 C5 S70 U1"));
queue.enqueue_one_now(F("M303 E-1 C5 S70 U1"));
break;
#endif
}
if (buf[0]) queue.enqueue_one_now(buf);
#if ENABLED(DGUS_UI_WAITING)
sendinfoscreen(F("PID is autotuning"), F("please wait"), NUL_STR, NUL_STR, true, true, true, true);
GotoScreen(DGUSLCD_SCREEN_WAITING);

4
Marlin/src/lcd/extui/dgus/mks/DGUSDisplayDef.h

@ -680,8 +680,8 @@ constexpr uint16_t SP_T_Bed_Set = 0x5040;
constexpr uint16_t VP_EX_TEMP_INFO2_Dis = 0x5620;
constexpr uint16_t VP_EX_TEMP_INFO3_Dis = 0x5630;
constexpr uint16_t VP_LCD_BLK_Dis = 0x56A0;
constexpr uint16_t VP_Info_PrinfFinsh_1_Dis = 0x5C00;
constexpr uint16_t VP_Info_PrinfFinsh_2_Dis = 0x5C10;
constexpr uint16_t VP_Info_PrintFinish_1_Dis = 0x5C00;
constexpr uint16_t VP_Info_PrintFinish_2_Dis = 0x5C10;
constexpr uint16_t VP_Length_Dis = 0x5B00;

33
Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp

@ -258,7 +258,7 @@ void DGUSScreenHandlerMKS::DGUSLCD_SendTMCStepValue(DGUS_VP_Variable &var) {
) filelist.refresh();
}
void DGUSScreenHandler::SDPrintingFinished() {
void DGUSScreenHandlerMKS::SDPrintingFinished() {
if (DGUSAutoTurnOff) {
queue.exhaust();
gcode.process_subcommands_now(F("M81"));
@ -416,15 +416,15 @@ void DGUSScreenHandlerMKS::LanguageChange(DGUS_VP_Variable &var, void *val_ptr)
case MKS_SimpleChinese:
DGUS_LanguageDisplay(MKS_SimpleChinese);
mks_language_index = MKS_SimpleChinese;
dgusdisplay.WriteVariable(VP_LANGUAGE_CHANGE1, MKS_Language_Choose);
dgusdisplay.WriteVariable(VP_LANGUAGE_CHANGE2, MKS_Language_NoChoose);
dgusdisplay.WriteVariable(VP_LANGUAGE_CHANGE1, (uint8_t)MKS_Language_Choose);
dgusdisplay.WriteVariable(VP_LANGUAGE_CHANGE2, (uint8_t)MKS_Language_NoChoose);
settings.save();
break;
case MKS_English:
DGUS_LanguageDisplay(MKS_English);
mks_language_index = MKS_English;
dgusdisplay.WriteVariable(VP_LANGUAGE_CHANGE1, MKS_Language_NoChoose);
dgusdisplay.WriteVariable(VP_LANGUAGE_CHANGE2, MKS_Language_Choose);
dgusdisplay.WriteVariable(VP_LANGUAGE_CHANGE1, (uint8_t)MKS_Language_NoChoose);
dgusdisplay.WriteVariable(VP_LANGUAGE_CHANGE2, (uint8_t)MKS_Language_Choose);
settings.save();
break;
default: break;
@ -564,7 +564,7 @@ void DGUSScreenHandlerMKS::MeshLevel(DGUS_VP_Variable &var, void *val_ptr) {
queue.enqueue_now(F("G29S2"));
mesh_point_count--;
if (mks_language_index == MKS_English) {
const char level_buf_en2[] = "Level Finsh";
const char level_buf_en2[] = "Leveling Done";
dgusdisplay.WriteVariable(VP_AutoLevel_1_Dis, level_buf_en2, 32, true);
}
else if (mks_language_index == MKS_SimpleChinese) {
@ -1125,7 +1125,6 @@ void DGUSScreenHandlerMKS::HandleAccChange(DGUS_VP_Variable &var, void *val_ptr)
#if ENABLED(BABYSTEPPING)
void DGUSScreenHandler::HandleLiveAdjustZ(DGUS_VP_Variable &var, void *val_ptr) {
DEBUG_ECHOLNPGM("HandleLiveAdjustZ");
char babystep_buf[30];
float step = ZOffset_distance;
uint16_t flag = swap16(*(uint16_t*)val_ptr);
@ -1142,7 +1141,7 @@ void DGUSScreenHandlerMKS::HandleAccChange(DGUS_VP_Variable &var, void *val_ptr)
else
queue.inject(F("M290 Z-0.01"));
z_offset_add = z_offset_add - ZOffset_distance;
z_offset_add -= ZOffset_distance;
break;
case 1:
@ -1157,7 +1156,7 @@ void DGUSScreenHandlerMKS::HandleAccChange(DGUS_VP_Variable &var, void *val_ptr)
else
queue.inject(F("M290 Z-0.01"));
z_offset_add = z_offset_add + ZOffset_distance;
z_offset_add += ZOffset_distance;
break;
default:
@ -1446,12 +1445,12 @@ bool DGUSScreenHandlerMKS::loop() {
void DGUSScreenHandlerMKS::LanguagePInit() {
switch (mks_language_index) {
case MKS_SimpleChinese:
dgusdisplay.WriteVariable(VP_LANGUAGE_CHANGE1, MKS_Language_Choose);
dgusdisplay.WriteVariable(VP_LANGUAGE_CHANGE2, MKS_Language_NoChoose);
dgusdisplay.WriteVariable(VP_LANGUAGE_CHANGE1, (uint8_t)MKS_Language_Choose);
dgusdisplay.WriteVariable(VP_LANGUAGE_CHANGE2, (uint8_t)MKS_Language_NoChoose);
break;
case MKS_English:
dgusdisplay.WriteVariable(VP_LANGUAGE_CHANGE1, MKS_Language_NoChoose);
dgusdisplay.WriteVariable(VP_LANGUAGE_CHANGE2, MKS_Language_Choose);
dgusdisplay.WriteVariable(VP_LANGUAGE_CHANGE1, (uint8_t)MKS_Language_NoChoose);
dgusdisplay.WriteVariable(VP_LANGUAGE_CHANGE2, (uint8_t)MKS_Language_Choose);
break;
default:
break;
@ -1709,8 +1708,8 @@ void DGUSScreenHandlerMKS::DGUS_LanguageDisplay(uint8_t var) {
const char Info_EEPROM_2_buf_en[] = "Revert setting?";
dgusdisplay.WriteVariable(VP_Info_EEPROM_2_Dis, Info_EEPROM_2_buf_en, 32, true);
const char Info_PrinfFinsh_1_buf_en[] = "Print Done";
dgusdisplay.WriteVariable(VP_Info_PrinfFinsh_1_Dis, Info_PrinfFinsh_1_buf_en, 32, true);
const char Info_PrintFinish_1_buf_en[] = "Print Done";
dgusdisplay.WriteVariable(VP_Info_PrintFinish_1_Dis, Info_PrintFinish_1_buf_en, 32, true);
const char TMC_X_Step_buf_en[] = "X_SenSitivity";
dgusdisplay.WriteVariable(VP_TMC_X_Step_Dis, TMC_X_Step_buf_en, 32, true);
@ -1973,8 +1972,8 @@ void DGUSScreenHandlerMKS::DGUS_LanguageDisplay(uint8_t var) {
const uint16_t TMC_Z_Step_buf_ch[] = { 0x205A, 0xE9C1, 0xF4C3, 0xC8B6, 0x2000 };
dgusdisplay.WriteVariable(VP_TMC_Z_Step_Dis, TMC_Z_Step_buf_ch, 16, true);
const uint16_t Info_PrinfFinsh_1_buf_ch[] = { 0xF2B4, 0xA1D3, 0xEACD, 0xC9B3, 0x2000 };
dgusdisplay.WriteVariable(VP_Info_PrinfFinsh_1_Dis, Info_PrinfFinsh_1_buf_ch, 32, true);
const uint16_t Info_PrintFinish_1_buf_ch[] = { 0xF2B4, 0xA1D3, 0xEACD, 0xC9B3, 0x2000 };
dgusdisplay.WriteVariable(VP_Info_PrintFinish_1_Dis, Info_PrintFinish_1_buf_ch, 32, true);
const uint16_t TMC_X_Current_buf_ch[] = { 0x2058, 0xE1D6, 0xE7B5, 0xF7C1, 0x2000 };
dgusdisplay.WriteVariable(VP_TMC_X_Current_Dis, TMC_X_Current_buf_ch, 16, true);

22
Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/printing_dialog_box.cpp

@ -32,12 +32,12 @@ using namespace Theme;
#define GRID_COLS 2
#define GRID_ROWS 9
void BioPrintingDialogBox::draw_status_message(draw_mode_t what, const char *message) {
void BioPrintingDialogBox::draw_status_message(draw_mode_t what, const char *cmsg) {
if (what & BACKGROUND) {
CommandProcessor cmd;
cmd.cmd(COLOR_RGB(bg_text_enabled))
.tag(0);
draw_text_box(cmd, BTN_POS(1,2), BTN_SIZE(2,2), message, OPT_CENTER, font_large);
draw_text_box(cmd, BTN_POS(1,2), BTN_SIZE(2,2), cmsg, OPT_CENTER, font_large);
}
}
@ -105,26 +105,30 @@ bool BioPrintingDialogBox::onTouchEnd(uint8_t tag) {
return true;
}
void BioPrintingDialogBox::setStatusMessage(FSTR_P message) {
char buff[strlen_P(FTOP(message)) + 1];
strcpy_P(buff, FTOP(message));
setStatusMessage(buff);
void BioPrintingDialogBox::setStatusMessage(FSTR_P fmsg) {
#ifdef __AVR__
char buff[strlen_P(FTOP(fmsg)) + 1];
strcpy_P(buff, FTOP(fmsg));
setStatusMessage(buff);
#else
setStatusMessage(FTOP(fmsg));
#endif
}
void BioPrintingDialogBox::setStatusMessage(const char *message) {
void BioPrintingDialogBox::setStatusMessage(const char *cmsg) {
CommandProcessor cmd;
cmd.cmd(CMD_DLSTART)
.cmd(CLEAR_COLOR_RGB(bg_color))
.cmd(CLEAR(true,true,true));
draw_status_message(BACKGROUND, message);
draw_status_message(BACKGROUND, cmsg);
draw_progress(BACKGROUND);
draw_time_remaining(BACKGROUND);
draw_interaction_buttons(BACKGROUND);
storeBackground();
#if ENABLED(TOUCH_UI_DEBUG)
SERIAL_ECHO_MSG("New status message: ", message);
SERIAL_ECHO_MSG("New status message: ", cmsg);
#endif
if (AT_SCREEN(BioPrintingDialogBox))

6
Marlin/src/lcd/extui/ftdi_eve_touch_ui/bioprinter/status_screen.cpp

@ -122,7 +122,7 @@ void StatusScreen::draw_temperature(draw_mode_t what) {
ui.bounds(POLY(bed_temp), x, y, h, v);
cmd.text(x, y, h, v, str);
#endif
#endif
}
}
@ -354,8 +354,8 @@ bool StatusScreen::onTouchHeld(uint8_t tag) {
return false;
}
void StatusScreen::setStatusMessage(FSTR_P pstr) {
BioPrintingDialogBox::setStatusMessage(pstr);
void StatusScreen::setStatusMessage(FSTR_P fstr) {
BioPrintingDialogBox::setStatusMessage(fstr);
}
void StatusScreen::setStatusMessage(const char * const str) {

4
Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/compat.h

@ -240,8 +240,8 @@
#define IS_PROBE(V...) SECOND(V, 0) // Get the second item passed, or 0
#define PROBE() ~, 1 // Second item will be 1 if this is passed
#define _NOT_0 PROBE()
#define NOT(x) IS_PROBE(_CAT(_NOT_, x)) // NOT('0') gets '1'. Anything else gets '0'.
#define _BOOL(x) NOT(NOT(x)) // NOT('0') gets '0'. Anything else gets '1'.
#define NOT(x) IS_PROBE(_CAT(_NOT_, x)) // NOT('0') gets '1'. Anything else gets '0'.
#define _BOOL(x) NOT(NOT(x)) // _BOOL('0') gets '0'. Anything else gets '1'.
#define _DO_1(W,C,A) (_##W##_1(A))
#define _DO_2(W,C,A,B) (_##W##_1(A) C _##W##_1(B))

10
Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/text_box.cpp

@ -136,9 +136,13 @@ namespace FTDI {
}
void draw_text_box(CommandProcessor& cmd, int x, int y, int w, int h, FSTR_P fstr, uint16_t options, uint8_t font) {
char str[strlen_P(FTOP(fstr)) + 1];
strcpy_P(str, FTOP(fstr));
draw_text_box(cmd, x, y, w, h, (const char*) str, options, font);
#ifdef __AVR__
char str[strlen_P(FTOP(fstr)) + 1];
strcpy_P(str, FTOP(fstr));
draw_text_box(cmd, x, y, w, h, (const char*) str, options, font);
#else
draw_text_box(cmd, x, y, w, h, FTOP(fstr), options, font);
#endif
}
} // namespace FTDI

10
Marlin/src/lcd/extui/ftdi_eve_touch_ui/ftdi_eve_lib/extended/unicode/unicode.cpp

@ -192,9 +192,13 @@
}
uint16_t FTDI::get_utf8_text_width(FSTR_P fstr, font_size_t fs) {
char str[strlen_P(FTOP(fstr)) + 1];
strcpy_P(str, FTOP(fstr));
return get_utf8_text_width(str, fs);
#ifdef __AVR__
char str[strlen_P(FTOP(fstr)) + 1];
strcpy_P(str, FTOP(fstr));
return get_utf8_text_width(str, fs);
#else
return get_utf8_text_width(FTOP(fstr), fs);
#endif
}
/**

5
Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/dialog_box_base_class.cpp

@ -32,7 +32,7 @@ using namespace Theme;
#define GRID_ROWS 8
template<typename T>
void DialogBoxBaseClass::drawMessage(T message, int16_t font) {
void DialogBoxBaseClass::drawMessage(T message, const int16_t font) {
CommandProcessor cmd;
cmd.cmd(CMD_DLSTART)
.cmd(CLEAR_COLOR_RGB(bg_color))
@ -43,8 +43,7 @@ void DialogBoxBaseClass::drawMessage(T message, int16_t font) {
cmd.colors(normal_btn);
}
template void DialogBoxBaseClass::drawMessage(const char *, int16_t font);
template void DialogBoxBaseClass::drawMessage(FSTR_P, int16_t font);
template void DialogBoxBaseClass::drawMessage(PGM_P const, const int16_t);
void DialogBoxBaseClass::drawYesNoButtons(uint8_t default_btn) {
CommandProcessor cmd;

7
Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/dialog_box_base_class.h

@ -27,12 +27,15 @@
class DialogBoxBaseClass : public BaseScreen {
protected:
template<typename T> static void drawMessage(T, int16_t font = 0);
template<typename T> static void drawMessage(T, const int16_t font=0);
static void drawMessage(FSTR_P const fstr, const int16_t font=0) { drawMessage(FTOP(fstr), font); }
template<typename T> static void drawButton(T);
static void drawYesNoButtons(uint8_t default_btn = 0);
static void drawOkayButton();
static void onRedraw(draw_mode_t) {};
static void onRedraw(draw_mode_t) {}
public:
static bool onTouchEnd(uint8_t tag);
static void onIdle();

12
Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/status_screen.cpp

@ -332,10 +332,14 @@ void StatusScreen::draw_status_message(draw_mode_t what, const char *message) {
}
}
void StatusScreen::setStatusMessage(FSTR_P message) {
char buff[strlen_P(FTOP(message)) + 1];
strcpy_P(buff, FTOP(message));
setStatusMessage((const char *) buff);
void StatusScreen::setStatusMessage(FSTR_P fmsg) {
#ifdef __AVR__
char buff[strlen_P(FTOP(fmsg)) + 1];
strcpy_P(buff, FTOP(fmsg));
setStatusMessage((const char *)buff);
#else
setStatusMessage(FTOP(fmsg));
#endif
}
void StatusScreen::setStatusMessage(const char *message) {

16
Marlin/src/lcd/extui/mks_ui/mks_hardware.cpp

@ -711,12 +711,16 @@ void disp_assets_update() {
}
void disp_assets_update_progress(FSTR_P const fmsg) {
static constexpr int buflen = 30;
char buf[buflen];
memset(buf, ' ', buflen);
strncpy_P(buf, FTOP(fmsg), buflen - 1);
buf[buflen - 1] = '\0';
disp_string(100, 165, buf, 0xFFFF, 0x0000);
#ifdef __AVR__
static constexpr int buflen = 30;
char buf[buflen];
memset(buf, ' ', buflen);
strncpy_P(buf, FTOP(fmsg), buflen - 1);
buf[buflen - 1] = '\0';
disp_string(100, 165, buf, 0xFFFF, 0x0000);
#else
disp_string(100, 165, FTOP(fmsg), 0xFFFF, 0x0000);
#endif
}
#if BOTH(MKS_TEST, SDSUPPORT)

2
Marlin/src/lcd/extui/mks_ui/wifi_module.cpp

@ -1638,7 +1638,7 @@ void esp_data_parser(char *cmdRxBuf, int len) {
esp_msg_index += cpyLen;
leftLen = leftLen - cpyLen;
leftLen -= cpyLen;
tail_pos = charAtArray(esp_msg_buf, esp_msg_index, ESP_PROTOC_TAIL);
if (tail_pos == -1) {

20
Marlin/src/lcd/extui/ui_api.cpp

@ -1112,15 +1112,23 @@ namespace ExtUI {
// Simplest approach is to make an SRAM copy
void onUserConfirmRequired(FSTR_P const fstr) {
char msg[strlen_P(FTOP(fstr)) + 1];
strcpy_P(msg, FTOP(fstr));
onUserConfirmRequired(msg);
#ifdef __AVR__
char msg[strlen_P(FTOP(fstr)) + 1];
strcpy_P(msg, FTOP(fstr));
onUserConfirmRequired(msg);
#else
onUserConfirmRequired(FTOP(fstr));
#endif
}
void onStatusChanged(FSTR_P const fstr) {
char msg[strlen_P(FTOP(fstr)) + 1];
strcpy_P(msg, FTOP(fstr));
onStatusChanged(msg);
#ifdef __AVR__
char msg[strlen_P(FTOP(fstr)) + 1];
strcpy_P(msg, FTOP(fstr));
onStatusChanged(msg);
#else
onStatusChanged(FTOP(fstr));
#endif
}
FileList::FileList() { refresh(); }

6
Marlin/src/lcd/fontutils.cpp

@ -31,8 +31,6 @@
#include "../inc/MarlinConfig.h"
#define MAX_UTF8_CHAR_SIZE 4
#if HAS_WIRED_LCD
#include "marlinui.h"
#include "../MarlinCore.h"
@ -99,7 +97,7 @@ static inline bool utf8_is_start_byte_of_char(const uint8_t b) {
/* This function gets the character at the pstart position, interpreting UTF8 multibyte sequences
and returns the pointer to the next character */
const uint8_t* get_utf8_value_cb(const uint8_t *pstart, read_byte_cb_t cb_read_byte, wchar_t *pval) {
const uint8_t* get_utf8_value_cb(const uint8_t *pstart, read_byte_cb_t cb_read_byte, lchar_t &pval) {
uint32_t val = 0;
const uint8_t *p = pstart;
@ -158,7 +156,7 @@ const uint8_t* get_utf8_value_cb(const uint8_t *pstart, read_byte_cb_t cb_read_b
else
for (; 0xFC < (0xFE & valcur); ) { p++; valcur = cb_read_byte(p); }
if (pval) *pval = val;
pval = val;
return p;
}

27
Marlin/src/lcd/fontutils.h

@ -31,36 +31,41 @@
#pragma once
#include <stdlib.h>
#include <stddef.h> // wchar_t
#include <stdint.h> // uint32_t
#include "../HAL/shared/Marduino.h"
#include "../core/macros.h"
#define MAX_UTF8_CHAR_SIZE 4
// Use a longer character type (if needed) because wchar_t is only 16 bits wide
#ifdef MAX_UTF8_CHAR_SIZE
#if MAX_UTF8_CHAR_SIZE > 2
typedef uint32_t lchar_t;
#else
typedef wchar_t lchar_t;
#endif
#else
#define wchar_t uint32_t
#endif
// read a byte from ROM or RAM
typedef uint8_t (*read_byte_cb_t)(const uint8_t * str);
uint8_t read_byte_ram(const uint8_t *str);
uint8_t read_byte_rom(const uint8_t *str);
// there's overflow of the wchar_t due to the 2-byte size in Arduino
// sizeof(wchar_t)=2; sizeof(size_t)=2; sizeof(uint32_t)=4;
// sizeof(int)=2; sizeof(long)=4; sizeof(unsigned)=2;
//#undef wchar_t
#define wchar_t uint32_t
//typedef uint32_t wchar_t;
typedef uint16_t pixel_len_t;
#define PIXEL_LEN_NOLIMIT ((pixel_len_t)(-1))
/* Perform binary search */
typedef int (* pf_bsearch_cb_comp_t)(void *userdata, size_t idx, void * data_pin); /*"data_list[idx] - *data_pin"*/
typedef int (* pf_bsearch_cb_comp_t)(void *userdata, size_t idx, void * data_pin);
int pf_bsearch_r(void *userdata, size_t num_data, pf_bsearch_cb_comp_t cb_comp, void *data_pinpoint, size_t *ret_idx);
/* Get the character, decoding multibyte UTF8 characters and returning a pointer to the start of the next UTF8 character */
const uint8_t* get_utf8_value_cb(const uint8_t *pstart, read_byte_cb_t cb_read_byte, wchar_t *pval);
const uint8_t* get_utf8_value_cb(const uint8_t *pstart, read_byte_cb_t cb_read_byte, lchar_t &pval);
inline const char* get_utf8_value_cb(const char *pstart, read_byte_cb_t cb_read_byte, wchar_t *pval) {
inline const char* get_utf8_value_cb(const char *pstart, read_byte_cb_t cb_read_byte, lchar_t &pval) {
return (const char *)get_utf8_value_cb((const uint8_t *)pstart, cb_read_byte, pval);
}

2
Marlin/src/lcd/language/language_cz.h

@ -432,8 +432,6 @@ namespace Language_cz {
LSTR MSG_DELTA_CALIBRATE_CENTER = _UxGT("Kalibrovat Střed");
LSTR MSG_DELTA_SETTINGS = _UxGT("Delta nastavení");
LSTR MSG_DELTA_AUTO_CALIBRATE = _UxGT("Autokalibrace");
LSTR MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Nast.výšku delty");
LSTR MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Nast. Z-ofset");
LSTR MSG_DELTA_DIAG_ROD = _UxGT("Diag rameno");
LSTR MSG_DELTA_HEIGHT = _UxGT("Výška");
LSTR MSG_DELTA_RADIUS = _UxGT("Poloměr");

2
Marlin/src/lcd/language/language_de.h

@ -544,8 +544,6 @@ namespace Language_de {
LSTR MSG_DELTA_CALIBRATE_CENTER = _UxGT("Kalibriere Mitte");
LSTR MSG_DELTA_SETTINGS = _UxGT("Delta Einst. anzeig.");
LSTR MSG_DELTA_AUTO_CALIBRATE = _UxGT("Autom. Kalibrierung");
LSTR MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Delta Höhe setzen");
LSTR MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Sondenversatz Z");
LSTR MSG_DELTA_DIAG_ROD = _UxGT("Diag Rod");
LSTR MSG_DELTA_HEIGHT = _UxGT("Höhe");
LSTR MSG_DELTA_RADIUS = _UxGT("Radius");

4
Marlin/src/lcd/language/language_en.h

@ -309,7 +309,7 @@ namespace Language_en {
LSTR MSG_MOVE_Z = _UxGT("Move Z");
LSTR MSG_MOVE_N = _UxGT("Move @");
LSTR MSG_MOVE_E = _UxGT("Move Extruder");
LSTR MSG_MOVE_EN = _UxGT("Move E*");
LSTR MSG_MOVE_EN = _UxGT("Move *");
LSTR MSG_HOTEND_TOO_COLD = _UxGT("Hotend too cold");
LSTR MSG_MOVE_N_MM = _UxGT("Move $mm");
LSTR MSG_MOVE_01MM = _UxGT("Move 0.1mm");
@ -600,8 +600,6 @@ namespace Language_en {
LSTR MSG_DELTA_CALIBRATE_CENTER = _UxGT("Calibrate Center");
LSTR MSG_DELTA_SETTINGS = _UxGT("Delta Settings");
LSTR MSG_DELTA_AUTO_CALIBRATE = _UxGT("Auto Calibration");
LSTR MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Set Delta Height");
LSTR MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Probe Z-offset");
LSTR MSG_DELTA_DIAG_ROD = _UxGT("Diag Rod");
LSTR MSG_DELTA_HEIGHT = _UxGT("Height");
LSTR MSG_DELTA_RADIUS = _UxGT("Radius");

2
Marlin/src/lcd/language/language_es.h

@ -430,8 +430,6 @@ namespace Language_es {
LSTR MSG_DELTA_CALIBRATE_CENTER = _UxGT("Calibrar Centro");
LSTR MSG_DELTA_SETTINGS = _UxGT("Configuración Delta");
LSTR MSG_DELTA_AUTO_CALIBRATE = _UxGT("Auto Calibración");
LSTR MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Est. Altura Delta");
LSTR MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Ajustar Sonda Z");
LSTR MSG_DELTA_DIAG_ROD = _UxGT("Barra Diagonal");
LSTR MSG_DELTA_HEIGHT = _UxGT("Altura");
LSTR MSG_DELTA_RADIUS = _UxGT("Radio");

1
Marlin/src/lcd/language/language_eu.h

@ -257,7 +257,6 @@ namespace Language_eu {
LSTR MSG_DELTA_CALIBRATE_CENTER = _UxGT("Kalibratu Zentrua");
LSTR MSG_DELTA_SETTINGS = _UxGT("Delta ezarpenak");
LSTR MSG_DELTA_AUTO_CALIBRATE = _UxGT("Auto Kalibraketa");
LSTR MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Delta Alt. Ezar.");
LSTR MSG_DELTA_DIAG_ROD = _UxGT("Barra diagonala");
LSTR MSG_DELTA_HEIGHT = _UxGT("Altuera");
LSTR MSG_DELTA_RADIUS = _UxGT("Erradioa");

2
Marlin/src/lcd/language/language_fr.h

@ -460,8 +460,6 @@ namespace Language_fr {
LSTR MSG_DELTA_CALIBRATE_CENTER = _UxGT("Calibrer centre");
LSTR MSG_DELTA_SETTINGS = _UxGT("Réglages Delta");
LSTR MSG_DELTA_AUTO_CALIBRATE = _UxGT("Calibration Auto");
LSTR MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Hauteur Delta");
LSTR MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Delta Z sonde");
LSTR MSG_DELTA_DIAG_ROD = _UxGT("Diagonale");
LSTR MSG_DELTA_HEIGHT = _UxGT("Hauteur");
LSTR MSG_DELTA_RADIUS = _UxGT("Rayon");

2
Marlin/src/lcd/language/language_gl.h

@ -445,8 +445,6 @@ namespace Language_gl {
LSTR MSG_DELTA_CALIBRATE_CENTER = _UxGT("Calibrar Centro");
LSTR MSG_DELTA_SETTINGS = _UxGT("Configuración Delta");
LSTR MSG_DELTA_AUTO_CALIBRATE = _UxGT("Auto Calibración");
LSTR MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Ax. Altura Delta");
LSTR MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Axustar Sonda Z");
LSTR MSG_DELTA_DIAG_ROD = _UxGT("Barra Diagonal");
LSTR MSG_DELTA_HEIGHT = _UxGT("Altura");
LSTR MSG_DELTA_RADIUS = _UxGT("Radio");

2
Marlin/src/lcd/language/language_hu.h

@ -508,8 +508,6 @@ namespace Language_hu {
LSTR MSG_DELTA_CALIBRATE_CENTER = _UxGT("Központ kalibrálás");
LSTR MSG_DELTA_SETTINGS = _UxGT("Delta beállítások");
LSTR MSG_DELTA_AUTO_CALIBRATE = _UxGT("Auto kalibráció");
LSTR MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Delta magasság kalib.");
LSTR MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Z eltolás");
LSTR MSG_DELTA_DIAG_ROD = _UxGT("Diag rúd");
LSTR MSG_DELTA_HEIGHT = _UxGT("Magasság");
LSTR MSG_DELTA_RADIUS = _UxGT("Sugár");

83
Marlin/src/lcd/language/language_it.h

@ -47,7 +47,10 @@ namespace Language_it {
LSTR WELCOME_MSG = MACHINE_NAME _UxGT(" pronta.");
LSTR MSG_YES = _UxGT("Si");
LSTR MSG_NO = _UxGT("No");
LSTR MSG_HIGH = _UxGT("ALTO");
LSTR MSG_LOW = _UxGT("BASSO");
LSTR MSG_BACK = _UxGT("Indietro");
LSTR MSG_ERROR = _UxGT("Errore");
LSTR MSG_MEDIA_ABORTING = _UxGT("Annullando...");
LSTR MSG_MEDIA_INSERTED = _UxGT("Media inserito");
LSTR MSG_MEDIA_REMOVED = _UxGT("Media rimosso");
@ -61,6 +64,8 @@ namespace Language_it {
LSTR MSG_LCD_SOFT_ENDSTOPS = _UxGT("Finecorsa Soft");
LSTR MSG_MAIN = _UxGT("Menu principale");
LSTR MSG_ADVANCED_SETTINGS = _UxGT("Impostaz. avanzate");
LSTR MSG_TOOLBAR_SETUP = _UxGT("Cnf barra strumenti");
LSTR MSG_OPTION_DISABLED = _UxGT("Opzione disab.");
LSTR MSG_CONFIGURATION = _UxGT("Configurazione");
LSTR MSG_RUN_AUTO_FILES = _UxGT("Esegui files auto");
LSTR MSG_DISABLE_STEPPERS = _UxGT("Disabilita Motori");
@ -74,6 +79,7 @@ namespace Language_it {
LSTR MSG_AUTO_HOME_Z = _UxGT("Home Z");
LSTR MSG_FILAMENT_SET = _UxGT("Impostaz.filamento");
LSTR MSG_FILAMENT_MAN = _UxGT("Gestione filamento");
LSTR MSG_MANUAL_LEVELING = _UxGT("Livel.manuale");
LSTR MSG_LEVBED_FL = _UxGT("Davanti Sinistra");
LSTR MSG_LEVBED_FR = _UxGT("Davanti Destra");
LSTR MSG_LEVBED_C = _UxGT("Centro");
@ -106,7 +112,14 @@ namespace Language_it {
LSTR MSG_PREHEAT_1_ALL = _UxGT("Preris.") PREHEAT_1_LABEL _UxGT(" Tutto");
LSTR MSG_PREHEAT_1_BEDONLY = _UxGT("Preris.") PREHEAT_1_LABEL _UxGT(" Piatto");
LSTR MSG_PREHEAT_1_SETTINGS = _UxGT("Preris.") PREHEAT_1_LABEL _UxGT(" conf");
#ifdef PREHEAT_2_LABEL
LSTR MSG_PREHEAT_2 = _UxGT("Preris.") PREHEAT_2_LABEL;
LSTR MSG_PREHEAT_2_SETTINGS = _UxGT("Preris.") PREHEAT_2_LABEL _UxGT(" conf");
#endif
#ifdef PREHEAT_3_LABEL
LSTR MSG_PREHEAT_3 = _UxGT("Preris.") PREHEAT_3_LABEL;
LSTR MSG_PREHEAT_3_SETTINGS = _UxGT("Preris.") PREHEAT_3_LABEL _UxGT(" conf");
#endif
LSTR MSG_PREHEAT_M = _UxGT("Preriscalda $");
LSTR MSG_PREHEAT_M_H = _UxGT("Preriscalda $ ~");
LSTR MSG_PREHEAT_M_END = _UxGT("Preris.$ Ugello");
@ -153,10 +166,19 @@ namespace Language_it {
LSTR MSG_MESH_VIEW = _UxGT("Visualizza Mesh");
LSTR MSG_EDITING_STOPPED = _UxGT("Modif. Mesh Fermata");
LSTR MSG_NO_VALID_MESH = _UxGT("Mesh non valida");
LSTR MSG_ACTIVATE_MESH = _UxGT("Attiva livellamento");
LSTR MSG_PROBING_POINT = _UxGT("Punto sondato");
LSTR MSG_MESH_X = _UxGT("Indice X");
LSTR MSG_MESH_Y = _UxGT("Indice Y");
LSTR MSG_MESH_INSET = _UxGT("Mesh Inset");
LSTR MSG_MESH_MIN_X = _UxGT("Mesh X minimo");
LSTR MSG_MESH_MAX_X = _UxGT("Mesh X massimo");
LSTR MSG_MESH_MIN_Y = _UxGT("Mesh Y minimo");
LSTR MSG_MESH_MAX_Y = _UxGT("Mesh Y massimo");
LSTR MSG_MESH_AMAX = _UxGT("Massimizza area");
LSTR MSG_MESH_CENTER = _UxGT("Area centrale");
LSTR MSG_MESH_EDIT_Z = _UxGT("Valore di Z");
LSTR MSG_MESH_CANCEL = _UxGT("Mesh cancellato");
LSTR MSG_CUSTOM_COMMANDS = _UxGT("Comandi personaliz.");
LSTR MSG_M48_TEST = _UxGT("Test sonda M48");
LSTR MSG_M48_POINT = _UxGT("Punto M48");
@ -175,6 +197,9 @@ namespace Language_it {
LSTR MSG_UBL_TOOLS = _UxGT("Strumenti UBL");
LSTR MSG_UBL_LEVEL_BED = _UxGT("Livel.letto unificato");
LSTR MSG_LCD_TILTING_MESH = _UxGT("Punto inclinaz.");
LSTR MSG_UBL_TILT_MESH = _UxGT("Inclina Mesh");
LSTR MSG_UBL_TILTING_GRID = _UxGT("Dim.griglia inclin.");
LSTR MSG_UBL_MESH_TILTED = _UxGT("Mesh inclinata");
LSTR MSG_UBL_MANUAL_MESH = _UxGT("Mesh Manuale");
LSTR MSG_UBL_MESH_WIZARD = _UxGT("Creaz.guid.mesh UBL");
LSTR MSG_UBL_BC_INSERT = _UxGT("Metti spes. e misura");
@ -225,6 +250,7 @@ namespace Language_it {
LSTR MSG_UBL_MANUAL_FILLIN = _UxGT("Riempimento Manuale");
LSTR MSG_UBL_SMART_FILLIN = _UxGT("Riempimento Smart");
LSTR MSG_UBL_FILLIN_MESH = _UxGT("Riempimento Mesh");
LSTR MSG_UBL_MESH_FILLED = _UxGT("Pts mancanti riempiti");
LSTR MSG_UBL_INVALIDATE_ALL = _UxGT("Invalida Tutto");
LSTR MSG_UBL_INVALIDATE_CLOSEST = _UxGT("Invalid.Punto Vicino");
LSTR MSG_UBL_FINE_TUNE_ALL = _UxGT("Ritocca Tutto");
@ -233,6 +259,7 @@ namespace Language_it {
LSTR MSG_UBL_STORAGE_SLOT = _UxGT("Slot di memoria");
LSTR MSG_UBL_LOAD_MESH = _UxGT("Carica Mesh Piatto");
LSTR MSG_UBL_SAVE_MESH = _UxGT("Salva Mesh Piatto");
LSTR MSG_UBL_INVALID_SLOT = _UxGT("Prima selez. uno slot Mesh");
LSTR MSG_MESH_LOADED = _UxGT("Mesh %i caricata");
LSTR MSG_MESH_SAVED = _UxGT("Mesh %i salvata");
LSTR MSG_UBL_NO_STORAGE = _UxGT("Nessuna memoria");
@ -290,6 +317,7 @@ namespace Language_it {
LSTR MSG_MOVE_001IN = _UxGT("Muovi di 0.01\"");
LSTR MSG_MOVE_01IN = _UxGT("Muovi di 0.1\"");
LSTR MSG_MOVE_1IN = _UxGT("Muovi di 1\"");
LSTR MSG_SPEED = _UxGT("Velocità");
LSTR MSG_BED_Z = _UxGT("Piatto Z");
LSTR MSG_NOZZLE = _UxGT("Ugello");
LSTR MSG_NOZZLE_N = _UxGT("Ugello ~");
@ -324,6 +352,10 @@ namespace Language_it {
LSTR MSG_PID_AUTOTUNE_E = _UxGT("Calib.PID *");
LSTR MSG_PID_CYCLE = _UxGT("Ciclo PID");
LSTR MSG_PID_AUTOTUNE_DONE = _UxGT("Calibr.PID eseguita");
LSTR MSG_PID_AUTOTUNE_FAILED = _UxGT("Calibr.PID fallito!");
LSTR MSG_BAD_EXTRUDER_NUM = _UxGT("Estrusore invalido.");
LSTR MSG_TEMP_TOO_HIGH = _UxGT("Temp.troppo alta.");
LSTR MSG_TIMEOUT = _UxGT("Tempo scaduto.");
LSTR MSG_PID_BAD_EXTRUDER_NUM = _UxGT("Calibrazione fallita! Estrusore errato.");
LSTR MSG_PID_TEMP_TOO_HIGH = _UxGT("Calibrazione fallita! Temperatura troppo alta.");
LSTR MSG_PID_TIMEOUT = _UxGT("Calibrazione fallita! Tempo scaduto.");
@ -401,6 +433,10 @@ namespace Language_it {
LSTR MSG_RESET_PRINTER = _UxGT("Resetta stampante");
LSTR MSG_REFRESH = LCD_STR_REFRESH _UxGT("Aggiorna");
LSTR MSG_INFO_SCREEN = _UxGT("Schermata info");
LSTR MSG_INFO_MACHINENAME = _UxGT("Nome macchina");
LSTR MSG_INFO_SIZE = _UxGT("Dimens.");
LSTR MSG_INFO_FWVERSION = _UxGT("Versione firmware");
LSTR MSG_INFO_BUILD = _UxGT("Dataora compilaz.");
LSTR MSG_PREPARE = _UxGT("Prepara");
LSTR MSG_TUNE = _UxGT("Regola");
LSTR MSG_POWER_MONITOR = _UxGT("Controllo aliment.");
@ -426,7 +462,8 @@ namespace Language_it {
LSTR MSG_BUTTON_PAUSE = _UxGT("Pausa");
LSTR MSG_BUTTON_RESUME = _UxGT("Riprendi");
LSTR MSG_BUTTON_ADVANCED = _UxGT("Avanzato");
LSTR MSG_BUTTON_SAVE = _UxGT("Save");
LSTR MSG_BUTTON_SAVE = _UxGT("Memorizza");
LSTR MSG_BUTTON_PURGE = _UxGT("Spurga");
LSTR MSG_PAUSING = _UxGT("Messa in pausa...");
LSTR MSG_PAUSE_PRINT = _UxGT("Pausa stampa");
LSTR MSG_ADVANCED_PAUSE = _UxGT("Pausa Avanzata");
@ -449,9 +486,12 @@ namespace Language_it {
LSTR MSG_REMAINING_TIME = _UxGT("Rimanente");
LSTR MSG_PRINT_ABORTED = _UxGT("Stampa Annullata");
LSTR MSG_PRINT_DONE = _UxGT("Stampa Eseguita");
LSTR MSG_PRINTER_KILLED = _UxGT("Stampante uccisa!");
LSTR MSG_TURN_OFF = _UxGT("Spegni stampante");
LSTR MSG_NO_MOVE = _UxGT("Nessun Movimento");
LSTR MSG_KILLED = _UxGT("UCCISO. ");
LSTR MSG_STOPPED = _UxGT("ARRESTATO. ");
LSTR MSG_FWRETRACT = _UxGT("Ritraz.da firmware");
LSTR MSG_CONTROL_RETRACT = _UxGT("Ritrai mm");
LSTR MSG_CONTROL_RETRACT_SWAP = _UxGT("Scamb. Ritrai mm");
LSTR MSG_CONTROL_RETRACTF = _UxGT("Ritrai V");
@ -517,6 +557,9 @@ namespace Language_it {
LSTR MSG_ZPROBE_XOFFSET = _UxGT("Offset X sonda");
LSTR MSG_ZPROBE_YOFFSET = _UxGT("Offset Y sonda");
LSTR MSG_ZPROBE_ZOFFSET = _UxGT("Offset Z sonda");
LSTR MSG_ZPROBE_MARGIN = _UxGT("Margine sonda");
LSTR MSG_Z_FEED_RATE = _UxGT("Velocità Z");
LSTR MSG_ENABLE_HS_MODE = _UxGT("Abilita modo HS");
LSTR MSG_MOVE_NOZZLE_TO_BED = _UxGT("Muovi ugel.su letto");
LSTR MSG_BABYSTEP_X = _UxGT("Babystep X");
LSTR MSG_BABYSTEP_Y = _UxGT("Babystep Y");
@ -554,8 +597,6 @@ namespace Language_it {
LSTR MSG_DELTA_CALIBRATE_CENTER = _UxGT("Calibra centro");
LSTR MSG_DELTA_SETTINGS = _UxGT("Impostaz. Delta");
LSTR MSG_DELTA_AUTO_CALIBRATE = _UxGT("Auto calibrazione");
LSTR MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Imp. altezza Delta");
LSTR MSG_DELTA_Z_OFFSET_CALIBRATE = _UxGT("Offset sonda-Z");
LSTR MSG_DELTA_DIAG_ROD = _UxGT("Barra Diagonale");
LSTR MSG_DELTA_HEIGHT = _UxGT("Altezza");
LSTR MSG_DELTA_RADIUS = _UxGT("Raggio");
@ -582,34 +623,38 @@ namespace Language_it {
LSTR MSG_CASE_LIGHT_BRIGHTNESS = _UxGT("Luminosità Luci");
LSTR MSG_KILL_EXPECTED_PRINTER = _UxGT("STAMPANTE ERRATA");
LSTR MSG_COLORS_GET = _UxGT("Ottieni colori");
LSTR MSG_COLORS_SELECT = _UxGT("Selez.colori");
LSTR MSG_COLORS_APPLIED = _UxGT("Colori applicati");
LSTR MSG_COLORS_RED = _UxGT("Rosso");
LSTR MSG_COLORS_GREEN = _UxGT("Verde");
LSTR MSG_COLORS_BLUE = _UxGT("Blu");
LSTR MSG_COLORS_WHITE = _UxGT("Bianco");
LSTR MSG_UI_LANGUAGE = _UxGT("Lingua UI");
LSTR MSG_SOUND_ENABLE = _UxGT("Abilita suono");
LSTR MSG_LOCKSCREEN = _UxGT("Blocca Schermo");
LSTR MSG_LOCKSCREEN_LOCKED = _UxGT("Stamp. bloccata,");
LSTR MSG_LOCKSCREEN_UNLOCK = _UxGT("Scroll x sbloccare.");
LSTR MSG_PLEASE_WAIT_REBOOT = _UxGT("Attendere fino al riavvio.");
#if LCD_WIDTH >= 20 || HAS_DWIN_E3V2
LSTR MSG_MEDIA_NOT_INSERTED = _UxGT("Nessun supporto inserito.");
LSTR MSG_PLEASE_WAIT_REBOOT = _UxGT("Attendere fino al riavvio.");
LSTR MSG_PLEASE_PREHEAT = _UxGT("Si prega di preriscaldare l'hot end.");
LSTR MSG_INFO_PRINT_COUNT_RESET = _UxGT("Azzera contatori stampa");
LSTR MSG_INFO_PRINT_COUNT = _UxGT("Contatori stampa");
LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Completati");
LSTR MSG_INFO_PRINT_TIME = _UxGT("Tempo totale");
LSTR MSG_INFO_PRINT_LONGEST = _UxGT("Lavoro più lungo");
LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("Totale estruso");
LSTR MSG_COLORS_GET = _UxGT("Get Color");
LSTR MSG_COLORS_SELECT = _UxGT("Seleziona colori");
LSTR MSG_COLORS_APPLIED = _UxGT("Colori applicati");
LSTR MSG_COLORS_RED = _UxGT("Rosso");
LSTR MSG_COLORS_GREEN = _UxGT("Verde");
LSTR MSG_COLORS_BLUE = _UxGT("Blu");
LSTR MSG_COLORS_WHITE = _UxGT("Bianco");
LSTR MSG_UI_LANGUAGE = _UxGT("Lingua UI");
LSTR MSG_SOUND_ENABLE = _UxGT("Abilita suono");
LSTR MSG_LOCKSCREEN = _UxGT("Blocca Schermo");
#else
LSTR MSG_MEDIA_NOT_INSERTED = _UxGT("No Supporto");
LSTR MSG_PLEASE_PREHEAT = _UxGT("Prerisc. hot end.");
LSTR MSG_INFO_PRINT_COUNT = _UxGT("Stampe");
LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Completati");
LSTR MSG_INFO_PRINT_TIME = _UxGT("Durata");
LSTR MSG_INFO_PRINT_LONGEST = _UxGT("Più lungo");
LSTR MSG_INFO_PRINT_FILAMENT = _UxGT("Estruso");
#endif
LSTR MSG_INFO_COMPLETED_PRINTS = _UxGT("Completate");
LSTR MSG_INFO_MIN_TEMP = _UxGT("Temp min");
LSTR MSG_INFO_MAX_TEMP = _UxGT("Temp max");
LSTR MSG_INFO_PSU = _UxGT("Alimentatore");
@ -624,10 +669,14 @@ namespace Language_it {
LSTR MSG_FILAMENT_CHANGE_OPTION_HEADER = _UxGT("OPZIONI RIPRESA:");
LSTR MSG_FILAMENT_CHANGE_OPTION_PURGE = _UxGT("Spurga di più");
LSTR MSG_FILAMENT_CHANGE_OPTION_RESUME = _UxGT("Riprendi stampa");
LSTR MSG_FILAMENT_CHANGE_PURGE_CONTINUE = _UxGT("Spurga o continua?");
LSTR MSG_FILAMENT_CHANGE_NOZZLE = _UxGT(" Ugello: ");
LSTR MSG_RUNOUT_SENSOR = _UxGT("Sens.filo termin."); // Max 17 characters
LSTR MSG_RUNOUT_DISTANCE_MM = _UxGT("Dist mm filo term.");
LSTR MSG_RUNOUT_ENABLE = _UxGT("Abil.filo termin.");
LSTR MSG_RUNOUT_ACTIVE = _UxGT("Filo termin. attivo");
LSTR MSG_INVERT_EXTRUDER = _UxGT("Inverti estrusore");
LSTR MSG_EXTRUDER_MIN_TEMP = _UxGT("Temp.min estrusore");
LSTR MSG_FANCHECK = _UxGT("Verif.tacho vent."); // Max 17 characters
LSTR MSG_KILL_HOMING_FAILED = _UxGT("Home fallito");
LSTR MSG_LCD_PROBING_FAILED = _UxGT("Sondaggio fallito");

2
Marlin/src/lcd/language/language_nl.h

@ -173,8 +173,8 @@ namespace Language_nl {
LSTR MSG_DELTA_CALIBRATE_Y = _UxGT("Kalibreer Y");
LSTR MSG_DELTA_CALIBRATE_Z = _UxGT("Kalibreer Z");
LSTR MSG_DELTA_CALIBRATE_CENTER = _UxGT("Kalibreer Midden");
LSTR MSG_DELTA_SETTINGS = _UxGT("Delta conf");
LSTR MSG_DELTA_AUTO_CALIBRATE = _UxGT("Auto Calibratie");
LSTR MSG_DELTA_HEIGHT_CALIBRATE = _UxGT("Zet Delta Hoogte");
LSTR MSG_CASE_LIGHT = _UxGT("Case licht");

Some files were not shown because too many files changed in this diff

Loading…
Cancel
Save