Browse Source

2.0.8.1 update

pull/45/head
Sergey 3 years ago
parent
commit
a399523691
  1. 16
      Marlin/Configuration.h
  2. 54
      Marlin/Configuration_adv.h
  3. 4
      Marlin/Version.h
  4. 15
      Marlin/src/HAL/AVR/HAL.h
  5. 32
      Marlin/src/HAL/AVR/MarlinSerial.cpp
  6. 21
      Marlin/src/HAL/AVR/MarlinSerial.h
  7. 21
      Marlin/src/HAL/DUE/HAL.h
  8. 7
      Marlin/src/HAL/DUE/MarlinSerial.cpp
  9. 9
      Marlin/src/HAL/DUE/MarlinSerial.h
  10. 13
      Marlin/src/HAL/DUE/MarlinSerialUSB.cpp
  11. 16
      Marlin/src/HAL/DUE/MarlinSerialUSB.h
  12. 2
      Marlin/src/HAL/ESP32/WebSocketSerial.cpp
  13. 4
      Marlin/src/HAL/ESP32/WebSocketSerial.h
  14. 10
      Marlin/src/HAL/LPC1768/HAL.h
  15. 1
      Marlin/src/HAL/LPC1768/HAL_MinSerial.cpp
  16. 8
      Marlin/src/HAL/LPC1768/MarlinSerial.cpp
  17. 2
      Marlin/src/HAL/LPC1768/tft/xpt2046.cpp
  18. 2
      Marlin/src/HAL/SAMD51/HAL.h
  19. 6
      Marlin/src/HAL/STM32/HAL.cpp
  20. 16
      Marlin/src/HAL/STM32/HAL.h
  21. 202
      Marlin/src/HAL/STM32/tft/gt911.cpp
  22. 120
      Marlin/src/HAL/STM32/tft/gt911.h
  23. 2
      Marlin/src/HAL/STM32/tft/tft_ltdc.cpp
  24. 2
      Marlin/src/HAL/STM32/tft/xpt2046.cpp
  25. 3
      Marlin/src/HAL/STM32/timers.h
  26. 2
      Marlin/src/HAL/STM32F1/HAL.cpp
  27. 43
      Marlin/src/HAL/STM32F1/HAL.h
  28. 2
      Marlin/src/HAL/STM32F1/onboard_sd.cpp
  29. 2
      Marlin/src/HAL/STM32F1/tft/xpt2046.cpp
  30. 8
      Marlin/src/HAL/STM32F1/timers.h
  31. 2
      Marlin/src/HAL/TEENSY31_32/HAL.h
  32. 3
      Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp
  33. 3
      Marlin/src/HAL/TEENSY35_36/HAL_SPI.cpp
  34. 3
      Marlin/src/HAL/TEENSY40_41/HAL.cpp
  35. 3
      Marlin/src/HAL/TEENSY40_41/HAL_SPI.cpp
  36. 4
      Marlin/src/HAL/shared/Marduino.h
  37. 10
      Marlin/src/HAL/shared/eeprom_if_i2c.cpp
  38. 44
      Marlin/src/MarlinCore.cpp
  39. 19
      Marlin/src/MarlinCore.h
  40. 30
      Marlin/src/core/boards.h
  41. 75
      Marlin/src/core/macros.h
  42. 12
      Marlin/src/core/serial.cpp
  43. 207
      Marlin/src/core/serial.h
  44. 109
      Marlin/src/core/serial_hook.h
  45. 45
      Marlin/src/feature/bedlevel/ubl/ubl.cpp
  46. 2
      Marlin/src/feature/bedlevel/ubl/ubl.h
  47. 44
      Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp
  48. 20
      Marlin/src/feature/caselight.cpp
  49. 2
      Marlin/src/feature/caselight.h
  50. 2
      Marlin/src/feature/dac/dac_mcp4728.cpp
  51. 14
      Marlin/src/feature/encoder_i2c.cpp
  52. 14
      Marlin/src/feature/fwretract.cpp
  53. 7
      Marlin/src/feature/joystick.cpp
  54. 2
      Marlin/src/feature/leds/leds.cpp
  55. 2
      Marlin/src/feature/leds/leds.h
  56. 2
      Marlin/src/feature/mmu/mmu2.cpp
  57. 19
      Marlin/src/feature/pause.cpp
  58. 202
      Marlin/src/feature/powerloss.cpp
  59. 18
      Marlin/src/feature/powerloss.h
  60. 2
      Marlin/src/feature/runout.h
  61. 8
      Marlin/src/gcode/bedlevel/G26.cpp
  62. 2
      Marlin/src/gcode/bedlevel/M420.cpp
  63. 12
      Marlin/src/gcode/bedlevel/abl/G29.cpp
  64. 2
      Marlin/src/gcode/bedlevel/mbl/G29.cpp
  65. 27
      Marlin/src/gcode/bedlevel/ubl/M421.cpp
  66. 6
      Marlin/src/gcode/calibrate/G28.cpp
  67. 4
      Marlin/src/gcode/calibrate/G33.cpp
  68. 2
      Marlin/src/gcode/feature/caselight/M355.cpp
  69. 5
      Marlin/src/gcode/feature/pause/G60.cpp
  70. 47
      Marlin/src/gcode/feature/pause/G61.cpp
  71. 6
      Marlin/src/gcode/feature/pause/M125.cpp
  72. 14
      Marlin/src/gcode/feature/pause/M600.cpp
  73. 4
      Marlin/src/gcode/feature/powerloss/M1000.cpp
  74. 12
      Marlin/src/gcode/feature/powerloss/M413.cpp
  75. 2
      Marlin/src/gcode/feature/runout/M412.cpp
  76. 5
      Marlin/src/gcode/feature/trinamic/M122.cpp
  77. 18
      Marlin/src/gcode/gcode.cpp
  78. 9
      Marlin/src/gcode/gcode.h
  79. 2
      Marlin/src/gcode/gcode_d.cpp
  80. 6
      Marlin/src/gcode/host/M114.cpp
  81. 3
      Marlin/src/gcode/host/M115.cpp
  82. 40
      Marlin/src/gcode/host/M154.cpp
  83. 2
      Marlin/src/gcode/lcd/M995.cpp
  84. 6
      Marlin/src/gcode/motion/G0_G1.cpp
  85. 4
      Marlin/src/gcode/motion/M290.cpp
  86. 92
      Marlin/src/gcode/parser.cpp
  87. 2
      Marlin/src/gcode/parser.h
  88. 16
      Marlin/src/gcode/queue.cpp
  89. 11
      Marlin/src/gcode/sd/M1001.cpp
  90. 6
      Marlin/src/gcode/sd/M24_M25.cpp
  91. 4
      Marlin/src/gcode/sd/M27.cpp
  92. 2
      Marlin/src/gcode/sd/M32.cpp
  93. 2
      Marlin/src/gcode/sd/M524.cpp
  94. 2
      Marlin/src/gcode/sd/M808.cpp
  95. 2
      Marlin/src/gcode/temp/M106_M107.cpp
  96. 2
      Marlin/src/gcode/temp/M303.cpp
  97. 44
      Marlin/src/inc/Conditionals_LCD.h
  98. 4
      Marlin/src/inc/Conditionals_adv.h
  99. 63
      Marlin/src/inc/Conditionals_post.h
  100. 2
      Marlin/src/inc/MarlinConfigPre.h

16
Marlin/Configuration.h

@ -35,7 +35,7 @@
*
* Advanced settings can be found in Configuration_adv.h
*/
#define CONFIGURATION_H_VERSION 020008
#define CONFIGURATION_H_VERSION 02000801
//===========================================================================
//============================= Getting Started =============================
@ -111,6 +111,13 @@
*/
#define SERIAL_PORT_2 1
/**
* Select a third serial port on the board to use for communication with the host.
* Currently only supported for AVR, DUE, LPC1768/9 and STM32/STM32F1
* :[-1, 0, 1, 2, 3, 4, 5, 6, 7]
*/
//#define SERIAL_PORT_3 1
/**
* This setting determines the communication speed of the printer.
*
@ -1516,6 +1523,8 @@
//#define UBL_Z_RAISE_WHEN_OFF_MESH 2.5 // When the nozzle is off the mesh, this value is used
// as the Z-Height correction value.
//#define UBL_MESH_WIZARD // Run several commands in a row to get a complete mesh
#elif ENABLED(MESH_BED_LEVELING)
//===========================================================================
@ -2312,7 +2321,8 @@ EEPROM_W25Q
// MKS LCD12864A/B with graphic controller and SD support. Follows MKS_MINI_12864 pinout.
// https://www.aliexpress.com/item/33018110072.html
//
//#define MKS_LCD12864
//#define MKS_LCD12864A
//#define MKS_LCD12864B
//
// FYSETC variant of the MINI12864 graphic controller with SD support
@ -2615,7 +2625,7 @@ EEPROM_W25Q
//#define DWIN_CREALITY_LCD
//
// ADS7843/XPT2046 ADC Touchscreen such as ILI9341 2.8
// Touch Screen Settings
//
#define TOUCH_SCREEN
#if ENABLED(TOUCH_SCREEN)

54
Marlin/Configuration_adv.h

@ -30,7 +30,7 @@
*
* Basic settings can be found in Configuration.h
*/
#define CONFIGURATION_ADV_H_VERSION 020008
#define CONFIGURATION_ADV_H_VERSION 02000801
//===========================================================================
//============================= Thermal Settings ============================
@ -1486,8 +1486,8 @@
#if ENABLED(MULTI_VOLUME)
#define VOLUME_SD_ONBOARD
#define VOLUME_USB_FLASH_DRIVE
#define DEFAULT_VOLUME SD_ONBOARD
#define DEFAULT_SHARED_VOLUME USB_FLASH_DRIVE
#define DEFAULT_VOLUME SV_SD_ONBOARD
#define DEFAULT_SHARED_VOLUME SV_USB_FLASH_DRIVE
#endif
#endif // SDSUPPORT
@ -2050,7 +2050,7 @@
*
* Override the default value based on the driver type set in Configuration.h.
*/
#define MINIMUM_STEPPER_PULSE 2
#define MINIMUM_STEPPER_PULSE 1
/**
* Maximum stepping rate (in Hz) the stepper driver allows
@ -2301,14 +2301,15 @@
#endif // HAS_MULTI_EXTRUDER
/**
* Advanced Pause
* Experimental feature for filament change support and for parking the nozzle when paused.
* Adds the GCode M600 for initiating filament change.
* If PARK_HEAD_ON_PAUSE enabled, adds the GCode M125 to pause printing and park the nozzle.
* Advanced Pause for Filament Change
* - Adds the G-code M600 Filament Change to initiate a filament change.
* - This feature is required for the default FILAMENT_RUNOUT_SCRIPT.
*
* Requires an LCD display.
* Requires NOZZLE_PARK_FEATURE.
* This feature is required for the default FILAMENT_RUNOUT_SCRIPT.
* Requirements:
* - For Filament Change parking enable and configure NOZZLE_PARK_FEATURE.
* - For user interaction enable an LCD display, HOST_PROMPT_SUPPORT, or EMERGENCY_PARSER.
*
* Enable PARK_HEAD_ON_PAUSE to add the G-code M125 Pause and Park.
*/
#define ADVANCED_PAUSE_FEATURE
#if ENABLED(ADVANCED_PAUSE_FEATURE)
@ -3166,13 +3167,19 @@
//#define AIR_EVACUATION // Cutter Vacuum / Laser Blower motor control with G-codes M10-M11
#if ENABLED(AIR_EVACUATION)
#define AIR_EVACUATION_ACTIVE LOW // Set to "HIGH" if the on/off function is active HIGH
#define AIR_EVACUATION_PIN 42 // Override the default Cutter Vacuum or Laser Blower pin
//#define AIR_EVACUATION_PIN 42 // Override the default Cutter Vacuum or Laser Blower pin
#endif
//#define AIR_ASSIST // Air Assist control with G-codes M8-M9
#if ENABLED(AIR_ASSIST)
#define AIR_ASSIST_ACTIVE LOW // Active state on air assist pin
//#define AIR_ASSIST_PIN 44 // Override the default Air Assist pin
#endif
//#define SPINDLE_SERVO // A servo converting an angle to spindle power
//#define SPINDLE_SERVO // A servo converting an angle to spindle power
#ifdef SPINDLE_SERVO
#define SPINDLE_SERVO_NR 0 // Index of servo used for spindle control
#define SPINDLE_SERVO_MIN 10 // Minimum angle for servo spindle
#define SPINDLE_SERVO_NR 0 // Index of servo used for spindle control
#define SPINDLE_SERVO_MIN 10 // Minimum angle for servo spindle
#endif
/**
@ -3409,6 +3416,11 @@
*/
#define AUTO_REPORT_TEMPERATURES
/**
* Auto-report position with M154 S<seconds>
*/
#define AUTO_REPORT_POSITION
/**
* Include capabilities in M115 output
*/
@ -3478,7 +3490,7 @@
#define PROPORTIONAL_FONT_RATIO 1.0
/**
* Spend 28 bytes of SRAM to optimize the GCode parser
* Spend 28 bytes of SRAM to optimize the G-code parser
*/
#define FASTER_GCODE_PARSER
@ -3774,6 +3786,16 @@
#define GANTRY_CALIBRATION_COMMANDS_POST "G28" // G28 highly recommended to ensure an accurate position
#endif
/**
* Instant freeze / unfreeze functionality
* Specified pin has pullup and connecting to ground will instantly pause motion.
* Potentially useful for emergency stop that allows being resumed.
*/
//#define FREEZE_FEATURE
#if ENABLED(FREEZE_FEATURE)
//#define FREEZE_PIN 41 // Override the default (KILL) pin here
#endif
/**
* MAX7219 Debug Matrix
*

4
Marlin/Version.h

@ -28,7 +28,7 @@
/**
* Marlin release version identifier
*/
//#define SHORT_BUILD_VERSION "2.0.8"
//#define SHORT_BUILD_VERSION "2.0.8.1"
/**
* Verbose version identifier which should contain a reference to the location
@ -41,7 +41,7 @@
* here we define this default string as the date where the latest release
* version was tagged.
*/
//#define STRING_DISTRIBUTION_DATE "2021-04-30"
//#define STRING_DISTRIBUTION_DATE "2021-05-15"
/**
* Defines a generic printer name to be output to the LCD after booting Marlin.

15
Marlin/src/HAL/AVR/HAL.h

@ -93,28 +93,35 @@ typedef int8_t pin_t;
#define MYSERIAL1 TERN(BLUETOOTH, btSerial, MSerial0)
#else
#if !WITHIN(SERIAL_PORT, -1, 3)
#error "SERIAL_PORT must be from 0 to 3. You can also use -1 if the board supports Native USB."
#error "SERIAL_PORT must be from 0 to 3, or -1 for USB Serial."
#endif
#define MYSERIAL1 customizedSerial1
#ifdef SERIAL_PORT_2
#if !WITHIN(SERIAL_PORT_2, -1, 3)
#error "SERIAL_PORT_2 must be from 0 to 3. You can also use -1 if the board supports Native USB."
#error "SERIAL_PORT_2 must be from 0 to 3, or -1 for USB Serial."
#endif
#define MYSERIAL2 customizedSerial2
#endif
#ifdef SERIAL_PORT_3
#if !WITHIN(SERIAL_PORT_3, -1, 3)
#error "SERIAL_PORT_3 must be from 0 to 3, or -1 for USB Serial."
#endif
#define MYSERIAL3 customizedSerial3
#endif
#endif
#ifdef MMU2_SERIAL_PORT
#if !WITHIN(MMU2_SERIAL_PORT, -1, 3)
#error "MMU2_SERIAL_PORT must be from 0 to 3. You can also use -1 if the board supports Native USB."
#error "MMU2_SERIAL_PORT must be from 0 to 3, or -1 for USB Serial."
#endif
#define MMU2_SERIAL mmuSerial
#endif
#ifdef LCD_SERIAL_PORT
#if !WITHIN(LCD_SERIAL_PORT, -1, 3)
#error "LCD_SERIAL_PORT must be from 0 to 3. You can also use -1 if the board supports Native USB."
#error "LCD_SERIAL_PORT must be from 0 to 3, or -1 for USB Serial."
#endif
#define LCD_SERIAL lcdSerial
#if HAS_DGUS_LCD

32
Marlin/src/HAL/AVR/MarlinSerial.cpp

@ -567,7 +567,7 @@ ISR(SERIAL_REGNAME(USART, SERIAL_PORT, _UDRE_vect)) {
// Because of the template definition above, it's required to instantiate the template to have all methods generated
template class MarlinSerial< MarlinSerialCfg<SERIAL_PORT> >;
MSerialT customizedSerial1(MSerialT::HasEmergencyParser);
MSerialT1 customizedSerial1(MSerialT1::HasEmergencyParser);
#ifdef SERIAL_PORT_2
@ -582,7 +582,24 @@ MSerialT customizedSerial1(MSerialT::HasEmergencyParser);
template class MarlinSerial< MarlinSerialCfg<SERIAL_PORT_2> >;
MSerialT2 customizedSerial2(MSerialT2::HasEmergencyParser);
#endif
#endif // SERIAL_PORT_2
#ifdef SERIAL_PORT_3
// Hookup ISR handlers
ISR(SERIAL_REGNAME(USART, SERIAL_PORT_3, _RX_vect)) {
MarlinSerial<MarlinSerialCfg<SERIAL_PORT_3>>::store_rxd_char();
}
ISR(SERIAL_REGNAME(USART, SERIAL_PORT_3, _UDRE_vect)) {
MarlinSerial<MarlinSerialCfg<SERIAL_PORT_3>>::_tx_udr_empty_irq();
}
template class MarlinSerial< MarlinSerialCfg<SERIAL_PORT_3> >;
MSerialT3 customizedSerial3(MSerialT3::HasEmergencyParser);
#endif // SERIAL_PORT_3
#ifdef MMU2_SERIAL_PORT
@ -595,8 +612,9 @@ MSerialT customizedSerial1(MSerialT::HasEmergencyParser);
}
template class MarlinSerial< MMU2SerialCfg<MMU2_SERIAL_PORT> >;
MSerialT3 mmuSerial(MSerialT3::HasEmergencyParser);
#endif
MSerialMMU2 mmuSerial(MSerialMMU2::HasEmergencyParser);
#endif // MMU2_SERIAL_PORT
#ifdef LCD_SERIAL_PORT
@ -609,7 +627,7 @@ MSerialT customizedSerial1(MSerialT::HasEmergencyParser);
}
template class MarlinSerial< LCDSerialCfg<LCD_SERIAL_PORT> >;
MSerialT4 lcdSerial(MSerialT4::HasEmergencyParser);
MSerialLCD lcdSerial(MSerialLCD::HasEmergencyParser);
#if HAS_DGUS_LCD
template<typename Cfg>
@ -622,13 +640,13 @@ MSerialT customizedSerial1(MSerialT::HasEmergencyParser);
}
#endif
#endif
#endif // LCD_SERIAL_PORT
#endif // !USBCON && (UBRRH || UBRR0H || UBRR1H || UBRR2H || UBRR3H)
// For AT90USB targets use the UART for BT interfacing
#if defined(USBCON) && ENABLED(BLUETOOTH)
MSerialT5 bluetoothSerial(false);
MSerialBT bluetoothSerial(false);
#endif
#endif // __AVR__

21
Marlin/src/HAL/AVR/MarlinSerial.h

@ -238,14 +238,19 @@
static constexpr bool MAX_RX_QUEUED = ENABLED(SERIAL_STATS_MAX_RX_QUEUED);
};
typedef Serial1Class< MarlinSerial< MarlinSerialCfg<SERIAL_PORT> > > MSerialT;
extern MSerialT customizedSerial1;
typedef Serial1Class< MarlinSerial< MarlinSerialCfg<SERIAL_PORT> > > MSerialT1;
extern MSerialT1 customizedSerial1;
#ifdef SERIAL_PORT_2
typedef Serial1Class< MarlinSerial< MarlinSerialCfg<SERIAL_PORT_2> > > MSerialT2;
extern MSerialT2 customizedSerial2;
#endif
#ifdef SERIAL_PORT_3
typedef Serial1Class< MarlinSerial< MarlinSerialCfg<SERIAL_PORT_3> > > MSerialT3;
extern MSerialT3 customizedSerial3;
#endif
#endif // !USBCON
#ifdef MMU2_SERIAL_PORT
@ -262,8 +267,8 @@
static constexpr bool RX_OVERRUNS = false;
};
typedef Serial1Class< MarlinSerial< MMU2SerialCfg<MMU2_SERIAL_PORT> > > MSerialT3;
extern MSerialT3 mmuSerial;
typedef Serial1Class< MarlinSerial< MMU2SerialCfg<MMU2_SERIAL_PORT> > > MSerialMMU2;
extern MSerialMMU2 mmuSerial;
#endif
#ifdef LCD_SERIAL_PORT
@ -281,12 +286,12 @@
static constexpr bool RX_OVERRUNS = BOTH(HAS_DGUS_LCD, SERIAL_STATS_RX_BUFFER_OVERRUNS);
};
typedef Serial1Class< MarlinSerial< LCDSerialCfg<LCD_SERIAL_PORT> > > MSerialT4;
extern MSerialT4 lcdSerial;
typedef Serial1Class< MarlinSerial< LCDSerialCfg<LCD_SERIAL_PORT> > > MSerialLCD;
extern MSerialLCD lcdSerial;
#endif
// Use the UART for Bluetooth in AT90USB configurations
#if defined(USBCON) && ENABLED(BLUETOOTH)
typedef Serial1Class<HardwareSerial> MSerialT5;
extern MSerialT5 bluetoothSerial;
typedef Serial1Class<HardwareSerial> MSerialBT;
extern MSerialBT bluetoothSerial;
#endif

21
Marlin/src/HAL/DUE/HAL.h

@ -50,13 +50,12 @@ extern DefaultSerial4 MSerial3;
#define _MSERIAL(X) MSerial##X
#define MSERIAL(X) _MSERIAL(X)
// Define MYSERIAL1/2 before MarlinSerial includes!
#if SERIAL_PORT == -1 || ENABLED(EMERGENCY_PARSER)
#define MYSERIAL1 customizedSerial1
#elif WITHIN(SERIAL_PORT, 0, 3)
#define MYSERIAL1 MSERIAL(SERIAL_PORT)
#else
#error "The required SERIAL_PORT must be from 0 to 3. You can also use -1 if the board supports Native USB."
#error "The required SERIAL_PORT must be from 0 to 3, or -1 for USB Serial."
#endif
#ifdef SERIAL_PORT_2
@ -65,7 +64,17 @@ extern DefaultSerial4 MSerial3;
#elif WITHIN(SERIAL_PORT_2, 0, 3)
#define MYSERIAL2 MSERIAL(SERIAL_PORT_2)
#else
#error "SERIAL_PORT_2 must be from 0 to 3. You can also use -1 if the board supports Native USB."
#error "SERIAL_PORT_2 must be from 0 to 3, or -1 for USB Serial."
#endif
#endif
#ifdef SERIAL_PORT_3
#if SERIAL_PORT_3 == -1 || ENABLED(EMERGENCY_PARSER)
#define MYSERIAL3 customizedSerial3
#elif WITHIN(SERIAL_PORT_3, 0, 3)
#define MYSERIAL3 MSERIAL(SERIAL_PORT_3)
#else
#error "SERIAL_PORT_3 must be from 0 to 3, or -1 for USB Serial."
#endif
#endif
@ -78,12 +87,10 @@ extern DefaultSerial4 MSerial3;
#endif
#ifdef LCD_SERIAL_PORT
#if LCD_SERIAL_PORT == -1
#define LCD_SERIAL lcdSerial
#elif WITHIN(LCD_SERIAL_PORT, 0, 3)
#if WITHIN(LCD_SERIAL_PORT, 0, 3)
#define LCD_SERIAL MSERIAL(LCD_SERIAL_PORT)
#else
#error "LCD_SERIAL_PORT must be from 0 to 3. You can also use -1 if the board supports Native USB."
#error "LCD_SERIAL_PORT must be from 0 to 3."
#endif
#endif

7
Marlin/src/HAL/DUE/MarlinSerial.cpp

@ -478,7 +478,7 @@ void MarlinSerial<Cfg>::flushTX() {
// If not using the USB port as serial port
#if defined(SERIAL_PORT) && SERIAL_PORT >= 0
template class MarlinSerial< MarlinSerialCfg<SERIAL_PORT> >;
MSerialT customizedSerial1(MarlinSerialCfg<SERIAL_PORT>::EMERGENCYPARSER);
MSerialT1 customizedSerial1(MarlinSerialCfg<SERIAL_PORT>::EMERGENCYPARSER);
#endif
#if defined(SERIAL_PORT_2) && SERIAL_PORT_2 >= 0
@ -486,4 +486,9 @@ void MarlinSerial<Cfg>::flushTX() {
MSerialT2 customizedSerial2(MarlinSerialCfg<SERIAL_PORT_2>::EMERGENCYPARSER);
#endif
#if defined(SERIAL_PORT_3) && SERIAL_PORT_3 >= 0
template class MarlinSerial< MarlinSerialCfg<SERIAL_PORT_3> >;
MSerialT3 customizedSerial3(MarlinSerialCfg<SERIAL_PORT_3>::EMERGENCYPARSER);
#endif
#endif // ARDUINO_ARCH_SAM

9
Marlin/src/HAL/DUE/MarlinSerial.h

@ -141,11 +141,16 @@ struct MarlinSerialCfg {
};
#if defined(SERIAL_PORT) && SERIAL_PORT >= 0
typedef Serial1Class< MarlinSerial< MarlinSerialCfg<SERIAL_PORT> > > MSerialT;
extern MSerialT customizedSerial1;
typedef Serial1Class< MarlinSerial< MarlinSerialCfg<SERIAL_PORT> > > MSerialT1;
extern MSerialT1 customizedSerial1;
#endif
#if defined(SERIAL_PORT_2) && SERIAL_PORT_2 >= 0
typedef Serial1Class< MarlinSerial< MarlinSerialCfg<SERIAL_PORT_2> > > MSerialT2;
extern MSerialT2 customizedSerial2;
#endif
#if defined(SERIAL_PORT_3) && SERIAL_PORT_3 >= 0
typedef Serial1Class< MarlinSerial< MarlinSerialCfg<SERIAL_PORT_3> > > MSerialT3;
extern MSerialT3 customizedSerial3;
#endif

13
Marlin/src/HAL/DUE/MarlinSerialUSB.cpp

@ -19,13 +19,13 @@
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#ifdef ARDUINO_ARCH_SAM
/**
* MarlinSerial_Due.cpp - Hardware serial library for Arduino DUE
* Copyright (c) 2017 Eduardo José Tagle. All right reserved
* Based on MarlinSerial for AVR, copyright (c) 2006 Nicholas Zambetti. All right reserved.
*/
#ifdef ARDUINO_ARCH_SAM
#include "../../inc/MarlinConfig.h"
@ -65,7 +65,7 @@ int MarlinSerialUSB::peek() {
pending_char = udi_cdc_getc();
TERN_(EMERGENCY_PARSER, emergency_parser.update(static_cast<MSerialT*>(this)->emergency_state, (char)pending_char));
TERN_(EMERGENCY_PARSER, emergency_parser.update(static_cast<MSerialT1*>(this)->emergency_state, (char)pending_char));
return pending_char;
}
@ -87,7 +87,7 @@ int MarlinSerialUSB::read() {
int c = udi_cdc_getc();
TERN_(EMERGENCY_PARSER, emergency_parser.update(static_cast<MSerialT*>(this)->emergency_state, (char)c));
TERN_(EMERGENCY_PARSER, emergency_parser.update(static_cast<MSerialT1*>(this)->emergency_state, (char)c));
return c;
}
@ -129,10 +129,13 @@ size_t MarlinSerialUSB::write(const uint8_t c) {
// Preinstantiate
#if SERIAL_PORT == -1
MSerialT customizedSerial1(TERN0(EMERGENCY_PARSER, true));
MSerialT1 customizedSerial1(TERN0(EMERGENCY_PARSER, true));
#endif
#if SERIAL_PORT_2 == -1
MSerialT customizedSerial2(TERN0(EMERGENCY_PARSER, true));
MSerialT2 customizedSerial2(TERN0(EMERGENCY_PARSER, true));
#endif
#if SERIAL_PORT_3 == -1
MSerialT3 customizedSerial3(TERN0(EMERGENCY_PARSER, true));
#endif
#endif // HAS_USB_SERIAL

16
Marlin/src/HAL/DUE/MarlinSerialUSB.h

@ -27,11 +27,9 @@
*/
#include "../../inc/MarlinConfig.h"
#if HAS_USB_SERIAL
#include <WString.h>
#include "../../core/serial_hook.h"
#include <WString.h>
struct MarlinSerialUSB {
void begin(const long);
@ -50,14 +48,18 @@ struct MarlinSerialUSB {
FORCE_INLINE int rxMaxEnqueued() { return 0; }
#endif
};
typedef Serial1Class<MarlinSerialUSB> MSerialT;
#if SERIAL_PORT == -1
extern MSerialT customizedSerial1;
typedef Serial1Class<MarlinSerialUSB> MSerialT1;
extern MSerialT1 customizedSerial1;
#endif
#if SERIAL_PORT_2 == -1
extern MSerialT customizedSerial2;
typedef Serial1Class<MarlinSerialUSB> MSerialT2;
extern MSerialT2 customizedSerial2;
#endif
#endif // HAS_USB_SERIAL
#if SERIAL_PORT_3 == -1
typedef Serial1Class<MarlinSerialUSB> MSerialT3;
extern MSerialT3 customizedSerial3;
#endif

2
Marlin/src/HAL/ESP32/WebSocketSerial.cpp

@ -29,7 +29,7 @@
#include "wifi.h"
#include <ESPAsyncWebServer.h>
MSerialT webSocketSerial(false);
MSerialWebSocketT webSocketSerial(false);
AsyncWebSocket ws("/ws"); // TODO Move inside the class.
// RingBuffer impl

4
Marlin/src/HAL/ESP32/WebSocketSerial.h

@ -81,5 +81,5 @@ public:
#endif
};
typedef Serial1Class<WebSocketSerial> MSerialT;
extern MSerialT webSocketSerial;
typedef Serial1Class<WebSocketSerial> MSerialWebSocketT;
extern MSerialWebSocketT webSocketSerial;

10
Marlin/src/HAL/LPC1768/HAL.h

@ -84,6 +84,16 @@ extern DefaultSerial1 USBSerial;
#endif
#endif
#ifdef SERIAL_PORT_3
#if SERIAL_PORT_3 == -1
#define MYSERIAL3 USBSerial
#elif WITHIN(SERIAL_PORT_3, 0, 3)
#define MYSERIAL3 MSERIAL(SERIAL_PORT_3)
#else
#error "SERIAL_PORT_3 must be from 0 to 3. You can also use -1 if the board supports Native USB."
#endif
#endif
#ifdef MMU2_SERIAL_PORT
#if MMU2_SERIAL_PORT == -1
#define MMU2_SERIAL USBSerial

1
Marlin/src/HAL/LPC1768/HAL_MinSerial.cpp

@ -21,6 +21,7 @@
*/
#ifdef TARGET_LPC1768
#include "../../inc/MarlinConfig.h"
#include "HAL.h"
#if ENABLED(POSTMORTEM_DEBUGGING)

8
Marlin/src/HAL/LPC1768/MarlinSerial.cpp

@ -26,9 +26,9 @@
#include "../../inc/MarlinConfig.h"
#if USING_HW_SERIAL0
MarlinSerial _MSerial(LPC_UART0);
MSerialT MSerial0(true, _MSerial);
extern "C" void UART0_IRQHandler() { _MSerial.IRQHandler(); }
MarlinSerial _MSerial0(LPC_UART0);
MSerialT MSerial0(true, _MSerial0);
extern "C" void UART0_IRQHandler() { _MSerial0.IRQHandler(); }
#endif
#if USING_HW_SERIAL1
MarlinSerial _MSerial1((LPC_UART_TypeDef *) LPC_UART1);
@ -52,7 +52,7 @@
// Need to figure out which serial port we are and react in consequence (Marlin does not have CONTAINER_OF macro)
if (false) {}
#if USING_HW_SERIAL0
else if (this == &_MSerial) emergency_parser.update(MSerial0.emergency_state, c);
else if (this == &_MSerial0) emergency_parser.update(MSerial0.emergency_state, c);
#endif
#if USING_HW_SERIAL1
else if (this == &_MSerial1) emergency_parser.update(MSerial1.emergency_state, c);

2
Marlin/src/HAL/LPC1768/tft/xpt2046.cpp

@ -22,7 +22,7 @@
#include "../../../inc/MarlinConfig.h"
#if HAS_TFT_XPT2046 || HAS_TOUCH_BUTTONS
#if HAS_TFT_XPT2046 || HAS_RES_TOUCH_BUTTONS
#include "xpt2046.h"
#include <SPI.h>

2
Marlin/src/HAL/SAMD51/HAL.h

@ -43,8 +43,6 @@
extern DefaultSerial4 MSerial3;
extern DefaultSerial5 MSerial4;
// MYSERIAL1 required before MarlinSerial includes!
#define __MSERIAL(X) MSerial##X
#define _MSERIAL(X) __MSERIAL(X)
#define MSERIAL(X) _MSERIAL(INCREMENT(X))

6
Marlin/src/HAL/STM32/HAL.cpp

@ -96,6 +96,12 @@ void HAL_init() {
#if HAS_SD_HOST_DRIVE
MSC_SD_init(); // Enable USB SD card access
#endif
#if PIN_EXISTS(USB_CONNECT)
OUT_WRITE(USB_CONNECT_PIN, !USB_CONNECT_INVERTING); // USB clear connection
delay(1000); // Give OS time to notice
WRITE(USB_CONNECT_PIN, USB_CONNECT_INVERTING);
#endif
}
// HAL idle task

16
Marlin/src/HAL/STM32/HAL.h

@ -37,6 +37,9 @@
#include <stdint.h>
//
// Serial Ports
//
#ifdef USBCON
#include <USBSerial.h>
#include "../../core/serial_hook.h"
@ -44,9 +47,6 @@
extern DefaultSerial1 MSerial0;
#endif
// ------------------------
// Defines
// ------------------------
#define _MSERIAL(X) MSerial##X
#define MSERIAL(X) _MSERIAL(X)
@ -68,6 +68,16 @@
#endif
#endif
#ifdef SERIAL_PORT_3
#if SERIAL_PORT_3 == -1
#define MYSERIAL3 MSerial0
#elif WITHIN(SERIAL_PORT_3, 1, 6)
#define MYSERIAL3 MSERIAL(SERIAL_PORT_3)
#else
#error "SERIAL_PORT_3 must be from 1 to 6. You can also use -1 if the board supports Native USB."
#endif
#endif
#ifdef MMU2_SERIAL_PORT
#if MMU2_SERIAL_PORT == -1
#define MMU2_SERIAL MSerial0

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

@ -0,0 +1,202 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#if defined(ARDUINO_ARCH_STM32) && !defined(STM32GENERIC)
#include "../../../inc/MarlinConfig.h"
#if ENABLED(TFT_TOUCH_DEVICE_GT911)
#include "gt911.h"
#include "pinconfig.h"
SW_IIC::SW_IIC(uint16_t sda, uint16_t scl) {
scl_pin = scl;
sda_pin = sda;
}
// Software I2C hardware io init
void SW_IIC::init() {
OUT_WRITE(scl_pin, HIGH);
OUT_WRITE(sda_pin, HIGH);
}
// Software I2C start signal
void SW_IIC::start() {
write_sda(HIGH); // SDA = 1
write_scl(HIGH); // SCL = 1
iic_delay(2);
write_sda(LOW); // SDA = 0
iic_delay(1);
write_scl(LOW); // SCL = 0 // keep SCL low, avoid false stop caused by level jump caused by SDA switching IN/OUT
}
// Software I2C stop signal
void SW_IIC::stop() {
write_scl(LOW); // SCL = 0
iic_delay(2);
write_sda(LOW); // SDA = 0
iic_delay(2);
write_scl(HIGH); // SCL = 1
iic_delay(2);
write_sda(HIGH); // SDA = 1
}
// Software I2C sends ACK or NACK signal
void SW_IIC::send_ack(bool ack) {
write_sda(ack ? LOW : HIGH); // SDA = !ack
iic_delay(2);
write_scl(HIGH); // SCL = 1
iic_delay(2);
write_scl(LOW); // SCL = 0
}
// Software I2C read ACK or NACK signal
bool SW_IIC::read_ack() {
bool error = 0;
set_sda_in();
iic_delay(2);
write_scl(HIGH); // SCL = 1
error = read_sda();
iic_delay(2);
write_scl(LOW); // SCL = 0
set_sda_out();
return error;
}
void SW_IIC::send_byte(uint8_t txd) {
LOOP_L_N(i, 8) {
write_sda(txd & 0x80); // write data bit
txd <<= 1;
iic_delay(1);
write_scl(HIGH); // SCL = 1
iic_delay(2);
write_scl(LOW); // SCL = 0
iic_delay(1);
}
read_ack(); // wait ack
}
uint8_t SW_IIC::read_byte(bool ack) {
uint8_t data = 0;
set_sda_in();
LOOP_L_N(i, 8) {
write_scl(HIGH); // SCL = 1
iic_delay(1);
data <<= 1;
if (read_sda()) data++;
write_scl(LOW); // SCL = 0
iic_delay(2);
}
set_sda_out();
send_ack(ack);
return data;
}
GT911_REG_MAP GT911::reg;
SW_IIC GT911::sw_iic = SW_IIC(GT911_SW_I2C_SDA_PIN, GT911_SW_I2C_SCL_PIN);
void GT911::write_reg(uint16_t reg, uint8_t reg_len, uint8_t* w_data, uint8_t w_len) {
sw_iic.start();
sw_iic.send_byte(gt911_slave_address); // Set IIC Slave address
LOOP_L_N(i, reg_len) { // Set reg address
uint8_t r = (reg >> (8 * (reg_len - 1 - i))) & 0xFF;
sw_iic.send_byte(r);
}
LOOP_L_N(i, w_len) { // Write data to reg
sw_iic.send_byte(w_data[i]);
}
sw_iic.stop();
}
void GT911::read_reg(uint16_t reg, uint8_t reg_len, uint8_t* r_data, uint8_t r_len) {
sw_iic.start();
sw_iic.send_byte(gt911_slave_address); // Set IIC Slave address
LOOP_L_N(i, reg_len) { // Set reg address
uint8_t r = (reg >> (8 * (reg_len - 1 - i))) & 0xFF;
sw_iic.send_byte(r);
}
sw_iic.start();
sw_iic.send_byte(gt911_slave_address + 1); // Set read mode
LOOP_L_N(i, r_len) {
r_data[i] = sw_iic.read_byte(1); // Read data from reg
}
sw_iic.stop();
}
void GT911::Init() {
OUT_WRITE(GT911_RST_PIN, LOW);
OUT_WRITE(GT911_INT_PIN, LOW);
delay(20);
WRITE(GT911_RST_PIN, HIGH);
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
}
bool GT911::getFirstTouchPoint(int16_t *x, int16_t *y) {
read_reg(0x814E, 2, &reg.REG.status, 1);
if (reg.REG.status & 0x80) {
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;
return true;
}
return false;
}
bool GT911::getPoint(int16_t *x, int16_t *y) {
static bool touched = 0;
static int16_t read_x = 0, read_y = 0;
static millis_t next_time = 0;
if (ELAPSED(millis(), next_time)) {
touched = getFirstTouchPoint(&read_x, &read_y);
next_time = millis() + 20;
}
*x = read_x;
*y = read_y;
return touched;
}
#endif // TFT_TOUCH_DEVICE_GT911
#endif // ARDUINO_ARCH_STM32 && !STM32GENERIC

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

@ -0,0 +1,120 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#pragma once
#include "../../../inc/MarlinConfig.h"
#define GT911_SLAVE_ADDRESS 0xBA
#if !PIN_EXISTS(GT911_RST)
#error "GT911_RST_PIN is not defined."
#elif !PIN_EXISTS(GT911_INT)
#error "GT911_INT_PIN is not defined."
#elif !PIN_EXISTS(GT911_SW_I2C_SCL)
#error "GT911_SW_I2C_SCL_PIN is not defined."
#elif !PIN_EXISTS(GT911_SW_I2C_SDA)
#error "GT911_SW_I2C_SDA_PIN is not defined."
#endif
class SW_IIC {
private:
uint16_t scl_pin;
uint16_t sda_pin;
void write_scl(bool level)
{
WRITE(scl_pin, level);
}
void write_sda(bool level)
{
WRITE(sda_pin, level);
}
bool read_sda()
{
return READ(sda_pin);
}
void set_sda_out()
{
SET_OUTPUT(sda_pin);
}
void set_sda_in()
{
SET_INPUT_PULLUP(sda_pin);
}
static void iic_delay(uint8_t t)
{
delayMicroseconds(t);
}
public:
SW_IIC(uint16_t sda, uint16_t scl);
// setSCL/SDA have to be called before begin()
void setSCL(uint16_t scl)
{
scl_pin = scl;
};
void setSDA(uint16_t sda)
{
sda_pin = sda;
};
void init(); // Initialize the IO port of IIC
void start(); // Send IIC start signal
void stop(); // Send IIC stop signal
void send_byte(uint8_t txd); // IIC sends a byte
uint8_t read_byte(bool ack); // IIC reads a byte
void send_ack(bool ack); // IIC sends ACK or NACK signal
bool read_ack();
};
typedef struct __attribute__((__packed__)) {
uint8_t xl;
uint8_t xh;
uint8_t yl;
uint8_t yh;
uint8_t sizel;
uint8_t sizeh;
uint8_t reserved;
uint8_t track_id;
} GT911_POINT;
typedef union __attribute__((__packed__)) {
uint8_t map[42];
struct {
uint8_t status; // 0x814E
uint8_t track_id; // 0x814F
GT911_POINT point[5]; // [0]:0x8150 - 0x8157 / [1]:0x8158 - 0x815F / [2]:0x8160 - 0x8167 / [3]:0x8168 - 0x816F / [4]:0x8170 - 0x8177
} REG;
} GT911_REG_MAP;
class GT911 {
private:
static const uint8_t gt911_slave_address = GT911_SLAVE_ADDRESS;
static GT911_REG_MAP reg;
static SW_IIC sw_iic;
static void write_reg(uint16_t reg, uint8_t reg_len, uint8_t* w_data, uint8_t w_len);
static void read_reg(uint16_t reg, uint8_t reg_len, uint8_t* r_data, uint8_t r_len);
public:
static void Init();
static bool getFirstTouchPoint(int16_t *x, int16_t *y);
static bool getPoint(int16_t *x, int16_t *y);
};

2
Marlin/src/HAL/STM32/tft/tft_ltdc.cpp

@ -312,7 +312,7 @@ void TFT_LTDC::DrawImage(uint16_t sx, uint16_t sy, uint16_t ex, uint16_t ey, uin
uint16_t offline = TFT_WIDTH - (ex - sx);
uint32_t addr = (uint32_t)&framebuffer[(TFT_WIDTH * sy) + sx];
CBI(DMA2D->CR, 0)
CBI(DMA2D->CR, 0);
DMA2D->CR = 0 << 16;
DMA2D->FGPFCCR = 0X02;
DMA2D->FGOR = 0;

2
Marlin/src/HAL/STM32/tft/xpt2046.cpp

@ -23,7 +23,7 @@
#include "../../../inc/MarlinConfig.h"
#if HAS_TFT_XPT2046 || HAS_TOUCH_BUTTONS
#if HAS_TFT_XPT2046 || HAS_RES_TOUCH_BUTTONS
#include "xpt2046.h"
#include "pinconfig.h"

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

@ -21,15 +21,12 @@
*/
#pragma once
#include <stdint.h>
#include "../../inc/MarlinConfig.h"
// ------------------------
// Defines
// ------------------------
#define FORCE_INLINE __attribute__((always_inline)) inline
// STM32 timers may be 16 or 32 bit. Limiting HAL_TIMER_TYPE_MAX to 16 bits
// avoids issues with STM32F0 MCUs, which seem to pause timers if UINT32_MAX
// is written to the register. STM32F4 timers do not manifest this issue,

2
Marlin/src/HAL/STM32F1/HAL.cpp

@ -293,7 +293,7 @@ void HAL_init() {
#if PIN_EXISTS(USB_CONNECT)
OUT_WRITE(USB_CONNECT_PIN, !USB_CONNECT_INVERTING); // USB clear connection
delay(1000); // Give OS time to notice
OUT_WRITE(USB_CONNECT_PIN, USB_CONNECT_INVERTING);
WRITE(USB_CONNECT_PIN, USB_CONNECT_INVERTING);
#endif
TERN_(POSTMORTEM_DEBUGGING, install_min_serial()); // Install the minimal serial handler
}

43
Marlin/src/HAL/STM32F1/HAL.h

@ -36,7 +36,6 @@
#include "fastio.h"
#include "watchdog.h"
#include <stdint.h>
#include <util/atomic.h>
@ -63,11 +62,10 @@
#ifdef SERIAL_USB
typedef ForwardSerial1Class< USBSerial > DefaultSerial1;
extern DefaultSerial1 MSerial0;
#if !HAS_SD_HOST_DRIVE
#define UsbSerial MSerial0
#else
#if HAS_SD_HOST_DRIVE
#define UsbSerial MarlinCompositeSerial
#else
#define UsbSerial MSerial0
#endif
#endif
@ -86,11 +84,7 @@
#define MYSERIAL1 MSERIAL(SERIAL_PORT)
#else
#define MYSERIAL1 MSERIAL(1) // dummy port
#if NUM_UARTS == 5
#error "SERIAL_PORT must be from 1 to 5. You can also use -1 if the board supports Native USB."
#else
#error "SERIAL_PORT must be from 1 to 3. You can also use -1 if the board supports Native USB."
#endif
static_assert(false, "SERIAL_PORT must be from 1 to " STRINGIFY(NUM_UARTS) ". You can also use -1 if the board supports Native USB.")
#endif
#ifdef SERIAL_PORT_2
@ -100,11 +94,18 @@
#define MYSERIAL2 MSERIAL(SERIAL_PORT_2)
#else
#define MYSERIAL2 MSERIAL(1) // dummy port
#if NUM_UARTS == 5
#error "SERIAL_PORT_2 must be from 1 to 5. You can also use -1 if the board supports Native USB."
#else
#error "SERIAL_PORT_2 must be from 1 to 3. You can also use -1 if the board supports Native USB."
#endif
static_assert(false, "SERIAL_PORT_2 must be from 1 to " STRINGIFY(NUM_UARTS) ". You can also use -1 if the board supports Native USB.")
#endif
#endif
#ifdef SERIAL_PORT_3
#if SERIAL_PORT_3 == -1
#define MYSERIAL3 UsbSerial
#elif WITHIN(SERIAL_PORT_3, 1, NUM_UARTS)
#define MYSERIAL3 MSERIAL(SERIAL_PORT_3)
#else
#define MYSERIAL3 MSERIAL(1) // dummy port
static_assert(false, "SERIAL_PORT_3 must be from 1 to " STRINGIFY(NUM_UARTS) ". You can also use -1 if the board supports Native USB.")
#endif
#endif
@ -115,11 +116,7 @@
#define MMU2_SERIAL MSERIAL(MMU2_SERIAL_PORT)
#else
#define MMU2_SERIAL MSERIAL(1) // dummy port
#if NUM_UARTS == 5
#error "MMU2_SERIAL_PORT must be from 1 to 5. You can also use -1 if the board supports Native USB."
#else
#error "MMU2_SERIAL_PORT must be from 1 to 3. You can also use -1 if the board supports Native USB."
#endif
static_assert(false, "MMU2_SERIAL_PORT must be from 1 to " STRINGIFY(NUM_UARTS) ". You can also use -1 if the board supports Native USB.")
#endif
#endif
@ -130,11 +127,7 @@
#define LCD_SERIAL MSERIAL(LCD_SERIAL_PORT)
#else
#define LCD_SERIAL MSERIAL(1) // dummy port
#if NUM_UARTS == 5
#error "LCD_SERIAL_PORT must be from 1 to 5. You can also use -1 if the board supports Native USB."
#else
#error "LCD_SERIAL_PORT must be from 1 to 3. You can also use -1 if the board supports Native USB."
#endif
static_assert(false, "LCD_SERIAL_PORT must be from 1 to " STRINGIFY(NUM_UARTS) ". You can also use -1 if the board supports Native USB.")
#endif
#if HAS_DGUS_LCD
#define SERIAL_GET_TX_BUFFER_FREE() LCD_SERIAL.availableForWrite()

2
Marlin/src/HAL/STM32F1/onboard_sd.cpp

@ -559,4 +559,4 @@ DRESULT disk_read (
#endif // SD_CONNECTION_IS(ONBOARD)
#endif
#endif // __STM32F1__
#endif // __STM32F1__

2
Marlin/src/HAL/STM32F1/tft/xpt2046.cpp

@ -22,7 +22,7 @@
#include "../../../inc/MarlinConfig.h"
#if HAS_TFT_XPT2046 || HAS_TOUCH_BUTTONS
#if HAS_TFT_XPT2046 || HAS_RES_TOUCH_BUTTONS
#include "xpt2046.h"
#include <SPI.h>

8
Marlin/src/HAL/STM32F1/timers.h

@ -25,9 +25,10 @@
* HAL for stm32duino.com based on Libmaple and compatible (STM32F1)
*/
#include <stdint.h>
#include "../../inc/MarlinConfig.h"
#include "HAL.h"
#include <libmaple/timer.h>
#include "../../core/boards.h"
// ------------------------
// Defines
@ -37,7 +38,6 @@
* TODO: Check and confirm what timer we will use for each Temps and stepper driving.
* We should probable drive temps with PWM.
*/
#define FORCE_INLINE __attribute__((always_inline)) inline
typedef uint16_t hal_timer_t;
#define HAL_TIMER_TYPE_MAX 0xFFFF
@ -80,7 +80,7 @@ typedef uint16_t hal_timer_t;
//#define TEMP_TIMER_NUM 4 // 2->4, Timer 2 for Stepper Current PWM
#endif
#if MB(BTT_SKR_MINI_E3_V1_0, BTT_SKR_E3_DIP, BTT_SKR_MINI_E3_V1_2, MKS_ROBIN_LITE)
#if MB(BTT_SKR_MINI_E3_V1_0, BTT_SKR_E3_DIP, BTT_SKR_MINI_E3_V1_2, MKS_ROBIN_LITE, MKS_ROBIN_E3D, MKS_ROBIN_E3)
// SKR Mini E3 boards use PA8 as FAN_PIN, so TIMER 1 is used for Fan PWM.
#ifdef STM32_HIGH_DENSITY
#define SERVO0_TIMER_NUM 8 // tone.cpp uses Timer 4

2
Marlin/src/HAL/TEENSY31_32/HAL.h

@ -68,6 +68,8 @@ extern USBSerialType USBSerial;
#elif WITHIN(SERIAL_PORT, 0, 3)
DECLARE_SERIAL(SERIAL_PORT);
#define MYSERIAL1 MSERIAL(SERIAL_PORT)
#else
#error "The required SERIAL_PORT must be from 0 to 3, or -1 for Native USB."
#endif
#define HAL_SERVO_LIB libServo

3
Marlin/src/HAL/TEENSY31_32/HAL_SPI.cpp

@ -21,11 +21,12 @@
*/
#ifdef __MK20DX256__
#include "../../inc/MarlinConfig.h"
#include "HAL.h"
#include <SPI.h>
#include <pins_arduino.h>
#include "spi_pins.h"
#include "../../core/macros.h"
static SPISettings spiConfig;

3
Marlin/src/HAL/TEENSY35_36/HAL_SPI.cpp

@ -26,11 +26,12 @@
#if defined(__MK64FX512__) || defined(__MK66FX1M0__)
#include "../../inc/MarlinConfig.h"
#include "HAL.h"
#include <SPI.h>
#include <pins_arduino.h>
#include "spi_pins.h"
#include "../../core/macros.h"
static SPISettings spiConfig;

3
Marlin/src/HAL/TEENSY40_41/HAL.cpp

@ -26,10 +26,11 @@
#ifdef __IMXRT1062__
#include "../../inc/MarlinConfig.h"
#include "HAL.h"
#include "../shared/Delay.h"
#include "timers.h"
#include <Wire.h>
#define _IMPLEMENT_SERIAL(X) DefaultSerial##X MSerial##X(false, Serial##X)

3
Marlin/src/HAL/TEENSY40_41/HAL_SPI.cpp

@ -26,11 +26,12 @@
#ifdef __IMXRT1062__
#include "../../inc/MarlinConfig.h"
#include "HAL.h"
#include <SPI.h>
#include <pins_arduino.h>
#include "spi_pins.h"
#include "../../core/macros.h"
static SPISettings spiConfig;

4
Marlin/src/HAL/shared/Marduino.h

@ -82,4 +82,8 @@
#define UNUSED(x) ((void)(x))
#endif
#ifndef FORCE_INLINE
#define FORCE_INLINE inline __attribute__((always_inline))
#endif
#include "progmem.h"

10
Marlin/src/HAL/shared/eeprom_if_i2c.cpp

@ -30,11 +30,17 @@
#if ENABLED(I2C_EEPROM)
#include "eeprom_if.h"
#include <Wire.h>
#if ENABLED(SOFT_I2C_EEPROM)
#include <SlowSoftWire.h>
SlowSoftWire Wire = SlowSoftWire(I2C_SDA_PIN, I2C_SCL_PIN, true);
#else
#include <Wire.h>
#endif
void eeprom_init() {
Wire.begin(
#if PINS_EXIST(I2C_SCL, I2C_SDA)
#if PINS_EXIST(I2C_SCL, I2C_SDA) && DISABLED(SOFT_I2C_EEPROM)
uint8_t(I2C_SDA_PIN), uint8_t(I2C_SCL_PIN)
#endif
);

44
Marlin/src/MarlinCore.cpp

@ -68,9 +68,9 @@
#endif
#if HAS_TFT_LVGL_UI
#include "lcd/extui/lib/mks_ui/tft_lvgl_configuration.h"
#include "lcd/extui/lib/mks_ui/draw_ui.h"
#include "lcd/extui/lib/mks_ui/mks_hardware_test.h"
#include "lcd/extui/mks_ui/tft_lvgl_configuration.h"
#include "lcd/extui/mks_ui/draw_ui.h"
#include "lcd/extui/mks_ui/mks_hardware_test.h"
#include <lvgl.h>
#endif
@ -229,7 +229,7 @@
#endif
#if ENABLED(DGUS_LCD_UI_MKS)
#include "lcd/extui/lib/dgus/DGUSScreenHandler.h"
#include "lcd/extui/dgus/DGUSScreenHandler.h"
#endif
#if HAS_DRIVER_SAFE_POWER_PROTECT
@ -331,18 +331,14 @@ void disable_all_steppers() {
}
/**
* A Print Job exists when the timer is running or SD printing
* A Print Job exists when the timer is running or SD is printing
*/
bool printJobOngoing() {
return print_job_timer.isRunning() || IS_SD_PRINTING();
}
bool printJobOngoing() { return print_job_timer.isRunning() || IS_SD_PRINTING(); }
/**
* Printing is active when the print job timer is running
* Printing is active when a job is underway but not paused
*/
bool printingIsActive() {
return !did_pause_print && (print_job_timer.isRunning() || IS_SD_PRINTING());
}
bool printingIsActive() { return !did_pause_print && printJobOngoing(); }
/**
* Printing is paused according to SD or host indicators
@ -367,7 +363,7 @@ void startOrResumeJob() {
inline void abortSDPrinting() {
IF_DISABLED(NO_SD_AUTOSTART, card.autofile_cancel());
card.endFilePrint(TERN_(SD_RESORT, true));
card.abortFilePrintNow(TERN_(SD_RESORT, true));
queue.clear();
quickstop_stepper();
@ -390,8 +386,8 @@ void startOrResumeJob() {
}
inline void finishSDPrinting() {
if (queue.enqueue_one_P(PSTR("M1001"))) {
marlin_state = MF_RUNNING;
if (queue.enqueue_one_P(PSTR("M1001"))) { // Keep trying until it gets queued
marlin_state = MF_RUNNING; // Signal to stop trying
TERN_(PASSWORD_AFTER_SD_PRINT_END, password.lock_machine());
TERN_(DGUS_LCD_UI_MKS, ScreenHandler.SDPrintingFinished());
}
@ -487,6 +483,10 @@ inline void manage_inactivity(const bool ignore_stepper_queue=false) {
}
#endif
#if HAS_FREEZE_PIN
Stepper::frozen = !READ(FREEZE_PIN);
#endif
#if HAS_HOME
// Handle a standalone HOME button
constexpr millis_t HOME_DEBOUNCE_DELAY = 1000UL;
@ -748,7 +748,7 @@ void idle(TERN_(ADVANCED_PAUSE_FEATURE, bool no_stepper_sleep/*=false*/)) {
// Handle Power-Loss Recovery
#if ENABLED(POWER_LOSS_RECOVERY) && PIN_EXISTS(POWER_LOSS)
if (printJobOngoing()) recovery.outage();
if (IS_SD_PRINTING()) recovery.outage();
#endif
// Run StallGuard endstop checks
@ -796,6 +796,7 @@ void idle(TERN_(ADVANCED_PAUSE_FEATURE, bool no_stepper_sleep/*=false*/)) {
if (!gcode.autoreport_paused) {
TERN_(AUTO_REPORT_TEMPERATURES, thermalManager.auto_reporter.tick());
TERN_(AUTO_REPORT_SD_STATUS, card.auto_reporter.tick());
TERN_(AUTO_REPORT_POSITION, position_auto_reporter.tick());
}
#endif
@ -901,7 +902,7 @@ void stop() {
thermalManager.set_fans_paused(false); // Un-pause fans for safety
#endif
if (IsRunning()) {
if (!IsStopped()) {
SERIAL_ERROR_MSG(STR_ERR_STOPPED);
LCD_MESSAGEPGM(MSG_STOPPED);
safe_delay(350); // allow enough time for messages to get out before stopping
@ -1079,6 +1080,11 @@ void setup() {
#endif
serial_connect_timeout = millis() + 1000UL;
while (!MYSERIAL2.connected() && PENDING(millis(), serial_connect_timeout)) { /*nada*/ }
#ifdef SERIAL_PORT_3
MYSERIAL3.begin(BAUDRATE);
serial_connect_timeout = millis() + 1000UL;
while (!MYSERIAL3.connected() && PENDING(millis(), serial_connect_timeout)) { /*nada*/ }
#endif
#endif
SERIAL_ECHOLNPGM("start");
@ -1092,6 +1098,10 @@ void setup() {
#endif
#endif
#if HAS_FREEZE_PIN
SET_INPUT_PULLUP(FREEZE_PIN);
#endif
#if HAS_SUICIDE
SETUP_LOG("SUICIDE_PIN");
OUT_WRITE(SUICIDE_PIN, !SUICIDE_PIN_INVERTING);

19
Marlin/src/MarlinCore.h

@ -56,20 +56,21 @@ void minkill(const bool steppers_off=false);
// Global State of the firmware
enum MarlinState : uint8_t {
MF_INITIALIZING = 0,
MF_RUNNING = _BV(0),
MF_PAUSED = _BV(1),
MF_WAITING = _BV(2),
MF_STOPPED = _BV(3),
MF_SD_COMPLETE = _BV(4),
MF_KILLED = _BV(7)
MF_INITIALIZING = 0,
MF_STOPPED,
MF_KILLED,
MF_RUNNING,
MF_SD_COMPLETE,
MF_PAUSED,
MF_WAITING,
};
extern MarlinState marlin_state;
inline bool IsRunning() { return marlin_state == MF_RUNNING; }
inline bool IsStopped() { return marlin_state != MF_RUNNING; }
inline bool IsRunning() { return marlin_state >= MF_RUNNING; }
inline bool IsStopped() { return marlin_state == MF_STOPPED; }
bool printingIsActive();
bool printJobOngoing();
bool printingIsPaused();
void startOrResumeJob();

30
Marlin/src/core/boards.h

@ -370,20 +370,22 @@
#define BOARD_BTT_SKR_V2_0_REV_A 4211 // BigTreeTech SKR v2.0 Rev A (STM32F407VGT6)
#define BOARD_BTT_SKR_V2_0_REV_B 4212 // BigTreeTech SKR v2.0 Rev B (STM32F407VGT6)
#define BOARD_BTT_GTR_V1_0 4213 // BigTreeTech GTR v1.0 (STM32F407IGT)
#define BOARD_LERDGE_K 4214 // Lerdge K (STM32F407ZG)
#define BOARD_LERDGE_S 4215 // Lerdge S (STM32F407VE)
#define BOARD_LERDGE_X 4216 // Lerdge X (STM32F407VE)
#define BOARD_VAKE403D 4217 // VAkE 403D (STM32F446VET6)
#define BOARD_FYSETC_S6 4218 // FYSETC S6 (STM32F446VET6)
#define BOARD_FYSETC_S6_V2_0 4219 // FYSETC S6 v2.0 (STM32F446VET6)
#define BOARD_FYSETC_SPIDER 4220 // FYSETC Spider (STM32F446VET6)
#define BOARD_FLYF407ZG 4221 // FLYF407ZG (STM32F407ZG)
#define BOARD_MKS_ROBIN2 4222 // MKS_ROBIN2 (STM32F407ZE)
#define BOARD_MKS_ROBIN_PRO_V2 4223 // MKS Robin Pro V2 (STM32F407VE)
#define BOARD_MKS_ROBIN_NANO_V3 4224 // MKS Robin Nano V3 (STM32F407VG)
#define BOARD_ANET_ET4 4225 // ANET ET4 V1.x (STM32F407VGT6)
#define BOARD_ANET_ET4P 4226 // ANET ET4P V1.x (STM32F407VGT6)
#define BOARD_FYSETC_CHEETAH_V20 4227 // FYSETC Cheetah V2.0
#define BOARD_BTT_OCTOPUS_V1_0 4214 // BigTreeTech Octopus v1.0 (STM32F446ZET6)
#define BOARD_LERDGE_K 4215 // Lerdge K (STM32F407ZG)
#define BOARD_LERDGE_S 4216 // Lerdge S (STM32F407VE)
#define BOARD_LERDGE_X 4217 // Lerdge X (STM32F407VE)
#define BOARD_VAKE403D 4218 // VAkE 403D (STM32F446VET6)
#define BOARD_FYSETC_S6 4219 // FYSETC S6 (STM32F446VET6)
#define BOARD_FYSETC_S6_V2_0 4220 // FYSETC S6 v2.0 (STM32F446VET6)
#define BOARD_FYSETC_SPIDER 4221 // FYSETC Spider (STM32F446VET6)
#define BOARD_FLYF407ZG 4222 // FLYF407ZG (STM32F407ZG)
#define BOARD_MKS_ROBIN2 4223 // MKS_ROBIN2 (STM32F407ZE)
#define BOARD_MKS_ROBIN_PRO_V2 4224 // MKS Robin Pro V2 (STM32F407VE)
#define BOARD_MKS_ROBIN_NANO_V3 4225 // MKS Robin Nano V3 (STM32F407VG)
#define BOARD_ANET_ET4 4226 // ANET ET4 V1.x (STM32F407VGT6)
#define BOARD_ANET_ET4P 4227 // ANET ET4P V1.x (STM32F407VGT6)
#define BOARD_FYSETC_CHEETAH_V20 4228 // FYSETC Cheetah V2.0
//
// ARM Cortex M7

75
Marlin/src/core/macros.h

@ -237,6 +237,38 @@
memcpy(&a[0],&b[0],_MIN(sizeof(a),sizeof(b))); \
}while(0)
#define CODE_9( A,B,C,D,E,F,G,H,I,...) A; B; C; D; E; F; G; H; I
#define CODE_8( A,B,C,D,E,F,G,H,...) A; B; C; D; E; F; G; H
#define CODE_7( A,B,C,D,E,F,G,...) A; B; C; D; E; F; G
#define CODE_6( A,B,C,D,E,F,...) A; B; C; D; E; F
#define CODE_5( A,B,C,D,E,...) A; B; C; D; E
#define CODE_4( A,B,C,D,...) A; B; C; D
#define CODE_3( A,B,C,...) A; B; C
#define CODE_2( A,B,...) A; B
#define CODE_1( A,...) A
#define _CODE_N(N,V...) CODE_##N(V)
#define CODE_N(N,V...) _CODE_N(N,V)
#define GANG_16(A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,...) A B C D E F G H I J K L M N O P
#define GANG_15(A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,...) A B C D E F G H I J K L M N O
#define GANG_14(A,B,C,D,E,F,G,H,I,J,K,L,M,N,...) A B C D E F G H I J K L M N
#define GANG_13(A,B,C,D,E,F,G,H,I,J,K,L,M...) A B C D E F G H I J K L M
#define GANG_12(A,B,C,D,E,F,G,H,I,J,K,L...) A B C D E F G H I J K L
#define GANG_11(A,B,C,D,E,F,G,H,I,J,K,...) A B C D E F G H I J K
#define GANG_10(A,B,C,D,E,F,G,H,I,J,...) A B C D E F G H I J
#define GANG_9( A,B,C,D,E,F,G,H,I,...) A B C D E F G H I
#define GANG_8( A,B,C,D,E,F,G,H,...) A B C D E F G H
#define GANG_7( A,B,C,D,E,F,G,...) A B C D E F G
#define GANG_6( A,B,C,D,E,F,...) A B C D E F
#define GANG_5( A,B,C,D,E,...) A B C D E
#define GANG_4( A,B,C,D,...) A B C D
#define GANG_3( A,B,C,...) A B C
#define GANG_2( A,B,...) A B
#define GANG_1( A,...) A
#define _GANG_N(N,V...) GANG_##N(V)
#define GANG_N(N,V...) _GANG_N(N,V)
#define GANG_N_1(N,K) _GANG_N(N,K,K,K,K,K,K,K,K,K,K,K,K,K,K,K,K)
// Macros for initializing arrays
#define LIST_16(A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,...) A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P
#define LIST_15(A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,...) A,B,C,D,E,F,G,H,I,J,K,L,M,N,O
@ -254,10 +286,13 @@
#define LIST_3( A,B,C,...) A,B,C
#define LIST_2( A,B,...) A,B
#define LIST_1( A,...) A
#define LIST_0(...)
#define _LIST_N(N,V...) LIST_##N(V)
#define LIST_N(N,V...) _LIST_N(N,V)
#define LIST_N_1(N,K) _LIST_N(N,K,K,K,K,K,K,K,K,K,K,K,K,K,K,K,K)
#define ARRAY_N(N,V...) { _LIST_N(N,V) }
#define ARRAY_N_1(N,K) { LIST_N_1(N,K) }
#define _JOIN_1(O) (O)
#define JOIN_N(N,C,V...) (DO(JOIN,C,LIST_N(N,V)))
@ -301,8 +336,12 @@
#define HYPOT(x,y) SQRT(HYPOT2(x,y))
// Use NUM_ARGS(__VA_ARGS__) to get the number of variadic arguments
#define _NUM_ARGS(_,Z,Y,X,W,V,U,T,S,R,Q,P,O,N,M,L,K,J,I,H,G,F,E,D,C,B,A,OUT,...) OUT
#define NUM_ARGS(V...) _NUM_ARGS(0,V,26,25,24,23,22,21,20,19,18,17,16,15,14,13,12,11,10,9,8,7,6,5,4,3,2,1,0)
#define _NUM_ARGS(_,n,m,l,k,j,i,h,g,f,e,d,c,b,a,Z,Y,X,W,V,U,T,S,R,Q,P,O,N,M,L,K,J,I,H,G,F,E,D,C,B,A,OUT,...) OUT
#define NUM_ARGS(V...) _NUM_ARGS(0,V,40,39,38,37,36,35,34,33,32,31,30,29,28,27,26,25,24,23,22,21,20,19,18,17,16,15,14,13,12,11,10,9,8,7,6,5,4,3,2,1,0)
// Use TWO_ARGS(__VA_ARGS__) to get whether there are 1, 2, or >2 arguments
#define _TWO_ARGS(_,n,m,l,k,j,i,h,g,f,e,d,c,b,a,Z,Y,X,W,V,U,T,S,R,Q,P,O,N,M,L,K,J,I,H,G,F,E,D,C,B,A,OUT,...) OUT
#define TWO_ARGS(V...) _TWO_ARGS(0,V,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,3,2,1,0)
#ifdef __cplusplus
@ -414,31 +453,19 @@
#else
#define MIN_2(a,b) ((a)<(b)?(a):(b))
#define MIN_3(a,V...) MIN_2(a,MIN_2(V))
#define MIN_4(a,V...) MIN_2(a,MIN_3(V))
#define MIN_5(a,V...) MIN_2(a,MIN_4(V))
#define MIN_6(a,V...) MIN_2(a,MIN_5(V))
#define MIN_7(a,V...) MIN_2(a,MIN_6(V))
#define MIN_8(a,V...) MIN_2(a,MIN_7(V))
#define MIN_9(a,V...) MIN_2(a,MIN_8(V))
#define MIN_10(a,V...) MIN_2(a,MIN_9(V))
#define __MIN_N(N,V...) MIN_##N(V)
#define _MIN_N(N,V...) __MIN_N(N,V)
#define _MIN(V...) _MIN_N(NUM_ARGS(V), V)
#define _MIN_N_REF() _MIN_N
#define _MIN(V...) EVAL(_MIN_N(TWO_ARGS(V),V))
#define MIN_2(a,b) ((a)<(b)?(a):(b))
#define MIN_3(a,V...) MIN_2(a,DEFER2(_MIN_N_REF)()(TWO_ARGS(V),V))
#define MAX_2(a,b) ((a)>(b)?(a):(b))
#define MAX_3(a,V...) MAX_2(a,MAX_2(V))
#define MAX_4(a,V...) MAX_2(a,MAX_3(V))
#define MAX_5(a,V...) MAX_2(a,MAX_4(V))
#define MAX_6(a,V...) MAX_2(a,MAX_5(V))
#define MAX_7(a,V...) MAX_2(a,MAX_6(V))
#define MAX_8(a,V...) MAX_2(a,MAX_7(V))
#define MAX_9(a,V...) MAX_2(a,MAX_8(V))
#define MAX_10(a,V...) MAX_2(a,MAX_9(V))
#define __MAX_N(N,V...) MAX_##N(V)
#define _MAX_N(N,V...) __MAX_N(N,V)
#define _MAX(V...) _MAX_N(NUM_ARGS(V), V)
#define _MAX_N_REF() _MAX_N
#define _MAX(V...) EVAL(_MAX_N(TWO_ARGS(V),V))
#define MAX_2(a,b) ((a)>(b)?(a):(b))
#define MAX_3(a,V...) MAX_2(a,DEFER2(_MAX_N_REF)()(TWO_ARGS(V),V))
#endif
@ -473,6 +500,9 @@
#define ADD8(N) ADD4(ADD4(N))
#define ADD9(N) ADD4(ADD5(N))
#define ADD10(N) ADD5(ADD5(N))
#define SUM(A,B) _CAT(ADD,A)(B)
#define DOUBLE_(n) ADD##n(n)
#define DOUBLE(n) DOUBLE_(n)
// Macros for subtracting
#define DEC_0 0
@ -581,6 +611,7 @@
// Repeat a macro passing S...N-1.
#define REPEAT_S(S,N,OP) EVAL(_REPEAT(S,SUB##S(N),OP))
#define REPEAT(N,OP) REPEAT_S(0,N,OP)
#define REPEAT_1(N,OP) REPEAT_S(1,INCREMENT(N),OP)
// Repeat a macro passing 0...N-1 plus additional arguments.
#define REPEAT2_S(S,N,OP,V...) EVAL(_REPEAT2(S,SUB##S(N),OP,V))

12
Marlin/src/core/serial.cpp

@ -44,6 +44,9 @@ PGMSTR(SP_X_LBL, " X:"); PGMSTR(SP_Y_LBL, " Y:"); PGMSTR(SP_Z_LBL, " Z:"); PGMST
#if ENABLED(MEATPACK_ON_SERIAL_PORT_2)
SerialLeafT2 mpSerial2(false, _SERIAL_LEAF_2);
#endif
#if ENABLED(MEATPACK_ON_SERIAL_PORT_3)
SerialLeafT3 mpSerial3(false, _SERIAL_LEAF_3);
#endif
// Step 2: For multiserial, handle the second serial port as well
#if HAS_MULTI_SERIAL
@ -52,7 +55,14 @@ PGMSTR(SP_X_LBL, " X:"); PGMSTR(SP_Y_LBL, " Y:"); PGMSTR(SP_Z_LBL, " Z:"); PGMST
SerialLeafT2 msSerial2(ethernet.have_telnet_client, MYSERIAL2, false);
#endif
SerialOutputT multiSerial(SERIAL_LEAF_1, SERIAL_LEAF_2);
#define __S_LEAF(N) ,SERIAL_LEAF_##N
#define _S_LEAF(N) __S_LEAF(N)
SerialOutputT multiSerial( SERIAL_LEAF_1 REPEAT_S(2, INCREMENT(NUM_SERIAL), _S_LEAF) );
#undef __S_LEAF
#undef _S_LEAF
#endif
void serialprintPGM(PGM_P str) {

207
Marlin/src/core/serial.h

@ -87,18 +87,17 @@ extern uint8_t marlin_debug_flags;
// If we have a catchall, use that directly
#ifdef SERIAL_CATCHALL
#define _SERIAL_LEAF_2 SERIAL_CATCHALL
#elif HAS_ETHERNET
typedef ConditionalSerial<decltype(MYSERIAL2)> SerialLeafT2; // We need to create an instance here
extern SerialLeafT2 msSerial2;
#define _SERIAL_LEAF_2 msSerial2
#else
#if HAS_ETHERNET
// We need to create an instance here
typedef ConditionalSerial<decltype(MYSERIAL2)> SerialLeafT2;
extern SerialLeafT2 msSerial2;
#define _SERIAL_LEAF_2 msSerial2
#else
// Don't create a useless instance here, directly use the existing instance
#define _SERIAL_LEAF_2 MYSERIAL2
#endif
#define _SERIAL_LEAF_2 MYSERIAL2 // Don't create a useless instance here, directly use the existing instance
#endif
// Nothing complicated here
#define _SERIAL_LEAF_3 MYSERIAL3
// Hook Meatpack if it's enabled on the second leaf
#if ENABLED(MEATPACK_ON_SERIAL_PORT_2)
typedef MeatpackSerial<decltype(_SERIAL_LEAF_2)> SerialLeafT2;
@ -108,7 +107,23 @@ extern uint8_t marlin_debug_flags;
#define SERIAL_LEAF_2 _SERIAL_LEAF_2
#endif
typedef MultiSerial<decltype(SERIAL_LEAF_1), decltype(SERIAL_LEAF_2), 0> SerialOutputT;
// Hook Meatpack if it's enabled on the third leaf
#if ENABLED(MEATPACK_ON_SERIAL_PORT_3)
typedef MeatpackSerial<decltype(_SERIAL_LEAF_3)> SerialLeafT3;
extern SerialLeafT3 mpSerial3;
#define SERIAL_LEAF_3 mpSerial3
#else
#define SERIAL_LEAF_3 _SERIAL_LEAF_3
#endif
#define __S_MULTI(N) decltype(SERIAL_LEAF_##N),
#define _S_MULTI(N) __S_MULTI(N)
typedef MultiSerial< REPEAT_1(NUM_SERIAL, _S_MULTI) 0> SerialOutputT;
#undef __S_MULTI
#undef _S_MULTI
extern SerialOutputT multiSerial;
#define SERIAL_IMPL multiSerial
#else
@ -167,139 +182,45 @@ inline void SERIAL_FLUSHTX() { SERIAL_IMPL.flushTX(); }
// Print a single PROGMEM string to serial
void serialprintPGM(PGM_P str);
// SERIAL_ECHOPAIR / SERIAL_ECHOPAIR_P is used to output a key value pair. The key must be a string and the value can be anything
// Print up to 12 pairs of values. Odd elements auto-wrapped in PSTR().
#define __SEP_N(N,V...) _SEP_##N(V)
#define _SEP_N(N,V...) __SEP_N(N,V)
#define _SEP_1(PRE) SERIAL_ECHOPGM(PRE)
#define _SEP_2(PRE,V) serial_echopair_PGM(PSTR(PRE),V)
#define _SEP_3(a,b,c) do{ _SEP_2(a,b); SERIAL_ECHOPGM(c); }while(0)
#define _SEP_4(a,b,V...) do{ _SEP_2(a,b); _SEP_2(V); }while(0)
#define _SEP_5(a,b,V...) do{ _SEP_2(a,b); _SEP_3(V); }while(0)
#define _SEP_6(a,b,V...) do{ _SEP_2(a,b); _SEP_4(V); }while(0)
#define _SEP_7(a,b,V...) do{ _SEP_2(a,b); _SEP_5(V); }while(0)
#define _SEP_8(a,b,V...) do{ _SEP_2(a,b); _SEP_6(V); }while(0)
#define _SEP_9(a,b,V...) do{ _SEP_2(a,b); _SEP_7(V); }while(0)
#define _SEP_10(a,b,V...) do{ _SEP_2(a,b); _SEP_8(V); }while(0)
#define _SEP_11(a,b,V...) do{ _SEP_2(a,b); _SEP_9(V); }while(0)
#define _SEP_12(a,b,V...) do{ _SEP_2(a,b); _SEP_10(V); }while(0)
#define _SEP_13(a,b,V...) do{ _SEP_2(a,b); _SEP_11(V); }while(0)
#define _SEP_14(a,b,V...) do{ _SEP_2(a,b); _SEP_12(V); }while(0)
#define _SEP_15(a,b,V...) do{ _SEP_2(a,b); _SEP_13(V); }while(0)
#define _SEP_16(a,b,V...) do{ _SEP_2(a,b); _SEP_14(V); }while(0)
#define _SEP_17(a,b,V...) do{ _SEP_2(a,b); _SEP_15(V); }while(0)
#define _SEP_18(a,b,V...) do{ _SEP_2(a,b); _SEP_16(V); }while(0)
#define _SEP_19(a,b,V...) do{ _SEP_2(a,b); _SEP_17(V); }while(0)
#define _SEP_20(a,b,V...) do{ _SEP_2(a,b); _SEP_18(V); }while(0)
#define _SEP_21(a,b,V...) do{ _SEP_2(a,b); _SEP_19(V); }while(0)
#define _SEP_22(a,b,V...) do{ _SEP_2(a,b); _SEP_20(V); }while(0)
#define _SEP_23(a,b,V...) do{ _SEP_2(a,b); _SEP_21(V); }while(0)
#define _SEP_24(a,b,V...) do{ _SEP_2(a,b); _SEP_22(V); }while(0)
#define SERIAL_ECHOPAIR(V...) _SEP_N(NUM_ARGS(V),V)
// Print up to 12 pairs of values. Odd elements must be PSTR pointers.
#define __SEP_N_P(N,V...) _SEP_##N##_P(V)
#define _SEP_N_P(N,V...) __SEP_N_P(N,V)
#define _SEP_1_P(PRE) serialprintPGM(PRE)
#define _SEP_2_P(PRE,V) serial_echopair_PGM(PRE,V)
#define _SEP_3_P(a,b,c) do{ _SEP_2_P(a,b); serialprintPGM(c); }while(0)
#define _SEP_4_P(a,b,V...) do{ _SEP_2_P(a,b); _SEP_2_P(V); }while(0)
#define _SEP_5_P(a,b,V...) do{ _SEP_2_P(a,b); _SEP_3_P(V); }while(0)
#define _SEP_6_P(a,b,V...) do{ _SEP_2_P(a,b); _SEP_4_P(V); }while(0)
#define _SEP_7_P(a,b,V...) do{ _SEP_2_P(a,b); _SEP_5_P(V); }while(0)
#define _SEP_8_P(a,b,V...) do{ _SEP_2_P(a,b); _SEP_6_P(V); }while(0)
#define _SEP_9_P(a,b,V...) do{ _SEP_2_P(a,b); _SEP_7_P(V); }while(0)
#define _SEP_10_P(a,b,V...) do{ _SEP_2_P(a,b); _SEP_8_P(V); }while(0)
#define _SEP_11_P(a,b,V...) do{ _SEP_2_P(a,b); _SEP_9_P(V); }while(0)
#define _SEP_12_P(a,b,V...) do{ _SEP_2_P(a,b); _SEP_10_P(V); }while(0)
#define _SEP_13_P(a,b,V...) do{ _SEP_2_P(a,b); _SEP_11_P(V); }while(0)
#define _SEP_14_P(a,b,V...) do{ _SEP_2_P(a,b); _SEP_12_P(V); }while(0)
#define _SEP_15_P(a,b,V...) do{ _SEP_2_P(a,b); _SEP_13_P(V); }while(0)
#define _SEP_16_P(a,b,V...) do{ _SEP_2_P(a,b); _SEP_14_P(V); }while(0)
#define _SEP_17_P(a,b,V...) do{ _SEP_2_P(a,b); _SEP_15_P(V); }while(0)
#define _SEP_18_P(a,b,V...) do{ _SEP_2_P(a,b); _SEP_16_P(V); }while(0)
#define _SEP_19_P(a,b,V...) do{ _SEP_2_P(a,b); _SEP_17_P(V); }while(0)
#define _SEP_20_P(a,b,V...) do{ _SEP_2_P(a,b); _SEP_18_P(V); }while(0)
#define _SEP_21_P(a,b,V...) do{ _SEP_2_P(a,b); _SEP_19_P(V); }while(0)
#define _SEP_22_P(a,b,V...) do{ _SEP_2_P(a,b); _SEP_20_P(V); }while(0)
#define _SEP_23_P(a,b,V...) do{ _SEP_2_P(a,b); _SEP_21_P(V); }while(0)
#define _SEP_24_P(a,b,V...) do{ _SEP_2_P(a,b); _SEP_22_P(V); }while(0)
// SERIAL_ECHOPAIR_P is used to output a key value pair. Unlike SERIAL_ECHOPAIR, the key must be a PGM string already and the value can be anything
#define SERIAL_ECHOPAIR_P(V...) _SEP_N_P(NUM_ARGS(V),V)
// Print up to 12 pairs of values followed by newline
#define __SELP_N(N,V...) _SELP_##N(V)
#define _SELP_N(N,V...) __SELP_N(N,V)
#define _SELP_1(PRE) SERIAL_ECHOLNPGM(PRE)
#define _SELP_2(PRE,V) do{ serial_echopair_PGM(PSTR(PRE),V); SERIAL_EOL(); }while(0)
#define _SELP_3(a,b,c) do{ _SEP_2(a,b); SERIAL_ECHOLNPGM(c); }while(0)
#define _SELP_4(a,b,V...) do{ _SEP_2(a,b); _SELP_2(V); }while(0)
#define _SELP_5(a,b,V...) do{ _SEP_2(a,b); _SELP_3(V); }while(0)
#define _SELP_6(a,b,V...) do{ _SEP_2(a,b); _SELP_4(V); }while(0)
#define _SELP_7(a,b,V...) do{ _SEP_2(a,b); _SELP_5(V); }while(0)
#define _SELP_8(a,b,V...) do{ _SEP_2(a,b); _SELP_6(V); }while(0)
#define _SELP_9(a,b,V...) do{ _SEP_2(a,b); _SELP_7(V); }while(0)
#define _SELP_10(a,b,V...) do{ _SEP_2(a,b); _SELP_8(V); }while(0)
#define _SELP_11(a,b,V...) do{ _SEP_2(a,b); _SELP_9(V); }while(0)
#define _SELP_12(a,b,V...) do{ _SEP_2(a,b); _SELP_10(V); }while(0)
#define _SELP_13(a,b,V...) do{ _SEP_2(a,b); _SELP_11(V); }while(0)
#define _SELP_14(a,b,V...) do{ _SEP_2(a,b); _SELP_12(V); }while(0)
#define _SELP_15(a,b,V...) do{ _SEP_2(a,b); _SELP_13(V); }while(0)
#define _SELP_16(a,b,V...) do{ _SEP_2(a,b); _SELP_14(V); }while(0)
#define _SELP_17(a,b,V...) do{ _SEP_2(a,b); _SELP_15(V); }while(0)
#define _SELP_18(a,b,V...) do{ _SEP_2(a,b); _SELP_16(V); }while(0)
#define _SELP_19(a,b,V...) do{ _SEP_2(a,b); _SELP_17(V); }while(0)
#define _SELP_20(a,b,V...) do{ _SEP_2(a,b); _SELP_18(V); }while(0)
#define _SELP_21(a,b,V...) do{ _SEP_2(a,b); _SELP_19(V); }while(0)
#define _SELP_22(a,b,V...) do{ _SEP_2(a,b); _SELP_20(V); }while(0)
#define _SELP_23(a,b,V...) do{ _SEP_2(a,b); _SELP_21(V); }while(0)
#define _SELP_24(a,b,V...) do{ _SEP_2(a,b); _SELP_22(V); }while(0)
#define _SELP_25(a,b,V...) do{ _SEP_2(a,b); _SELP_23(V); }while(0)
#define _SELP_26(a,b,V...) do{ _SEP_2(a,b); _SELP_24(V); }while(0)
#define _SELP_27(a,b,V...) do{ _SEP_2(a,b); _SELP_25(V); }while(0)
#define _SELP_28(a,b,V...) do{ _SEP_2(a,b); _SELP_26(V); }while(0)
#define _SELP_29(a,b,V...) do{ _SEP_2(a,b); _SELP_27(V); }while(0)
#define _SELP_30(a,b,V...) do{ _SEP_2(a,b); _SELP_28(V); }while(0) // Eat two args, pass the rest up
#define SERIAL_ECHOLNPAIR(V...) _SELP_N(NUM_ARGS(V),V)
// Print up to 12 pairs of values followed by newline
#define __SELP_N_P(N,V...) _SELP_##N##_P(V)
#define _SELP_N_P(N,V...) __SELP_N_P(N,V)
#define _SELP_1_P(PRE) serialprintPGM(PRE)
#define _SELP_2_P(PRE,V) do{ serial_echopair_PGM(PRE,V); SERIAL_EOL(); }while(0)
#define _SELP_3_P(a,b,c) do{ _SEP_2_P(a,b); serialprintPGM(c); }while(0)
#define _SELP_4_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_2_P(V); }while(0)
#define _SELP_5_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_3_P(V); }while(0)
#define _SELP_6_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_4_P(V); }while(0)
#define _SELP_7_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_5_P(V); }while(0)
#define _SELP_8_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_6_P(V); }while(0)
#define _SELP_9_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_7_P(V); }while(0)
#define _SELP_10_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_8_P(V); }while(0)
#define _SELP_11_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_9_P(V); }while(0)
#define _SELP_12_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_10_P(V); }while(0)
#define _SELP_13_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_11_P(V); }while(0)
#define _SELP_14_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_12_P(V); }while(0)
#define _SELP_15_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_13_P(V); }while(0)
#define _SELP_16_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_14_P(V); }while(0)
#define _SELP_17_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_15_P(V); }while(0)
#define _SELP_18_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_16_P(V); }while(0)
#define _SELP_19_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_17_P(V); }while(0)
#define _SELP_20_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_18_P(V); }while(0)
#define _SELP_21_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_19_P(V); }while(0)
#define _SELP_22_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_20_P(V); }while(0)
#define _SELP_23_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_21_P(V); }while(0)
#define _SELP_24_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_22_P(V); }while(0)
#define _SELP_25_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_23_P(V); }while(0)
#define _SELP_26_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_24_P(V); }while(0)
#define _SELP_27_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_25_P(V); }while(0)
#define _SELP_28_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_26_P(V); }while(0)
#define _SELP_29_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_27_P(V); }while(0)
#define _SELP_30_P(a,b,V...) do{ _SEP_2_P(a,b); _SELP_28_P(V); }while(0) // Eat two args, pass the rest up
#define SERIAL_ECHOLNPAIR_P(V...) _SELP_N_P(NUM_ARGS(V),V)
//
// SERIAL_ECHOPAIR... macros are used to output string-value pairs.
//
// Print up to 20 pairs of values. Odd elements must be literal strings.
#define __SEP_N(N,V...) _SEP_##N(V)
#define _SEP_N(N,V...) __SEP_N(N,V)
#define _SEP_N_REF() _SEP_N
#define _SEP_1(s) SERIAL_ECHOPGM(s);
#define _SEP_2(s,v) serial_echopair_PGM(PSTR(s),v);
#define _SEP_3(s,v,V...) _SEP_2(s,v); DEFER2(_SEP_N_REF)()(TWO_ARGS(V),V);
#define SERIAL_ECHOPAIR(V...) do{ EVAL(_SEP_N(TWO_ARGS(V),V)); }while(0)
// Print up to 20 pairs of values followed by newline. Odd elements must be literal strings.
#define __SELP_N(N,V...) _SELP_##N(V)
#define _SELP_N(N,V...) __SELP_N(N,V)
#define _SELP_N_REF() _SELP_N
#define _SELP_1(s) SERIAL_ECHOLNPGM(s);
#define _SELP_2(s,v) serial_echopair_PGM(PSTR(s),v); SERIAL_EOL();
#define _SELP_3(s,v,V...) _SEP_2(s,v); DEFER2(_SELP_N_REF)()(TWO_ARGS(V),V);
#define SERIAL_ECHOLNPAIR(V...) do{ EVAL(_SELP_N(TWO_ARGS(V),V)); }while(0)
// Print up to 20 pairs of values. Odd elements must be PSTR pointers.
#define __SEP_N_P(N,V...) _SEP_##N##_P(V)
#define _SEP_N_P(N,V...) __SEP_N_P(N,V)
#define _SEP_N_P_REF() _SEP_N_P
#define _SEP_1_P(s) serialprintPGM(s);
#define _SEP_2_P(s,v) serial_echopair_PGM(s,v);
#define _SEP_3_P(s,v,V...) _SEP_2_P(s,v); DEFER2(_SEP_N_P_REF)()(TWO_ARGS(V),V);
#define SERIAL_ECHOPAIR_P(V...) do{ EVAL(_SEP_N_P(TWO_ARGS(V),V)); }while(0)
// Print up to 20 pairs of values followed by newline. Odd elements must be PSTR pointers.
#define __SELP_N_P(N,V...) _SELP_##N##_P(V)
#define _SELP_N_P(N,V...) __SELP_N_P(N,V)
#define _SELP_N_P_REF() _SELP_N_P
#define _SELP_1_P(s) { serialprintPGM(s); SERIAL_EOL(); }
#define _SELP_2_P(s,v) { serial_echopair_PGM(s,v); SERIAL_EOL(); }
#define _SELP_3_P(s,v,V...) { _SEP_2_P(s,v); DEFER2(_SELP_N_P_REF)()(TWO_ARGS(V),V); }
#define SERIAL_ECHOLNPAIR_P(V...) do{ EVAL(_SELP_N_P(TWO_ARGS(V),V)); }while(0)
#ifdef AllowDifferentTypeInList

109
Marlin/src/core/serial_hook.h

@ -196,54 +196,71 @@ struct RuntimeSerial : public SerialBase< RuntimeSerial<SerialT> >, public Seria
RuntimeSerial(const bool e, Args... args) : BaseClassT(e), SerialT(args...), writeHook(0), eofHook(0), userPointer(0) {}
};
// A class that duplicates its output conditionally to 2 serial interfaces
template <class Serial0T, class Serial1T, const uint8_t offset = 0, const uint8_t step = 1>
struct MultiSerial : public SerialBase< MultiSerial<Serial0T, Serial1T, offset, step> > {
typedef SerialBase< MultiSerial<Serial0T, Serial1T, offset, step> > BaseClassT;
#define _S_CLASS(N) class Serial##N##T,
#define _S_NAME(N) Serial##N##T,
template < REPEAT(NUM_SERIAL, _S_CLASS) const uint8_t offset=0, const uint8_t step=1 >
struct MultiSerial : public SerialBase< MultiSerial< REPEAT(NUM_SERIAL, _S_NAME) offset, step > > {
typedef SerialBase< MultiSerial< REPEAT(NUM_SERIAL, _S_NAME) offset, step > > BaseClassT;
#undef _S_CLASS
#undef _S_NAME
SerialMask portMask;
Serial0T & serial0;
Serial1T & serial1;
static constexpr uint8_t Usage = ((1 << step) - 1); // A bit mask containing as many bits as step
static constexpr uint8_t FirstOutput = (Usage << offset);
static constexpr uint8_t SecondOutput = (Usage << (offset + step));
static constexpr uint8_t Both = FirstOutput | SecondOutput;
#define _S_DECLARE(N) Serial##N##T & serial##N;
REPEAT(NUM_SERIAL, _S_DECLARE);
#undef _S_DECLARE
static constexpr uint8_t Usage = _BV(step) - 1; // A bit mask containing 'step' bits
#define _OUT_PORT(N) (Usage << (offset + (step * N))),
static constexpr uint8_t output[] = { REPEAT(NUM_SERIAL, _OUT_PORT) };
#undef _OUT_PORT
#define _OUT_MASK(N) | output[N]
static constexpr uint8_t ALL = 0 REPEAT(NUM_SERIAL, _OUT_MASK);
#undef _OUT_MASK
NO_INLINE void write(uint8_t c) {
if (portMask.enabled(FirstOutput)) serial0.write(c);
if (portMask.enabled(SecondOutput)) mks_wifi_out_add((uint8_t *)&c,1);
#define _S_WRITE(N) if(N != 1){if (portMask.enabled(output[N])) serial##N.write(c);}else{mks_wifi_out_add((uint8_t *)&c,1);};
REPEAT(NUM_SERIAL, _S_WRITE);
#undef _S_WRITE
}
NO_INLINE void msgDone() {
if (portMask.enabled(FirstOutput)) serial0.msgDone();
if (portMask.enabled(SecondOutput)) serial1.msgDone();
#define _S_DONE(N) if (portMask.enabled(output[N])) serial##N.msgDone();
REPEAT(NUM_SERIAL, _S_DONE);
#undef _S_DONE
}
int available(serial_index_t index) {
if (index.within(0 + offset, step + offset - 1))
return serial0.available(index);
else if (index.within(step + offset, 2 * step + offset - 1))
return serial1.available(index);
uint8_t pos = offset;
#define _S_AVAILABLE(N) if (index.within(pos, pos + step - 1)) return serial##N.available(index); else pos += step;
REPEAT(NUM_SERIAL, _S_AVAILABLE);
#undef _S_AVAILABLE
return false;
}
int read(serial_index_t index) {
if (index.within(0 + offset, step + offset - 1))
return serial0.read(index);
else if (index.within(step + offset, 2 * step + offset - 1))
return serial1.read(index);
uint8_t pos = offset;
#define _S_READ(N) if (index.within(pos, pos + step - 1)) return serial##N.read(index); else pos += step;
REPEAT(NUM_SERIAL, _S_READ);
#undef _S_READ
return -1;
}
void begin(const long br) {
if (portMask.enabled(FirstOutput)) serial0.begin(br);
if (portMask.enabled(SecondOutput)) serial1.begin(br);
#define _S_BEGIN(N) if (portMask.enabled(output[N])) serial##N.begin(br);
REPEAT(NUM_SERIAL, _S_BEGIN);
#undef _S_BEGIN
}
void end() {
if (portMask.enabled(FirstOutput)) serial0.end();
if (portMask.enabled(SecondOutput)) serial1.end();
#define _S_END(N) if (portMask.enabled(output[N])) serial##N.end();
REPEAT(NUM_SERIAL, _S_END);
#undef _S_END
}
bool connected() {
bool ret = true;
if (portMask.enabled(FirstOutput)) ret = CALL_IF_EXISTS(bool, &serial0, connected);
if (portMask.enabled(SecondOutput)) ret = ret && CALL_IF_EXISTS(bool, &serial1, connected);
#define _S_CONNECTED(N) if (portMask.enabled(output[N]) && !CALL_IF_EXISTS(bool, &serial##N, connected)) ret = false;
REPEAT(NUM_SERIAL, _S_CONNECTED);
#undef _S_CONNECTED
return ret;
}
@ -251,27 +268,32 @@ struct MultiSerial : public SerialBase< MultiSerial<Serial0T, Serial1T, offset,
using BaseClassT::read;
// Redirect flush
NO_INLINE void flush() {
if (portMask.enabled(FirstOutput)) serial0.flush();
if (portMask.enabled(SecondOutput)) serial1.flush();
NO_INLINE void flush() {
#define _S_FLUSH(N) if (portMask.enabled(output[N])) serial##N.flush();
REPEAT(NUM_SERIAL, _S_FLUSH);
#undef _S_FLUSH
}
NO_INLINE void flushTX() {
if (portMask.enabled(FirstOutput)) CALL_IF_EXISTS(void, &serial0, flushTX);
if (portMask.enabled(SecondOutput)) CALL_IF_EXISTS(void, &serial1, flushTX);
NO_INLINE void flushTX() {
#define _S_FLUSHTX(N) if (portMask.enabled(output[N])) CALL_IF_EXISTS(void, &serial0, flushTX);
REPEAT(NUM_SERIAL, _S_FLUSHTX);
#undef _S_FLUSHTX
}
// Forward feature queries
SerialFeature features(serial_index_t index) const {
if (index.within(0 + offset, step + offset - 1))
return serial0.features(index);
else if (index.within(step + offset, 2 * step + offset - 1))
return serial1.features(index);
SerialFeature features(serial_index_t index) const {
uint8_t pos = offset;
#define _S_FEATURES(N) if (index.within(pos, pos + step - 1)) return serial##N.features(index); else pos += step;
REPEAT(NUM_SERIAL, _S_FEATURES);
#undef _S_FEATURES
return SerialFeature::None;
}
MultiSerial(Serial0T & serial0, Serial1T & serial1, const SerialMask mask = Both, const bool e = false) :
BaseClassT(e),
portMask(mask), serial0(serial0), serial1(serial1) {}
#define _S_REFS(N) Serial##N##T & serial##N,
#define _S_INIT(N) ,serial##N (serial##N)
MultiSerial(REPEAT(NUM_SERIAL, _S_REFS) const SerialMask mask = ALL, const bool e = false)
: BaseClassT(e), portMask(mask) REPEAT(NUM_SERIAL, _S_INIT) {}
};
// Build the actual serial object depending on current configuration
@ -279,4 +301,7 @@ struct MultiSerial : public SerialBase< MultiSerial<Serial0T, Serial1T, offset,
#define ForwardSerial1Class TERN(SERIAL_RUNTIME_HOOK, RuntimeSerial, ForwardSerial)
#ifdef HAS_MULTI_SERIAL
#define Serial2Class ConditionalSerial
#if NUM_SERIAL >= 3
#define Serial3Class ConditionalSerial
#endif
#endif

45
Marlin/src/feature/bedlevel/ubl/ubl.cpp

@ -35,6 +35,7 @@ unified_bed_leveling ubl;
#include "../../../module/planner.h"
#include "../../../module/motion.h"
#include "../../../module/probe.h"
#include "../../../module/temperature.h"
#if ENABLED(EXTENSIBLE_UI)
#include "../../../lcd/extui/ui_api.h"
@ -254,4 +255,48 @@ bool unified_bed_leveling::sanity_check() {
return !!error_flag;
}
#if ENABLED(UBL_MESH_WIZARD)
/**
* M1004: UBL Mesh Wizard - One-click mesh creation with or without a probe
*/
void GcodeSuite::M1004() {
#define ALIGN_GCODE TERN(Z_STEPPER_AUTO_ALIGN, "G34", "")
#define PROBE_GCODE TERN(HAS_BED_PROBE, "G29P1\nG29P3", "G29P4R255")
#if HAS_HOTEND
if (parser.seenval('H')) { // Handle H# parameter to set Hotend temp
const celsius_t hotend_temp = parser.value_int(); // Marlin never sends itself F or K, always C
thermalManager.setTargetHotend(hotend_temp, 0);
thermalManager.wait_for_hotend(false);
}
#endif
#if HAS_HEATED_BED
if (parser.seenval('B')) { // Handle B# parameter to set Bed temp
const celsius_t bed_temp = parser.value_int(); // Marlin never sends itself F or K, always C
thermalManager.setTargetBed(bed_temp);
thermalManager.wait_for_bed(false);
}
#endif
process_subcommands_now_P(G28_STR); // Home
process_subcommands_now_P(PSTR(ALIGN_GCODE "\n" // Align multi z axis if available
PROBE_GCODE "\n" // Build mesh with available hardware
"G29P3\nG29P3")); // Ensure mesh is complete by running smart fill twice
if (parser.seenval('S')) {
char umw_gcode[32];
sprintf_P(umw_gcode, PSTR("G29S%i"), parser.value_int());
queue.inject(umw_gcode);
}
process_subcommands_now_P(PSTR("G29A\nG29F10\n" // Set UBL Active & Fade 10
"M140S0\nM104S0\n" // Turn off heaters
"M500")); // Store settings
}
#endif // UBL_MESH_WIZARD
#endif // AUTO_BED_LEVELING_UBL

2
Marlin/src/feature/bedlevel/ubl/ubl.h

@ -32,7 +32,7 @@
#define UBL_OK false
#define UBL_ERR true
enum MeshPointType : char { INVALID, REAL, SET_IN_BITMAP };
enum MeshPointType : char { INVALID, REAL, SET_IN_BITMAP, CLOSEST };
// External references

44
Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp

@ -306,7 +306,7 @@ void unified_bed_leveling::G29() {
if (G29_parse_parameters()) return; // Abort on parameter error
const int8_t p_val = parser.intval('P', -1);
const bool may_move = p_val == 1 || p_val == 2 || p_val == 4 || parser.seen('J');
const bool may_move = p_val == 1 || p_val == 2 || p_val == 4 || parser.seen_test('J');
#if ENABLED(HAS_MULTI_HOTEND)
const uint8_t old_tool_index = active_extruder;
#endif
@ -315,7 +315,7 @@ void unified_bed_leveling::G29() {
if (may_move) {
planner.synchronize();
// Send 'N' to force homing before G29 (internal only)
if (axes_should_home() || parser.seen('N')) gcode.home_all_axes();
if (axes_should_home() || parser.seen_test('N')) gcode.home_all_axes();
TERN_(HAS_MULTI_HOTEND, if (active_extruder) tool_change(0));
}
@ -380,7 +380,7 @@ void unified_bed_leveling::G29() {
// Allow the user to specify the height because 10mm is a little extreme in some cases.
for (uint8_t x = (GRID_MAX_POINTS_X) / 3; x < 2 * (GRID_MAX_POINTS_X) / 3; x++) // Create a rectangular raised area in
for (uint8_t y = (GRID_MAX_POINTS_Y) / 3; y < 2 * (GRID_MAX_POINTS_Y) / 3; y++) { // the center of the bed
z_values[x][y] += parser.seen('C') ? param.C_constant : 9.99f;
z_values[x][y] += parser.seen_test('C') ? param.C_constant : 9.99f;
TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(x, y, z_values[x][y]));
}
break;
@ -389,7 +389,7 @@ void unified_bed_leveling::G29() {
#if HAS_BED_PROBE
if (parser.seen('J')) {
if (parser.seen_test('J')) {
save_ubl_active_state_and_disable();
tilt_mesh_based_on_probed_grid(param.J_grid_size == 0); // Zero size does 3-Point
restore_ubl_active_state_and_leave();
@ -402,7 +402,7 @@ void unified_bed_leveling::G29() {
#endif // HAS_BED_PROBE
if (parser.seen('P')) {
if (parser.seen_test('P')) {
if (WITHIN(param.P_phase, 0, 1) && storage_slot == -1) {
storage_slot = 0;
SERIAL_ECHOLNPGM("Default storage slot 0 selected.");
@ -423,7 +423,7 @@ void unified_bed_leveling::G29() {
//
// Invalidate Entire Mesh and Automatically Probe Mesh in areas that can be reached by the probe
//
if (!parser.seen('C')) {
if (!parser.seen_test('C')) {
invalidate();
SERIAL_ECHOLNPGM("Mesh invalidated. Probing mesh.");
}
@ -433,7 +433,7 @@ void unified_bed_leveling::G29() {
SERIAL_DECIMAL(param.XY_pos.y);
SERIAL_ECHOLNPGM(").\n");
}
probe_entire_mesh(param.XY_pos, parser.seen('T'), parser.seen('E'), parser.seen('U'));
probe_entire_mesh(param.XY_pos, parser.seen_test('T'), parser.seen_test('E'), parser.seen_test('U'));
report_current_position();
probe_deployed = true;
@ -449,7 +449,7 @@ void unified_bed_leveling::G29() {
SERIAL_ECHOLNPGM("Manually probing unreachable points.");
do_z_clearance(Z_CLEARANCE_BETWEEN_PROBES);
if (parser.seen('C') && !param.XY_seen) {
if (parser.seen_test('C') && !param.XY_seen) {
/**
* Use a good default location for the path.
@ -483,7 +483,7 @@ void unified_bed_leveling::G29() {
}
const float height = parser.floatval('H', Z_CLEARANCE_BETWEEN_PROBES);
manually_probe_remaining_mesh(param.XY_pos, height, param.B_shim_thickness, parser.seen('T'));
manually_probe_remaining_mesh(param.XY_pos, height, param.B_shim_thickness, parser.seen_test('T'));
SERIAL_ECHOLNPGM("G29 P2 finished.");
@ -555,7 +555,7 @@ void unified_bed_leveling::G29() {
case 4: // Fine Tune (i.e., Edit) the Mesh
#if HAS_LCD_MENU
fine_tune_mesh(param.XY_pos, parser.seen('T'));
fine_tune_mesh(param.XY_pos, parser.seen_test('T'));
#else
SERIAL_ECHOLNPGM("?P4 is only available when an LCD is present.");
return;
@ -574,14 +574,14 @@ void unified_bed_leveling::G29() {
// Much of the 'What?' command can be eliminated. But until we are fully debugged, it is
// good to have the extra information. Soon... we prune this to just a few items
//
if (parser.seen('W')) g29_what_command();
if (parser.seen_test('W')) g29_what_command();
//
// When we are fully debugged, this may go away. But there are some valid
// use cases for the users. So we can wait and see what to do with it.
//
if (parser.seen('K')) // Kompare Current Mesh Data to Specified Stored Mesh
if (parser.seen_test('K')) // Kompare Current Mesh Data to Specified Stored Mesh
g29_compare_current_mesh_to_stored_mesh();
#endif // UBL_DEVEL_DEBUGGING
@ -640,7 +640,7 @@ void unified_bed_leveling::G29() {
SERIAL_ECHOLNPGM("Done.");
}
if (parser.seen('T'))
if (parser.seen_test('T'))
display_map(param.T_map_type);
LEAVE:
@ -915,7 +915,7 @@ void set_message_with_feedback(PGM_P const msg_P) {
if (do_ubl_mesh_map) display_map(param.T_map_type); // Show user where we're probing
if (parser.seen('B')) {
if (parser.seen_test('B')) {
SERIAL_ECHOPGM_P(GET_TEXT(MSG_UBL_BC_INSERT));
LCD_MESSAGEPGM(MSG_UBL_BC_INSERT);
}
@ -954,7 +954,7 @@ void set_message_with_feedback(PGM_P const msg_P) {
* NOTE: Blocks the G-code queue and captures Marlin UI during use.
*/
void unified_bed_leveling::fine_tune_mesh(const xy_pos_t &pos, const bool do_ubl_mesh_map) {
if (!parser.seen('R')) // fine_tune_mesh() is special. If no repetition count flag is specified
if (!parser.seen_test('R')) // fine_tune_mesh() is special. If no repetition count flag is specified
param.R_repetition = 1; // do exactly one mesh location. Otherwise use what the parser decided.
#if ENABLED(UBL_MESH_EDIT_MOVES_Z)
@ -1091,7 +1091,7 @@ bool unified_bed_leveling::G29_parse_parameters() {
}
}
param.V_verbosity = parser.seen('V') ? parser.value_int() : 0;
param.V_verbosity = parser.intval('V');
if (!WITHIN(param.V_verbosity, 0, 4)) {
SERIAL_ECHOLNPGM("?(V)erbose level implausible (0-4).\n");
err_flag = true;
@ -1153,15 +1153,15 @@ bool unified_bed_leveling::G29_parse_parameters() {
* Leveling is being enabled here with old data, possibly
* none. Error handling should disable for safety...
*/
if (parser.seen('A')) {
if (parser.seen('D')) {
if (parser.seen_test('A')) {
if (parser.seen_test('D')) {
SERIAL_ECHOLNPGM("?Can't activate and deactivate at the same time.\n");
return UBL_ERR;
}
set_bed_leveling_enabled(true);
report_state();
}
else if (parser.seen('D')) {
else if (parser.seen_test('D')) {
set_bed_leveling_enabled(false);
report_state();
}
@ -1282,7 +1282,7 @@ mesh_index_pair unified_bed_leveling::find_furthest_invalid_mesh_point() {
static bool test_func(uint8_t i, uint8_t j, void *data) {
find_closest_t *d = (find_closest_t*)data;
if ( (d->type == (isnan(ubl.z_values[i][j]) ? INVALID : REAL))
if ( d->type == CLOSEST || d->type == (isnan(ubl.z_values[i][j]) ? INVALID : REAL)
|| (d->type == SET_IN_BITMAP && !d->done_flags->marked(i, j))
) {
// Found a Mesh Point of the specified type!
@ -1326,7 +1326,7 @@ mesh_index_pair unified_bed_leveling::find_closest_mesh_point_of_type(const Mesh
float best_so_far = 99999.99f;
GRID_LOOP(i, j) {
if ( (type == (isnan(z_values[i][j]) ? INVALID : REAL))
if ( type == CLOSEST || type == (isnan(z_values[i][j]) ? INVALID : REAL)
|| (type == SET_IN_BITMAP && !done_flags->marked(i, j))
) {
// Found a Mesh Point of the specified type!
@ -1520,7 +1520,7 @@ void unified_bed_leveling::smart_fill_mesh() {
SERIAL_ECHOLNPAIR("Tilting mesh point ", point_num, "/", total_points, "\n");
TERN_(HAS_STATUS_MESSAGE, ui.status_printf_P(0, PSTR(S_FMT " %i/%i"), GET_TEXT(MSG_LCD_TILTING_MESH), point_num, total_points));
measured_z = probe.probe_at_point(rpos, parser.seen('E') ? PROBE_PT_STOW : PROBE_PT_RAISE, param.V_verbosity); // TODO: Needs error handling
measured_z = probe.probe_at_point(rpos, parser.seen_test('E') ? PROBE_PT_STOW : PROBE_PT_RAISE, param.V_verbosity); // TODO: Needs error handling
abort_flag = isnan(measured_z);

20
Marlin/src/feature/caselight.cpp

@ -28,10 +28,6 @@
CaseLight caselight;
#if CASE_LIGHT_IS_COLOR_LED
#include "leds/leds.h"
#endif
#if CASELIGHT_USES_BRIGHTNESS && !defined(CASE_LIGHT_DEFAULT_BRIGHTNESS)
#define CASE_LIGHT_DEFAULT_BRIGHTNESS 0 // For use on PWM pin as non-PWM just sets a default
#endif
@ -43,13 +39,9 @@ CaseLight caselight;
bool CaseLight::on = CASE_LIGHT_DEFAULT_ON;
#if CASE_LIGHT_IS_COLOR_LED
LEDColor CaseLight::color =
#ifdef CASE_LIGHT_DEFAULT_COLOR
CASE_LIGHT_DEFAULT_COLOR
#else
{ 255, 255, 255, 255 }
#endif
;
#include "leds/leds.h"
constexpr uint8_t init_case_light[] = CASE_LIGHT_DEFAULT_COLOR;
LEDColor CaseLight::color = { init_case_light[0], init_case_light[1], init_case_light[2], TERN_(HAS_WHITE_LED, init_case_light[3]) };
#endif
#ifndef INVERT_CASE_LIGHT
@ -73,14 +65,12 @@ void CaseLight::update(const bool sflag) {
brightness = brightness_sav; // Restore last brightness for M355 S1
const uint8_t i = on ? brightness : 0, n10ct = INVERT_CASE_LIGHT ? 255 - i : i;
UNUSED(n10ct);
#endif
#if CASE_LIGHT_IS_COLOR_LED
leds.set_color(
MakeLEDColor(color.r, color.g, color.b, color.w, n10ct),
false
);
leds.set_color(MakeLEDColor(color.r, color.g, color.b, color.w, n10ct));
#else // !CASE_LIGHT_IS_COLOR_LED

2
Marlin/src/feature/caselight.h

@ -27,7 +27,7 @@
#include "leds/leds.h" // for LEDColor
#endif
#if DISABLED(CASE_LIGHT_NO_BRIGHTNESS) || ENABLED(CASE_LIGHT_USE_NEOPIXEL)
#if NONE(CASE_LIGHT_NO_BRIGHTNESS, CASE_LIGHT_IS_COLOR_LED) || ENABLED(CASE_LIGHT_USE_NEOPIXEL)
#define CASELIGHT_USES_BRIGHTNESS 1
#endif

2
Marlin/src/feature/dac/dac_mcp4728.cpp

@ -66,7 +66,7 @@ uint8_t MCP4728::analogWrite(const uint8_t channel, const uint16_t value) {
}
/**
* Write all input resistor values to EEPROM using SequencialWrite method.
* Write all input resistor values to EEPROM using SequentialWrite method.
* This will update both input register and EEPROM value
* This will also write current Vref, PowerDown, Gain settings to EEPROM
*/

14
Marlin/src/feature/encoder_i2c.cpp

@ -819,11 +819,11 @@ int8_t I2CPositionEncodersMgr::parse() {
void I2CPositionEncodersMgr::M860() {
if (parse()) return;
const bool hasU = parser.seen('U'), hasO = parser.seen('O');
const bool hasU = parser.seen_test('U'), hasO = parser.seen_test('O');
if (I2CPE_idx == 0xFF) {
LOOP_XYZE(i) {
if (!I2CPE_anyaxis || parser.seen(axis_codes[i])) {
if (!I2CPE_anyaxis || parser.seen_test(axis_codes[i])) {
const uint8_t idx = idx_from_axis(AxisEnum(i));
if ((int8_t)idx >= 0) report_position(idx, hasU, hasO);
}
@ -956,10 +956,10 @@ void I2CPositionEncodersMgr::M864() {
return;
}
else {
if (parser.seen('X')) newAddress = I2CPE_PRESET_ADDR_X;
else if (parser.seen('Y')) newAddress = I2CPE_PRESET_ADDR_Y;
else if (parser.seen('Z')) newAddress = I2CPE_PRESET_ADDR_Z;
else if (parser.seen('E')) newAddress = I2CPE_PRESET_ADDR_E;
if (parser.seen_test('X')) newAddress = I2CPE_PRESET_ADDR_X;
else if (parser.seen_test('Y')) newAddress = I2CPE_PRESET_ADDR_Y;
else if (parser.seen_test('Z')) newAddress = I2CPE_PRESET_ADDR_Z;
else if (parser.seen_test('E')) newAddress = I2CPE_PRESET_ADDR_E;
else return;
}
@ -1012,7 +1012,7 @@ void I2CPositionEncodersMgr::M865() {
void I2CPositionEncodersMgr::M866() {
if (parse()) return;
const bool hasR = parser.seen('R');
const bool hasR = parser.seen_test('R');
if (I2CPE_idx == 0xFF) {
LOOP_XYZE(i) {

14
Marlin/src/feature/fwretract.cpp

@ -212,10 +212,10 @@ void FWRetract::retract(const bool retracting
*/
void FWRetract::M207() {
if (!parser.seen("FSWZ")) return M207_report();
if (parser.seen('S')) settings.retract_length = parser.value_axis_units(E_AXIS);
if (parser.seen('F')) settings.retract_feedrate_mm_s = MMM_TO_MMS(parser.value_axis_units(E_AXIS));
if (parser.seen('Z')) settings.retract_zraise = parser.value_linear_units();
if (parser.seen('W')) settings.swap_retract_length = parser.value_axis_units(E_AXIS);
if (parser.seenval('S')) settings.retract_length = parser.value_axis_units(E_AXIS);
if (parser.seenval('F')) settings.retract_feedrate_mm_s = MMM_TO_MMS(parser.value_axis_units(E_AXIS));
if (parser.seenval('Z')) settings.retract_zraise = parser.value_linear_units();
if (parser.seenval('W')) settings.swap_retract_length = parser.value_axis_units(E_AXIS);
}
void FWRetract::M207_report(const bool forReplay/*=false*/) {
@ -238,10 +238,10 @@ void FWRetract::M207_report(const bool forReplay/*=false*/) {
*/
void FWRetract::M208() {
if (!parser.seen("FSRW")) return M208_report();
if (parser.seen('S')) settings.retract_recover_extra = parser.value_axis_units(E_AXIS);
if (parser.seen('F')) settings.retract_recover_feedrate_mm_s = MMM_TO_MMS(parser.value_axis_units(E_AXIS));
if (parser.seen('S')) settings.retract_recover_extra = parser.value_axis_units(E_AXIS);
if (parser.seen('F')) settings.retract_recover_feedrate_mm_s = MMM_TO_MMS(parser.value_axis_units(E_AXIS));
if (parser.seen('R')) settings.swap_retract_recover_feedrate_mm_s = MMM_TO_MMS(parser.value_axis_units(E_AXIS));
if (parser.seen('W')) settings.swap_retract_recover_extra = parser.value_axis_units(E_AXIS);
if (parser.seen('W')) settings.swap_retract_recover_extra = parser.value_axis_units(E_AXIS);
}
void FWRetract::M208_report(const bool forReplay/*=false*/) {

7
Marlin/src/feature/joystick.cpp

@ -164,12 +164,7 @@ Joystick joystick;
xyz_float_t move_dist{0};
float hypot2 = 0;
LOOP_XYZ(i) if (norm_jog[i]) {
move_dist[i] = seg_time * norm_jog[i] *
#if ENABLED(EXTENSIBLE_UI)
manual_feedrate_mm_s[i];
#else
planner.settings.max_feedrate_mm_s[i];
#endif
move_dist[i] = seg_time * norm_jog[i] * TERN(EXTENSIBLE_UI, manual_feedrate_mm_s, planner.settings.max_feedrate_mm_s)[i];
hypot2 += sq(move_dist[i]);
}

2
Marlin/src/feature/leds/leds.cpp

@ -53,7 +53,7 @@
);
#endif
#if EITHER(LED_CONTROL_MENU, PRINTER_EVENT_LEDS)
#if ANY(LED_CONTROL_MENU, PRINTER_EVENT_LEDS, CASE_LIGHT_IS_COLOR_LED)
LEDColor LEDLights::color;
bool LEDLights::lights_on;
#endif

2
Marlin/src/feature/leds/leds.h

@ -187,7 +187,7 @@ public:
static inline LEDColor get_color() { return lights_on ? color : LEDColorOff(); }
#endif
#if EITHER(LED_CONTROL_MENU, PRINTER_EVENT_LEDS)
#if ANY(LED_CONTROL_MENU, PRINTER_EVENT_LEDS, CASE_LIGHT_IS_COLOR_LED)
static LEDColor color; // last non-off color
static bool lights_on; // the last set color was "on"
#endif

2
Marlin/src/feature/mmu/mmu2.cpp

@ -159,7 +159,7 @@ void MMU2::mmu_loop() {
MMU2_COMMAND("S1"); // Read Version
state = -2;
}
else if (millis() > 3000000) {
else if (millis() > 30000) { // 30sec after reset disable MMU
SERIAL_ECHOLNPGM("MMU not responding - DISABLED");
state = 0;
}

19
Marlin/src/feature/pause.cpp

@ -406,6 +406,15 @@ bool pause_print(const_float_t retract, const xyz_pos_t &park_point, const bool
// Save current position
resume_position = current_position;
// Will the nozzle be parking?
const bool do_park = !axes_should_home();
#if ENABLED(POWER_LOSS_RECOVERY)
// Save PLR info in case the power goes out while parked
const float park_raise = do_park ? nozzle.park_mode_0_height(park_point.z) - current_position.z : POWER_LOSS_ZRAISE;
if (was_sd_printing && recovery.enabled) recovery.save(true, park_raise, do_park);
#endif
// Wait for buffered blocks to complete
planner.synchronize();
@ -419,9 +428,8 @@ bool pause_print(const_float_t retract, const xyz_pos_t &park_point, const bool
unscaled_e_move(retract, PAUSE_PARK_RETRACT_FEEDRATE);
}
// Park the nozzle by doing a Minimum Z Raise followed by an XY Move
if (!axes_should_home())
nozzle.park(0, park_point);
// If axes don't need to home then the nozzle can park
if (do_park) nozzle.park(0, park_point); // Park the nozzle by doing a Minimum Z Raise followed by an XY Move
#if ENABLED(DUAL_X_CARRIAGE)
const int8_t saved_ext = active_extruder;
@ -429,7 +437,8 @@ bool pause_print(const_float_t retract, const xyz_pos_t &park_point, const bool
set_duplication_enabled(false, DXC_ext);
#endif
if (unload_length) // Unload the filament
// Unload the filament, if specified
if (unload_length)
unload_filament(unload_length, show_lcd, PAUSE_MODE_CHANGE_FILAMENT);
#if ENABLED(DUAL_X_CARRIAGE)
@ -649,7 +658,7 @@ void resume_print(const_float_t slow_load_length/*=0*/, const_float_t fast_load_
#if ENABLED(SDSUPPORT)
if (did_pause_print) {
--did_pause_print;
card.startFileprint();
card.startOrResumeFilePrinting();
// Write PLR now to update the z axis value
TERN_(POWER_LOSS_RECOVERY, if (recovery.enabled) recovery.save(true));
}

202
Marlin/src/feature/powerloss.cpp

@ -66,9 +66,6 @@ PrintJobRecovery recovery;
#ifndef POWER_LOSS_PURGE_LEN
#define POWER_LOSS_PURGE_LEN 0
#endif
#ifndef POWER_LOSS_ZRAISE
#define POWER_LOSS_ZRAISE 2 // Move on loss with backup power, or on resume without it
#endif
#if DISABLED(BACKUP_POWER_SUPPLY)
#undef POWER_LOSS_RETRACT_LEN // No retract at outage without backup power
@ -140,14 +137,14 @@ void PrintJobRecovery::load() {
* Set info fields that won't change
*/
void PrintJobRecovery::prepare() {
card.getAbsFilename(info.sd_filename); // SD filename
card.getAbsFilenameInCWD(info.sd_filename); // SD filename
cmd_sdpos = 0;
}
/**
* Save the current machine state to the power-loss recovery file
*/
void PrintJobRecovery::save(const bool force/*=false*/, const float zraise/*=0*/) {
void PrintJobRecovery::save(const bool force/*=false*/, const float zraise/*=POWER_LOSS_ZRAISE*/, const bool raised/*=false*/) {
// We don't check IS_SD_PRINTING here so a save may occur during a pause
@ -184,14 +181,12 @@ void PrintJobRecovery::save(const bool force/*=false*/, const float zraise/*=0*/
info.current_position = current_position;
info.feedrate = uint16_t(MMS_TO_MMM(feedrate_mm_s));
info.zraise = zraise;
info.flag.raised = raised; // Was Z raised before power-off?
TERN_(GCODE_REPEAT_MARKERS, info.stored_repeat = repeat);
TERN_(HAS_HOME_OFFSET, info.home_offset = home_offset);
TERN_(HAS_POSITION_SHIFT, info.position_shift = position_shift);
#if HAS_MULTI_EXTRUDER
info.active_extruder = active_extruder;
#endif
TERN_(HAS_MULTI_EXTRUDER, info.active_extruder = active_extruder);
#if DISABLED(NO_VOLUMETRICS)
info.flag.volumetric_enabled = parser.volumetric_enabled;
@ -256,7 +251,7 @@ void PrintJobRecovery::save(const bool force/*=false*/, const float zraise/*=0*/
// Raise the Z axis now
if (zraise) {
char cmd[20], str_1[16];
sprintf_P(cmd, PSTR("G0 Z%s"), dtostrf(zraise, 1, 3, str_1));
sprintf_P(cmd, PSTR("G0Z%s"), dtostrf(zraise, 1, 3, str_1));
gcode.process_subcommands_now(cmd);
}
#else
@ -292,8 +287,9 @@ void PrintJobRecovery::save(const bool force/*=false*/, const float zraise/*=0*/
constexpr float zraise = 0;
#endif
// Save, including the limited Z raise
if (IS_SD_PRINTING()) save(true, zraise);
// Save the current position, distance that Z was (or should be) raised,
// and a flag whether the raise was already done here.
if (IS_SD_PRINTING()) save(true, zraise, ENABLED(BACKUP_POWER_SUPPLY));
// Disable all heaters to reduce power loss
thermalManager.disable_all_heaters();
@ -348,57 +344,78 @@ void PrintJobRecovery::resume() {
const celsius_t bt = info.target_temperature_bed;
if (bt) {
// Restore the bed temperature
sprintf_P(cmd, PSTR("M190 S%i"), bt);
sprintf_P(cmd, PSTR("M190S%i"), bt);
gcode.process_subcommands_now(cmd);
}
#endif
// Restore all hotend temperatures
// Heat hotend enough to soften material
#if HAS_HOTEND
HOTEND_LOOP() {
const celsius_t et = info.target_temperature[e];
const celsius_t et = _MAX(info.target_temperature[e], 180);
if (et) {
#if HAS_MULTI_HOTEND
sprintf_P(cmd, PSTR("T%i S"), e);
sprintf_P(cmd, PSTR("T%iS"), e);
gcode.process_subcommands_now(cmd);
#endif
sprintf_P(cmd, PSTR("M109 S%i"), et);
sprintf_P(cmd, PSTR("M109S%i"), et);
gcode.process_subcommands_now(cmd);
}
}
#endif
// Interpret the saved Z according to flags
const float z_print = info.current_position.z,
z_raised = z_print + info.zraise;
//
// Home the axes that can safely be homed, and
// establish the current position as best we can
// establish the current position as best we can.
//
#if Z_HOME_DIR > 0
// If Z homing goes to max...
gcode.process_subcommands_now_P(PSTR(
"G92.9 E0\n" // Reset E to 0
"G28R0" // Home all axes (no raise)
));
gcode.process_subcommands_now_P(PSTR("G92.9E0")); // Reset E to 0
#else // "G92.9 E0 ..."
#if Z_HOME_DIR > 0
// If a Z raise occurred at outage restore Z, otherwise raise Z now
sprintf_P(cmd, PSTR("G92.9 E0 " TERN(BACKUP_POWER_SUPPLY, "Z%s", "Z0\nG1Z%s")), dtostrf(info.zraise, 1, 3, str_1));
float z_now = z_raised;
// If Z homing goes to max then just move back to the "raised" position
sprintf_P(cmd, PSTR(
"G28R0\n" // Home all axes (no raise)
"G1Z%sF1200" // Move Z down to (raised) height
), dtostrf(z_now, 1, 3, str_1));
gcode.process_subcommands_now(cmd);
// Home safely with no Z raise
gcode.process_subcommands_now_P(PSTR(
"G28R0" // No raise during G28
#if IS_CARTESIAN && (DISABLED(POWER_LOSS_RECOVER_ZHOME) || defined(POWER_LOSS_ZHOME_POS))
"XY" // Don't home Z on Cartesian unless overridden
#endif
));
#else
#if ENABLED(POWER_LOSS_RECOVER_ZHOME) && defined(POWER_LOSS_ZHOME_POS)
#define HOMING_Z_DOWN 1
#else
#define HOME_XY_ONLY 1
#endif
float z_now = info.flag.raised ? z_raised : z_print;
// Reset E to 0 and set Z to the real position
#if HOME_XY_ONLY
sprintf_P(cmd, PSTR("G92.9Z%s"), dtostrf(z_now, 1, 3, str_1));
gcode.process_subcommands_now(cmd);
#endif
// Does Z need to be raised now? It should be raised before homing XY.
if (z_raised > z_now) {
z_now = z_raised;
sprintf_P(cmd, PSTR("G1Z%sF600"), dtostrf(z_now, 1, 3, str_1));
gcode.process_subcommands_now(cmd);
}
// Home XY with no Z raise, and also home Z here if Z isn't homing down below.
gcode.process_subcommands_now_P(PSTR("G28R0" TERN_(HOME_XY_ONLY, "XY"))); // No raise during G28
#endif
#if ENABLED(POWER_LOSS_RECOVER_ZHOME) && defined(POWER_LOSS_ZHOME_POS)
// Move to a safe XY position where Z can home while avoiding the print.
// If Z_SAFE_HOMING is enabled, its position must also be outside the print area!
#if HOMING_Z_DOWN
// Move to a safe XY position and home Z while avoiding the print.
constexpr xy_pos_t p = POWER_LOSS_ZHOME_POS;
sprintf_P(cmd, PSTR("G1X%sY%sF1000\nG28Z"), dtostrf(p.x, 1, 3, str_1), dtostrf(p.y, 1, 3, str_2));
gcode.process_subcommands_now(cmd);
@ -407,9 +424,24 @@ void PrintJobRecovery::resume() {
// Mark all axes as having been homed (no effect on current_position)
set_all_homed();
#if HAS_LEVELING
// Restore Z fade and possibly re-enable bed leveling compensation.
// Leveling may already be enabled due to the ENABLE_LEVELING_AFTER_G28 option.
// TODO: Add a G28 parameter to leave leveling disabled.
sprintf_P(cmd, PSTR("M420S%cZ%s"), '0' + (char)info.flag.leveling, dtostrf(info.fade, 1, 1, str_1));
gcode.process_subcommands_now(cmd);
#if HOME_XY_ONLY
// The physical Z was adjusted at power-off so undo the M420S1 correction to Z with G92.9.
sprintf_P(cmd, PSTR("G92.9Z%s"), dtostrf(z_now, 1, 1, str_1));
gcode.process_subcommands_now(cmd);
#endif
#endif
#if ENABLED(POWER_LOSS_RECOVER_ZHOME)
// Z was homed. Now move Z back up to the saved Z height, plus the POWER_LOSS_ZRAISE.
sprintf_P(cmd, PSTR("G1Z%sF500"), dtostrf(info.current_position.z + POWER_LOSS_ZRAISE, 1, 3, str_1));
// Z was homed down to the bed, so move up to the raised height.
z_now = z_raised;
sprintf_P(cmd, PSTR("G1Z%sF600"), dtostrf(z_now, 1, 3, str_1));
gcode.process_subcommands_now(cmd);
#endif
@ -432,8 +464,23 @@ void PrintJobRecovery::resume() {
#endif
#endif
// Select the previously active tool (with no_move)
#if HAS_MULTI_EXTRUDER
// Restore all hotend temperatures
#if HAS_HOTEND
HOTEND_LOOP() {
const celsius_t et = info.target_temperature[e];
if (et) {
#if HAS_MULTI_HOTEND
sprintf_P(cmd, PSTR("T%iS"), e);
gcode.process_subcommands_now(cmd);
#endif
sprintf_P(cmd, PSTR("M109S%i"), et);
gcode.process_subcommands_now(cmd);
}
}
#endif
// Restore the previously active tool (with no_move)
#if HAS_MULTI_EXTRUDER || HAS_MULTI_HOTEND
sprintf_P(cmd, PSTR("T%i S"), info.active_extruder);
gcode.process_subcommands_now(cmd);
#endif
@ -460,22 +507,13 @@ void PrintJobRecovery::resume() {
fwretract.current_hop = info.retract_hop;
#endif
#if HAS_LEVELING
// Restore leveling state before 'G92 Z' to ensure
// the Z stepper count corresponds to the native Z.
if (info.fade || info.flag.leveling) {
sprintf_P(cmd, PSTR("M420S%cZ%s"), '0' + (char)info.flag.leveling, dtostrf(info.fade, 1, 1, str_1));
gcode.process_subcommands_now(cmd);
}
#endif
#if ENABLED(GRADIENT_MIX)
memcpy(&mixer.gradient, &info.gradient, sizeof(info.gradient));
#endif
// Un-retract if there was a retract at outage
#if ENABLED(BACKUP_POWER_SUPPLY) && POWER_LOSS_RETRACT_LEN > 0
gcode.process_subcommands_now_P(PSTR("G1 E" STRINGIFY(POWER_LOSS_RETRACT_LEN) " F3000"));
gcode.process_subcommands_now_P(PSTR("G1E" STRINGIFY(POWER_LOSS_RETRACT_LEN) "F3000"));
#endif
// Additional purge on resume if configured
@ -488,29 +526,23 @@ void PrintJobRecovery::resume() {
gcode.process_subcommands_now_P(PSTR("G12"));
#endif
// Move back to the saved XY
sprintf_P(cmd, PSTR("G1 X%s Y%s F3000"),
// Move back over to the saved XY
sprintf_P(cmd, PSTR("G1X%sY%sF3000"),
dtostrf(info.current_position.x, 1, 3, str_1),
dtostrf(info.current_position.y, 1, 3, str_2)
);
gcode.process_subcommands_now(cmd);
// Move back to the saved Z
dtostrf(info.current_position.z, 1, 3, str_1);
#if Z_HOME_DIR > 0 || ENABLED(POWER_LOSS_RECOVER_ZHOME)
sprintf_P(cmd, PSTR("G1 Z%s F500"), str_1);
#else
gcode.process_subcommands_now_P(PSTR("G1 Z0 F200"));
sprintf_P(cmd, PSTR("G92.9 Z%s"), str_1);
#endif
// Move back down to the saved Z for printing
sprintf_P(cmd, PSTR("G1Z%sF600"), dtostrf(z_print, 1, 3, str_1));
gcode.process_subcommands_now(cmd);
// Restore the feedrate
sprintf_P(cmd, PSTR("G1 F%d"), info.feedrate);
sprintf_P(cmd, PSTR("G1F%d"), info.feedrate);
gcode.process_subcommands_now(cmd);
// Restore E position with G92.9
sprintf_P(cmd, PSTR("G92.9 E%s"), dtostrf(info.current_position.e, 1, 3, str_1));
sprintf_P(cmd, PSTR("G92.9E%s"), dtostrf(info.current_position.e, 1, 3, str_1));
gcode.process_subcommands_now(cmd);
TERN_(GCODE_REPEAT_MARKERS, repeat = info.stored_repeat);
@ -535,7 +567,7 @@ void PrintJobRecovery::resume() {
char *fn = info.sd_filename;
sprintf_P(cmd, M23_STR, fn);
gcode.process_subcommands_now(cmd);
sprintf_P(cmd, PSTR("M24 S%ld T%ld"), resume_sdpos, info.print_job_elapsed);
sprintf_P(cmd, PSTR("M24S%ldT%ld"), resume_sdpos, info.print_job_elapsed);
gcode.process_subcommands_now(cmd);
TERN_(DEBUG_POWER_LOSS_RECOVERY, marlin_debug_flags = old_flags);
@ -555,7 +587,15 @@ void PrintJobRecovery::resume() {
}
DEBUG_EOL();
DEBUG_ECHOLNPAIR("zraise: ", info.zraise);
DEBUG_ECHOLNPAIR("feedrate: ", info.feedrate);
DEBUG_ECHOLNPAIR("zraise: ", info.zraise, " ", info.flag.raised ? "(before)" : "");
#if ENABLED(GCODE_REPEAT_MARKERS)
DEBUG_ECHOLNPAIR("repeat index: ", info.stored_repeat.index);
LOOP_L_N(i, info.stored_repeat.index)
DEBUG_ECHOLNPAIR("..... sdpos: ", info.stored_repeat.marker.sdpos, " count: ", info.stored_repeat.marker.counter);
#endif
#if HAS_HOME_OFFSET
DEBUG_ECHOPGM("home_offset: ");
@ -575,12 +615,16 @@ void PrintJobRecovery::resume() {
DEBUG_EOL();
#endif
DEBUG_ECHOLNPAIR("feedrate: ", info.feedrate);
#if HAS_MULTI_EXTRUDER
DEBUG_ECHOLNPAIR("active_extruder: ", info.active_extruder);
#endif
#if DISABLED(NO_VOLUMETRICS)
DEBUG_ECHOPGM("filament_size:");
LOOP_L_N(i, EXTRUDERS) DEBUG_ECHOLNPAIR(" ", info.filament_size[i]);
DEBUG_EOL();
#endif
#if HAS_HOTEND
DEBUG_ECHOPGM("target_temperature: ");
HOTEND_LOOP() {
@ -604,8 +648,9 @@ void PrintJobRecovery::resume() {
#endif
#if HAS_LEVELING
DEBUG_ECHOLNPAIR("leveling: ", info.flag.leveling, " fade: ", info.fade);
DEBUG_ECHOLNPAIR("leveling: ", info.flag.leveling ? "ON" : "OFF", " fade: ", info.fade);
#endif
#if ENABLED(FWRETRACT)
DEBUG_ECHOPGM("retract: ");
for (int8_t e = 0; e < EXTRUDERS; e++) {
@ -615,11 +660,28 @@ void PrintJobRecovery::resume() {
DEBUG_EOL();
DEBUG_ECHOLNPAIR("retract_hop: ", info.retract_hop);
#endif
// Mixing extruder and gradient
#if BOTH(MIXING_EXTRUDER, GRADIENT_MIX)
DEBUG_ECHOLNPAIR("gradient: ", info.gradient.enabled ? "ON" : "OFF");
#endif
DEBUG_ECHOLNPAIR("sd_filename: ", info.sd_filename);
DEBUG_ECHOLNPAIR("sdpos: ", info.sdpos);
DEBUG_ECHOLNPAIR("print_job_elapsed: ", info.print_job_elapsed);
DEBUG_ECHOLNPAIR("dryrun: ", AS_DIGIT(info.flag.dryrun));
DEBUG_ECHOLNPAIR("allow_cold_extrusion: ", info.flag.allow_cold_extrusion);
DEBUG_ECHOPGM("axis_relative:");
if (TEST(info.axis_relative, REL_X)) DEBUG_ECHOPGM(" REL_X");
if (TEST(info.axis_relative, REL_Y)) DEBUG_ECHOPGM(" REL_Y");
if (TEST(info.axis_relative, REL_Z)) DEBUG_ECHOPGM(" REL_Z");
if (TEST(info.axis_relative, REL_E)) DEBUG_ECHOPGM(" REL_E");
if (TEST(info.axis_relative, E_MODE_ABS)) DEBUG_ECHOPGM(" E_MODE_ABS");
if (TEST(info.axis_relative, E_MODE_REL)) DEBUG_ECHOPGM(" E_MODE_REL");
DEBUG_EOL();
DEBUG_ECHOLNPAIR("flag.dryrun: ", AS_DIGIT(info.flag.dryrun));
DEBUG_ECHOLNPAIR("flag.allow_cold_extrusion: ", AS_DIGIT(info.flag.allow_cold_extrusion));
DEBUG_ECHOLNPAIR("flag.volumetric_enabled: ", AS_DIGIT(info.flag.volumetric_enabled));
}
else
DEBUG_ECHOLNPGM("INVALID DATA");

18
Marlin/src/feature/powerloss.h

@ -42,6 +42,10 @@
#define POWER_LOSS_STATE HIGH
#endif
#ifndef POWER_LOSS_ZRAISE
#define POWER_LOSS_ZRAISE 2
#endif
//#define DEBUG_POWER_LOSS_RECOVERY
//#define SAVE_EACH_CMD_MODE
//#define SAVE_INFO_INTERVAL_MS 0
@ -52,6 +56,7 @@ typedef struct {
// Machine state
xyze_pos_t current_position;
uint16_t feedrate;
float zraise;
// Repeat information
@ -112,6 +117,7 @@ typedef struct {
// Misc. Marlin flags
struct {
bool raised:1; // Raised before saved
bool dryrun:1; // M111 S8
bool allow_cold_extrusion:1; // M302 P1
#if ENABLED(HAS_LEVELING)
@ -177,12 +183,18 @@ class PrintJobRecovery {
static inline void cancel() { purge(); IF_DISABLED(NO_SD_AUTOSTART, card.autofile_begin()); }
static void load();
static void save(const bool force=ENABLED(SAVE_EACH_CMD_MODE), const float zraise=0);
static void save(const bool force=ENABLED(SAVE_EACH_CMD_MODE), const float zraise=POWER_LOSS_ZRAISE, const bool raised=false);
#if PIN_EXISTS(POWER_LOSS)
static inline void outage() {
if (enabled && READ(POWER_LOSS_PIN) == POWER_LOSS_STATE)
_outage();
static constexpr uint8_t OUTAGE_THRESHOLD = 3;
static uint8_t outage_counter = 0;
if (enabled && READ(POWER_LOSS_PIN) == POWER_LOSS_STATE) {
outage_counter++;
if (outage_counter >= OUTAGE_THRESHOLD) _outage();
}
else
outage_counter = 0;
}
#endif

2
Marlin/src/feature/runout.h

@ -207,7 +207,7 @@ class FilamentSensorBase {
// Return a bitmask of runout pin states
static inline uint8_t poll_runout_pins() {
#define _OR_RUNOUT(N) | (READ(FIL_RUNOUT##N##_PIN) ? _BV((N) - 1) : 0)
return (0 REPEAT_S(1, INCREMENT(NUM_RUNOUT_SENSORS), _OR_RUNOUT));
return (0 REPEAT_1(NUM_RUNOUT_SENSORS, _OR_RUNOUT));
#undef _OR_RUNOUT
}

8
Marlin/src/gcode/bedlevel/G26.cpp

@ -648,12 +648,12 @@ void GcodeSuite::G26() {
#if HAS_LCD_MENU
g26_repeats = parser.intval('R', GRID_MAX_POINTS + 1);
#else
if (!parser.seen('R')) {
if (parser.seen('R'))
g26_repeats = parser.has_value() ? parser.value_int() : GRID_MAX_POINTS + 1;
else {
SERIAL_ECHOLNPGM("?(R)epeat must be specified when not using an LCD.");
return;
}
else
g26_repeats = parser.has_value() ? parser.value_int() : GRID_MAX_POINTS + 1;
#endif
if (g26_repeats < 1) {
SERIAL_ECHOLNPGM("?(R)epeat value not plausible; must be at least 1.");
@ -671,7 +671,7 @@ void GcodeSuite::G26() {
/**
* Wait until all parameters are verified before altering the state!
*/
set_bed_leveling_enabled(!parser.seen('D'));
set_bed_leveling_enabled(!parser.seen_test('D'));
do_z_clearance(Z_CLEARANCE_BETWEEN_PROBES);

2
Marlin/src/gcode/bedlevel/M420.cpp

@ -133,7 +133,7 @@ void GcodeSuite::M420() {
#endif // AUTO_BED_LEVELING_UBL
const bool seenV = parser.seen('V');
const bool seenV = parser.seen_test('V');
#if HAS_MESH

12
Marlin/src/gcode/bedlevel/abl/G29.cpp

@ -223,7 +223,7 @@ G29_TYPE GcodeSuite::G29() {
reset_stepper_timeout();
const bool seenQ = EITHER(DEBUG_LEVELING_FEATURE, PROBE_MANUALLY) && parser.seen('Q');
const bool seenQ = EITHER(DEBUG_LEVELING_FEATURE, PROBE_MANUALLY) && parser.seen_test('Q');
// G29 Q is also available if debugging
#if ENABLED(DEBUG_LEVELING_FEATURE)
@ -235,7 +235,7 @@ G29_TYPE GcodeSuite::G29() {
if (DISABLED(PROBE_MANUALLY) && seenQ) G29_RETURN(false);
#endif
const bool seenA = TERN0(PROBE_MANUALLY, parser.seen('A')),
const bool seenA = TERN0(PROBE_MANUALLY, parser.seen_test('A')),
no_action = seenA || seenQ,
faux = ENABLED(DEBUG_LEVELING_FEATURE) && DISABLED(PROBE_MANUALLY) ? parser.boolval('C') : no_action;
@ -245,7 +245,7 @@ G29_TYPE GcodeSuite::G29() {
}
// Send 'N' to force homing before G29 (internal only)
if (parser.seen('N'))
if (parser.seen_test('N'))
process_subcommands_now_P(TERN(G28_L0_ENSURES_LEVELING_OFF, PSTR("G28L0"), G28_STR));
// Don't allow auto-leveling without homing first
@ -275,7 +275,7 @@ G29_TYPE GcodeSuite::G29() {
#if ENABLED(AUTO_BED_LEVELING_BILINEAR)
const bool seen_w = parser.seen('W');
const bool seen_w = parser.seen_test('W');
if (seen_w) {
if (!leveling_is_valid()) {
SERIAL_ERROR_MSG("No bilinear grid");
@ -308,7 +308,7 @@ G29_TYPE GcodeSuite::G29() {
if (abl.reenable) report_current_position();
}
G29_RETURN(false);
} // parser.seen('W')
} // parser.seen_test('W')
#else
@ -317,7 +317,7 @@ G29_TYPE GcodeSuite::G29() {
#endif
// Jettison bed leveling data
if (!seen_w && parser.seen('J')) {
if (!seen_w && parser.seen_test('J')) {
reset_bed_level();
G29_RETURN(false);
}

2
Marlin/src/gcode/bedlevel/mbl/G29.cpp

@ -87,7 +87,7 @@ void GcodeSuite::G29() {
mbl.reset();
mbl_probe_index = 0;
if (!ui.wait_for_move) {
queue.inject_P(parser.seen('N') ? PSTR("G28" TERN(G28_L0_ENSURES_LEVELING_OFF, "L0", "") "\nG29S2") : PSTR("G29S2"));
queue.inject_P(parser.seen_test('N') ? PSTR("G28" TERN(G28_L0_ENSURES_LEVELING_OFF, "L0", "") "\nG29S2") : PSTR("G29S2"));
return;
}
state = MeshNext;

27
Marlin/src/gcode/bedlevel/ubl/M421.cpp

@ -21,7 +21,7 @@
*/
/**
* unified.cpp - Unified Bed Leveling
* M421.cpp - Unified Bed Leveling
*/
#include "../../../inc/MarlinConfig.h"
@ -39,31 +39,34 @@
* M421: Set a single Mesh Bed Leveling Z coordinate
*
* Usage:
* M421 I<xindex> J<yindex> Z<linear>
* M421 I<xindex> J<yindex> Q<offset>
* M421 I<xindex> J<yindex> N
* M421 C Z<linear>
* M421 C Q<offset>
* M421 I<xindex> J<yindex> Z<linear> : Set the Mesh Point IJ to the Z value
* M421 I<xindex> J<yindex> Q<offset> : Add the Q value to the Mesh Point IJ
* M421 I<xindex> J<yindex> N : Set the Mesh Point IJ to NAN (not set)
* M421 C Z<linear> : Set the closest Mesh Point to the Z value
* M421 C Q<offset> : Add the Q value to the closest Mesh Point
*/
void GcodeSuite::M421() {
xy_int8_t ij = { int8_t(parser.intval('I', -1)), int8_t(parser.intval('J', -1)) };
const bool hasI = ij.x >= 0,
hasJ = ij.y >= 0,
hasC = parser.seen('C'),
hasN = parser.seen('N'),
hasC = parser.seen_test('C'),
hasN = parser.seen_test('N'),
hasZ = parser.seen('Z'),
hasQ = !hasZ && parser.seen('Q');
if (hasC) ij = ubl.find_closest_mesh_point_of_type(REAL, current_position);
if (hasC) ij = ubl.find_closest_mesh_point_of_type(CLOSEST, current_position);
// Test for bad parameter combinations
if (int(hasC) + int(hasI && hasJ) != 1 || !(hasZ || hasQ || hasN))
SERIAL_ERROR_MSG(STR_ERR_M421_PARAMETERS);
// Test for I J out of range
else if (!WITHIN(ij.x, 0, GRID_MAX_POINTS_X - 1) || !WITHIN(ij.y, 0, GRID_MAX_POINTS_Y - 1))
SERIAL_ERROR_MSG(STR_ERR_MESH_XY);
else {
float &zval = ubl.z_values[ij.x][ij.y];
zval = hasN ? NAN : parser.value_linear_units() + (hasQ ? zval : 0);
TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(ij.x, ij.y, zval));
float &zval = ubl.z_values[ij.x][ij.y]; // Altering this Mesh Point
zval = hasN ? NAN : parser.value_linear_units() + (hasQ ? zval : 0); // N=NAN, Z=NEWVAL, or Q=ADDVAL
TERN_(EXTENSIBLE_UI, ExtUI::onMeshUpdate(ij.x, ij.y, zval)); // Ping ExtUI in case it's showing the mesh
}
}

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

@ -219,7 +219,7 @@ void GcodeSuite::G28() {
#endif
#if ENABLED(MARLIN_DEV_MODE)
if (parser.seen('S')) {
if (parser.seen_test('S')) {
LOOP_XYZ(a) set_axis_is_at_home((AxisEnum)a);
sync_plan_position();
SERIAL_ECHOLNPGM("Simulated Homing");
@ -321,10 +321,10 @@ void GcodeSuite::G28() {
#else
const bool homeZ = parser.seen('Z'),
const bool homeZ = parser.seen_test('Z'),
needX = homeZ && TERN0(Z_SAFE_HOMING, axes_should_home(_BV(X_AXIS))),
needY = homeZ && TERN0(Z_SAFE_HOMING, axes_should_home(_BV(Y_AXIS))),
homeX = needX || parser.seen('X'), homeY = needY || parser.seen('Y'),
homeX = needX || parser.seen_test('X'), homeY = needY || parser.seen_test('Y'),
home_all = homeX == homeY && homeX == homeZ, // All or None
doX = home_all || homeX, doY = home_all || homeY, doZ = home_all || homeZ;

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

@ -395,7 +395,7 @@ void GcodeSuite::G33() {
return;
}
const bool towers_set = !parser.seen('T');
const bool towers_set = !parser.seen_test('T');
const float calibration_precision = parser.floatval('C', 0.0f);
if (calibration_precision < 0) {
@ -415,7 +415,7 @@ void GcodeSuite::G33() {
return;
}
const bool stow_after_each = parser.seen('E');
const bool stow_after_each = parser.seen_test('E');
const bool _0p_calibration = probe_points == 0,
_1p_calibration = probe_points == 1 || probe_points == -1,

2
Marlin/src/gcode/feature/caselight/M355.cpp

@ -61,7 +61,7 @@ void GcodeSuite::M355() {
SERIAL_ECHOLNPGM(STR_OFF);
else {
#if CASELIGHT_USES_BRIGHTNESS
if (TERN(CASE_LIGHT_USE_NEOPIXEL, true, PWM_PIN(CASE_LIGHT_PIN))) {
if (TERN(CASE_LIGHT_USE_NEOPIXEL, true, TERN0(NEED_CASE_LIGHT_PIN, PWM_PIN(CASE_LIGHT_PIN)))) {
SERIAL_ECHOLN(int(caselight.brightness));
return;
}

5
Marlin/src/gcode/feature/pause/G60.cpp

@ -48,10 +48,11 @@ void GcodeSuite::G60() {
#if ENABLED(SAVED_POSITIONS_DEBUG)
const xyze_pos_t &pos = stored_position[slot];
DEBUG_ECHOPAIR_F(STR_SAVED_POS " S", slot);
DEBUG_ECHOPAIR(STR_SAVED_POS " S", slot);
DEBUG_ECHOPAIR_F(" : X", pos.x);
DEBUG_ECHOPAIR_F_P(SP_Y_STR, pos.y);
DEBUG_ECHOLNPAIR_F_P(SP_Z_STR, pos.z);
DEBUG_ECHOPAIR_F_P(SP_Z_STR, pos.z);
DEBUG_ECHOLNPAIR_F_P(SP_E_STR, pos.e);
#endif
}

47
Marlin/src/gcode/feature/pause/G61.cpp

@ -27,6 +27,10 @@
#include "../../../module/planner.h"
#include "../../gcode.h"
#include "../../../module/motion.h"
#include "../../../module/planner.h"
#define DEBUG_OUT ENABLED(SAVED_POSITIONS_DEBUG)
#include "../../../core/debug_out.h"
/**
* G61: Return to saved position
@ -34,11 +38,16 @@
* F<rate> - Feedrate (optional) for the move back.
* S<slot> - Slot # (0-based) to restore from (default 0).
* X Y Z - Axes to restore. At least one is required.
* E - Restore extruder position
*
* If XYZE are not given, default restore uses the smart blocking move.
*/
void GcodeSuite::G61(void) {
const uint8_t slot = parser.byteval('S');
#define SYNC_E(POINT) planner.set_e_position_mm((destination.e = current_position.e = (POINT)))
#if SAVED_POSITIONS < 256
if (slot >= SAVED_POSITIONS) {
SERIAL_ERROR_MSG(STR_INVALID_POS_SLOT STRINGIFY(SAVED_POSITIONS));
@ -47,25 +56,37 @@ void GcodeSuite::G61(void) {
#endif
// No saved position? No axes being restored?
if (!TEST(saved_slots[slot >> 3], slot & 0x07) || !parser.seen("XYZ")) return;
SERIAL_ECHOPAIR(STR_RESTORING_POS " S", slot);
LOOP_XYZ(i) {
destination[i] = parser.seen(XYZ_CHAR(i))
? stored_position[slot][i] + parser.value_axis_units((AxisEnum)i)
: current_position[i];
SERIAL_CHAR(' ', XYZ_CHAR(i));
SERIAL_ECHO_F(destination[i]);
}
SERIAL_EOL();
if (!TEST(saved_slots[slot >> 3], slot & 0x07)) return;
// Apply any given feedrate over 0.0
feedRate_t saved_feedrate = feedrate_mm_s;
const float fr = parser.linearval('F');
if (fr > 0.0) feedrate_mm_s = MMM_TO_MMS(fr);
// Move to the saved position
prepare_line_to_destination();
if (!parser.seen_axis()) {
DEBUG_ECHOLNPGM("Default position restore");
do_blocking_move_to(stored_position[slot], feedrate_mm_s);
SYNC_E(stored_position[slot].e);
}
else {
if (parser.seen("XYZ")) {
DEBUG_ECHOPAIR(STR_RESTORING_POS " S", slot);
LOOP_XYZ(i) {
destination[i] = parser.seen(XYZ_CHAR(i))
? stored_position[slot][i] + parser.value_axis_units((AxisEnum)i)
: current_position[i];
DEBUG_CHAR(' ', XYZ_CHAR(i));
DEBUG_ECHO_F(destination[i]);
}
DEBUG_EOL();
// Move to the saved position
prepare_line_to_destination();
}
if (parser.seen_test('E')) {
DEBUG_ECHOLNPAIR(STR_RESTORING_POS " S", slot, " E", current_position.e, "=>", stored_position[slot].e);
SYNC_E(stored_position[slot].e);
}
}
feedrate_mm_s = saved_feedrate;
}

6
Marlin/src/gcode/feature/pause/M125.cpp

@ -56,7 +56,7 @@
*/
void GcodeSuite::M125() {
// Initial retract before move to filament change position
const float retract = -ABS(parser.seen('L') ? parser.value_axis_units(E_AXIS) : (PAUSE_PARK_RETRACT_LENGTH));
const float retract = -ABS(parser.axisunitsval('L', E_AXIS, PAUSE_PARK_RETRACT_LENGTH));
xyz_pos_t park_point = NOZZLE_PARK_POINT;
@ -78,10 +78,8 @@ void GcodeSuite::M125() {
// If possible, show an LCD prompt with the 'P' flag
const bool show_lcd = TERN0(HAS_LCD_MENU, parser.boolval('P'));
TERN_(POWER_LOSS_RECOVERY, if (recovery.enabled) recovery.save(true));
if (pause_print(retract, park_point, show_lcd, 0)) {
if (ENABLED(EXTENSIBLE_UI) || !sd_printing || show_lcd) {
if (ENABLED(EXTENSIBLE_UI) || BOTH(EMERGENCY_PARSER, HOST_PROMPT_SUPPORT) || !sd_printing || show_lcd) {
wait_for_confirmation(false, 0);
resume_print(0, 0, -retract, 0);
}

14
Marlin/src/gcode/feature/pause/M600.cpp

@ -81,8 +81,8 @@ void GcodeSuite::M600() {
#if ENABLED(DUAL_X_CARRIAGE)
int8_t DXC_ext = target_extruder;
if (!parser.seen('T')) { // If no tool index is specified, M600 was (probably) sent in response to filament runout.
// In this case, for duplicating modes set DXC_ext to the extruder that ran out.
if (!parser.seen_test('T')) { // If no tool index is specified, M600 was (probably) sent in response to filament runout.
// In this case, for duplicating modes set DXC_ext to the extruder that ran out.
#if MULTI_FILAMENT_SENSOR
if (idex_is_duplicating())
DXC_ext = (READ(FIL_RUNOUT2_PIN) == FIL_RUNOUT2_STATE) ? 1 : 0;
@ -110,7 +110,7 @@ void GcodeSuite::M600() {
#endif
// Initial retract before move to filament change position
const float retract = -ABS(parser.seen('E') ? parser.value_axis_units(E_AXIS) : (PAUSE_PARK_RETRACT_LENGTH));
const float retract = -ABS(parser.axisunitsval('E', E_AXIS, PAUSE_PARK_RETRACT_LENGTH));
xyz_pos_t park_point NOZZLE_PARK_POINT;
@ -132,15 +132,11 @@ void GcodeSuite::M600() {
fast_load_length = 0.0f;
#else
// Unload filament
const float unload_length = -ABS(parser.seen('U') ? parser.value_axis_units(E_AXIS)
: fc_settings[active_extruder].unload_length);
const float unload_length = -ABS(parser.axisunitsval('U', E_AXIS, fc_settings[active_extruder].unload_length));
// Slow load filament
constexpr float slow_load_length = FILAMENT_CHANGE_SLOW_LOAD_LENGTH;
// Fast load filament
const float fast_load_length = ABS(parser.seen('L') ? parser.value_axis_units(E_AXIS)
: fc_settings[active_extruder].load_length);
const float fast_load_length = ABS(parser.axisunitsval('L', E_AXIS, fc_settings[active_extruder].load_length));
#endif
const int beep_count = parser.intval('B', -1

4
Marlin/src/gcode/feature/powerloss/M1000.cpp

@ -59,7 +59,7 @@ inline void plr_error(PGM_P const prefix) {
void GcodeSuite::M1000() {
if (recovery.valid()) {
if (parser.seen('S')) {
if (parser.seen_test('S')) {
#if HAS_LCD_MENU
ui.goto_screen(menu_job_recovery);
#elif ENABLED(DWIN_CREALITY_LCD)
@ -70,7 +70,7 @@ void GcodeSuite::M1000() {
SERIAL_ECHO_MSG("Resume requires LCD.");
#endif
}
else if (parser.seen('C')) {
else if (parser.seen_test('C')) {
#if HAS_LCD_MENU
lcd_power_loss_recovery_cancel();
#else

12
Marlin/src/gcode/feature/powerloss/M413.cpp

@ -48,14 +48,14 @@ void GcodeSuite::M413() {
#if ENABLED(DEBUG_POWER_LOSS_RECOVERY)
if (parser.seen("RL")) recovery.load();
if (parser.seen('W')) recovery.save(true);
if (parser.seen('P')) recovery.purge();
if (parser.seen('D')) recovery.debug(PSTR("M413"));
if (parser.seen_test('W')) recovery.save(true);
if (parser.seen_test('P')) recovery.purge();
if (parser.seen_test('D')) recovery.debug(PSTR("M413"));
#if PIN_EXISTS(POWER_LOSS)
if (parser.seen('O')) recovery._outage();
if (parser.seen_test('O')) recovery._outage();
#endif
if (parser.seen('E')) SERIAL_ECHOPGM_P(recovery.exists() ? PSTR("PLR Exists\n") : PSTR("No PLR\n"));
if (parser.seen('V')) SERIAL_ECHOPGM_P(recovery.valid() ? PSTR("Valid\n") : PSTR("Invalid\n"));
if (parser.seen_test('E')) SERIAL_ECHOPGM_P(recovery.exists() ? PSTR("PLR Exists\n") : PSTR("No PLR\n"));
if (parser.seen_test('V')) SERIAL_ECHOPGM_P(recovery.valid() ? PSTR("Valid\n") : PSTR("Invalid\n"));
#endif
}

2
Marlin/src/gcode/feature/runout/M412.cpp

@ -44,7 +44,7 @@ void GcodeSuite::M412() {
#if ENABLED(HOST_ACTION_COMMANDS)
if (parser.seen('H')) runout.host_handling = parser.value_bool();
#endif
const bool seenR = parser.seen('R'), seenS = parser.seen('S');
const bool seenR = parser.seen_test('R'), seenS = parser.seen('S');
if (seenR || seenS) runout.reset();
if (seenS) runout.enabled = parser.value_bool();
#if HAS_FILAMENT_RUNOUT_DISTANCE

5
Marlin/src/gcode/feature/trinamic/M122.cpp

@ -32,7 +32,8 @@
* M122: Debug TMC drivers
*/
void GcodeSuite::M122() {
xyze_bool_t print_axis = { false, false, false, false };
xyze_bool_t print_axis = ARRAY_N_1(XYZE, false);
bool print_all = true;
LOOP_XYZE(i) if (parser.seen(axis_codes[i])) { print_axis[i] = true; print_all = false; }
@ -48,7 +49,7 @@ void GcodeSuite::M122() {
tmc_set_report_interval(interval);
#endif
if (parser.seen('V'))
if (parser.seen_test('V'))
tmc_get_registers(print_axis.x, print_axis.y, print_axis.z, print_axis.e);
else
tmc_report_all(print_axis.x, print_axis.y, print_axis.z, print_axis.e);

18
Marlin/src/gcode/gcode.cpp

@ -215,7 +215,7 @@ void GcodeSuite::dwell(millis_t time) {
* When G29_RETRY_AND_RECOVER is enabled, call G29() in
* a loop with recovery and retry handling.
*/
#if BOTH(HAS_LEVELING, G29_RETRY_AND_RECOVER)
#if ENABLED(G29_RETRY_AND_RECOVER)
void GcodeSuite::event_probe_recover() {
TERN_(HOST_PROMPT_SUPPORT, host_prompt_do(PROMPT_INFO, PSTR("G29 Retrying"), DISMISS_STR));
@ -227,6 +227,10 @@ void GcodeSuite::dwell(millis_t time) {
#endif
}
#if ENABLED(G29_HALT_ON_FAILURE)
#include "../lcd/marlinui.h"
#endif
void GcodeSuite::event_probe_failure() {
#ifdef ACTION_ON_G29_FAILURE
host_action(PSTR(ACTION_ON_G29_FAILURE));
@ -266,15 +270,13 @@ void GcodeSuite::dwell(millis_t time) {
#endif
}
#endif // HAS_LEVELING && G29_RETRY_AND_RECOVER
#endif // G29_RETRY_AND_RECOVER
/**
* Process the parsed command and dispatch it to its handler
*/
void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) {
KEEPALIVE_STATE(IN_HANDLER);
#if ENABLED(MKS_WIFI)
serial_index_t port = queue.ring_buffer.command_port();
@ -609,6 +611,10 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) {
case 193: M193(); break; // M193: Wait for cooler temperature to reach target
#endif
#if ENABLED(AUTO_REPORT_POSITION)
case 154: M154(); break; // M155: Set position auto-report interval
#endif
#if BOTH(AUTO_REPORT_TEMPERATURES, HAS_TEMP_SENSOR)
case 155: M155(); break; // M155: Set temperature auto-report interval
#endif
@ -1061,6 +1067,10 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) {
case 1002: M1002(); break; // M1002: [INTERNAL] Tool-change and Relative E Move
#endif
#if ENABLED(UBL_MESH_WIZARD)
case 1004: M1004(); break; // M1004: UBL Mesh Wizard
#endif
#if ENABLED(MAX7219_GCODE)
case 7219: M7219(); break; // M7219: Set LEDs, columns, and rows
#endif

9
Marlin/src/gcode/gcode.h

@ -159,6 +159,7 @@
* M145 - Set heatup values for materials on the LCD. H<hotend> B<bed> F<fan speed> for S<material> (0=PLA, 1=ABS)
* M149 - Set temperature units. (Requires TEMPERATURE_UNITS_SUPPORT)
* M150 - Set Status LED Color as R<red> U<green> B<blue> W<white> P<bright>. Values 0-255. (Requires BLINKM, RGB_LED, RGBW_LED, NEOPIXEL_LED, PCA9533, or PCA9632).
* M154 - Auto-report position with interval of S<seconds>. (Requires AUTO_REPORT_POSITION)
* M155 - Auto-report temperatures with interval of S<seconds>. (Requires AUTO_REPORT_TEMPERATURES)
* M163 - Set a single proportion for a mixing extruder. (Requires MIXING_EXTRUDER)
* M164 - Commit the mix and save to a virtual tool (current, or as specified by 'S'). (Requires MIXING_EXTRUDER)
@ -721,6 +722,10 @@ private:
static void M150();
#endif
#if ENABLED(AUTO_REPORT_POSITION)
static void M154();
#endif
#if BOTH(AUTO_REPORT_TEMPERATURES, HAS_TEMP_SENSOR)
static void M155();
#endif
@ -1079,6 +1084,10 @@ private:
static void M1002();
#endif
#if ENABLED(UBL_MESH_WIZARD)
static void M1004();
#endif
#if ENABLED(MAX7219_GCODE)
static void M7219();
#endif

2
Marlin/src/gcode/gcode_d.cpp

@ -52,7 +52,7 @@
break;
case 10:
kill(PSTR("D10"), PSTR("KILL TEST"), parser.seen('P'));
kill(PSTR("D10"), PSTR("KILL TEST"), parser.seen_test('P'));
break;
case 1: {

6
Marlin/src/gcode/host/M114.cpp

@ -193,7 +193,7 @@
void GcodeSuite::M114() {
#if ENABLED(M114_DETAIL)
if (parser.seen('D')) {
if (parser.seen_test('D')) {
#if DISABLED(M114_LEGACY)
planner.synchronize();
#endif
@ -201,14 +201,14 @@ void GcodeSuite::M114() {
report_current_position_detail();
return;
}
if (parser.seen('E')) {
if (parser.seen_test('E')) {
SERIAL_ECHOLNPAIR("Count E:", stepper.position(E_AXIS));
return;
}
#endif
#if ENABLED(M114_REALTIME)
if (parser.seen('R')) { report_real_position(); return; }
if (parser.seen_test('R')) { report_real_position(); return; }
#endif
TERN_(M114_LEGACY, planner.synchronize());

3
Marlin/src/gcode/host/M115.cpp

@ -82,6 +82,9 @@ void GcodeSuite::M115() {
// Volumetric Extrusion (M200)
cap_line(PSTR("VOLUMETRIC"), DISABLED(NO_VOLUMETRICS));
// AUTOREPORT_POS (M154)
cap_line(PSTR("AUTOREPORT_POS"), ENABLED(AUTO_REPORT_POSITION));
// AUTOREPORT_TEMP (M155)
cap_line(PSTR("AUTOREPORT_TEMP"), ENABLED(AUTO_REPORT_TEMPERATURES));

40
Marlin/src/gcode/host/M154.cpp

@ -0,0 +1,40 @@
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
*
* Based on Sprinter and grbl.
* Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm
*
* This program is free software: you can redistribute it and/or modify
* it under the terms of the GNU General Public License as published by
* the Free Software Foundation, either version 3 of the License, or
* (at your option) any later version.
*
* This program is distributed in the hope that it will be useful,
* but WITHOUT ANY WARRANTY; without even the implied warranty of
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
* GNU General Public License for more details.
*
* You should have received a copy of the GNU General Public License
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#include "../../inc/MarlinConfigPre.h"
#if ENABLED(AUTO_REPORT_POSITION)
#include "../gcode.h"
#include "../../module/motion.h"
/**
* M154: Set position auto-report interval. M154 S<seconds>
*/
void GcodeSuite::M154() {
if (parser.seenval('S'))
position_auto_reporter.set_interval(parser.value_byte());
}
#endif // AUTO_REPORT_POSITION

2
Marlin/src/gcode/lcd/M995.cpp

@ -27,7 +27,7 @@
#include "../gcode.h"
#if ENABLED(TFT_LVGL_UI)
#include "../../lcd/extui/lib/mks_ui/draw_touch_calibration.h"
#include "../../lcd/extui/mks_ui/draw_touch_calibration.h"
#else
#include "../../lcd/menu/menu.h"
#endif

6
Marlin/src/gcode/motion/G0_G1.cpp

@ -49,9 +49,9 @@ void GcodeSuite::G0_G1(TERN_(HAS_FAST_MOVES, const bool fast_move/*=false*/)) {
if (IsRunning()
#if ENABLED(NO_MOTION_BEFORE_HOMING)
&& !homing_needed_error(
(parser.seen('X') ? _BV(X_AXIS) : 0)
| (parser.seen('Y') ? _BV(Y_AXIS) : 0)
| (parser.seen('Z') ? _BV(Z_AXIS) : 0) )
(parser.seen_test('X') ? _BV(X_AXIS) : 0)
| (parser.seen_test('Y') ? _BV(Y_AXIS) : 0)
| (parser.seen_test('Z') ? _BV(Z_AXIS) : 0) )
#endif
) {
TERN_(FULL_REPORT_TO_HOST_FEATURE, set_and_report_grblstate(M_RUNNING));

4
Marlin/src/gcode/motion/M290.cpp

@ -74,7 +74,7 @@ void GcodeSuite::M290() {
const float offs = constrain(parser.value_axis_units((AxisEnum)a), -2, 2);
babystep.add_mm((AxisEnum)a, offs);
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
if (a == Z_AXIS && (!parser.seen('P') || parser.value_bool())) mod_probe_offset(offs);
if (a == Z_AXIS && parser.boolval('P', true)) mod_probe_offset(offs);
#endif
}
#else
@ -82,7 +82,7 @@ void GcodeSuite::M290() {
const float offs = constrain(parser.value_axis_units(Z_AXIS), -2, 2);
babystep.add_mm(Z_AXIS, offs);
#if ENABLED(BABYSTEP_ZPROBE_OFFSET)
if (!parser.seen('P') || parser.value_bool()) mod_probe_offset(offs);
if (parser.boolval('P', true)) mod_probe_offset(offs);
#endif
}
#endif

92
Marlin/src/gcode/parser.cpp

@ -149,13 +149,31 @@ void GCodeParser::parse(char *p) {
#define SIGNED_CODENUM 1
#endif
/**
* Screen for good command letters.
* With Realtime Reporting, commands S000, P000, and R000 are allowed.
*/
#if ENABLED(REALTIME_REPORTING_COMMANDS)
switch (letter) {
case 'P': case 'R' ... 'S': {
uint8_t digits = 0;
char *a = p;
while (*a++ == '0') digits++; // Count up '0' characters
if (digits == 3) { // Three '0' digits is a good command
codenum = 0;
command_letter = letter;
return;
}
}
}
#endif
/**
* Screen for good command letters. G, M, and T are always accepted.
* With Motion Modes enabled any axis letter can come first.
* With Realtime Reporting, commands S000, P000, and R000 are allowed.
*/
switch (letter) {
case 'G': case 'M': case 'T': TERN_(MARLIN_DEV_MODE, case 'D':)
case 'G': case 'M': case 'T': TERN_(MARLIN_DEV_MODE, case 'D':) {
// Skip spaces to get the numeric part
while (*p == ' ') p++;
@ -177,20 +195,18 @@ void GCodeParser::parse(char *p) {
// A '?' signifies an unknown command
command_letter = letter;
{
#if ENABLED(SIGNED_CODENUM)
int sign = 1; // Allow for a negative code like D-1 or T-1
if (*p == '-') { sign = -1; ++p; }
#endif
#if ENABLED(SIGNED_CODENUM)
int sign = 1; // Allow for a negative code like D-1 or T-1
if (*p == '-') { sign = -1; ++p; }
#endif
// Get the code number - integer digits only
codenum = 0;
// Get the code number - integer digits only
codenum = 0;
do { codenum = codenum * 10 + *p++ - '0'; } while (NUMERIC(*p));
do { codenum = codenum * 10 + *p++ - '0'; } while (NUMERIC(*p));
// Apply the sign, if any
TERN_(SIGNED_CODENUM, codenum *= sign);
}
// Apply the sign, if any
TERN_(SIGNED_CODENUM, codenum *= sign);
// Allow for decimal point in command
#if USE_GCODE_SUBCODES
@ -213,39 +229,33 @@ void GCodeParser::parse(char *p) {
}
#endif
break;
} break;
#if ENABLED(GCODE_MOTION_MODES)
#if EITHER(BEZIER_CURVE_SUPPORT, ARC_SUPPORT)
case 'I' ... 'J': case 'P':
if (TERN1(BEZIER_CURVE_SUPPORT, motion_mode_codenum != 5)
&& TERN1(ARC_P_CIRCLES, !WITHIN(motion_mode_codenum, 2, 3))
) return;
#endif
#if ENABLED(BEZIER_CURVE_SUPPORT)
case 'Q': if (motion_mode_codenum != 5) return;
#endif
#if ENABLED(ARC_SUPPORT)
case 'I' ... 'J':
if (motion_mode_codenum != 2 && motion_mode_codenum != 3) return;
case 'R': if (!WITHIN(motion_mode_codenum, 2, 3)) return;
#endif
case 'Q':
if (motion_mode_codenum != 5) return;
case 'X' ... 'Z': case 'E' ... 'F':
if (motion_mode_codenum < 0) return;
command_letter = 'G';
codenum = motion_mode_codenum;
TERN_(USE_GCODE_SUBCODES, subcode = motion_mode_subcode);
p--; // Back up one character to use the current parameter
break;
#endif
break;
#if ENABLED(REALTIME_REPORTING_COMMANDS)
case 'P': case 'R': {
if (letter == 'R') {
#if ENABLED(GCODE_MOTION_MODES)
if (ENABLED(ARC_SUPPORT) && !WITHIN(motion_mode_codenum, 2, 3)) return;
#endif
}
else if (TERN0(GCODE_MOTION_MODES, motion_mode_codenum != 5)) return;
} // fall-thru
case 'S': {
codenum = 0; // The only valid codenum is 0
uint8_t digits = 0;
while (*p++ == '0') digits++; // Count up '0' characters
command_letter = (digits == 3) ? letter : '?'; // Three '0' digits is a good command
} return; // No parameters needed, so return now
#endif
default: return;
@ -253,18 +263,12 @@ void GCodeParser::parse(char *p) {
// The command parameters (if any) start here, for sure!
#if DISABLED(FASTER_GCODE_PARSER)
command_args = p; // Scan for parameters in seen()
#endif
IF_DISABLED(FASTER_GCODE_PARSER, command_args = p); // Scan for parameters in seen()
// Only use string_arg for these M codes
if (letter == 'M') switch (codenum) {
#if ENABLED(GCODE_MACROS)
case 810 ... 819:
#endif
#if ENABLED(EXPECTED_PRINTER_CHECK)
case 16:
#endif
TERN_(GCODE_MACROS, case 810 ... 819:)
TERN_(EXPECTED_PRINTER_CHECK, case 16:)
case 23: case 28: case 30: case 117 ... 118: case 928:
string_arg = unescape_string(p);
return;

2
Marlin/src/gcode/parser.h

@ -408,6 +408,8 @@ public:
static inline int32_t longval(const char c, const int32_t dval=0) { return seenval(c) ? value_long() : dval; }
static inline uint32_t ulongval(const char c, const uint32_t dval=0) { return seenval(c) ? value_ulong() : dval; }
static inline float linearval(const char c, const float dval=0) { return seenval(c) ? value_linear_units() : dval; }
static inline float axisunitsval(const char c, const AxisEnum a, const float dval=0)
{ return seenval(c) ? value_axis_units(a) : dval; }
static inline celsius_t celsiusval(const char c, const float dval=0) { return seenval(c) ? value_celsius() : dval; }
#if ENABLED(MARLIN_DEV_MODE)

16
Marlin/src/gcode/queue.cpp

@ -268,8 +268,7 @@ void GCodeQueue::flush_and_request_resend(const serial_index_t serial_ind) {
PORT_REDIRECT(SERIAL_PORTMASK(serial_ind)); // Reply to the serial port that sent the command
#endif
SERIAL_FLUSH();
SERIAL_ECHOPGM(STR_RESEND);
SERIAL_ECHOLN(serial_state[serial_ind.index].last_N + 1);
SERIAL_ECHOLNPAIR(STR_RESEND, serial_state[serial_ind.index].last_N + 1);
SERIAL_ECHOLNPGM(STR_OK);
}
@ -516,13 +515,9 @@ void GCodeQueue::get_serial_commands() {
char* gpos = strchr(command, 'G');
if (gpos) {
switch (strtol(gpos + 1, nullptr, 10)) {
case 0: case 1:
#if ENABLED(ARC_SUPPORT)
case 2: case 3:
#endif
#if ENABLED(BEZIER_CURVE_SUPPORT)
case 5:
#endif
case 0 ... 1:
TERN_(ARC_SUPPORT, case 2 ... 3:)
TERN_(BEZIER_CURVE_SUPPORT, case 5:)
PORT_REDIRECT(SERIAL_PORTMASK(p)); // Reply to the serial port that sent the command
SERIAL_ECHOLNPGM(STR_ERR_STOPPED);
LCD_MESSAGEPGM(MSG_STOPPED);
@ -569,7 +564,8 @@ void GCodeQueue::get_serial_commands() {
inline void GCodeQueue::get_sdcard_commands() {
static uint8_t sd_input_state = PS_NORMAL;
if (!IS_SD_PRINTING()) return;
// Get commands if there are more in the file
if (!IS_SD_FETCHING()) return;
int sd_count = 0;
while (!ring_buffer.full() && !card.eof()) {

11
Marlin/src/gcode/sd/M1001.cpp

@ -25,11 +25,9 @@
#if ENABLED(SDSUPPORT)
#include "../gcode.h"
#include "../../module/planner.h"
#include "../../module/printcounter.h"
#if DISABLED(NO_SD_AUTOSTART)
#include "../../sd/cardreader.h"
#endif
#include "../../sd/cardreader.h"
#ifdef SD_FINISHED_RELEASECOMMAND
#include "../queue.h"
@ -64,6 +62,11 @@
* M1001: Execute actions for SD print completion
*/
void GcodeSuite::M1001() {
planner.synchronize();
// SD Printing is finished when the queue reaches M1001
card.flag.sdprinting = card.flag.sdprintdone = false;
// If there's another auto#.g file to run...
if (TERN(NO_SD_AUTOSTART, false, card.autofile_check())) return;

6
Marlin/src/gcode/sd/M24_M25.cpp

@ -42,7 +42,7 @@
#endif
#if ENABLED(DGUS_LCD_UI_MKS)
#include "../../lcd/extui/lib/dgus/DGUSDisplayDef.h"
#include "../../lcd/extui/dgus/DGUSDisplayDef.h"
#endif
#include "../../MarlinCore.h" // for startOrResumeJob
@ -70,7 +70,7 @@ void GcodeSuite::M24() {
#endif
if (card.isFileOpen()) {
card.startFileprint(); // SD card will now be read for commands
card.startOrResumeFilePrinting(); // SD card will now be read for commands
startOrResumeJob(); // Start (or resume) the print job timer
TERN_(POWER_LOSS_RECOVERY, recovery.prepare());
}
@ -105,7 +105,7 @@ void GcodeSuite::M25() {
if (IS_SD_PRINTING()) card.pauseSDPrint();
#endif
#if ENABLED(POWER_LOSS_RECOVERY)
#if ENABLED(POWER_LOSS_RECOVERY) && DISABLED(DGUS_LCD_UI_MKS)
if (recovery.enabled) recovery.save(true);
#endif

4
Marlin/src/gcode/sd/M27.cpp

@ -33,9 +33,9 @@
* OR, with 'C' get the current filename.
*/
void GcodeSuite::M27() {
if (parser.seen('C')) {
if (parser.seen_test('C')) {
SERIAL_ECHOPGM("Current file: ");
card.printFilename();
card.printSelectedFilename();
return;
}

2
Marlin/src/gcode/sd/M32.cpp

@ -49,7 +49,7 @@ void GcodeSuite::M32() {
if (parser.seenval('S')) card.setIndex(parser.value_long());
card.startFileprint();
card.startOrResumeFilePrinting();
// Procedure calls count as normal print time.
if (!call_procedure) startOrResumeJob();

2
Marlin/src/gcode/sd/M524.cpp

@ -33,7 +33,7 @@
void GcodeSuite::M524() {
if (IS_SD_PRINTING())
card.flag.abort_sd_printing = true;
card.abortFilePrintSoon();
else if (card.isMounted())
card.closefile();

2
Marlin/src/gcode/sd/M808.cpp

@ -44,7 +44,7 @@ void GcodeSuite::M808() {
// Allowed to go into the queue for logging purposes.
// M808 K sent from the host to cancel all loops
if (parser.seen('K')) repeat.cancel();
if (parser.seen_test('K')) repeat.cancel();
}

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

@ -68,7 +68,7 @@ void GcodeSuite::M106() {
if (t > 0) return thermalManager.set_temp_fan_speed(pfan, t);
#endif
const uint16_t dspeed = parser.seen('A') ? thermalManager.fan_speed[active_extruder] : 255;
const uint16_t dspeed = parser.seen_test('A') ? thermalManager.fan_speed[active_extruder] : 255;
uint16_t speed = dspeed;

2
Marlin/src/gcode/temp/M303.cpp

@ -47,7 +47,7 @@
void GcodeSuite::M303() {
#if ANY(PID_DEBUG, PID_BED_DEBUG, PID_CHAMBER_DEBUG)
if (parser.seen('D')) {
if (parser.seen_test('D')) {
thermalManager.pid_debug_flag ^= true;
SERIAL_ECHO_START();
SERIAL_ECHOPGM("PID Debug ");

44
Marlin/src/inc/Conditionals_LCD.h

@ -26,8 +26,8 @@
* Conditionals that need to be set before Configuration_adv.h or pins.h
*/
// MKS_LCD12864 is a variant of MKS_MINI_12864
#if ENABLED(MKS_LCD12864)
// MKS_LCD12864A/B is a variant of MKS_MINI_12864
#if EITHER(MKS_LCD12864A, MKS_LCD12864B)
#define MKS_MINI_12864
#endif
@ -617,9 +617,9 @@
// Helper macros for extruder and hotend arrays
#define HOTEND_LOOP() for (int8_t e = 0; e < HOTENDS; e++)
#define ARRAY_BY_EXTRUDERS(V...) ARRAY_N(EXTRUDERS, V)
#define ARRAY_BY_EXTRUDERS1(v1) ARRAY_BY_EXTRUDERS(v1, v1, v1, v1, v1, v1, v1, v1)
#define ARRAY_BY_EXTRUDERS1(v1) ARRAY_N_1(EXTRUDERS, v1)
#define ARRAY_BY_HOTENDS(V...) ARRAY_N(HOTENDS, V)
#define ARRAY_BY_HOTENDS1(v1) ARRAY_BY_HOTENDS(v1, v1, v1, v1, v1, v1, v1, v1)
#define ARRAY_BY_HOTENDS1(v1) ARRAY_N_1(HOTENDS, v1)
#if ENABLED(SWITCHING_EXTRUDER) && (DISABLED(SWITCHING_NOZZLE) || SWITCHING_EXTRUDER_SERVO_NR != SWITCHING_NOZZLE_SERVO_NR)
#define DO_SWITCH_EXTRUDER 1
@ -870,6 +870,7 @@
#if !HAS_LEVELING
#undef RESTORE_LEVELING_AFTER_G28
#undef ENABLE_LEVELING_AFTER_G28
#undef G29_RETRY_AND_RECOVER
#endif
#if !HAS_LEVELING || EITHER(MESH_BED_LEVELING, AUTO_BED_LEVELING_UBL)
#undef PROBE_MANUALLY
@ -955,15 +956,19 @@
// Serial Port Info
//
#ifdef SERIAL_PORT_2
#define NUM_SERIAL 2
#define HAS_MULTI_SERIAL 1
#ifdef SERIAL_PORT_3
#define NUM_SERIAL 3
#else
#define NUM_SERIAL 2
#endif
#elif defined(SERIAL_PORT)
#define NUM_SERIAL 1
#else
#define NUM_SERIAL 0
#undef BAUD_RATE_GCODE
#endif
#if SERIAL_PORT == -1 || SERIAL_PORT_2 == -1
#if SERIAL_PORT == -1 || SERIAL_PORT_2 == -1 || SERIAL_PORT_3 == -1
#define HAS_USB_SERIAL 1
#endif
#if SERIAL_PORT_2 == -2
@ -1127,6 +1132,9 @@
#define TFT_DEFAULT_ORIENTATION (TFT_EXCHANGE_XY)
#define TFT_RES_1024x600
#define TFT_INTERFACE_LTDC
#if ENABLED(TOUCH_SCREEN)
#define TFT_TOUCH_DEVICE_GT911
#endif
#elif ENABLED(TFT_GENERIC)
#define TFT_DEFAULT_ORIENTATION (TFT_EXCHANGE_XY | TFT_INVERT_X | TFT_INVERT_Y)
#if NONE(TFT_RES_320x240, TFT_RES_480x272, TFT_RES_480x320)
@ -1215,16 +1223,30 @@
#define HAS_UI_1024x600 1
#endif
#if ANY(HAS_UI_320x240, HAS_UI_480x320, HAS_UI_480x272)
#define LCD_HEIGHT TERN(TOUCH_SCREEN, 6, 7) // Fewer lines with touch buttons onscreen
#define LCD_HEIGHT TERN(TOUCH_SCREEN, 6, 7) // Fewer lines with touch buttons onscreen
#elif HAS_UI_1024x600
#define LCD_HEIGHT TERN(TOUCH_SCREEN, 12, 13) // Fewer lines with touch buttons onscreen
#endif
// This emulated DOGM has 'touch/xpt2046', not 'tft/xpt2046'
#if ENABLED(TOUCH_SCREEN) && !HAS_GRAPHICAL_TFT
#undef TOUCH_SCREEN
#if ENABLED(TFT_CLASSIC_UI)
#define HAS_TOUCH_BUTTONS 1
#if ENABLED(TOUCH_SCREEN)
#if NONE(TFT_TOUCH_DEVICE_GT911, TFT_TOUCH_DEVICE_XPT2046)
#define TFT_TOUCH_DEVICE_XPT2046 // ADS7843/XPT2046 ADC Touchscreen such as ILI9341 2.8
#endif
#if ENABLED(TFT_TOUCH_DEVICE_GT911) // GT911 Capacitive touch screen such as BIQU_BX_TFT70
#undef TOUCH_SCREEN_CALIBRATION
#undef TOUCH_CALIBRATION_AUTO_SAVE
#endif
#if !HAS_GRAPHICAL_TFT
#undef TOUCH_SCREEN
#if ENABLED(TFT_CLASSIC_UI)
#define HAS_TOUCH_BUTTONS 1
#if ENABLED(TFT_TOUCH_DEVICE_GT911)
#define HAS_CAP_TOUCH_BUTTONS 1
#else
#define HAS_RES_TOUCH_BUTTONS 1
#endif
#endif
#endif
#endif

4
Marlin/src/inc/Conditionals_adv.h

@ -371,13 +371,13 @@
#endif
// Full Touch Screen needs 'tft/xpt2046'
#if EITHER(TOUCH_SCREEN, HAS_TFT_LVGL_UI)
#if EITHER(TFT_TOUCH_DEVICE_XPT2046, HAS_TFT_LVGL_UI)
#define HAS_TFT_XPT2046 1
#endif
// Touch Screen or "Touch Buttons" need XPT2046 pins
// but they use different components
#if EITHER(HAS_TFT_XPT2046, HAS_TOUCH_BUTTONS)
#if HAS_TFT_XPT2046 || HAS_RES_TOUCH_BUTTONS
#define NEED_TOUCH_PINS 1
#endif

63
Marlin/src/inc/Conditionals_post.h

@ -270,7 +270,7 @@
#elif ENABLED(AZSMZ_12864)
#define _LCD_CONTRAST_MIN 120
#define _LCD_CONTRAST_INIT 190
#elif ENABLED(MKS_LCD12864)
#elif EITHER(MKS_LCD12864A, MKS_LCD12864B)
#define _LCD_CONTRAST_MIN 120
#define _LCD_CONTRAST_INIT 205
#elif EITHER(MKS_MINI_12864, ENDER2_STOCKDISPLAY)
@ -330,11 +330,6 @@
*/
#if ENABLED(SDSUPPORT)
// Extender cable doesn't support SD_DETECT_PIN
#if ENABLED(NO_SD_DETECT)
#undef SD_DETECT_PIN
#endif
#if HAS_SD_HOST_DRIVE && SD_CONNECTION_IS(ONBOARD)
//
// The external SD card is not used. Hardware SPI is used to access the card.
@ -345,18 +340,20 @@
#define HAS_SHARED_MEDIA 1
#endif
#if PIN_EXISTS(SD_DETECT)
#if HAS_LCD_MENU && (SD_CONNECTION_IS(LCD) || !defined(SDCARD_CONNECTION))
#undef SD_DETECT_STATE
#if ENABLED(ELB_FULL_GRAPHIC_CONTROLLER)
#define SD_DETECT_STATE HIGH
#endif
#endif
#ifndef SD_DETECT_STATE
// Set SD_DETECT_STATE based on hardware if not overridden
#if PIN_EXISTS(SD_DETECT) && !defined(SD_DETECT_STATE)
#if BOTH(HAS_LCD_MENU, ELB_FULL_GRAPHIC_CONTROLLER) && (SD_CONNECTION_IS(LCD) || !defined(SDCARD_CONNECTION))
#define SD_DETECT_STATE HIGH
#else
#define SD_DETECT_STATE LOW
#endif
#endif
// Extender cable doesn't support SD_DETECT_PIN
#if ENABLED(NO_SD_DETECT)
#undef SD_DETECT_PIN
#endif
#if DISABLED(USB_FLASH_DRIVE_SUPPORT) || BOTH(MULTI_VOLUME, VOLUME_SD_ONBOARD)
#if ENABLED(SDIO_SUPPORT)
#define NEED_SD2CARD_SDIO 1
@ -1859,6 +1856,7 @@
// Flag the indexed hardware serial ports in use
#define CONF_SERIAL_IS(N) ( (defined(SERIAL_PORT) && SERIAL_PORT == N) \
|| (defined(SERIAL_PORT_2) && SERIAL_PORT_2 == N) \
|| (defined(SERIAL_PORT_3) && SERIAL_PORT_3 == N) \
|| (defined(MMU2_SERIAL_PORT) && MMU2_SERIAL_PORT == N) \
|| (defined(LCD_SERIAL_PORT) && LCD_SERIAL_PORT == N) )
@ -1949,7 +1947,6 @@
#undef _SERIAL_ID
#undef _TMC_UART_IS
#undef TMC_UART_IS
#undef CONF_SERIAL_IS
#undef ANY_SERIAL_IS
//
@ -1983,15 +1980,6 @@
#if _HAS_STOP(Z,MAX)
#define HAS_Z_MAX 1
#endif
#if _HAS_STOP(X,STOP)
#define HAS_X_STOP 1
#endif
#if _HAS_STOP(Y,STOP)
#define HAS_Y_STOP 1
#endif
#if _HAS_STOP(Z,STOP)
#define HAS_Z_STOP 1
#endif
#if PIN_EXISTS(X2_MIN)
#define HAS_X2_MIN 1
#endif
@ -2022,10 +2010,17 @@
#if PIN_EXISTS(Z4_MAX)
#define HAS_Z4_MAX 1
#endif
#if HAS_CUSTOM_PROBE_PIN && PIN_EXISTS(Z_MIN_PROBE)
#if BOTH(HAS_BED_PROBE, HAS_CUSTOM_PROBE_PIN) && PIN_EXISTS(Z_MIN_PROBE)
#define HAS_Z_MIN_PROBE_PIN 1
#endif
#undef IS_PROBE_PIN
#undef IS_X2_ENDSTOP
#undef IS_Y2_ENDSTOP
#undef IS_Z2_ENDSTOP
#undef IS_Z3_ENDSTOP
#undef IS_Z4_ENDSTOP
//
// ADC Temp Sensors (Thermistor or Thermocouple with amplifier ADC interface)
//
@ -2236,7 +2231,7 @@
#if !HAS_TEMP_SENSOR
#undef AUTO_REPORT_TEMPERATURES
#endif
#if EITHER(AUTO_REPORT_TEMPERATURES, AUTO_REPORT_SD_STATUS)
#if ANY(AUTO_REPORT_TEMPERATURES, AUTO_REPORT_SD_STATUS, AUTO_REPORT_POSITION)
#define HAS_AUTO_REPORTING 1
#endif
@ -2323,12 +2318,22 @@
#endif
// User Interface
#if PIN_EXISTS(HOME)
#define HAS_HOME 1
#if ENABLED(FREEZE_FEATURE)
#if !PIN_EXISTS(FREEZE) && PIN_EXISTS(KILL)
#define FREEZE_PIN KILL_PIN
#endif
#if PIN_EXISTS(FREEZE)
#define HAS_FREEZE_PIN 1
#endif
#else
#undef FREEZE_PIN
#endif
#if PIN_EXISTS(KILL)
#if PIN_EXISTS(KILL) && TERN1(FREEZE_FEATURE, KILL_PIN != FREEZE_PIN)
#define HAS_KILL 1
#endif
#if PIN_EXISTS(HOME)
#define HAS_HOME 1
#endif
#if PIN_EXISTS(SUICIDE)
#define HAS_SUICIDE 1
#endif

2
Marlin/src/inc/MarlinConfigPre.h

@ -34,8 +34,8 @@
#include "../HAL/platforms.h"
#endif
#include "../core/boards.h"
#include "../core/macros.h"
#include "../core/boards.h"
#include "../../Configuration.h"
#ifdef CUSTOM_VERSION_FILE

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

Loading…
Cancel
Save