Browse Source

Merge branch '2.0.x' into vanilla_fb_2.0.x

2.0.9.2 update
vanilla_fb_2.0.x
Sergey 3 years ago
parent
commit
faa04e9d7e
  1. 1
      .github/workflows/test-builds.yml
  2. 102
      Marlin/Configuration.h
  3. 140
      Marlin/Configuration_adv.h
  4. 4
      Marlin/Version.h
  5. 13
      Marlin/src/HAL/AVR/HAL.h
  6. 3
      Marlin/src/HAL/AVR/HAL_SPI.cpp
  7. 26
      Marlin/src/HAL/AVR/MarlinSPI.h
  8. 10
      Marlin/src/HAL/AVR/fastio.cpp
  9. 4
      Marlin/src/HAL/AVR/inc/SanityCheck.h
  10. 20
      Marlin/src/HAL/AVR/pinsDebug.h
  11. 3
      Marlin/src/HAL/AVR/pinsDebug_Teensyduino.h
  12. 3
      Marlin/src/HAL/AVR/pinsDebug_plus_70.h
  13. 4
      Marlin/src/HAL/AVR/u8g_com_HAL_AVR_sw_spi.cpp
  14. 16
      Marlin/src/HAL/DUE/HAL_SPI.cpp
  15. 26
      Marlin/src/HAL/DUE/MarlinSPI.h
  16. 1
      Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_shared_hw_spi.cpp
  17. 34
      Marlin/src/HAL/DUE/eeprom_flash.cpp
  18. 6
      Marlin/src/HAL/DUE/pinsDebug.h
  19. 26
      Marlin/src/HAL/ESP32/MarlinSPI.h
  20. 3
      Marlin/src/HAL/ESP32/spi_pins.h
  21. 2
      Marlin/src/HAL/ESP32/wifi.cpp
  22. 6
      Marlin/src/HAL/LINUX/HAL.h
  23. 26
      Marlin/src/HAL/LINUX/MarlinSPI.h
  24. 2
      Marlin/src/HAL/LINUX/inc/SanityCheck.h
  25. 4
      Marlin/src/HAL/LINUX/main.cpp
  26. 4
      Marlin/src/HAL/LINUX/pinsDebug.h
  27. 22
      Marlin/src/HAL/LPC1768/HAL.h
  28. 2
      Marlin/src/HAL/LPC1768/MarlinSerial.h
  29. 42
      Marlin/src/HAL/LPC1768/eeprom_sdcard.cpp
  30. 2
      Marlin/src/HAL/LPC1768/inc/SanityCheck.h
  31. 12
      Marlin/src/HAL/LPC1768/pinsDebug.h
  32. 45
      Marlin/src/HAL/LPC1768/tft/tft_spi.cpp
  33. 6
      Marlin/src/HAL/NATIVE_SIM/HAL.h
  34. 2
      Marlin/src/HAL/NATIVE_SIM/inc/SanityCheck.h
  35. 2
      Marlin/src/HAL/NATIVE_SIM/pinsDebug.h
  36. 26
      Marlin/src/HAL/SAMD51/MarlinSPI.h
  37. 1
      Marlin/src/HAL/SAMD51/QSPIFlash.h
  38. 12
      Marlin/src/HAL/SAMD51/endstop_interrupts.h
  39. 3
      Marlin/src/HAL/SAMD51/pinsDebug.h
  40. 14
      Marlin/src/HAL/STM32/HAL.h
  41. 1
      Marlin/src/HAL/STM32/MarlinSPI.cpp
  42. 4
      Marlin/src/HAL/STM32/MarlinSerial.cpp
  43. 3
      Marlin/src/HAL/STM32/MarlinSerial.h
  44. 1
      Marlin/src/HAL/STM32/Sd2Card_sdio_stm32duino.cpp
  45. 1
      Marlin/src/HAL/STM32/eeprom_bl24cxx.cpp
  46. 16
      Marlin/src/HAL/STM32/eeprom_flash.cpp
  47. 1
      Marlin/src/HAL/STM32/eeprom_if_iic.cpp
  48. 1
      Marlin/src/HAL/STM32/eeprom_sdcard.cpp
  49. 1
      Marlin/src/HAL/STM32/fast_pwm.cpp
  50. 2
      Marlin/src/HAL/STM32/inc/SanityCheck.h
  51. 6
      Marlin/src/HAL/STM32/pinsDebug.h
  52. 3
      Marlin/src/HAL/STM32/spi_pins.h
  53. 1
      Marlin/src/HAL/STM32/tft/tft_fsmc.cpp
  54. 4
      Marlin/src/HAL/STM32/tft/tft_ltdc.cpp
  55. 1
      Marlin/src/HAL/STM32/tft/tft_spi.cpp
  56. 1
      Marlin/src/HAL/STM32/tft/xpt2046.cpp
  57. 7
      Marlin/src/HAL/STM32/usb_host.cpp
  58. 4
      Marlin/src/HAL/STM32/usb_serial.cpp
  59. 3
      Marlin/src/HAL/STM32/usb_serial.h
  60. 1
      Marlin/src/HAL/STM32/watchdog.cpp
  61. 2
      Marlin/src/HAL/STM32F1/HAL.cpp
  62. 14
      Marlin/src/HAL/STM32F1/HAL.h
  63. 4
      Marlin/src/HAL/STM32F1/dogm/u8g_com_stm32duino_swspi.cpp
  64. 5
      Marlin/src/HAL/STM32F1/eeprom_wired.cpp
  65. 2
      Marlin/src/HAL/STM32F1/onboard_sd.cpp
  66. 4
      Marlin/src/HAL/STM32F1/pinsDebug.h
  67. 3
      Marlin/src/HAL/STM32F1/spi_pins.h
  68. 48
      Marlin/src/HAL/STM32F1/tft/tft_spi.cpp
  69. 6
      Marlin/src/HAL/TEENSY31_32/HAL.h
  70. 26
      Marlin/src/HAL/TEENSY31_32/MarlinSPI.h
  71. 4
      Marlin/src/HAL/TEENSY31_32/eeprom.cpp
  72. 6
      Marlin/src/HAL/TEENSY35_36/HAL.h
  73. 26
      Marlin/src/HAL/TEENSY35_36/MarlinSPI.h
  74. 3
      Marlin/src/HAL/TEENSY35_36/pinsDebug.h
  75. 6
      Marlin/src/HAL/TEENSY40_41/HAL.h
  76. 26
      Marlin/src/HAL/TEENSY40_41/MarlinSPI.h
  77. 4
      Marlin/src/HAL/TEENSY40_41/pinsDebug.h
  78. 7
      Marlin/src/HAL/shared/Delay.cpp
  79. 12
      Marlin/src/HAL/shared/eeprom_if_spi.cpp
  80. 134
      Marlin/src/MarlinCore.cpp
  81. 34
      Marlin/src/MarlinCore.h
  82. 92
      Marlin/src/core/boards.h
  83. 12
      Marlin/src/core/bug_on.h
  84. 23
      Marlin/src/core/debug_out.h
  85. 56
      Marlin/src/core/language.h
  86. 65
      Marlin/src/core/macros.h
  87. 62
      Marlin/src/core/multi_language.h
  88. 2
      Marlin/src/core/serial.cpp
  89. 38
      Marlin/src/core/serial.h
  90. 8
      Marlin/src/core/types.h
  91. 12
      Marlin/src/core/utility.cpp
  92. 10
      Marlin/src/feature/backlash.cpp
  93. 2
      Marlin/src/feature/backlash.h
  94. 10
      Marlin/src/feature/bedlevel/abl/abl.cpp
  95. 2
      Marlin/src/feature/bedlevel/ubl/ubl.cpp
  96. 8
      Marlin/src/feature/bedlevel/ubl/ubl.h
  97. 68
      Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp
  98. 3
      Marlin/src/feature/bedlevel/ubl/ubl_motion.cpp
  99. 14
      Marlin/src/feature/binary_stream.h
  100. 8
      Marlin/src/feature/bltouch.cpp

1
.github/workflows/test-builds.yml

@ -97,6 +97,7 @@ jobs:
- REMRAM_V1
- BTT_SKR_SE_BX
- chitu_f103
- Index_Mobo_Rev03
# Put lengthy tests last

102
Marlin/Configuration.h

@ -35,7 +35,7 @@
*
* Advanced settings can be found in Configuration_adv.h
*/
#define CONFIGURATION_H_VERSION 02000901
#define CONFIGURATION_H_VERSION 02000902
//===========================================================================
//============================= Getting Started =============================
@ -342,6 +342,7 @@
#define MIXING_VIRTUAL_TOOLS 16 // Use the Virtual Tool method with M163 and M164
//#define DIRECT_MIXING_IN_G1 // Allow ABCDHI mix factors in G1 movement commands
//#define GRADIENT_MIX // Support for gradient mixing with M166 and LCD
//#define MIXING_PRESETS // Assign 8 default V-tool presets for 2 or 3 MIXING_STEPPERS
#if ENABLED(GRADIENT_MIX)
//#define GRADIENT_VTOOL // Add M166 T to use a V-tool index as a Gradient alias
#endif
@ -366,6 +367,9 @@
//#define PSU_NAME "Power Supply"
#if ENABLED(PSU_CONTROL)
//#define MKS_PWC // Using the MKS PWC add-on
//#define PS_OFF_CONFIRM // Confirm dialog when power off
//#define PS_OFF_SOUND // Beep 1s when power off
#define PSU_ACTIVE_STATE LOW // Set 'LOW' for ATX, 'HIGH' for X-Box
//#define PSU_DEFAULT_OFF // Keep power off until enabled directly with M80
@ -449,6 +453,7 @@
* 67 : 500 SliceEngineering 450°C Thermistor
* 70 : 100 bq Hephestos 2
* 75 : 100 Generic Silicon Heat Pad with NTC100K MGB18-104F39050L32
* 2000 : 100 Ultimachine Rambo TDK NTCG104LH104KT1 NTC100K motherboard Thermistor
*
* Analog Thermistors - 1 pullup - Atypical, and requires changing out the 4.7 pullup for 1.
* ------- (but gives greater accuracy and more stable PID)
@ -472,7 +477,7 @@
* NOTE: ADC pins are not 5V tolerant. Not recommended because it's possible to damage the CPU by going over 500°C.
* 201 : Pt100 with circuit in Overlord, similar to Ultimainboard V2.x
*
* Custom/Dummy/Other Thermos
* Custom/Dummy/Other Thermal Sensors
* ------
* 0 : not used
* 1000 : Custom - Specify parameters in Configuration_adv.h
@ -494,6 +499,7 @@
#define TEMP_SENSOR_PROBE 0
#define TEMP_SENSOR_CHAMBER 0
#define TEMP_SENSOR_COOLER 0
#define TEMP_SENSOR_BOARD 0
#define TEMP_SENSOR_REDUNDANT 0
// Dummy thermistor constant temperature readings, for use with 998 and 999
@ -526,17 +532,11 @@
* the print will be aborted. Whichever sensor is selected will have its normal functions disabled; i.e. selecting
* the Bed sensor (-1) will disable bed heating/monitoring.
*
* Use the following to select temp sensors:
* -5 : Cooler
* -4 : Probe
* -3 : not used
* -2 : Chamber
* -1 : Bed
* 0-7 : E0 through E7
* For selecting source/target use: COOLER, PROBE, BOARD, CHAMBER, BED, E0, E1, E2, E3, E4, E5, E6, E7
*/
#if TEMP_SENSOR_REDUNDANT
#define TEMP_SENSOR_REDUNDANT_SOURCE 1 // The sensor that will provide the redundant reading.
#define TEMP_SENSOR_REDUNDANT_TARGET 0 // The sensor that we are providing a redundant reading for.
#define TEMP_SENSOR_REDUNDANT_SOURCE E1 // The sensor that will provide the redundant reading.
#define TEMP_SENSOR_REDUNDANT_TARGET E0 // The sensor that we are providing a redundant reading for.
#define TEMP_SENSOR_REDUNDANT_MAX_DIFF 10 // (°C) Temperature difference that will trigger a print abort.
#endif
@ -595,11 +595,11 @@
// Set/get with gcode: M301 E[extruder number, 0-2]
#if ENABLED(PID_PARAMS_PER_HOTEND)
// Specify between 1 and HOTENDS values per array.
// If fewer than EXTRUDER values are provided, the last element will be repeated.
#define DEFAULT_Kp_LIST { 22.20, 20.0 }
#define DEFAULT_Ki_LIST { 1.08, 1.0 }
#define DEFAULT_Kd_LIST { 114.00, 112.0 }
// Specify up to one value per hotend here, according to your setup.
// If there are fewer values, the last one applies to the remaining hotends.
#define DEFAULT_Kp_LIST { 22.20, 22.20 }
#define DEFAULT_Ki_LIST { 1.08, 1.08 }
#define DEFAULT_Kd_LIST { 114.00, 114.00 }
#else
#define DEFAULT_Kp 17.04
#define DEFAULT_Ki 1.31
@ -757,6 +757,16 @@
//#define COREZY
//#define MARKFORGED_XY // MarkForged. See https://reprap.org/forum/read.php?152,504042
// Enable for a belt style printer with endless "Z" motion
//#define BELTPRINTER
// Enable for Polargraph Kinematics
//#define POLARGRAPH
#if ENABLED(POLARGRAPH)
#define POLARGRAPH_MAX_BELT_LEN 1035.0
#define POLAR_SEGMENTS_PER_SECOND 5
#endif
//===========================================================================
//============================== Endstop Settings ===========================
//===========================================================================
@ -783,18 +793,18 @@
#define ENDSTOPPULLUPS
#if DISABLED(ENDSTOPPULLUPS)
// Disable ENDSTOPPULLUPS to set pullups individually
//#define ENDSTOPPULLUP_XMAX
//#define ENDSTOPPULLUP_YMAX
//#define ENDSTOPPULLUP_ZMAX
//#define ENDSTOPPULLUP_IMAX
//#define ENDSTOPPULLUP_JMAX
//#define ENDSTOPPULLUP_KMAX
//#define ENDSTOPPULLUP_XMIN
//#define ENDSTOPPULLUP_YMIN
//#define ENDSTOPPULLUP_ZMIN
//#define ENDSTOPPULLUP_IMIN
//#define ENDSTOPPULLUP_JMIN
//#define ENDSTOPPULLUP_KMIN
//#define ENDSTOPPULLUP_XMAX
//#define ENDSTOPPULLUP_YMAX
//#define ENDSTOPPULLUP_ZMAX
//#define ENDSTOPPULLUP_IMAX
//#define ENDSTOPPULLUP_JMAX
//#define ENDSTOPPULLUP_KMAX
//#define ENDSTOPPULLUP_ZMIN_PROBE
#endif
@ -802,18 +812,18 @@
//#define ENDSTOPPULLDOWNS
#if DISABLED(ENDSTOPPULLDOWNS)
// Disable ENDSTOPPULLDOWNS to set pulldowns individually
//#define ENDSTOPPULLDOWN_XMAX
//#define ENDSTOPPULLDOWN_YMAX
//#define ENDSTOPPULLDOWN_ZMAX
//#define ENDSTOPPULLDOWN_IMAX
//#define ENDSTOPPULLDOWN_JMAX
//#define ENDSTOPPULLDOWN_KMAX
//#define ENDSTOPPULLDOWN_XMIN
//#define ENDSTOPPULLDOWN_YMIN
//#define ENDSTOPPULLDOWN_ZMIN
//#define ENDSTOPPULLDOWN_IMIN
//#define ENDSTOPPULLDOWN_JMIN
//#define ENDSTOPPULLDOWN_KMIN
//#define ENDSTOPPULLDOWN_XMAX
//#define ENDSTOPPULLDOWN_YMAX
//#define ENDSTOPPULLDOWN_ZMAX
//#define ENDSTOPPULLDOWN_IMAX
//#define ENDSTOPPULLDOWN_JMAX
//#define ENDSTOPPULLDOWN_KMAX
//#define ENDSTOPPULLDOWN_ZMIN_PROBE
#endif
@ -2071,10 +2081,10 @@
*
* Select the language to display on the LCD. These languages are available:
*
* en, an, bg, ca, cz, da, de, el, el_gr, es, eu, fi, fr, gl, hr, hu, it,
* en, an, bg, ca, cz, da, de, el, el_CY, es, eu, fi, fr, gl, hr, hu, it,
* jp_kana, ko_KR, nl, pl, pt, pt_br, ro, ru, sk, sv, tr, uk, vi, zh_CN, zh_TW
*
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cz':'Czech', 'da':'Danish', 'de':'German', 'el':'Greek', 'el_gr':'Greek (Greece)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'hu':'Hungarian', 'it':'Italian', 'jp_kana':'Japanese', 'ko_KR':'Korean (South Korea)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt_br':'Portuguese (Brazilian)', 'ro':'Romanian', 'ru':'Russian', 'sk':'Slovak', 'sv':'Swedish', 'tr':'Turkish', 'uk':'Ukrainian', 'vi':'Vietnamese', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Traditional)' }
* :{ 'en':'English', 'an':'Aragonese', 'bg':'Bulgarian', 'ca':'Catalan', 'cz':'Czech', 'da':'Danish', 'de':'German', 'el':'Greek (Greece)', 'el_CY':'Greek (Cyprus)', 'es':'Spanish', 'eu':'Basque-Euskera', 'fi':'Finnish', 'fr':'French', 'gl':'Galician', 'hr':'Croatian', 'hu':'Hungarian', 'it':'Italian', 'jp_kana':'Japanese', 'ko_KR':'Korean (South Korea)', 'nl':'Dutch', 'pl':'Polish', 'pt':'Portuguese', 'pt_br':'Portuguese (Brazilian)', 'ro':'Romanian', 'ru':'Russian', 'sk':'Slovak', 'sv':'Swedish', 'tr':'Turkish', 'uk':'Ukrainian', 'vi':'Vietnamese', 'zh_CN':'Chinese (Simplified)', 'zh_TW':'Chinese (Traditional)' }
*/
#define LCD_LANGUAGE en
@ -2186,6 +2196,7 @@
// Add individual axis homing items (Home X, Home Y, and Home Z) to the LCD menu.
//
#define INDIVIDUAL_AXIS_HOMING_MENU
//#define INDIVIDUAL_AXIS_HOMING_SUBMENU
//
// SPEAKER/BUZZER
@ -2591,10 +2602,15 @@
// - Download https://github.com/makerbase-mks/MKS-H43
// - Copy the downloaded DWIN_SET folder to the SD card.
//
// RELOADED (T5UID1)
// - Download https://github.com/Desuuuu/DGUS-reloaded/releases
// - Copy the downloaded DWIN_SET folder to the SD card.
//
//#define DGUS_LCD_UI_ORIGIN
//#define DGUS_LCD_UI_FYSETC
//#define DGUS_LCD_UI_HIPRECY
//#define DGUS_LCD_UI_MKS
//#define DGUS_LCD_UI_RELOADED
#if ENABLED(DGUS_LCD_UI_MKS)
#define USE_MKS_GREEN_UI
#endif
@ -2737,6 +2753,7 @@
//#define TFT_RES_320x240
//#define TFT_RES_480x272
//#define TFT_RES_480x320
//#define TFT_RES_1024x600
#endif
/**
@ -2776,6 +2793,22 @@
//
//#define DWIN_CREALITY_LCD
//
// Ender-3 v2 OEM display, enhanced.
//
//#define DWIN_CREALITY_LCD_ENHANCED
//
// Ender-3 v2 OEM display with enhancements by Jacob Myers
//
//#define DWIN_CREALITY_LCD_JYERSUI
//
// MarlinUI for Creality's DWIN display (and others)
//
//#define DWIN_MARLINUI_PORTRAIT
//#define DWIN_MARLINUI_LANDSCAPE
//
// Touch Screen Settings
//
@ -2784,6 +2817,8 @@
#define BUTTON_DELAY_EDIT 50 // (ms) Button repeat delay for edit screens
#define BUTTON_DELAY_MENU 250 // (ms) Button repeat delay for menus
//#define TOUCH_IDLE_SLEEP 300 // (secs) Turn off the TFT backlight if set (5mn)
#define TOUCH_SCREEN_CALIBRATION
#define TOUCH_CALIBRATION_X 17880
@ -2938,9 +2973,9 @@
* Set this manually if there are extra servos needing manual control.
* Set to 0 to turn off servo support.
*/
//#define NUM_SERVOS 3 // Servo index starts with 0 for M280 command
//#define NUM_SERVOS 3 // Note: Servo index starts with 0 for M280-M282 commands
// (ms) Delay before the next move will start, to give the servo time to reach its target angle.
// (ms) Delay before the next move will start, to give the servo time to reach its target angle.
// 300ms is a good value but you can try less delay.
// If the servo can't reach the requested position, increase it.
#define SERVO_DELAY { 300 }
@ -2950,3 +2985,6 @@
// Edit servo angles with M281 and save to EEPROM with M500
//#define EDITABLE_SERVO_ANGLES
// Disable servo with M282 to reduce power consumption, noise, and heat when not in use
//#define SERVO_DETACH_GCODE

140
Marlin/Configuration_adv.h

@ -30,7 +30,7 @@
*
* Basic settings can be found in Configuration.h
*/
#define CONFIGURATION_ADV_H_VERSION 02000901
#define CONFIGURATION_ADV_H_VERSION 02000902
//===========================================================================
//============================= Thermal Settings ============================
@ -125,6 +125,12 @@
#define PROBE_BETA 3950 // Beta value
#endif
#if TEMP_SENSOR_BOARD == 1000
#define BOARD_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor
#define BOARD_RESISTANCE_25C_OHMS 100000 // Resistance at 25C
#define BOARD_BETA 3950 // Beta value
#endif
#if TEMP_SENSOR_REDUNDANT == 1000
#define REDUNDANT_PULLUP_RESISTOR_OHMS 4700 // Pullup resistor
#define REDUNDANT_RESISTANCE_25C_OHMS 100000 // Resistance at 25C
@ -224,6 +230,18 @@
#endif
#endif
//
// Motherboard Sensor options
//
#if TEMP_SENSOR_BOARD
#define THERMAL_PROTECTION_BOARD // Halt the printer if the board sensor leaves the temp range below.
#define BOARD_MINTEMP 8 // (°C)
#define BOARD_MAXTEMP 70 // (°C)
#ifndef TEMP_BOARD_PIN
//#define TEMP_BOARD_PIN -1 // Board temp sensor pin, if not set in pins file.
#endif
#endif
//
// Laser Coolant Flow Meter
//
@ -480,16 +498,20 @@
*/
//#define USE_CONTROLLER_FAN
#if ENABLED(USE_CONTROLLER_FAN)
//#define CONTROLLER_FAN_PIN -1 // Set a custom pin for the controller fan
//#define CONTROLLER_FAN_USE_Z_ONLY // With this option only the Z axis is considered
//#define CONTROLLER_FAN_IGNORE_Z // Ignore Z stepper. Useful when stepper timeout is disabled.
#define CONTROLLERFAN_SPEED_MIN 0 // (0-255) Minimum speed. (If set below this value the fan is turned off.)
#define CONTROLLERFAN_SPEED_ACTIVE 255 // (0-255) Active speed, used when any motor is enabled
#define CONTROLLERFAN_SPEED_IDLE 0 // (0-255) Idle speed, used when motors are disabled
#define CONTROLLERFAN_IDLE_TIME 60 // (seconds) Extra time to keep the fan running after disabling motors
//#define CONTROLLER_FAN_EDITABLE // Enable M710 configurable settings
//#define CONTROLLER_FAN_PIN -1 // Set a custom pin for the controller fan
//#define CONTROLLER_FAN_USE_Z_ONLY // With this option only the Z axis is considered
//#define CONTROLLER_FAN_IGNORE_Z // Ignore Z stepper. Useful when stepper timeout is disabled.
#define CONTROLLERFAN_SPEED_MIN 0 // (0-255) Minimum speed. (If set below this value the fan is turned off.)
#define CONTROLLERFAN_SPEED_ACTIVE 255 // (0-255) Active speed, used when any motor is enabled
#define CONTROLLERFAN_SPEED_IDLE 0 // (0-255) Idle speed, used when motors are disabled
#define CONTROLLERFAN_IDLE_TIME 60 // (seconds) Extra time to keep the fan running after disabling motors
// Use TEMP_SENSOR_BOARD as a trigger for enabling the controller fan
//#define CONTROLLER_FAN_MIN_BOARD_TEMP 40 // (°C) Turn on the fan if the board reaches this temperature
//#define CONTROLLER_FAN_EDITABLE // Enable M710 configurable settings
#if ENABLED(CONTROLLER_FAN_EDITABLE)
#define CONTROLLER_FAN_MENU // Enable the Controller Fan submenu
#define CONTROLLER_FAN_MENU // Enable the Controller Fan submenu
#endif
#endif
@ -1174,7 +1196,7 @@
// @section lcd
#if EITHER(IS_ULTIPANEL, EXTENSIBLE_UI)
#if ANY(HAS_LCD_MENU, EXTENSIBLE_UI, HAS_DWIN_E3V2)
#define MANUAL_FEEDRATE { 50*60, 50*60, 4*60, 2*60 } // (mm/min) Feedrates for manual moves along X, Y, Z, E from panel
#define FINE_MANUAL_MOVE 0.025 // (mm) Smallest manual move (< 0.1mm) applying to Z on most machines
#if IS_ULTIPANEL
@ -1284,7 +1306,7 @@
// LCD Print Progress options
#if EITHER(SDSUPPORT, LCD_SET_PROGRESS_MANUALLY)
#if ANY(HAS_MARLINUI_U8GLIB, EXTENSIBLE_UI, HAS_MARLINUI_HD44780, IS_TFTGLCD_PANEL)
#if ANY(HAS_MARLINUI_U8GLIB, EXTENSIBLE_UI, HAS_MARLINUI_HD44780, IS_TFTGLCD_PANEL, IS_DWIN_MARLINUI)
//#define SHOW_REMAINING_TIME // Display estimated time to completion
#if ENABLED(SHOW_REMAINING_TIME)
//#define USE_M73_REMAINING_TIME // Use remaining time from M73 command instead of estimation
@ -1557,16 +1579,10 @@
* printing performance versus fast display updates.
*/
#if HAS_MARLINUI_U8GLIB
// Show SD percentage next to the progress bar
//#define DOGM_SD_PERCENT
// Save many cycles by drawing a hollow frame or no frame on the Info Screen
//#define XYZ_NO_FRAME
#define XYZ_HOLLOW_FRAME
// Enable to save many cycles by drawing a hollow frame on Menu Screens
#define MENU_HOLLOW_FRAME
// A bigger font is available for edit items. Costs 3120 bytes of PROGMEM.
// Western only. Not available for Cyrillic, Kana, Turkish, Greek, or Chinese.
//#define USE_BIG_EDIT_FONT
@ -1575,9 +1591,6 @@
// Western only. Not available for Cyrillic, Kana, Turkish, Greek, or Chinese.
//#define USE_SMALL_INFOFONT
// Swap the CW/CCW indicators in the graphics overlay
//#define OVERLAY_GFX_REVERSE
/**
* ST7920-based LCDs can emulate a 16 x 4 character display using
* the ST7920 character-generator for very fast screen updates.
@ -1629,6 +1642,17 @@
#endif // HAS_MARLINUI_U8GLIB
#if HAS_MARLINUI_U8GLIB || IS_DWIN_MARLINUI
// Show SD percentage next to the progress bar
//#define SHOW_SD_PERCENT
// Enable to save many cycles by drawing a hollow frame on Menu Screens
#define MENU_HOLLOW_FRAME
// Swap the CW/CCW indicators in the graphics overlay
//#define OVERLAY_GFX_REVERSE
#endif
//
// Additional options for DGUS / DWIN displays
//
@ -1694,7 +1718,7 @@
//
// Specify additional languages for the UI. Default specified by LCD_LANGUAGE.
//
#if ANY(DOGLCD, TFT_COLOR_UI, TOUCH_UI_FTDI_EVE)
#if ANY(DOGLCD, TFT_COLOR_UI, TOUCH_UI_FTDI_EVE, IS_DWIN_MARLINUI)
#define LCD_LANGUAGE_2 ru
//#define LCD_LANGUAGE_3 de
//#define LCD_LANGUAGE_4 es
@ -1713,7 +1737,7 @@
//#define LCD_4DSYSTEMS_4DLCD_FT843 // 4D Systems 4.3" (480x272)
//#define LCD_HAOYU_FT800CB // Haoyu with 4.3" or 5" (480x272)
//#define LCD_HAOYU_FT810CB // Haoyu with 5" (800x480)
//#define LCD_ALEPHOBJECTS_CLCD_UI // Aleph Objects Color LCD UI
//#define LCD_LULZBOT_CLCD_UI // LulzBot Color LCD UI
//#define LCD_FYSETC_TFT81050 // FYSETC with 5" (800x480)
//#define LCD_EVE3_50G // Matrix Orbital 5.0", 800x480, BT815
//#define LCD_EVE2_50G // Matrix Orbital 5.0", 800x480, FT813
@ -1724,8 +1748,8 @@
//#define TOUCH_UI_800x480
// Mappings for boards with a standard RepRapDiscount Display connector
//#define AO_EXP1_PINMAP // AlephObjects CLCD UI EXP1 mapping
//#define AO_EXP2_PINMAP // AlephObjects CLCD UI EXP2 mapping
//#define AO_EXP1_PINMAP // LulzBot CLCD UI EXP1 mapping
//#define AO_EXP2_PINMAP // LulzBot CLCD UI EXP2 mapping
//#define CR10_TFT_PINMAP // Rudolph Riedel's CR10 pin mapping
//#define S6_TFT_PINMAP // FYSETC S6 pin mapping
//#define F6_TFT_PINMAP // FYSETC F6 pin mapping
@ -2028,20 +2052,23 @@
//
// G2/G3 Arc Support
//
#define ARC_SUPPORT // Disable this feature to save ~3226 bytes
#define ARC_SUPPORT // Requires ~3226 bytes
#if ENABLED(ARC_SUPPORT)
#define MM_PER_ARC_SEGMENT 1 // (mm) Length (or minimum length) of each arc segment
//#define ARC_SEGMENTS_PER_R 1 // Max segment length, MM_PER = Min
#define MIN_ARC_SEGMENTS 24 // Minimum number of segments in a complete circle
//#define ARC_SEGMENTS_PER_SEC 50 // Use feedrate to choose segment length (with MM_PER_ARC_SEGMENT as the minimum)
#define N_ARC_CORRECTION 25 // Number of interpolated segments between corrections
//#define ARC_P_CIRCLES // Enable the 'P' parameter to specify complete circles
//#define CNC_WORKSPACE_PLANES // Allow G2/G3 to operate in XY, ZX, or YZ planes
//#define SF_ARC_FIX // Enable only if using SkeinForge with "Arc Point" fillet procedure
#define MIN_ARC_SEGMENT_MM 0.1 // (mm) Minimum length of each arc segment
#define MAX_ARC_SEGMENT_MM 1.0 // (mm) Maximum length of each arc segment
#define MIN_CIRCLE_SEGMENTS 72 // Minimum number of segments in a complete circle
//#define ARC_SEGMENTS_PER_SEC 50 // Use the feedrate to choose the segment length
#define N_ARC_CORRECTION 25 // Number of interpolated segments between corrections
//#define ARC_P_CIRCLES // Enable the 'P' parameter to specify complete circles
//#define SF_ARC_FIX // Enable only if using SkeinForge with "Arc Point" fillet procedure
#endif
// Support for G5 with XYZE destination and IJPQ offsets. Requires ~2666 bytes.
#define BEZIER_CURVE_SUPPORT
// G5 Bézier Curve Support with XYZE destination and IJPQ offsets
#define BEZIER_CURVE_SUPPORT // Requires ~2666 bytes
#if EITHER(ARC_SUPPORT, BEZIER_CURVE_SUPPORT)
//#define CNC_WORKSPACE_PLANES // Allow G2/G3/G5 to operate in XY, ZX, or YZ planes
#endif
/**
* Direct Stepping
@ -2398,6 +2425,8 @@
#define PAUSE_PARK_NOZZLE_TIMEOUT 45 // (seconds) Time limit before the nozzle is turned off for safety.
#define FILAMENT_CHANGE_ALERT_BEEPS 10 // Number of alert beeps to play when a response is needed.
#define PAUSE_PARK_NO_STEPPER_TIMEOUT // Enable for XYZ steppers to stay powered on during filament change.
//#define FILAMENT_CHANGE_RESUME_ON_INSERT // Automatically continue / load filament when runout sensor is triggered again.
//#define PAUSE_REHEAT_FAST_RESUME // Reduce number of waits by not prompting again post-timeout before continuing.
#define PARK_HEAD_ON_PAUSE // Park the nozzle during pause and filament change.
#define HOME_BEFORE_FILAMENT_CHANGE // If needed, home before parking for filament change
@ -3296,11 +3325,13 @@
//#define SPINDLE_FEATURE
//#define LASER_FEATURE
#if EITHER(SPINDLE_FEATURE, LASER_FEATURE)
#define SPINDLE_LASER_ACTIVE_STATE LOW // Set to "HIGH" if the on/off function is active HIGH
#define SPINDLE_LASER_PWM true // Set to "true" if your controller supports setting the speed/power
#define SPINDLE_LASER_PWM_INVERT false // Set to "true" if the speed/power goes up when you want it to go slower
#define SPINDLE_LASER_ACTIVE_STATE LOW // Set to "HIGH" if SPINDLE_LASER_ENA_PIN is active HIGH
#define SPINDLE_LASER_FREQUENCY 2500 // (Hz) Spindle/laser frequency (only on supported HALs: AVR and LPC)
#define SPINDLE_LASER_USE_PWM // Enable if your controller supports setting the speed/power
#if ENABLED(SPINDLE_LASER_USE_PWM)
#define SPINDLE_LASER_PWM_INVERT false // Set to "true" if the speed/power goes up when you want it to go slower
#define SPINDLE_LASER_FREQUENCY 2500 // (Hz) Spindle/laser frequency (only on supported HALs: AVR and LPC)
#endif
//#define AIR_EVACUATION // Cutter Vacuum / Laser Blower motor control with G-codes M10-M11
#if ENABLED(AIR_EVACUATION)
@ -3356,17 +3387,21 @@
* Speed/Power = (PWMDC / 255 * 100 - SPEED_POWER_INTERCEPT) / SPEED_POWER_SLOPE
* PWMDC = (spdpwr - SPEED_POWER_MIN) / (SPEED_POWER_MAX - SPEED_POWER_MIN) / SPEED_POWER_SLOPE
*/
#define SPEED_POWER_INTERCEPT 0 // (%) 0-100 i.e., Minimum power percentage
#define SPEED_POWER_MIN 5000 // (RPM)
#define SPEED_POWER_MAX 30000 // (RPM) SuperPID router controller 0 - 30,000 RPM
#define SPEED_POWER_STARTUP 25000 // (RPM) M3/M4 speed/power default (with no arguments)
#if ENABLED(SPINDLE_LASER_USE_PWM)
#define SPEED_POWER_INTERCEPT 0 // (%) 0-100 i.e., Minimum power percentage
#define SPEED_POWER_MIN 5000 // (RPM)
#define SPEED_POWER_MAX 30000 // (RPM) SuperPID router controller 0 - 30,000 RPM
#define SPEED_POWER_STARTUP 25000 // (RPM) M3/M4 speed/power default (with no arguments)
#endif
#else
#define SPEED_POWER_INTERCEPT 0 // (%) 0-100 i.e., Minimum power percentage
#define SPEED_POWER_MIN 0 // (%) 0-100
#define SPEED_POWER_MAX 100 // (%) 0-100
#define SPEED_POWER_STARTUP 80 // (%) M3/M4 speed/power default (with no arguments)
#if ENABLED(SPINDLE_LASER_USE_PWM)
#define SPEED_POWER_INTERCEPT 0 // (%) 0-100 i.e., Minimum power percentage
#define SPEED_POWER_MIN 0 // (%) 0-100
#define SPEED_POWER_MAX 100 // (%) 0-100
#define SPEED_POWER_STARTUP 80 // (%) M3/M4 speed/power default (with no arguments)
#endif
// Define the minimum and maximum test pulse time values for a laser test fire function
#define LASER_TEST_PULSE_MIN 1 // Used with Laser Control Menu
@ -3800,6 +3835,7 @@
*/
//#define HOST_ACTION_COMMANDS
#if ENABLED(HOST_ACTION_COMMANDS)
//#define HOST_PAUSE_M76
//#define HOST_PROMPT_SUPPORT
//#define HOST_START_MENU_ITEM // Add a menu item that tells the host to start
#endif
@ -4155,6 +4191,14 @@
// Enable Marlin dev mode which adds some special commands
//#define MARLIN_DEV_MODE
#if ENABLED(MARLIN_DEV_MODE)
/**
* D576 - Buffer Monitoring
* To help diagnose print quality issues stemming from empty command buffers.
*/
//#define BUFFER_MONITORING
#endif
/**
* Postmortem Debugging captures misbehavior and outputs the CPU status and backtrace to serial.
* When running in the debugger it will break for debugging. This is useful to help understand

4
Marlin/Version.h

@ -28,7 +28,7 @@
/**
* Marlin release version identifier
*/
//#define SHORT_BUILD_VERSION "2.0.9.1"
//#define SHORT_BUILD_VERSION "2.0.9.2"
/**
* 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-06-27"
//#define STRING_DISTRIBUTION_DATE "2021-09-03"
/**
* Defines a generic printer name to be output to the LCD after booting Marlin.

13
Marlin/src/HAL/AVR/HAL.h

@ -39,6 +39,19 @@
#include <avr/interrupt.h>
#include <avr/io.h>
//
// Default graphical display delays
//
#if F_CPU >= 20000000
#define CPU_ST7920_DELAY_1 150
#define CPU_ST7920_DELAY_2 0
#define CPU_ST7920_DELAY_3 150
#elif F_CPU == 16000000
#define CPU_ST7920_DELAY_1 125
#define CPU_ST7920_DELAY_2 0
#define CPU_ST7920_DELAY_3 188
#endif
#ifndef pgm_read_ptr
// Compatibility for avr-libc 1.8.0-4.1 included with Ubuntu for
// Windows Subsystem for Linux on Windows 10 as of 10/18/2019

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

@ -74,7 +74,8 @@ void spiBegin() {
#elif defined(PRR0)
PRR0
#endif
, PRSPI);
, PRSPI
);
SPCR = _BV(SPE) | _BV(MSTR) | (spiRate >> 1);
SPSR = spiRate & 1 || spiRate == 6 ? 0 : _BV(SPI2X);

26
Marlin/src/HAL/AVR/MarlinSPI.h

@ -0,0 +1,26 @@
/**
* 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 <SPI.h>
using MarlinSPI = SPIClass;

10
Marlin/src/HAL/AVR/fastio.cpp

@ -267,11 +267,11 @@ uint16_t set_pwm_frequency_hz(const_float_t hz, const float dca, const float dcb
SET_WGM(5, FAST_PWM_ICRn); // Fast PWM with ICR5 as TOP
//SERIAL_ECHOLNPGM("Timer 5 Settings:");
//SERIAL_ECHOLNPAIR(" Prescaler=", prescaler);
//SERIAL_ECHOLNPAIR(" TOP=", ICR5);
//SERIAL_ECHOLNPAIR(" OCR5A=", OCR5A);
//SERIAL_ECHOLNPAIR(" OCR5B=", OCR5B);
//SERIAL_ECHOLNPAIR(" OCR5C=", OCR5C);
//SERIAL_ECHOLNPGM(" Prescaler=", prescaler);
//SERIAL_ECHOLNPGM(" TOP=", ICR5);
//SERIAL_ECHOLNPGM(" OCR5A=", OCR5A);
//SERIAL_ECHOLNPGM(" OCR5B=", OCR5B);
//SERIAL_ECHOLNPGM(" OCR5C=", OCR5C);
}
else {
// Restore the default for Timer 5

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

@ -35,7 +35,7 @@
/**
* Sanity checks for Spindle / Laser PWM
*/
#if ENABLED(SPINDLE_LASER_PWM)
#if ENABLED(SPINDLE_LASER_USE_PWM)
#include "../ServoTimers.h" // Needed to check timer availability (_useTimer3)
#if SPINDLE_LASER_PWM_PIN == 4 || WITHIN(SPINDLE_LASER_PWM_PIN, 11, 13)
#error "Counter/Timer for SPINDLE_LASER_PWM_PIN is used by a system interrupt."
@ -43,7 +43,7 @@
#error "Counter/Timer for SPINDLE_LASER_PWM_PIN is used by the servo system."
#endif
#elif defined(SPINDLE_LASER_FREQUENCY)
#error "SPINDLE_LASER_FREQUENCY requires SPINDLE_LASER_PWM."
#error "SPINDLE_LASER_FREQUENCY requires SPINDLE_LASER_USE_PWM."
#endif
/**

20
Marlin/src/HAL/AVR/pinsDebug.h

@ -2,6 +2,9 @@
* Marlin 3D Printer Firmware
* Copyright (c) 2020 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
@ -235,9 +238,9 @@ static void print_is_also_tied() { SERIAL_ECHOPGM(" is also tied to this pin");
inline void com_print(const uint8_t N, const uint8_t Z) {
const uint8_t *TCCRA = (uint8_t*)TCCR_A(N);
SERIAL_ECHOPAIR(" COM", AS_CHAR('0' + N));
SERIAL_ECHOPGM(" COM", AS_DIGIT(N));
SERIAL_CHAR(Z);
SERIAL_ECHOPAIR(": ", int((*TCCRA >> (6 - Z * 2)) & 0x03));
SERIAL_ECHOPGM(": ", int((*TCCRA >> (6 - Z * 2)) & 0x03));
}
void timer_prefix(uint8_t T, char L, uint8_t N) { // T - timer L - pwm N - WGM bit layout
@ -247,7 +250,7 @@ void timer_prefix(uint8_t T, char L, uint8_t N) { // T - timer L - pwm N -
uint8_t WGM = (((*TCCRB & _BV(WGM_2)) >> 1) | (*TCCRA & (_BV(WGM_0) | _BV(WGM_1))));
if (N == 4) WGM |= ((*TCCRB & _BV(WGM_3)) >> 1);
SERIAL_ECHOPAIR(" TIMER", AS_CHAR(T + '0'));
SERIAL_ECHOPGM(" TIMER", AS_DIGIT(T));
SERIAL_CHAR(L);
SERIAL_ECHO_SP(3);
@ -259,14 +262,14 @@ void timer_prefix(uint8_t T, char L, uint8_t N) { // T - timer L - pwm N -
const uint16_t *OCRVAL16 = (uint16_t*)OCR_VAL(T, L - 'A');
PWM_PRINT(*OCRVAL16);
}
SERIAL_ECHOPAIR(" WGM: ", WGM);
SERIAL_ECHOPGM(" WGM: ", WGM);
com_print(T,L);
SERIAL_ECHOPAIR(" CS: ", (*TCCRB & (_BV(CS_0) | _BV(CS_1) | _BV(CS_2)) ));
SERIAL_ECHOPAIR(" TCCR", AS_CHAR(T + '0'), "A: ", *TCCRA);
SERIAL_ECHOPAIR(" TCCR", AS_CHAR(T + '0'), "B: ", *TCCRB);
SERIAL_ECHOPGM(" CS: ", (*TCCRB & (_BV(CS_0) | _BV(CS_1) | _BV(CS_2)) ));
SERIAL_ECHOPGM(" TCCR", AS_DIGIT(T), "A: ", *TCCRA);
SERIAL_ECHOPGM(" TCCR", AS_DIGIT(T), "B: ", *TCCRB);
const uint8_t *TMSK = (uint8_t*)TIMSK(T);
SERIAL_ECHOPAIR(" TIMSK", AS_CHAR(T + '0'), ": ", *TMSK);
SERIAL_ECHOPGM(" TIMSK", AS_DIGIT(T), ": ", *TMSK);
const uint8_t OCIE = L - 'A' + 1;
if (N == 3) { if (WGM == 0 || WGM == 2 || WGM == 4 || WGM == 6) err_is_counter(); }
@ -393,3 +396,4 @@ static void pwm_details(uint8_t pin) {
#endif
#define PRINT_PIN(p) do{ sprintf_P(buffer, PSTR("%3d "), p); SERIAL_ECHO(buffer); }while(0)
#define PRINT_PIN_ANALOG(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), DIGITAL_PIN_TO_ANALOG_PIN(pin)); SERIAL_ECHO(buffer); }while(0)

3
Marlin/src/HAL/AVR/pinsDebug_Teensyduino.h

@ -2,6 +2,9 @@
* Marlin 3D Printer Firmware
* Copyright (c) 2020 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

3
Marlin/src/HAL/AVR/pinsDebug_plus_70.h

@ -2,6 +2,9 @@
* Marlin 3D Printer Firmware
* Copyright (c) 2020 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

4
Marlin/src/HAL/AVR/u8g_com_HAL_AVR_sw_spi.cpp

@ -64,8 +64,8 @@
#include <U8glib-HAL.h>
uint8_t u8g_bitData, u8g_bitNotData, u8g_bitClock, u8g_bitNotClock;
volatile uint8_t *u8g_outData, *u8g_outClock;
static uint8_t u8g_bitData, u8g_bitNotData, u8g_bitClock, u8g_bitNotClock;
static volatile uint8_t *u8g_outData, *u8g_outClock;
static void u8g_com_arduino_init_shift_out(uint8_t dataPin, uint8_t clockPin) {
u8g_outData = portOutputRegister(digitalPinToPort(dataPin));

16
Marlin/src/HAL/DUE/HAL_SPI.cpp

@ -594,18 +594,14 @@
SPI_Configure(SPI0, ID_SPI0, SPI_MR_MSTR | SPI_MR_MODFDIS | SPI_MR_PS);
SPI_Enable(SPI0);
SET_OUTPUT(DAC0_SYNC);
SET_OUTPUT(DAC0_SYNC_PIN);
#if HAS_MULTI_EXTRUDER
SET_OUTPUT(DAC1_SYNC);
WRITE(DAC1_SYNC, HIGH);
OUT_WRITE(DAC1_SYNC_PIN, HIGH);
#endif
SET_OUTPUT(SPI_EEPROM1_CS);
SET_OUTPUT(SPI_EEPROM2_CS);
SET_OUTPUT(SPI_FLASH_CS);
WRITE(DAC0_SYNC, HIGH);
WRITE(SPI_EEPROM1_CS, HIGH);
WRITE(SPI_EEPROM2_CS, HIGH);
WRITE(SPI_FLASH_CS, HIGH);
WRITE(DAC0_SYNC_PIN, HIGH);
OUT_WRITE(SPI_EEPROM1_CS_PIN, HIGH);
OUT_WRITE(SPI_EEPROM2_CS_PIN, HIGH);
OUT_WRITE(SPI_FLASH_CS_PIN, HIGH);
WRITE(SD_SS_PIN, HIGH);
OUT_WRITE(SDSS, LOW);

26
Marlin/src/HAL/DUE/MarlinSPI.h

@ -0,0 +1,26 @@
/**
* 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 <SPI.h>
using MarlinSPI = SPIClass;

1
Marlin/src/HAL/DUE/dogm/u8g_com_HAL_DUE_shared_hw_spi.cpp

@ -20,7 +20,6 @@
*
*/
/**
* Based on u8g_com_msp430_hw_spi.c
*

34
Marlin/src/HAL/DUE/eeprom_flash.cpp

@ -200,9 +200,9 @@ static bool ee_PageWrite(uint16_t page, const void *data) {
pageContents[i] = (((uint32_t*)data)[i]) | (~(pageContents[i] ^ ((uint32_t*)data)[i]));
DEBUG_ECHO_START();
DEBUG_ECHOLNPAIR("EEPROM PageWrite ", page);
DEBUG_ECHOLNPAIR(" in FLASH address ", (uint32_t)addrflash);
DEBUG_ECHOLNPAIR(" base address ", (uint32_t)getFlashStorage(0));
DEBUG_ECHOLNPGM("EEPROM PageWrite ", page);
DEBUG_ECHOLNPGM(" in FLASH address ", (uint32_t)addrflash);
DEBUG_ECHOLNPGM(" base address ", (uint32_t)getFlashStorage(0));
DEBUG_FLUSH();
// Get the page relative to the start of the EFC controller, and the EFC controller to use
@ -246,7 +246,7 @@ static bool ee_PageWrite(uint16_t page, const void *data) {
__enable_irq();
DEBUG_ECHO_START();
DEBUG_ECHOLNPAIR("EEPROM Unlock failure for page ", page);
DEBUG_ECHOLNPGM("EEPROM Unlock failure for page ", page);
return false;
}
@ -271,7 +271,7 @@ static bool ee_PageWrite(uint16_t page, const void *data) {
__enable_irq();
DEBUG_ECHO_START();
DEBUG_ECHOLNPAIR("EEPROM Write failure for page ", page);
DEBUG_ECHOLNPGM("EEPROM Write failure for page ", page);
return false;
}
@ -287,7 +287,7 @@ static bool ee_PageWrite(uint16_t page, const void *data) {
#ifdef EE_EMU_DEBUG
DEBUG_ECHO_START();
DEBUG_ECHOLNPAIR("EEPROM Verify Write failure for page ", page);
DEBUG_ECHOLNPGM("EEPROM Verify Write failure for page ", page);
ee_Dump( page, (uint32_t *)addrflash);
ee_Dump(-page, data);
@ -306,7 +306,7 @@ static bool ee_PageWrite(uint16_t page, const void *data) {
}
}
}
DEBUG_ECHOLNPAIR("--> Differing bits: ", count);
DEBUG_ECHOLNPGM("--> Differing bits: ", count);
#endif
return false;
@ -326,9 +326,9 @@ static bool ee_PageErase(uint16_t page) {
uint32_t addrflash = uint32_t(getFlashStorage(page));
DEBUG_ECHO_START();
DEBUG_ECHOLNPAIR("EEPROM PageErase ", page);
DEBUG_ECHOLNPAIR(" in FLASH address ", (uint32_t)addrflash);
DEBUG_ECHOLNPAIR(" base address ", (uint32_t)getFlashStorage(0));
DEBUG_ECHOLNPGM("EEPROM PageErase ", page);
DEBUG_ECHOLNPGM(" in FLASH address ", (uint32_t)addrflash);
DEBUG_ECHOLNPGM(" base address ", (uint32_t)getFlashStorage(0));
DEBUG_FLUSH();
// Get the page relative to the start of the EFC controller, and the EFC controller to use
@ -371,7 +371,7 @@ static bool ee_PageErase(uint16_t page) {
__enable_irq();
DEBUG_ECHO_START();
DEBUG_ECHOLNPAIR("EEPROM Unlock failure for page ",page);
DEBUG_ECHOLNPGM("EEPROM Unlock failure for page ",page);
return false;
}
@ -395,7 +395,7 @@ static bool ee_PageErase(uint16_t page) {
__enable_irq();
DEBUG_ECHO_START();
DEBUG_ECHOLNPAIR("EEPROM Erase failure for page ",page);
DEBUG_ECHOLNPGM("EEPROM Erase failure for page ",page);
return false;
}
@ -411,7 +411,7 @@ static bool ee_PageErase(uint16_t page) {
for (i = 0; i < PageSize >> 2; i++) {
if (*aligned_src++ != 0xFFFFFFFF) {
DEBUG_ECHO_START();
DEBUG_ECHOLNPAIR("EEPROM Verify Erase failure for page ",page);
DEBUG_ECHOLNPGM("EEPROM Verify Erase failure for page ",page);
ee_Dump(page, (uint32_t *)addrflash);
return false;
}
@ -922,7 +922,7 @@ static void ee_Init() {
if (curGroup >= GroupCount) curGroup = 0;
DEBUG_ECHO_START();
DEBUG_ECHOLNPAIR("EEPROM Current Group: ",curGroup);
DEBUG_ECHOLNPGM("EEPROM Current Group: ",curGroup);
DEBUG_FLUSH();
// Now, validate that all the other group pages are empty
@ -932,7 +932,7 @@ static void ee_Init() {
for (int page = 0; page < PagesPerGroup; page++) {
if (!ee_IsPageClean(grp * PagesPerGroup + page)) {
DEBUG_ECHO_START();
DEBUG_ECHOLNPAIR("EEPROM Page ", page, " not clean on group ", grp);
DEBUG_ECHOLNPGM("EEPROM Page ", page, " not clean on group ", grp);
DEBUG_FLUSH();
ee_PageErase(grp * PagesPerGroup + page);
}
@ -949,14 +949,14 @@ static void ee_Init() {
}
DEBUG_ECHO_START();
DEBUG_ECHOLNPAIR("EEPROM Active page: ", curPage);
DEBUG_ECHOLNPGM("EEPROM Active page: ", curPage);
DEBUG_FLUSH();
// Make sure the pages following the first clean one are also clean
for (int page = curPage + 1; page < PagesPerGroup; page++) {
if (!ee_IsPageClean(curGroup * PagesPerGroup + page)) {
DEBUG_ECHO_START();
DEBUG_ECHOLNPAIR("EEPROM Page ", page, " not clean on active group ", curGroup);
DEBUG_ECHOLNPGM("EEPROM Page ", page, " not clean on active group ", curGroup);
DEBUG_FLUSH();
ee_Dump(curGroup * PagesPerGroup + page, getFlashStorage(curGroup * PagesPerGroup + page));
ee_PageErase(curGroup * PagesPerGroup + page);

6
Marlin/src/HAL/DUE/pinsDebug.h

@ -2,6 +2,9 @@
* Marlin 3D Printer Firmware
* Copyright (c) 2020 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
@ -64,6 +67,7 @@
#define PRINT_PORT(p)
#define PRINT_ARRAY_NAME(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0)
#define PRINT_PIN(p) do{ sprintf_P(buffer, PSTR("%02d"), p); SERIAL_ECHO(buffer); }while(0)
#define PRINT_PIN_ANALOG(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), DIGITAL_PIN_TO_ANALOG_PIN(pin)); SERIAL_ECHO(buffer); }while(0)
#define GET_ARRAY_PIN(p) pin_array[p].pin
#define GET_ARRAY_IS_DIGITAL(p) pin_array[p].is_digital
#define VALID_PIN(pin) (pin >= 0 && pin < (int8_t)NUMBER_PINS_TOTAL ? 1 : 0)
@ -86,7 +90,7 @@ bool GET_PINMODE(int8_t pin) { // 1: output, 0: input
void pwm_details(int32_t pin) {
if (pwm_status(pin)) {
uint32_t chan = g_APinDescription[pin].ulPWMChannel;
SERIAL_ECHOPAIR("PWM = ", PWM_INTERFACE->PWM_CH_NUM[chan].PWM_CDTY);
SERIAL_ECHOPGM("PWM = ", PWM_INTERFACE->PWM_CH_NUM[chan].PWM_CDTY);
}
}

26
Marlin/src/HAL/ESP32/MarlinSPI.h

@ -0,0 +1,26 @@
/**
* 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 <SPI.h>
using MarlinSPI = SPIClass;

3
Marlin/src/HAL/ESP32/spi_pins.h

@ -2,6 +2,9 @@
* Marlin 3D Printer Firmware
* Copyright (c) 2020 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

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

@ -59,7 +59,7 @@ void wifi_init() {
MDNS.addService("http", "tcp", 80);
SERIAL_ECHOLNPAIR("Successfully connected to WiFi with SSID '" WIFI_SSID "', hostname: '" WIFI_HOSTNAME "', IP address: ", WiFi.localIP().toString().c_str());
SERIAL_ECHOLNPGM("Successfully connected to WiFi with SSID '" WIFI_SSID "', hostname: '" WIFI_HOSTNAME "', IP address: ", WiFi.localIP().toString().c_str());
}
#endif // WIFISUPPORT

6
Marlin/src/HAL/LINUX/HAL.h

@ -63,9 +63,9 @@ uint8_t _getc();
extern MSerialT usb_serial;
#define MYSERIAL1 usb_serial
#define ST7920_DELAY_1 DELAY_NS(600)
#define ST7920_DELAY_2 DELAY_NS(750)
#define ST7920_DELAY_3 DELAY_NS(750)
#define CPU_ST7920_DELAY_1 600
#define CPU_ST7920_DELAY_2 750
#define CPU_ST7920_DELAY_3 750
//
// Interrupts

26
Marlin/src/HAL/LINUX/MarlinSPI.h

@ -0,0 +1,26 @@
/**
* 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 <SPI.h>
using MarlinSPI = SPIClass;

2
Marlin/src/HAL/LINUX/inc/SanityCheck.h

@ -26,7 +26,7 @@
*/
// Emulating RAMPS
#if ENABLED(SPINDLE_LASER_PWM) && !(SPINDLE_LASER_PWM_PIN == 4 || SPINDLE_LASER_PWM_PIN == 6 || SPINDLE_LASER_PWM_PIN == 11)
#if ENABLED(SPINDLE_LASER_USE_PWM) && !(SPINDLE_LASER_PWM_PIN == 4 || SPINDLE_LASER_PWM_PIN == 6 || SPINDLE_LASER_PWM_PIN == 11)
#error "SPINDLE_LASER_PWM_PIN must use SERVO0, SERVO1 or SERVO3 connector"
#endif

4
Marlin/src/HAL/LINUX/main.cpp

@ -2,6 +2,9 @@
* Marlin 3D Printer Firmware
* Copyright (c) 2020 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
@ -16,6 +19,7 @@
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#ifdef __PLAT_LINUX__
//#define GPIO_LOGGING // Full GPIO and Positional Logging

4
Marlin/src/HAL/LINUX/pinsDebug.h

@ -2,6 +2,9 @@
* Marlin 3D Printer Firmware
* Copyright (c) 2020 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
@ -34,6 +37,7 @@
#define GET_ARRAY_PIN(p) pin_array[p].pin
#define PRINT_ARRAY_NAME(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0)
#define PRINT_PIN(p) do{ sprintf_P(buffer, PSTR("%3d "), p); SERIAL_ECHO(buffer); }while(0)
#define PRINT_PIN_ANALOG(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), DIGITAL_PIN_TO_ANALOG_PIN(pin)); SERIAL_ECHO(buffer); }while(0)
#define MULTI_NAME_PAD 16 // space needed to be pretty if not first name assigned to a pin
// active ADC function/mode/code values for PINSEL registers

22
Marlin/src/HAL/LPC1768/HAL.h

@ -50,15 +50,9 @@ extern "C" volatile uint32_t _millis;
//
// Default graphical display delays
//
#ifndef ST7920_DELAY_1
#define ST7920_DELAY_1 DELAY_NS(600)
#endif
#ifndef ST7920_DELAY_2
#define ST7920_DELAY_2 DELAY_NS(750)
#endif
#ifndef ST7920_DELAY_3
#define ST7920_DELAY_3 DELAY_NS(750)
#endif
#define CPU_ST7920_DELAY_1 600
#define CPU_ST7920_DELAY_2 750
#define CPU_ST7920_DELAY_3 750
typedef ForwardSerial1Class< decltype(UsbSerial) > DefaultSerial1;
extern DefaultSerial1 USBSerial;
@ -113,7 +107,7 @@ extern DefaultSerial1 USBSerial;
#error "LCD_SERIAL_PORT must be from 0 to 3. You can also use -1 if the board supports Native USB."
#endif
#if HAS_DGUS_LCD
#define SERIAL_GET_TX_BUFFER_FREE() MSerial0.available()
#define SERIAL_GET_TX_BUFFER_FREE() LCD_SERIAL.available()
#endif
#endif
@ -162,17 +156,17 @@ int freeMemory();
using FilteredADC = LPC176x::ADC<ADC_LOWPASS_K_VALUE, ADC_MEDIAN_FILTER_SIZE>;
extern uint32_t HAL_adc_reading;
[[gnu::always_inline]] inline void HAL_start_adc(const pin_t pin) {
[[gnu::always_inline]] inline void HAL_adc_start_conversion(const pin_t pin) {
HAL_adc_reading = FilteredADC::read(pin) >> (16 - HAL_ADC_RESOLUTION); // returns 16bit value, reduce to required bits
}
[[gnu::always_inline]] inline uint16_t HAL_read_adc() {
[[gnu::always_inline]] inline uint16_t HAL_adc_get_result() {
return HAL_adc_reading;
}
#define HAL_adc_init()
#define HAL_ANALOG_SELECT(pin) FilteredADC::enable_channel(pin)
#define HAL_START_ADC(pin) HAL_start_adc(pin)
#define HAL_READ_ADC() HAL_read_adc()
#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin)
#define HAL_READ_ADC() HAL_adc_get_result()
#define HAL_ADC_READY() (true)
// Test whether the pin is valid

2
Marlin/src/HAL/LPC1768/MarlinSerial.h

@ -46,6 +46,8 @@ public:
void end() {}
uint8_t availableForWrite(void) { /* flushTX(); */ return TX_BUFFER_SIZE; }
#if ENABLED(EMERGENCY_PARSER)
bool recv_callback(const char c) override;
#endif

42
Marlin/src/HAL/LPC1768/eeprom_sdcard.cpp

@ -1,10 +1,9 @@
/**
* Marlin 3D Printer Firmware
*
* Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin]
* Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com
* Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.com
* Copyright (c) 2016 Victor Perez victor_pv@hotmail.com
*
* 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
@ -20,12 +19,19 @@
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
/**
* Implementation of EEPROM settings in SD Card
*/
#ifdef TARGET_LPC1768
#include "../../inc/MarlinConfig.h"
#if ENABLED(SDCARD_EEPROM_EMULATION)
//#define DEBUG_SD_EEPROM_EMULATION
#include "../shared/eeprom_api.h"
#include <chanfs/diskio.h>
@ -38,9 +44,11 @@ FATFS fat_fs;
FIL eeprom_file;
bool eeprom_file_open = false;
#define EEPROM_FILENAME "eeprom.dat"
#ifndef MARLIN_EEPROM_SIZE
#define MARLIN_EEPROM_SIZE size_t(0x1000) // 4KiB of Emulated EEPROM
#endif
size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; }
bool PersistentStore::access_start() {
@ -50,7 +58,7 @@ bool PersistentStore::access_start() {
MSC_Release_Lock();
return false;
}
FRESULT res = f_open(&eeprom_file, "eeprom.dat", FA_OPEN_ALWAYS | FA_WRITE | FA_READ);
FRESULT res = f_open(&eeprom_file, EEPROM_FILENAME, FA_OPEN_ALWAYS | FA_WRITE | FA_READ);
if (res) MSC_Release_Lock();
if (res == FR_OK) {
@ -81,18 +89,20 @@ bool PersistentStore::access_finish() {
// This extra chit-chat goes away soon, but is helpful for now
// to see errors that are happening in read_data / write_data
static void debug_rw(const bool write, int &pos, const uint8_t *value, const size_t size, const FRESULT s, const size_t total=0) {
PGM_P const rw_str = write ? PSTR("write") : PSTR("read");
SERIAL_CHAR(' ');
SERIAL_ECHOPGM_P(rw_str);
SERIAL_ECHOLNPAIR("_data(", pos, ",", value, ",", size, ", ...)");
if (total) {
SERIAL_ECHOPGM(" f_");
#if ENABLED(DEBUG_SD_EEPROM_EMULATION)
PGM_P const rw_str = write ? PSTR("write") : PSTR("read");
SERIAL_CHAR(' ');
SERIAL_ECHOPGM_P(rw_str);
SERIAL_ECHOPAIR("()=", s, "\n size=", size, "\n bytes_");
SERIAL_ECHOLNPAIR_P(write ? PSTR("written=") : PSTR("read="), total);
}
else
SERIAL_ECHOLNPAIR(" f_lseek()=", s);
SERIAL_ECHOLNPGM("_data(", pos, ",", *value, ",", size, ", ...)");
if (total) {
SERIAL_ECHOPGM(" f_");
SERIAL_ECHOPGM_P(rw_str);
SERIAL_ECHOPGM("()=", s, "\n size=", size, "\n bytes_");
SERIAL_ECHOLNPGM_P(write ? PSTR("written=") : PSTR("read="), total);
}
else
SERIAL_ECHOLNPGM(" f_lseek()=", s);
#endif
}
// File function return codes for type FRESULT. This goes away soon, but

2
Marlin/src/HAL/LPC1768/inc/SanityCheck.h

@ -67,7 +67,7 @@ static_assert(!(NUM_SERVOS && ENABLED(FAST_PWM_FAN)), "BLTOUCH and Servos are in
* Test LPC176x-specific configuration values for errors at compile-time.
*/
//#if ENABLED(SPINDLE_LASER_PWM) && !(SPINDLE_LASER_PWM_PIN == 4 || SPINDLE_LASER_PWM_PIN == 6 || SPINDLE_LASER_PWM_PIN == 11)
//#if ENABLED(SPINDLE_LASER_USE_PWM) && !(SPINDLE_LASER_PWM_PIN == 4 || SPINDLE_LASER_PWM_PIN == 6 || SPINDLE_LASER_PWM_PIN == 11)
// #error "SPINDLE_LASER_PWM_PIN must use SERVO0, SERVO1 or SERVO3 connector"
//#endif

12
Marlin/src/HAL/LPC1768/pinsDebug.h

@ -2,6 +2,9 @@
* Marlin 3D Printer Firmware
* Copyright (c) 2020 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
@ -33,8 +36,9 @@
#define PRINT_PORT(p)
#define GET_ARRAY_PIN(p) pin_array[p].pin
#define PRINT_ARRAY_NAME(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0)
#define PRINT_PIN(p) do{ sprintf_P(buffer, PSTR("%d.%02d"), LPC176x::pin_port(p), LPC176x::pin_bit(p)); SERIAL_ECHO(buffer); }while(0)
#define MULTI_NAME_PAD 16 // space needed to be pretty if not first name assigned to a pin
#define PRINT_PIN(p) do{ sprintf_P(buffer, PSTR("P%d_%02d"), LPC176x::pin_port(p), LPC176x::pin_bit(p)); SERIAL_ECHO(buffer); }while(0)
#define PRINT_PIN_ANALOG(p) do{ sprintf_P(buffer, PSTR("_A%d "), LPC176x::pin_get_adc_channel(pin)); SERIAL_ECHO(buffer); }while(0)
#define MULTI_NAME_PAD 17 // space needed to be pretty if not first name assigned to a pin
// pins that will cause hang/reset/disconnect in M43 Toggle and Watch utilities
#ifndef M43_NEVER_TOUCH
@ -48,6 +52,4 @@ bool GET_PINMODE(const pin_t pin) {
return LPC176x::gpio_direction(pin);
}
bool GET_ARRAY_IS_DIGITAL(const pin_t pin) {
return (!LPC176x::pin_has_adc(pin) || !LPC176x::pin_adc_enabled(pin));
}
#define GET_ARRAY_IS_DIGITAL(x) ((bool) pin_array[x].is_digital)

45
Marlin/src/HAL/LPC1768/tft/tft_spi.cpp

@ -26,39 +26,22 @@
#include "tft_spi.h"
//TFT_SPI tft;
SPIClass TFT_SPI::SPIx(1);
#define TFT_CS_H WRITE(TFT_CS_PIN, HIGH)
#define TFT_CS_L WRITE(TFT_CS_PIN, LOW)
#define TFT_DC_H WRITE(TFT_DC_PIN, HIGH)
#define TFT_DC_L WRITE(TFT_DC_PIN, LOW)
#define TFT_RST_H WRITE(TFT_RESET_PIN, HIGH)
#define TFT_RST_L WRITE(TFT_RESET_PIN, LOW)
#define TFT_BLK_H WRITE(TFT_BACKLIGHT_PIN, HIGH)
#define TFT_BLK_L WRITE(TFT_BACKLIGHT_PIN, LOW)
void TFT_SPI::Init() {
#if PIN_EXISTS(TFT_RESET)
SET_OUTPUT(TFT_RESET_PIN);
TFT_RST_H;
OUT_WRITE(TFT_RESET_PIN, HIGH);
delay(100);
#endif
#if PIN_EXISTS(TFT_BACKLIGHT)
SET_OUTPUT(TFT_BACKLIGHT_PIN);
TFT_BLK_H;
OUT_WRITE(TFT_BACKLIGHT_PIN, HIGH);
#endif
SET_OUTPUT(TFT_DC_PIN);
SET_OUTPUT(TFT_CS_PIN);
TFT_DC_H;
TFT_CS_H;
WRITE(TFT_DC_PIN, HIGH);
WRITE(TFT_CS_PIN, HIGH);
/**
* STM32F1 APB2 = 72MHz, APB1 = 36MHz, max SPI speed of this MCU if 18Mhz
@ -97,7 +80,7 @@ void TFT_SPI::Init() {
void TFT_SPI::DataTransferBegin(uint16_t DataSize) {
SPIx.setDataSize(DataSize);
SPIx.begin();
TFT_CS_L;
WRITE(TFT_CS_PIN, LOW);
}
uint32_t TFT_SPI::GetID() {
@ -116,7 +99,7 @@ uint32_t TFT_SPI::ReadID(uint16_t Reg) {
SPIx.setDataSize(DATASIZE_8BIT);
SPIx.setClock(SPI_CLOCK_DIV64);
SPIx.begin();
TFT_CS_L;
WRITE(TFT_CS_PIN, LOW);
WriteReg(Reg);
LOOP_L_N(i, 4) {
@ -131,21 +114,15 @@ uint32_t TFT_SPI::ReadID(uint16_t Reg) {
return data >> 7;
}
bool TFT_SPI::isBusy() {
return false;
}
bool TFT_SPI::isBusy() { return false; }
void TFT_SPI::Abort() {
DataTransferEnd();
}
void TFT_SPI::Abort() { DataTransferEnd(); }
void TFT_SPI::Transmit(uint16_t Data) {
SPIx.transfer(Data);
}
void TFT_SPI::Transmit(uint16_t Data) { SPIx.transfer(Data); }
void TFT_SPI::TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count) {
DataTransferBegin(DATASIZE_16BIT); //16
TFT_DC_H;
DataTransferBegin(DATASIZE_16BIT);
WRITE(TFT_DC_PIN, HIGH);
SPIx.dmaSend(Data, Count, MemoryIncrease);
DataTransferEnd();
}

6
Marlin/src/HAL/NATIVE_SIM/HAL.h

@ -99,9 +99,9 @@ extern MSerialT serial_stream_3;
#endif
#define ST7920_DELAY_1 DELAY_NS(600)
#define ST7920_DELAY_2 DELAY_NS(750)
#define ST7920_DELAY_3 DELAY_NS(750)
#define CPU_ST7920_DELAY_1 600
#define CPU_ST7920_DELAY_2 750
#define CPU_ST7920_DELAY_3 750
//
// Interrupts

2
Marlin/src/HAL/NATIVE_SIM/inc/SanityCheck.h

@ -26,7 +26,7 @@
*/
// Emulating RAMPS
#if ENABLED(SPINDLE_LASER_PWM) && !(SPINDLE_LASER_PWM_PIN == 4 || SPINDLE_LASER_PWM_PIN == 6 || SPINDLE_LASER_PWM_PIN == 11)
#if ENABLED(SPINDLE_LASER_USE_PWM) && !(SPINDLE_LASER_PWM_PIN == 4 || SPINDLE_LASER_PWM_PIN == 6 || SPINDLE_LASER_PWM_PIN == 11)
#error "SPINDLE_LASER_PWM_PIN must use SERVO0, SERVO1 or SERVO3 connector"
#endif

2
Marlin/src/HAL/NATIVE_SIM/pinsDebug.h

@ -20,7 +20,6 @@
/**
* Support routines for X86_64
*/
#pragma once
/**
@ -36,6 +35,7 @@
#define GET_ARRAY_PIN(p) pin_array[p].pin
#define PRINT_ARRAY_NAME(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0)
#define PRINT_PIN(p) do{ sprintf_P(buffer, PSTR("%3d "), p); SERIAL_ECHO(buffer); }while(0)
#define PRINT_PIN_ANALOG(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), DIGITAL_PIN_TO_ANALOG_PIN(pin)); SERIAL_ECHO(buffer); }while(0)
#define MULTI_NAME_PAD 16 // space needed to be pretty if not first name assigned to a pin
// active ADC function/mode/code values for PINSEL registers

26
Marlin/src/HAL/SAMD51/MarlinSPI.h

@ -0,0 +1,26 @@
/**
* 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 <SPI.h>
using MarlinSPI = SPIClass;

1
Marlin/src/HAL/SAMD51/QSPIFlash.h

@ -25,7 +25,6 @@
*
* Derived from Adafruit_SPIFlash class with no SdFat references
*/
#pragma once
#include <Adafruit_SPIFlashBase.h>

12
Marlin/src/HAL/SAMD51/endstop_interrupts.h

@ -162,12 +162,14 @@ void setup_endstop_interrupts() {
#error "Z_MIN_PROBE_PIN has no EXTINT line available."
#endif
_ATTACH(Z_MIN_PROBE_PIN);
#elif HAS_I_MAX
#endif
#if HAS_I_MAX
#if !AVAILABLE_EILINE(I_MAX_PIN)
#error "I_MAX_PIN has no EXTINT line available."
#endif
attachInterrupt(I_MAX_PIN, endstop_ISR, CHANGE);
#elif HAS_I_MIN
#endif
#if HAS_I_MIN
#if !AVAILABLE_EILINE(I_MIN_PIN)
#error "I_MIN_PIN has no EXTINT line available."
#endif
@ -178,7 +180,8 @@ void setup_endstop_interrupts() {
#error "J_MAX_PIN has no EXTINT line available."
#endif
attachInterrupt(J_MAX_PIN, endstop_ISR, CHANGE);
#elif HAS_J_MIN
#endif
#if HAS_J_MIN
#if !AVAILABLE_EILINE(J_MIN_PIN)
#error "J_MIN_PIN has no EXTINT line available."
#endif
@ -189,7 +192,8 @@ void setup_endstop_interrupts() {
#error "K_MAX_PIN has no EXTINT line available."
#endif
attachInterrupt(K_MAX_PIN, endstop_ISR, CHANGE);
#elif HAS_K_MIN
#endif
#if HAS_K_MIN
#if !AVAILABLE_EILINE(K_MIN_PIN)
#error "K_MIN_PIN has no EXTINT line available."
#endif

3
Marlin/src/HAL/SAMD51/pinsDebug.h

@ -26,6 +26,7 @@
#define PRINT_PORT(p) do{ SERIAL_ECHOPGM(" Port: "); sprintf_P(buffer, PSTR("%c%02ld"), 'A' + g_APinDescription[p].ulPort, g_APinDescription[p].ulPin); SERIAL_ECHO(buffer); }while (0)
#define PRINT_ARRAY_NAME(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0)
#define PRINT_PIN(p) do{ sprintf_P(buffer, PSTR("%3d "), p); SERIAL_ECHO(buffer); }while(0)
#define PRINT_PIN_ANALOG(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), DIGITAL_PIN_TO_ANALOG_PIN(pin)); SERIAL_ECHO(buffer); }while(0)
#define GET_ARRAY_PIN(p) pin_array[p].pin
#define GET_ARRAY_IS_DIGITAL(p) pin_array[p].is_digital
#define VALID_PIN(pin) (pin >= 0 && pin < (int8_t)NUMBER_PINS_TOTAL)
@ -47,7 +48,7 @@ bool GET_PINMODE(int8_t pin) { // 1: output, 0: input
void pwm_details(int32_t pin) {
if (pwm_status(pin)) {
//uint32_t chan = g_APinDescription[pin].ulPWMChannel TODO when fast pwm is operative;
//SERIAL_ECHOPAIR("PWM = ", duty);
//SERIAL_ECHOPGM("PWM = ", duty);
}
}

14
Marlin/src/HAL/STM32/HAL.h

@ -37,6 +37,13 @@
#include <stdint.h>
//
// Default graphical display delays
//
#define CPU_ST7920_DELAY_1 300
#define CPU_ST7920_DELAY_2 40
#define CPU_ST7920_DELAY_3 340
//
// Serial Ports
//
@ -176,8 +183,13 @@ static inline int freeMemory() {
#define HAL_ANALOG_SELECT(pin) pinMode(pin, INPUT)
#ifdef ADC_RESOLUTION
#define HAL_ADC_RESOLUTION ADC_RESOLUTION
#else
#define HAL_ADC_RESOLUTION 12
#endif
#define HAL_ADC_VREF 3.3
#define HAL_ADC_RESOLUTION ADC_RESOLUTION // 12
#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin)
#define HAL_READ_ADC() HAL_adc_result
#define HAL_ADC_READY() true

1
Marlin/src/HAL/STM32/MarlinSPI.cpp

@ -19,6 +19,7 @@
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#include "../platforms.h"
#if defined(HAL_STM32) && !defined(STM32H7xx)

4
Marlin/src/HAL/STM32/MarlinSerial.cpp

@ -2,6 +2,9 @@
* Marlin 3D Printer Firmware
* Copyright (c) 2020 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
@ -16,6 +19,7 @@
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#include "../platforms.h"
#ifdef HAL_STM32

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

@ -2,6 +2,9 @@
* Marlin 3D Printer Firmware
* Copyright (c) 2020 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

1
Marlin/src/HAL/STM32/Sd2Card_sdio_stm32duino.cpp

@ -19,6 +19,7 @@
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#include "../platforms.h"
#ifdef HAL_STM32

1
Marlin/src/HAL/STM32/eeprom_bl24cxx.cpp

@ -19,6 +19,7 @@
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#include "../platforms.h"
#ifdef HAL_STM32

16
Marlin/src/HAL/STM32/eeprom_flash.cpp

@ -133,7 +133,7 @@ bool PersistentStore::access_start() {
// load current settings
uint8_t *eeprom_data = (uint8_t *)SLOT_ADDRESS(current_slot);
for (int i = 0; i < MARLIN_EEPROM_SIZE; i++) ram_eeprom[i] = eeprom_data[i];
DEBUG_ECHOLNPAIR("EEPROM loaded from slot ", current_slot, ".");
DEBUG_ECHOLNPGM("EEPROM loaded from slot ", current_slot, ".");
}
eeprom_data_written = false;
}
@ -179,9 +179,9 @@ bool PersistentStore::access_finish() {
ENABLE_ISRS();
TERN_(HAS_PAUSE_SERVO_OUTPUT, RESUME_SERVO_OUTPUT());
if (status != HAL_OK) {
DEBUG_ECHOLNPAIR("HAL_FLASHEx_Erase=", status);
DEBUG_ECHOLNPAIR("GetError=", HAL_FLASH_GetError());
DEBUG_ECHOLNPAIR("SectorError=", SectorError);
DEBUG_ECHOLNPGM("HAL_FLASHEx_Erase=", status);
DEBUG_ECHOLNPGM("GetError=", HAL_FLASH_GetError());
DEBUG_ECHOLNPGM("SectorError=", SectorError);
LOCK_FLASH();
return false;
}
@ -204,9 +204,9 @@ bool PersistentStore::access_finish() {
offset += sizeof(uint32_t);
}
else {
DEBUG_ECHOLNPAIR("HAL_FLASH_Program=", status);
DEBUG_ECHOLNPAIR("GetError=", HAL_FLASH_GetError());
DEBUG_ECHOLNPAIR("address=", address);
DEBUG_ECHOLNPGM("HAL_FLASH_Program=", status);
DEBUG_ECHOLNPGM("GetError=", HAL_FLASH_GetError());
DEBUG_ECHOLNPGM("address=", address);
success = false;
break;
}
@ -216,7 +216,7 @@ bool PersistentStore::access_finish() {
if (success) {
eeprom_data_written = false;
DEBUG_ECHOLNPAIR("EEPROM saved to slot ", current_slot, ".");
DEBUG_ECHOLNPGM("EEPROM saved to slot ", current_slot, ".");
}
return success;

1
Marlin/src/HAL/STM32/eeprom_if_iic.cpp

@ -19,6 +19,7 @@
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#include "../platforms.h"
#ifdef HAL_STM32

1
Marlin/src/HAL/STM32/eeprom_sdcard.cpp

@ -19,6 +19,7 @@
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#include "../platforms.h"
#ifdef HAL_STM32

1
Marlin/src/HAL/STM32/fast_pwm.cpp

@ -19,6 +19,7 @@
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#include "../platforms.h"
#ifdef HAL_STM32

2
Marlin/src/HAL/STM32/inc/SanityCheck.h

@ -24,7 +24,7 @@
/**
* Test STM32-specific configuration values for errors at compile-time.
*/
//#if ENABLED(SPINDLE_LASER_PWM) && !(SPINDLE_LASER_PWM_PIN == 4 || SPINDLE_LASER_PWM_PIN == 6 || SPINDLE_LASER_PWM_PIN == 11)
//#if ENABLED(SPINDLE_LASER_USE_PWM) && !(SPINDLE_LASER_PWM_PIN == 4 || SPINDLE_LASER_PWM_PIN == 6 || SPINDLE_LASER_PWM_PIN == 11)
// #error "SPINDLE_LASER_PWM_PIN must use SERVO0, SERVO1 or SERVO3 connector"
//#endif

6
Marlin/src/HAL/STM32/pinsDebug.h

@ -2,6 +2,9 @@
* Marlin 3D Printer Firmware
* Copyright (c) 2020 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
@ -109,6 +112,7 @@ const XrefInfo pin_xref[] PROGMEM = {
#define VALID_PIN(ANUM) ((ANUM) >= 0 && (ANUM) < NUMBER_PINS_TOTAL)
#define digitalRead_mod(Ard_num) extDigitalRead(Ard_num) // must use Arduino pin numbers when doing reads
#define PRINT_PIN(Q)
#define PRINT_PIN_ANALOG(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), DIGITAL_PIN_TO_ANALOG_PIN(pin)); SERIAL_ECHO(buffer); }while(0)
#define PRINT_PORT(ANUM) port_print(ANUM)
#define DIGITAL_PIN_TO_ANALOG_PIN(ANUM) -1 // will report analog pin number in the print port routine
#define GET_PIN_MAP_PIN_M43(Index) pin_xref[Index].Ard_num
@ -236,7 +240,7 @@ void pwm_details(const pin_t Ard_num) {
if (over_7) pin_number -= 8;
uint8_t alt_func = (alt_all >> (4 * pin_number)) & 0x0F;
SERIAL_ECHOPAIR("Alt Function: ", alt_func);
SERIAL_ECHOPGM("Alt Function: ", alt_func);
if (alt_func < 10) SERIAL_CHAR(' ');
SERIAL_ECHOPGM(" - ");
switch (alt_func) {

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

@ -2,6 +2,9 @@
* Marlin 3D Printer Firmware
* Copyright (c) 2020 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

1
Marlin/src/HAL/STM32/tft/tft_fsmc.cpp

@ -19,6 +19,7 @@
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#include "../../platforms.h"
#ifdef HAL_STM32

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

@ -183,7 +183,7 @@ void LTDC_Config() {
hltdc_F.Init.AccumulatedVBP = (LTDC_LCD_VSYNC + LTDC_LCD_VBP - 1);
hltdc_F.Init.AccumulatedActiveH = (TFT_HEIGHT + LTDC_LCD_VSYNC + LTDC_LCD_VBP - 1);
hltdc_F.Init.AccumulatedActiveW = (TFT_WIDTH + LTDC_LCD_HSYNC + LTDC_LCD_HBP - 1);
hltdc_F.Init.TotalHeight = (TFT_HEIGHT + LTDC_LCD_VSYNC + LTDC_LCD_VBP + LTDC_LCD_VFP - 1);
hltdc_F.Init.TotalHeigh = (TFT_HEIGHT + LTDC_LCD_VSYNC + LTDC_LCD_VBP + LTDC_LCD_VFP - 1);
hltdc_F.Init.TotalWidth = (TFT_WIDTH + LTDC_LCD_HSYNC + LTDC_LCD_HBP + LTDC_LCD_HFP - 1);
/* Configure R,G,B component values for LCD background color : all black background */
@ -205,7 +205,7 @@ void LTDC_Config() {
pLayerCfg.PixelFormat = LTDC_PIXEL_FORMAT_RGB565;
/* Start Address configuration : frame buffer is located at SDRAM memory */
pLayerCfg.FBStartAddress = (uint32_t)(FRAME_BUFFER_ADDRESS);
pLayerCfg.FBStartAdress = (uint32_t)(FRAME_BUFFER_ADDRESS);
/* Alpha constant (255 == totally opaque) */
pLayerCfg.Alpha = 255;

1
Marlin/src/HAL/STM32/tft/tft_spi.cpp

@ -19,6 +19,7 @@
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#include "../../platforms.h"
#ifdef HAL_STM32

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

@ -19,6 +19,7 @@
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#include "../../platforms.h"
#ifdef HAL_STM32

7
Marlin/src/HAL/STM32/usb_host.cpp

@ -19,6 +19,7 @@
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#include "../platforms.h"
#ifdef HAL_STM32
@ -88,9 +89,9 @@ void USBHost::setUsbTaskState(uint8_t state) {
capacity = info.capacity.block_nbr / 2000;
block_size = info.capacity.block_size;
block_count = info.capacity.block_nbr;
// SERIAL_ECHOLNPAIR("info.capacity.block_nbr : %ld\n", info.capacity.block_nbr);
// SERIAL_ECHOLNPAIR("info.capacity.block_size: %d\n", info.capacity.block_size);
// SERIAL_ECHOLNPAIR("capacity : %d MB\n", capacity);
//SERIAL_ECHOLNPGM("info.capacity.block_nbr : %ld\n", info.capacity.block_nbr);
//SERIAL_ECHOLNPGM("info.capacity.block_size: %d\n", info.capacity.block_size);
//SERIAL_ECHOLNPGM("capacity : %d MB\n", capacity);
}
};

4
Marlin/src/HAL/STM32/usb_serial.cpp

@ -2,6 +2,9 @@
* Marlin 3D Printer Firmware
* Copyright (c) 2020 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
@ -16,6 +19,7 @@
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#include "../platforms.h"
#ifdef HAL_STM32

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

@ -2,6 +2,9 @@
* Marlin 3D Printer Firmware
* Copyright (c) 2020 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

1
Marlin/src/HAL/STM32/watchdog.cpp

@ -19,6 +19,7 @@
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#include "../platforms.h"
#ifdef HAL_STM32

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

@ -437,7 +437,7 @@ void HAL_adc_start_conversion(const uint8_t adc_pin) {
case POWER_MONITOR_VOLTAGE_PIN: pin_index = POWERMON_VOLTS; break;
#endif
}
HAL_adc_result = (HAL_adc_results[(int)pin_index] >> 2) & 0x3FF; // shift to get 10 bits only.
HAL_adc_result = HAL_adc_results[(int)pin_index] >> (12 - HAL_ADC_RESOLUTION); // shift out unused bits
}
uint16_t HAL_adc_get_result() { return HAL_adc_result; }

14
Marlin/src/HAL/STM32F1/HAL.h

@ -51,6 +51,13 @@
// Defines
// ------------------------
//
// Default graphical display delays
//
#define CPU_ST7920_DELAY_1 300
#define CPU_ST7920_DELAY_2 40
#define CPU_ST7920_DELAY_3 340
#ifndef STM32_FLASH_SIZE
#if ANY(MCU_STM32F103RE, MCU_STM32F103VE, MCU_STM32F103ZE)
#define STM32_FLASH_SIZE 512
@ -230,8 +237,13 @@ static inline int freeMemory() {
void HAL_adc_init();
#ifdef ADC_RESOLUTION
#define HAL_ADC_RESOLUTION ADC_RESOLUTION
#else
#define HAL_ADC_RESOLUTION 12
#endif
#define HAL_ADC_VREF 3.3
#define HAL_ADC_RESOLUTION 10
#define HAL_START_ADC(pin) HAL_adc_start_conversion(pin)
#define HAL_READ_ADC() HAL_adc_result
#define HAL_ADC_READY() true

4
Marlin/src/HAL/STM32F1/dogm/u8g_com_stm32duino_swspi.cpp

@ -2,6 +2,9 @@
* Marlin 3D Printer Firmware
* Copyright (c) 2020 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
@ -16,6 +19,7 @@
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#ifdef __STM32F1__
#include "../../../inc/MarlinConfig.h"

5
Marlin/src/HAL/STM32F1/eeprom_wired.cpp

@ -2,6 +2,9 @@
* Marlin 3D Printer Firmware
* Copyright (c) 2020 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
@ -44,7 +47,7 @@ bool PersistentStore::access_start() {
SET_OUTPUT(BOARD_SPI1_SCK_PIN);
SET_OUTPUT(BOARD_SPI1_MOSI_PIN);
SET_INPUT(BOARD_SPI1_MISO_PIN);
SET_OUTPUT(SPI_EEPROM1_CS);
SET_OUTPUT(SPI_EEPROM1_CS_PIN);
#endif
spiInit(0);
#endif

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

@ -158,7 +158,7 @@ static void sd_power_on() {
ONBOARD_SD_SPI.begin();
ONBOARD_SD_SPI.setBitOrder(MSBFIRST);
ONBOARD_SD_SPI.setDataMode(SPI_MODE0);
OUT_WRITE(ONBOARD_SD_CS_PIN, HIGH); // Set CS# high
CS_HIGH();
}
// Disable SPI function

4
Marlin/src/HAL/STM32F1/pinsDebug.h

@ -2,6 +2,9 @@
* Marlin 3D Printer Firmware
* Copyright (c) 2020 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
@ -41,6 +44,7 @@ extern const stm32_pin_info PIN_MAP[BOARD_NR_GPIO_PINS];
#define pwm_status(pin) PWM_PIN(pin)
#define digitalRead_mod(p) extDigitalRead(p)
#define PRINT_PIN(p) do{ sprintf_P(buffer, PSTR("%3hd "), int16_t(p)); SERIAL_ECHO(buffer); }while(0)
#define PRINT_PIN_ANALOG(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), DIGITAL_PIN_TO_ANALOG_PIN(pin)); SERIAL_ECHO(buffer); }while(0)
#define PRINT_PORT(p) print_port(p)
#define PRINT_ARRAY_NAME(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0)
#define MULTI_NAME_PAD 21 // space needed to be pretty if not first name assigned to a pin

3
Marlin/src/HAL/STM32F1/spi_pins.h

@ -2,6 +2,9 @@
* Marlin 3D Printer Firmware
* Copyright (c) 2020 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

48
Marlin/src/HAL/STM32F1/tft/tft_spi.cpp

@ -26,36 +26,20 @@
#include "tft_spi.h"
// TFT_SPI tft;
SPIClass TFT_SPI::SPIx(1);
#define TFT_CS_H OUT_WRITE(TFT_CS_PIN, HIGH)
#define TFT_CS_L OUT_WRITE(TFT_CS_PIN, LOW)
#define TFT_DC_H OUT_WRITE(TFT_DC_PIN, HIGH)
#define TFT_DC_L OUT_WRITE(TFT_DC_PIN, LOW)
#define TFT_RST_H OUT_WRITE(TFT_RST_PIN, HIGH)
#define TFT_RST_L OUT_WRITE(TFT_RST_PIN, LOW)
#define TFT_BLK_H OUT_WRITE(TFT_BACKLIGHT_PIN, HIGH)
#define TFT_BLK_L OUT_WRITE(TFT_BACKLIGHT_PIN, LOW)
void TFT_SPI::Init() {
#if PIN_EXISTS(TFT_RESET)
// OUT_WRITE(TFT_RESET_PIN, HIGH);
TFT_RST_H;
OUT_WRITE(TFT_RST_PIN, HIGH);
delay(100);
#endif
#if PIN_EXISTS(TFT_BACKLIGHT)
// OUT_WRITE(TFT_BACKLIGHT_PIN, HIGH);
TFT_BLK_H;
OUT_WRITE(TFT_BACKLIGHT_PIN, HIGH);
#endif
TFT_DC_H;
TFT_CS_H;
OUT_WRITE(TFT_DC_PIN, HIGH);
OUT_WRITE(TFT_CS_PIN, HIGH);
/**
* STM32F1 APB2 = 72MHz, APB1 = 36MHz, max SPI speed of this MCU if 18Mhz
@ -87,7 +71,7 @@ void TFT_SPI::Init() {
void TFT_SPI::DataTransferBegin(uint16_t DataSize) {
SPIx.setDataSize(DataSize);
SPIx.begin();
TFT_CS_L;
OUT_WRITE(TFT_CS_PIN, LOW);
}
#ifdef TFT_DEFAULT_DRIVER
@ -129,28 +113,16 @@ uint32_t TFT_SPI::ReadID(uint16_t Reg) {
#endif
}
bool TFT_SPI::isBusy() {
return false;
}
bool TFT_SPI::isBusy() { return false; }
void TFT_SPI::Abort() {
DataTransferEnd();
}
void TFT_SPI::Abort() { DataTransferEnd(); }
void TFT_SPI::Transmit(uint16_t Data) {
SPIx.send(Data);
}
void TFT_SPI::Transmit(uint16_t Data) { SPIx.send(Data); }
void TFT_SPI::TransmitDMA(uint32_t MemoryIncrease, uint16_t *Data, uint16_t Count) {
DataTransferBegin();
TFT_DC_H;
if (MemoryIncrease == DMA_MINC_ENABLE) {
SPIx.dmaSend(Data, Count, true);
}
else {
SPIx.dmaSend(Data, Count, false);
}
OUT_WRITE(TFT_DC_PIN, HIGH);
SPIx.dmaSend(Data, Count, MemoryIncrease == DMA_MINC_ENABLE);
DataTransferEnd();
}

6
Marlin/src/HAL/TEENSY31_32/HAL.h

@ -36,9 +36,9 @@
#include <stdint.h>
#define ST7920_DELAY_1 DELAY_NS(600)
#define ST7920_DELAY_2 DELAY_NS(750)
#define ST7920_DELAY_3 DELAY_NS(750)
#define CPU_ST7920_DELAY_1 600
#define CPU_ST7920_DELAY_2 750
#define CPU_ST7920_DELAY_3 750
//#undef MOTHERBOARD
//#define MOTHERBOARD BOARD_TEENSY31_32

26
Marlin/src/HAL/TEENSY31_32/MarlinSPI.h

@ -0,0 +1,26 @@
/**
* 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 <SPI.h>
using MarlinSPI = SPIClass;

4
Marlin/src/HAL/TEENSY31_32/eeprom.cpp

@ -2,6 +2,9 @@
* Marlin 3D Printer Firmware
* Copyright (c) 2020 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
@ -16,6 +19,7 @@
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#ifdef __MK20DX256__
/**

6
Marlin/src/HAL/TEENSY35_36/HAL.h

@ -37,9 +37,9 @@
#include <stdint.h>
#include <util/atomic.h>
#define ST7920_DELAY_1 DELAY_NS(600)
#define ST7920_DELAY_2 DELAY_NS(750)
#define ST7920_DELAY_3 DELAY_NS(750)
#define CPU_ST7920_DELAY_1 600
#define CPU_ST7920_DELAY_2 750
#define CPU_ST7920_DELAY_3 750
// ------------------------
// Defines

26
Marlin/src/HAL/TEENSY35_36/MarlinSPI.h

@ -0,0 +1,26 @@
/**
* 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 <SPI.h>
using MarlinSPI = SPIClass;

3
Marlin/src/HAL/TEENSY35_36/pinsDebug.h

@ -2,6 +2,9 @@
* Marlin 3D Printer Firmware
* Copyright (c) 2020 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

6
Marlin/src/HAL/TEENSY40_41/HAL.h

@ -41,9 +41,9 @@
#include "../../feature/ethernet.h"
#endif
//#define ST7920_DELAY_1 DELAY_NS(600)
//#define ST7920_DELAY_2 DELAY_NS(750)
//#define ST7920_DELAY_3 DELAY_NS(750)
#define CPU_ST7920_DELAY_1 600
#define CPU_ST7920_DELAY_2 750
#define CPU_ST7920_DELAY_3 750
// ------------------------
// Defines

26
Marlin/src/HAL/TEENSY40_41/MarlinSPI.h

@ -0,0 +1,26 @@
/**
* 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 <SPI.h>
using MarlinSPI = SPIClass;

4
Marlin/src/HAL/TEENSY40_41/pinsDebug.h

@ -2,6 +2,9 @@
* Marlin 3D Printer Firmware
* Copyright (c) 2020 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
@ -30,6 +33,7 @@
#define PRINT_PORT(p)
#define PRINT_ARRAY_NAME(x) do{ sprintf_P(buffer, PSTR("%-" STRINGIFY(MAX_NAME_LENGTH) "s"), pin_array[x].name); SERIAL_ECHO(buffer); }while(0)
#define PRINT_PIN(p) do{ sprintf_P(buffer, PSTR("%02d"), p); SERIAL_ECHO(buffer); }while(0)
#define PRINT_PIN_ANALOG(p) do{ sprintf_P(buffer, PSTR(" (A%2d) "), DIGITAL_PIN_TO_ANALOG_PIN(pin)); SERIAL_ECHO(buffer); }while(0)
#define GET_ARRAY_PIN(p) pin_array[p].pin
#define GET_ARRAY_IS_DIGITAL(p) pin_array[p].is_digital
#define VALID_PIN(pin) (pin >= 0 && pin < (int8_t)NUMBER_PINS_TOTAL ? 1 : 0)

7
Marlin/src/HAL/shared/Delay.cpp

@ -19,6 +19,7 @@
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#include "Delay.h"
#include "../../inc/MarlinConfig.h"
@ -110,16 +111,16 @@
auto report_call_time = [](PGM_P const name, PGM_P const unit, const uint32_t cycles, const uint32_t total, const bool do_flush=true) {
SERIAL_ECHOPGM("Calling ");
SERIAL_ECHOPGM_P(name);
SERIAL_ECHOLNPAIR(" for ", cycles);
SERIAL_ECHOLNPGM(" for ", cycles);
SERIAL_ECHOPGM_P(unit);
SERIAL_ECHOLNPAIR(" took: ", total);
SERIAL_ECHOLNPGM(" took: ", total);
SERIAL_ECHOPGM_P(unit);
if (do_flush) SERIAL_FLUSHTX();
};
uint32_t s, e;
SERIAL_ECHOLNPAIR("Computed delay calibration value: ", ASM_CYCLES_PER_ITERATION);
SERIAL_ECHOLNPGM("Computed delay calibration value: ", ASM_CYCLES_PER_ITERATION);
SERIAL_FLUSH();
// Display the results of the calibration above
constexpr uint32_t testValues[] = { 1, 5, 10, 20, 50, 100, 150, 200, 350, 500, 750, 1000 };

12
Marlin/src/HAL/shared/eeprom_if_spi.cpp

@ -49,8 +49,8 @@ static void _eeprom_begin(uint8_t * const pos, const uint8_t cmd) {
(unsigned(pos) >> 8) & 0xFF, // Address High
unsigned(pos) & 0xFF // Address Low
};
WRITE(SPI_EEPROM1_CS, HIGH); // Usually free already
WRITE(SPI_EEPROM1_CS, LOW); // Activate the Bus
WRITE(SPI_EEPROM1_CS_PIN, HIGH); // Usually free already
WRITE(SPI_EEPROM1_CS_PIN, LOW); // Activate the Bus
spiSend(SPI_CHAN_EEPROM1, eeprom_temp, 3);
// Leave the Bus in-use
}
@ -60,23 +60,23 @@ uint8_t eeprom_read_byte(uint8_t *pos) {
const uint8_t v = spiRec(SPI_CHAN_EEPROM1); // After READ a value sits on the Bus
WRITE(SPI_EEPROM1_CS, HIGH); // Done with device
WRITE(SPI_EEPROM1_CS_PIN, HIGH); // Done with device
return v;
}
void eeprom_write_byte(uint8_t *pos, uint8_t value) {
const uint8_t eeprom_temp = CMD_WREN;
WRITE(SPI_EEPROM1_CS, LOW);
WRITE(SPI_EEPROM1_CS_PIN, LOW);
spiSend(SPI_CHAN_EEPROM1, &eeprom_temp, 1); // Write Enable
WRITE(SPI_EEPROM1_CS, HIGH); // Done with the Bus
WRITE(SPI_EEPROM1_CS_PIN, HIGH); // Done with the Bus
delay(1); // For a small amount of time
_eeprom_begin(pos, CMD_WRITE); // Set write address and begin transmission
spiSend(SPI_CHAN_EEPROM1, value); // Send the value to be written
WRITE(SPI_EEPROM1_CS, HIGH); // Done with the Bus
WRITE(SPI_EEPROM1_CS_PIN, HIGH); // Done with the Bus
delay(EEPROM_WRITE_DELAY); // Give page write time to complete
}

134
Marlin/src/MarlinCore.cpp

@ -30,10 +30,6 @@
#include "MarlinCore.h"
#if ENABLED(MARLIN_DEV_MODE)
#warning "WARNING! Disable MARLIN_DEV_MODE for the final build!"
#endif
#include "HAL/shared/Delay.h"
#include "HAL/shared/esp_wifi.h"
#include "HAL/shared/cpu_exception/exception_hook.h"
@ -74,13 +70,15 @@
#include <lvgl.h>
#endif
#if ENABLED(DWIN_CREALITY_LCD)
#include "lcd/e3v2/creality/dwin.h"
#include "lcd/e3v2/creality/rotary_encoder.h"
#endif
#if ENABLED(EXTENSIBLE_UI)
#include "lcd/extui/ui_api.h"
#if HAS_DWIN_E3V2
#include "lcd/e3v2/common/encoder.h"
#if ENABLED(DWIN_CREALITY_LCD)
#include "lcd/e3v2/creality/dwin.h"
#elif ENABLED(DWIN_CREALITY_LCD_ENHANCED)
#include "lcd/e3v2/enhanced/dwin.h"
#elif ENABLED(DWIN_CREALITY_LCD_JYERSUI)
#include "lcd/e3v2/jyersui/dwin.h"
#endif
#endif
#if HAS_ETHERNET
@ -166,6 +164,8 @@
#if ENABLED(DELTA)
#include "module/delta.h"
#elif ENABLED(POLARGRAPH)
#include "module/polargraph.h"
#elif IS_SCARA
#include "module/scara.h"
#endif
@ -236,6 +236,10 @@
#include "feature/stepper_driver_safety.h"
#endif
#if ENABLED(PSU_CONTROL)
#include "feature/power.h"
#endif
PGMSTR(M112_KILL_STR, "M112 Shutdown");
MarlinState marlin_state = MF_INITIALIZING;
@ -304,48 +308,6 @@ bool pin_is_protected(const pin_t pin) {
#pragma GCC diagnostic pop
void enable_e_steppers() {
#define _ENA_E(N) ENABLE_AXIS_E##N();
REPEAT(E_STEPPERS, _ENA_E)
}
void enable_all_steppers() {
TERN_(AUTO_POWER_CONTROL, powerManager.power_on());
ENABLE_AXIS_X();
ENABLE_AXIS_Y();
ENABLE_AXIS_Z();
ENABLE_AXIS_I(); // Marlin 6-axis support by DerAndere (https://github.com/DerAndere1/Marlin/wiki)
ENABLE_AXIS_J();
ENABLE_AXIS_K();
enable_e_steppers();
TERN_(EXTENSIBLE_UI, ExtUI::onSteppersEnabled());
}
void disable_e_steppers() {
#define _DIS_E(N) DISABLE_AXIS_E##N();
REPEAT(E_STEPPERS, _DIS_E)
}
void disable_e_stepper(const uint8_t e) {
#define _CASE_DIS_E(N) case N: DISABLE_AXIS_E##N(); break;
switch (e) {
REPEAT(E_STEPPERS, _CASE_DIS_E)
}
}
void disable_all_steppers() {
DISABLE_AXIS_X();
DISABLE_AXIS_Y();
DISABLE_AXIS_Z();
DISABLE_AXIS_I();
DISABLE_AXIS_J();
DISABLE_AXIS_K();
disable_e_steppers();
TERN_(EXTENSIBLE_UI, ExtUI::onSteppersDisabled());
}
/**
* A Print Job exists when the timer is running or SD is printing
*/
@ -456,13 +418,13 @@ inline void manage_inactivity(const bool no_stepper_sleep=false) {
already_shutdown_steppers = true; // L6470 SPI will consume 99% of free time without this
// Individual axes will be disabled if configured
if (ENABLED(DISABLE_INACTIVE_X)) DISABLE_AXIS_X();
if (ENABLED(DISABLE_INACTIVE_Y)) DISABLE_AXIS_Y();
if (ENABLED(DISABLE_INACTIVE_Z)) DISABLE_AXIS_Z();
if (ENABLED(DISABLE_INACTIVE_I)) DISABLE_AXIS_I();
if (ENABLED(DISABLE_INACTIVE_J)) DISABLE_AXIS_J();
if (ENABLED(DISABLE_INACTIVE_K)) DISABLE_AXIS_K();
if (ENABLED(DISABLE_INACTIVE_E)) disable_e_steppers();
TERN_(DISABLE_INACTIVE_X, stepper.disable_axis(X_AXIS));
TERN_(DISABLE_INACTIVE_Y, stepper.disable_axis(Y_AXIS));
TERN_(DISABLE_INACTIVE_Z, stepper.disable_axis(Z_AXIS));
TERN_(DISABLE_INACTIVE_I, stepper.disable_axis(I_AXIS));
TERN_(DISABLE_INACTIVE_J, stepper.disable_axis(J_AXIS));
TERN_(DISABLE_INACTIVE_K, stepper.disable_axis(K_AXIS));
TERN_(DISABLE_INACTIVE_E, stepper.disable_e_steppers());
TERN_(AUTO_BED_LEVELING_UBL, ubl.steppers_were_disabled());
}
@ -532,6 +494,7 @@ inline void manage_inactivity(const bool no_stepper_sleep=false) {
next_cub_ms_##N = ms + CUB_DEBOUNCE_DELAY_##N; \
CODE; \
queue.inject_P(PSTR(BUTTON##N##_GCODE)); \
TERN_(HAS_LCD_MENU, ui.quick_feedback()); \
} \
} \
}while(0)
@ -680,13 +643,13 @@ inline void manage_inactivity(const bool no_stepper_sleep=false) {
#if ENABLED(SWITCHING_EXTRUDER)
bool oldstatus;
switch (active_extruder) {
default: oldstatus = E0_ENABLE_READ(); ENABLE_AXIS_E0(); break;
default: oldstatus = stepper.AXIS_IS_ENABLED(E_AXIS, 0); stepper.ENABLE_EXTRUDER(0); break;
#if E_STEPPERS > 1
case 2: case 3: oldstatus = E1_ENABLE_READ(); ENABLE_AXIS_E1(); break;
case 2: case 3: oldstatus = stepper.AXIS_IS_ENABLED(E_AXIS, 1); stepper.ENABLE_EXTRUDER(1); break;
#if E_STEPPERS > 2
case 4: case 5: oldstatus = E2_ENABLE_READ(); ENABLE_AXIS_E2(); break;
case 4: case 5: oldstatus = stepper.AXIS_IS_ENABLED(E_AXIS, 2); stepper.ENABLE_EXTRUDER(2); break;
#if E_STEPPERS > 3
case 6: case 7: oldstatus = E3_ENABLE_READ(); ENABLE_AXIS_E3(); break;
case 6: case 7: oldstatus = stepper.AXIS_IS_ENABLED(E_AXIS, 3); stepper.ENABLE_EXTRUDER(3); break;
#endif // E_STEPPERS > 3
#endif // E_STEPPERS > 2
#endif // E_STEPPERS > 1
@ -695,7 +658,7 @@ inline void manage_inactivity(const bool no_stepper_sleep=false) {
bool oldstatus;
switch (active_extruder) {
default:
#define _CASE_EN(N) case N: oldstatus = E##N##_ENABLE_READ(); ENABLE_AXIS_E##N(); break;
#define _CASE_EN(N) case N: oldstatus = stepper.AXIS_IS_ENABLED(E_AXIS, N); stepper.ENABLE_EXTRUDER(N); break;
REPEAT(E_STEPPERS, _CASE_EN);
}
#endif
@ -709,17 +672,17 @@ inline void manage_inactivity(const bool no_stepper_sleep=false) {
#if ENABLED(SWITCHING_EXTRUDER)
switch (active_extruder) {
default: oldstatus = E0_ENABLE_WRITE(oldstatus); break;
default: if (oldstatus) stepper.ENABLE_EXTRUDER(0); else stepper.DISABLE_EXTRUDER(0); break;
#if E_STEPPERS > 1
case 2: case 3: oldstatus = E1_ENABLE_WRITE(oldstatus); break;
case 2: case 3: if (oldstatus) stepper.ENABLE_EXTRUDER(1); else stepper.DISABLE_EXTRUDER(1); break;
#if E_STEPPERS > 2
case 4: case 5: oldstatus = E2_ENABLE_WRITE(oldstatus); break;
case 4: case 5: if (oldstatus) stepper.ENABLE_EXTRUDER(2); else stepper.DISABLE_EXTRUDER(2); break;
#endif // E_STEPPERS > 2
#endif // E_STEPPERS > 1
}
#else // !SWITCHING_EXTRUDER
switch (active_extruder) {
#define _CASE_RESTORE(N) case N: E##N##_ENABLE_WRITE(oldstatus); break;
#define _CASE_RESTORE(N) case N: if (oldstatus) stepper.ENABLE_EXTRUDER(N); else stepper.DISABLE_EXTRUDER(N); break;
REPEAT(E_STEPPERS, _CASE_RESTORE);
}
#endif // !SWITCHING_EXTRUDER
@ -788,7 +751,7 @@ inline void manage_inactivity(const bool no_stepper_sleep=false) {
void idle(bool no_stepper_sleep/*=false*/) {
#if ENABLED(MARLIN_DEV_MODE)
static uint16_t idle_depth = 0;
if (++idle_depth > 5) SERIAL_ECHOLNPAIR("idle() call depth: ", idle_depth);
if (++idle_depth > 5) SERIAL_ECHOLNPGM("idle() call depth: ", idle_depth);
#endif
// Core Marlin activities
@ -842,7 +805,7 @@ void idle(bool no_stepper_sleep/*=false*/) {
TERN_(USE_BEEPER, buzzer.tick());
// Handle UI input / draw events
TERN(DWIN_CREALITY_LCD, DWIN_Update(), ui.update());
TERN(HAS_DWIN_E3V2_BASIC, DWIN_Update(), ui.update());
// Run i2c Position Encoders
#if ENABLED(I2C_POSITION_ENCODERS)
@ -864,6 +827,7 @@ void idle(bool no_stepper_sleep/*=false*/) {
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());
TERN_(BUFFER_MONITORING, queue.auto_report_buffer_statistics());
}
#endif
@ -896,7 +860,7 @@ void kill(PGM_P const lcd_error/*=nullptr*/, PGM_P const lcd_component/*=nullptr
// Echo the LCD message to serial for extra context
if (lcd_error) { SERIAL_ECHO_START(); SERIAL_ECHOLNPGM_P(lcd_error); }
#if HAS_DISPLAY
#if EITHER(HAS_DISPLAY, DWIN_CREALITY_LCD_ENHANCED)
ui.kill_screen(lcd_error ?: GET_TEXT(MSG_KILLED), lcd_component ?: NUL_STR);
#else
UNUSED(lcd_error); UNUSED(lcd_component);
@ -930,9 +894,9 @@ void minkill(const bool steppers_off/*=false*/) {
TERN_(HAS_CUTTER, cutter.kill()); // Reiterate cutter shutdown
// Power off all steppers (for M112) or just the E steppers
steppers_off ? disable_all_steppers() : disable_e_steppers();
steppers_off ? stepper.disable_all_steppers() : stepper.disable_e_steppers();
TERN_(PSU_CONTROL, PSU_OFF());
TERN_(PSU_CONTROL, powerManager.power_off());
TERN_(HAS_SUICIDE, suicide());
@ -1187,7 +1151,7 @@ void setup() {
#if HAS_SUICIDE
SETUP_LOG("SUICIDE_PIN");
OUT_WRITE(SUICIDE_PIN, !SUICIDE_PIN_INVERTING);
OUT_WRITE(SUICIDE_PIN, !SUICIDE_PIN_STATE);
#endif
#ifdef JTAGSWD_RESET
@ -1214,10 +1178,10 @@ void setup() {
SETUP_RUN(HAL_init());
// Init and disable SPI thermocouples; this is still needed
#if TEMP_SENSOR_0_IS_MAX_TC || (TEMP_SENSOR_REDUNDANT_IS_MAX_TC && TEMP_SENSOR_REDUNDANT_SOURCE == 0)
#if TEMP_SENSOR_0_IS_MAX_TC || (TEMP_SENSOR_REDUNDANT_IS_MAX_TC && REDUNDANT_TEMP_MATCH(SOURCE, E0))
OUT_WRITE(TEMP_0_CS_PIN, HIGH); // Disable
#endif
#if TEMP_SENSOR_1_IS_MAX_TC || (TEMP_SENSOR_REDUNDANT_IS_MAX_TC && TEMP_SENSOR_REDUNDANT_SOURCE == 1)
#if TEMP_SENSOR_1_IS_MAX_TC || (TEMP_SENSOR_REDUNDANT_IS_MAX_TC && REDUNDANT_TEMP_MATCH(SOURCE, E1))
OUT_WRITE(TEMP_1_CS_PIN, HIGH);
#endif
@ -1235,8 +1199,7 @@ void setup() {
#if ENABLED(PSU_CONTROL)
SETUP_LOG("PSU_CONTROL");
powersupply_on = ENABLED(PSU_DEFAULT_OFF);
if (ENABLED(PSU_DEFAULT_OFF)) PSU_OFF(); else PSU_ON();
powerManager.init();
#endif
#if ENABLED(POWER_LOSS_RECOVERY)
@ -1275,14 +1238,13 @@ void setup() {
HAL_clear_reset_source();
SERIAL_ECHOLNPGM("Marlin " SHORT_BUILD_VERSION);
SERIAL_EOL();
#if defined(STRING_DISTRIBUTION_DATE) && defined(STRING_CONFIG_H_AUTHOR)
SERIAL_ECHO_MSG(
" Last Updated: " STRING_DISTRIBUTION_DATE
" | Author: " STRING_CONFIG_H_AUTHOR
);
#endif
SERIAL_ECHO_MSG("Compiled: " __DATE__);
SERIAL_ECHO_MSG(" Compiled: " __DATE__);
SERIAL_ECHO_MSG(STR_FREE_MEMORY, freeMemory(), STR_PLANNER_BUFFER_BYTES, sizeof(block_t) * (BLOCK_BUFFER_SIZE));
// Some HAL need precise delay adjustment
@ -1309,7 +1271,7 @@ void setup() {
// UI must be initialized before EEPROM
// (because EEPROM code calls the UI).
#if ENABLED(DWIN_CREALITY_LCD)
#if HAS_DWIN_E3V2_BASIC
SETUP_RUN(DWIN_Startup());
#else
SETUP_RUN(ui.init());
@ -1345,7 +1307,7 @@ void setup() {
#endif
#if HAS_TOUCH_BUTTONS
SETUP_RUN(touch.init());
SETUP_RUN(touchBt.init());
#endif
TERN_(HAS_M206_COMMAND, current_position += home_offset); // Init current position based on home_offset
@ -1584,7 +1546,7 @@ void setup() {
SERIAL_ECHO_TERNARY(err, "BL24CXX Check ", "failed", "succeeded", "!\n");
#endif
#if ENABLED(DWIN_CREALITY_LCD)
#if HAS_DWIN_E3V2_BASIC
Encoder_Configuration();
HMI_Init();
HMI_SetLanguageCache();
@ -1592,7 +1554,7 @@ void setup() {
DWIN_StatusChanged_P(GET_TEXT(WELCOME_MSG));
#endif
#if HAS_SERVICE_INTERVALS && DISABLED(DWIN_CREALITY_LCD)
#if HAS_SERVICE_INTERVALS && !HAS_DWIN_E3V2_BASIC
ui.reset_status(true); // Show service messages or keep current status
#endif
@ -1614,7 +1576,7 @@ void setup() {
#if BOTH(HAS_WIRED_LCD, SHOW_BOOTSCREEN)
const millis_t elapsed = millis() - bootscreen_ms;
#if ENABLED(MARLIN_DEV_MODE)
SERIAL_ECHOLNPAIR("elapsed=", elapsed);
SERIAL_ECHOLNPGM("elapsed=", elapsed);
#endif
SETUP_RUN(ui.bootscreen_completion(elapsed));
#endif

34
Marlin/src/MarlinCore.h

@ -23,10 +23,6 @@
#include "inc/MarlinConfig.h"
#ifdef DEBUG_GCODE_PARSER
#include "gcode/parser.h"
#endif
#include <math.h>
#include <stdio.h>
#include <stdlib.h>
@ -42,15 +38,6 @@ inline void idle_no_sleep() { idle(true); }
extern bool G38_did_trigger; // Flag from the ISR to indicate the endstop changed
#endif
/**
* The axis order in all axis related arrays is X, Y, Z, E
*/
void enable_e_steppers();
void enable_all_steppers();
void disable_e_stepper(const uint8_t e);
void disable_e_steppers();
void disable_all_steppers();
void kill(PGM_P const lcd_error=nullptr, PGM_P const lcd_component=nullptr, const bool steppers_off=false);
void minkill(const bool steppers_off=false);
@ -81,29 +68,10 @@ extern bool wait_for_heatup;
void wait_for_user_response(millis_t ms=0, const bool no_sleep=false);
#endif
#if ENABLED(PSU_CONTROL)
extern bool powersupply_on;
#define PSU_PIN_ON() do{ OUT_WRITE(PS_ON_PIN, PSU_ACTIVE_STATE); powersupply_on = true; }while(0)
#define PSU_PIN_OFF() do{ OUT_WRITE(PS_ON_PIN, !PSU_ACTIVE_STATE); powersupply_on = false; }while(0)
#if ENABLED(AUTO_POWER_CONTROL)
#define PSU_ON() powerManager.power_on()
#define PSU_OFF() powerManager.power_off()
#define PSU_OFF_SOON() powerManager.power_off_soon()
#else
#define PSU_ON() PSU_PIN_ON()
#if ENABLED(PS_OFF_SOUND)
#define PSU_OFF() do{ BUZZ(1000, 659); PSU_PIN_OFF(); }while(0)
#else
#define PSU_OFF() PSU_PIN_OFF()
#endif
#define PSU_OFF_SOON PSU_OFF
#endif
#endif
bool pin_is_protected(const pin_t pin);
#if HAS_SUICIDE
inline void suicide() { OUT_WRITE(SUICIDE_PIN, SUICIDE_PIN_INVERTING); }
inline void suicide() { OUT_WRITE(SUICIDE_PIN, SUICIDE_PIN_STATE); }
#endif
#if HAS_KILL

92
Marlin/src/core/boards.h

@ -149,10 +149,10 @@
#define BOARD_GT2560_REV_A 1314 // Geeetech GT2560 Rev A
#define BOARD_GT2560_REV_A_PLUS 1315 // Geeetech GT2560 Rev A+ (with auto level probe)
#define BOARD_GT2560_REV_B 1316 // Geeetech GT2560 Rev B
#define BOARD_GT2560_V3 1317 // Geeetech GT2560 Rev B for A10(M/D)
#define BOARD_GT2560_V4 1318 // Geeetech GT2560 Rev B for A10(M/D)
#define BOARD_GT2560_V3 1317 // Geeetech GT2560 Rev B for A10(M/T/D)
#define BOARD_GT2560_V4 1318 // Geeetech GT2560 Rev B for A10(M/T/D)
#define BOARD_GT2560_V3_MC2 1319 // Geeetech GT2560 Rev B for Mecreator2
#define BOARD_GT2560_V3_A20 1320 // Geeetech GT2560 Rev B for A20(M/D)
#define BOARD_GT2560_V3_A20 1320 // Geeetech GT2560 Rev B for A20(M/T/D)
#define BOARD_EINSTART_S 1321 // Einstart retrofit
#define BOARD_WANHAO_ONEPLUS 1322 // Wanhao 0ne+ i3 Mini
#define BOARD_LEAPFROG_XEED2015 1323 // Leapfrog Xeed 2015
@ -160,6 +160,8 @@
#define BOARD_PICA 1325 // PICA Shield (rev C or later)
#define BOARD_INTAMSYS40 1326 // Intamsys 4.0 (Funmat HT)
#define BOARD_MALYAN_M180 1327 // Malyan M180 Mainboard Version 2 (no display function, direct gcode only)
#define BOARD_GT2560_V4_A20 1328 // Geeetech GT2560 Rev B for A20(M/T/D)
#define BOARD_PROTONEER_CNC_SHIELD_V3 1329 // Mega controller & Protoneer CNC Shield V3.00
//
// ATmega1281, ATmega2561
@ -338,17 +340,21 @@
#define BOARD_CREALITY_V427 4040 // Creality v4.2.7 (STM32F103RE)
#define BOARD_CREALITY_V4210 4041 // Creality v4.2.10 (STM32F103RE) as found in the CR-30
#define BOARD_CREALITY_V431 4042 // Creality v4.3.1 (STM32F103RE)
#define BOARD_CREALITY_V452 4043 // Creality v4.5.2 (STM32F103RE)
#define BOARD_CREALITY_V453 4044 // Creality v4.5.3 (STM32F103RE)
#define BOARD_TRIGORILLA_PRO 4045 // Trigorilla Pro (STM32F103ZET6)
#define BOARD_FLY_MINI 4046 // FLYmaker FLY MINI (STM32F103RCT6)
#define BOARD_FLSUN_HISPEED 4047 // FLSUN HiSpeedV1 (STM32F103VET6)
#define BOARD_BEAST 4048 // STM32F103RET6 Libmaple-based controller
#define BOARD_MINGDA_MPX_ARM_MINI 4049 // STM32F103ZET6 Mingda MD-16
#define BOARD_GTM32_PRO_VD 4050 // STM32F103VET6 controller
#define BOARD_ZONESTAR_ZM3E2 4051 // Zonestar ZM3E2 (STM32F103RCT6)
#define BOARD_ZONESTAR_ZM3E4 4052 // Zonestar ZM3E4 V1 (STM32F103VCT6)
#define BOARD_ZONESTAR_ZM3E4V2 4053 // Zonestar ZM3E4 V2 (STM32F103VCT6)
#define BOARD_CREALITY_V431_A 4043 // Creality v4.3.1a (STM32F103RE)
#define BOARD_CREALITY_V431_B 4044 // Creality v4.3.1b (STM32F103RE)
#define BOARD_CREALITY_V431_C 4045 // Creality v4.3.1c (STM32F103RE)
#define BOARD_CREALITY_V431_D 4046 // Creality v4.3.1d (STM32F103RE)
#define BOARD_CREALITY_V452 4047 // Creality v4.5.2 (STM32F103RE)
#define BOARD_CREALITY_V453 4048 // Creality v4.5.3 (STM32F103RE)
#define BOARD_TRIGORILLA_PRO 4049 // Trigorilla Pro (STM32F103ZET6)
#define BOARD_FLY_MINI 4050 // FLYmaker FLY MINI (STM32F103RCT6)
#define BOARD_FLSUN_HISPEED 4051 // FLSUN HiSpeedV1 (STM32F103VET6)
#define BOARD_BEAST 4052 // STM32F103RET6 Libmaple-based controller
#define BOARD_MINGDA_MPX_ARM_MINI 4053 // STM32F103ZET6 Mingda MD-16
#define BOARD_GTM32_PRO_VD 4054 // STM32F103VET6 controller
#define BOARD_ZONESTAR_ZM3E2 4055 // Zonestar ZM3E2 (STM32F103RCT6)
#define BOARD_ZONESTAR_ZM3E4 4056 // Zonestar ZM3E4 V1 (STM32F103VCT6)
#define BOARD_ZONESTAR_ZM3E4V2 4057 // Zonestar ZM3E4 V2 (STM32F103VCT6)
//
// ARM Cortex-M4F
@ -365,33 +371,37 @@
#define BOARD_RUMBA32_V1_0 4201 // RUMBA32 STM32F446VET6 based controller from Aus3D
#define BOARD_RUMBA32_V1_1 4202 // RUMBA32 STM32F446VET6 based controller from Aus3D
#define BOARD_RUMBA32_MKS 4203 // RUMBA32 STM32F446VET6 based controller from Makerbase
#define BOARD_BLACK_STM32F407VE 4204 // BLACK_STM32F407VE
#define BOARD_BLACK_STM32F407ZE 4205 // BLACK_STM32F407ZE
#define BOARD_STEVAL_3DP001V1 4206 // STEVAL-3DP001V1 3D PRINTER BOARD
#define BOARD_BTT_SKR_PRO_V1_1 4207 // BigTreeTech SKR Pro v1.1 (STM32F407ZGT6)
#define BOARD_BTT_SKR_PRO_V1_2 4208 // BigTreeTech SKR Pro v1.2 (STM32F407ZGT6)
#define BOARD_BTT_BTT002_V1_0 4209 // BigTreeTech BTT002 v1.0 (STM32F407VGT6)
#define BOARD_BTT_E3_RRF 4210 // BigTreeTech E3 RRF (STM32F407VGT6)
#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_BTT_OCTOPUS_V1_0 4214 // BigTreeTech Octopus v1.0 (STM32F446ZET6)
#define BOARD_BTT_OCTOPUS_V1_1 4215 // BigTreeTech Octopus v1.1 (STM32F446ZET6)
#define BOARD_LERDGE_K 4216 // Lerdge K (STM32F407ZG)
#define BOARD_LERDGE_S 4217 // Lerdge S (STM32F407VE)
#define BOARD_LERDGE_X 4218 // Lerdge X (STM32F407VE)
#define BOARD_VAKE403D 4219 // VAkE 403D (STM32F446VET6)
#define BOARD_FYSETC_S6 4220 // FYSETC S6 (STM32F446VET6)
#define BOARD_FYSETC_S6_V2_0 4221 // FYSETC S6 v2.0 (STM32F446VET6)
#define BOARD_FYSETC_SPIDER 4222 // FYSETC Spider (STM32F446VET6)
#define BOARD_FLYF407ZG 4223 // FLYmaker FLYF407ZG (STM32F407ZG)
#define BOARD_MKS_ROBIN2 4224 // MKS_ROBIN2 (STM32F407ZE)
#define BOARD_MKS_ROBIN_PRO_V2 4225 // MKS Robin Pro V2 (STM32F407VE)
#define BOARD_MKS_ROBIN_NANO_V3 4226 // MKS Robin Nano V3 (STM32F407VG)
#define BOARD_MKS_MONSTER8 4227 // MKS Monster8 (STM32F407VGT6)
#define BOARD_ANET_ET4 4228 // ANET ET4 V1.x (STM32F407VGT6)
#define BOARD_ANET_ET4P 4229 // ANET ET4P V1.x (STM32F407VGT6)
#define BOARD_FYSETC_CHEETAH_V20 4230 // FYSETC Cheetah V2.0
#define BOARD_RUMBA32_BTT 4204 // RUMBA32 STM32F446VET6 based controller from BIGTREETECH
#define BOARD_BLACK_STM32F407VE 4205 // BLACK_STM32F407VE
#define BOARD_BLACK_STM32F407ZE 4206 // BLACK_STM32F407ZE
#define BOARD_STEVAL_3DP001V1 4207 // STEVAL-3DP001V1 3D PRINTER BOARD
#define BOARD_BTT_SKR_PRO_V1_1 4208 // BigTreeTech SKR Pro v1.1 (STM32F407ZGT6)
#define BOARD_BTT_SKR_PRO_V1_2 4209 // BigTreeTech SKR Pro v1.2 (STM32F407ZGT6)
#define BOARD_BTT_BTT002_V1_0 4210 // BigTreeTech BTT002 v1.0 (STM32F407VGT6)
#define BOARD_BTT_E3_RRF 4211 // BigTreeTech E3 RRF (STM32F407VGT6)
#define BOARD_BTT_SKR_V2_0_REV_A 4212 // BigTreeTech SKR v2.0 Rev A (STM32F407VGT6)
#define BOARD_BTT_SKR_V2_0_REV_B 4213 // BigTreeTech SKR v2.0 Rev B (STM32F407VGT6)
#define BOARD_BTT_GTR_V1_0 4214 // BigTreeTech GTR v1.0 (STM32F407IGT)
#define BOARD_BTT_OCTOPUS_V1_0 4215 // BigTreeTech Octopus v1.0 (STM32F446ZET6)
#define BOARD_BTT_OCTOPUS_V1_1 4216 // BigTreeTech Octopus v1.1 (STM32F446ZET6)
#define BOARD_LERDGE_K 4217 // Lerdge K (STM32F407ZG)
#define BOARD_LERDGE_S 4218 // Lerdge S (STM32F407VE)
#define BOARD_LERDGE_X 4219 // Lerdge X (STM32F407VE)
#define BOARD_VAKE403D 4220 // VAkE 403D (STM32F446VET6)
#define BOARD_FYSETC_S6 4221 // FYSETC S6 (STM32F446VET6)
#define BOARD_FYSETC_S6_V2_0 4222 // FYSETC S6 v2.0 (STM32F446VET6)
#define BOARD_FYSETC_SPIDER 4223 // FYSETC Spider (STM32F446VET6)
#define BOARD_FLYF407ZG 4224 // FLYmaker FLYF407ZG (STM32F407ZG)
#define BOARD_MKS_ROBIN2 4225 // MKS_ROBIN2 (STM32F407ZE)
#define BOARD_MKS_ROBIN_PRO_V2 4226 // MKS Robin Pro V2 (STM32F407VE)
#define BOARD_MKS_ROBIN_NANO_V3 4227 // MKS Robin Nano V3 (STM32F407VG)
#define BOARD_MKS_MONSTER8 4228 // MKS Monster8 (STM32F407VGT6)
#define BOARD_ANET_ET4 4229 // ANET ET4 V1.x (STM32F407VGT6)
#define BOARD_ANET_ET4P 4230 // ANET ET4P V1.x (STM32F407VGT6)
#define BOARD_FYSETC_CHEETAH_V20 4231 // FYSETC Cheetah V2.0
#define BOARD_TH3D_EZBOARD_LITE_V2 4232 // TH3D EZBoard Lite v2.0
#define BOARD_INDEX_REV03 4233 // Index PnP Controller REV03 (STM32F407VET6/VGT6)
#define BOARD_MKS_ROBIN_NANO_V1_3_F4 4234 // MKS Robin Nano V1.3 and MKS Robin Nano-S V1.3 (STM32F407VET6)
//
// ARM Cortex M7

12
Marlin/src/core/bug_on.h

@ -20,19 +20,19 @@
*/
#pragma once
// We need SERIAL_ECHOPAIR and macros.h
// We need SERIAL_ECHOPGM and macros.h
#include "serial.h"
#if ENABLED(POSTMORTEM_DEBUGGING)
// Useful macro for stopping the CPU on an unexpected condition
// This is used like SERIAL_ECHOPAIR, that is: a key-value call of the local variables you want
// This is used like SERIAL_ECHOPGM, that is: a key-value call of the local variables you want
// to dump to the serial port before stopping the CPU.
// \/ Don't replace by SERIAL_ECHOPAIR since ONLY_FILENAME cannot be transformed to a PGM string on Arduino and it breaks building
#define BUG_ON(V...) do { SERIAL_ECHO(ONLY_FILENAME); SERIAL_ECHO(__LINE__); SERIAL_ECHOLNPGM(": "); SERIAL_ECHOLNPAIR(V); SERIAL_FLUSHTX(); *(char*)0 = 42; } while(0)
// \/ Don't replace by SERIAL_ECHOPGM since ONLY_FILENAME cannot be transformed to a PGM string on Arduino and it breaks building
#define BUG_ON(V...) do { SERIAL_ECHO(ONLY_FILENAME); SERIAL_ECHO(__LINE__); SERIAL_ECHOLNPGM(": "); SERIAL_ECHOLNPGM(V); SERIAL_FLUSHTX(); *(char*)0 = 42; } while(0)
#elif ENABLED(MARLIN_DEV_MODE)
// Don't stop the CPU here, but at least dump the bug on the serial port
// \/ Don't replace by SERIAL_ECHOPAIR since ONLY_FILENAME cannot be transformed to a PGM string on Arduino and it breaks building
#define BUG_ON(V...) do { SERIAL_ECHO(ONLY_FILENAME); SERIAL_ECHO(__LINE__); SERIAL_ECHOLNPGM(": BUG!"); SERIAL_ECHOLNPAIR(V); SERIAL_FLUSHTX(); } while(0)
// \/ Don't replace by SERIAL_ECHOPGM since ONLY_FILENAME cannot be transformed to a PGM string on Arduino and it breaks building
#define BUG_ON(V...) do { SERIAL_ECHO(ONLY_FILENAME); SERIAL_ECHO(__LINE__); SERIAL_ECHOLNPGM(": BUG!"); SERIAL_ECHOLNPGM(V); SERIAL_FLUSHTX(); } while(0)
#else
// Release mode, let's ignore the bug
#define BUG_ON(V...) NOOP

23
Marlin/src/core/debug_out.h

@ -27,7 +27,6 @@
//
#undef DEBUG_SECTION
#undef DEBUG_ECHOPGM_P
#undef DEBUG_ECHO_START
#undef DEBUG_ERROR_START
#undef DEBUG_CHAR
@ -37,12 +36,10 @@
#undef DEBUG_ECHOLN
#undef DEBUG_ECHOPGM
#undef DEBUG_ECHOLNPGM
#undef DEBUG_ECHOPAIR
#undef DEBUG_ECHOPAIR_P
#undef DEBUG_ECHOPGM_P
#undef DEBUG_ECHOLNPGM_P
#undef DEBUG_ECHOPAIR_F
#undef DEBUG_ECHOPAIR_F_P
#undef DEBUG_ECHOLNPAIR
#undef DEBUG_ECHOLNPAIR_P
#undef DEBUG_ECHOLNPAIR_F
#undef DEBUG_ECHOLNPAIR_F_P
#undef DEBUG_ECHO_MSG
@ -59,7 +56,6 @@
#include "debug_section.h"
#define DEBUG_SECTION(N,S,D) SectionLog N(PSTR(S),D)
#define DEBUG_ECHOPGM_P(P) SERIAL_ECHOPGM_P(P)
#define DEBUG_ECHO_START SERIAL_ECHO_START
#define DEBUG_ERROR_START SERIAL_ERROR_START
#define DEBUG_CHAR SERIAL_CHAR
@ -69,12 +65,12 @@
#define DEBUG_ECHOLN SERIAL_ECHOLN
#define DEBUG_ECHOPGM SERIAL_ECHOPGM
#define DEBUG_ECHOLNPGM SERIAL_ECHOLNPGM
#define DEBUG_ECHOPAIR SERIAL_ECHOPAIR
#define DEBUG_ECHOPAIR_P SERIAL_ECHOPAIR_P
#define DEBUG_ECHOPGM SERIAL_ECHOPGM
#define DEBUG_ECHOPGM_P SERIAL_ECHOPGM_P
#define DEBUG_ECHOPAIR_F SERIAL_ECHOPAIR_F
#define DEBUG_ECHOPAIR_F_P SERIAL_ECHOPAIR_F_P
#define DEBUG_ECHOLNPAIR SERIAL_ECHOLNPAIR
#define DEBUG_ECHOLNPAIR_P SERIAL_ECHOLNPAIR_P
#define DEBUG_ECHOLNPGM SERIAL_ECHOLNPGM
#define DEBUG_ECHOLNPGM_P SERIAL_ECHOLNPGM_P
#define DEBUG_ECHOLNPAIR_F SERIAL_ECHOLNPAIR_F
#define DEBUG_ECHOLNPAIR_F_P SERIAL_ECHOLNPAIR_F_P
#define DEBUG_ECHO_MSG SERIAL_ECHO_MSG
@ -89,7 +85,6 @@
#else
#define DEBUG_SECTION(...) NOOP
#define DEBUG_ECHOPGM_P(P) NOOP
#define DEBUG_ECHO_START() NOOP
#define DEBUG_ERROR_START() NOOP
#define DEBUG_CHAR(...) NOOP
@ -99,12 +94,10 @@
#define DEBUG_ECHOLN(...) NOOP
#define DEBUG_ECHOPGM(...) NOOP
#define DEBUG_ECHOLNPGM(...) NOOP
#define DEBUG_ECHOPAIR(...) NOOP
#define DEBUG_ECHOPAIR_P(...) NOOP
#define DEBUG_ECHOPGM_P(...) NOOP
#define DEBUG_ECHOLNPGM_P(...) NOOP
#define DEBUG_ECHOPAIR_F(...) NOOP
#define DEBUG_ECHOPAIR_F_P(...) NOOP
#define DEBUG_ECHOLNPAIR(...) NOOP
#define DEBUG_ECHOLNPAIR_P(...) NOOP
#define DEBUG_ECHOLNPAIR_F(...) NOOP
#define DEBUG_ECHOLNPAIR_F_P(...) NOOP
#define DEBUG_ECHO_MSG(...) NOOP

56
Marlin/src/core/language.h

@ -48,8 +48,8 @@
// cz Czech
// da Danish
// de German
// el Greek
// el_gr Greek (Greece)
// el Greek (Greece)
// el_CY Greek (Cyprus)
// en English
// es Spanish
// eu Basque-Euskera
@ -158,15 +158,14 @@
#define STR_OFF "OFF"
#define STR_ENDSTOP_HIT "TRIGGERED"
#define STR_ENDSTOP_OPEN "open"
#define STR_HOTEND_OFFSET "Hotend offsets:"
#define STR_DUPLICATION_MODE "Duplication mode: "
#define STR_SOFT_ENDSTOPS "Soft endstops: "
#define STR_SOFT_MIN " Min: "
#define STR_SOFT_MAX " Max: "
#define STR_SAVED_POS "Position saved"
#define STR_RESTORING_POS "Restoring position"
#define STR_INVALID_POS_SLOT "Invalid slot. Total: "
#define STR_DONE "Done."
#define STR_SD_CANT_OPEN_SUBDIR "Cannot open subdir "
#define STR_SD_INIT_FAIL "No SD card"
@ -231,6 +230,9 @@
#define STR_HEATER_BED "bed"
#define STR_HEATER_CHAMBER "chamber"
#define STR_COOLER "cooler"
#define STR_MOTHERBOARD "motherboard"
#define STR_PROBE "probe"
#define STR_REDUNDANT "redundant "
#define STR_LASER_TEMP "laser temperature"
#define STR_STOPPED_HEATER ", system stopped! Heater_ID: "
@ -259,6 +261,50 @@
#define STR_REMINDER_SAVE_SETTINGS "Remember to save!"
#define STR_PASSWORD_SET "Password is "
// Settings Report Strings
#define STR_Z_AUTO_ALIGN "Z Auto-Align"
#define STR_BACKLASH_COMPENSATION "Backlash compensation"
#define STR_S_SEG_PER_SEC "S<seg-per-sec>"
#define STR_DELTA_SETTINGS "Delta (L<diagonal-rod> R<radius> H<height> S<seg-per-sec> XYZ<tower-angle-trim> ABC<rod-trim>)"
#define STR_SCARA_SETTINGS "SCARA"
#define STR_POLARGRAPH_SETTINGS "Polargraph"
#define STR_SCARA_P_T_Z "P<theta-psi-offset> T<theta-offset> Z<home-offset>"
#define STR_ENDSTOP_ADJUSTMENT "Endstop adjustment"
#define STR_SKEW_FACTOR "Skew Factor"
#define STR_FILAMENT_SETTINGS "Filament settings"
#define STR_MAX_ACCELERATION "Max Acceleration (units/s2)"
#define STR_MAX_FEEDRATES "Max feedrates (units/s)"
#define STR_ACCELERATION_P_R_T "Acceleration (units/s2) (P<print-accel> R<retract-accel> T<travel-accel>)"
#define STR_TOOL_CHANGING "Tool-changing"
#define STR_HOTEND_OFFSETS "Hotend offsets"
#define STR_SERVO_ANGLES "Servo Angles"
#define STR_HOTEND_PID "Hotend PID"
#define STR_BED_PID "Bed PID"
#define STR_CHAMBER_PID "Chamber PID"
#define STR_STEPS_PER_UNIT "Steps per unit"
#define STR_LINEAR_ADVANCE "Linear Advance"
#define STR_CONTROLLER_FAN "Controller Fan"
#define STR_STEPPER_MOTOR_CURRENTS "Stepper motor currents"
#define STR_RETRACT_S_F_Z "Retract (S<length> F<feedrate> Z<lift>)"
#define STR_RECOVER_S_F "Recover (S<length> F<feedrate>)"
#define STR_AUTO_RETRACT_S "Auto-Retract (S<enable>)"
#define STR_FILAMENT_LOAD_UNLOAD "Filament load/unload"
#define STR_POWER_LOSS_RECOVERY "Power-loss recovery"
#define STR_FILAMENT_RUNOUT_SENSOR "Filament runout sensor"
#define STR_DRIVER_STEPPING_MODE "Driver stepping mode"
#define STR_STEPPER_DRIVER_CURRENT "Stepper driver current"
#define STR_HYBRID_THRESHOLD "Hybrid Threshold"
#define STR_STALLGUARD_THRESHOLD "StallGuard threshold"
#define STR_HOME_OFFSET "Home offset"
#define STR_SOFT_ENDSTOPS "Soft endstops"
#define STR_MATERIAL_HEATUP "Material heatup parameters"
#define STR_LCD_CONTRAST "LCD Contrast"
#define STR_LCD_BRIGHTNESS "LCD Brightness"
#define STR_UI_LANGUAGE "UI Language"
#define STR_Z_PROBE_OFFSET "Z-Probe Offset"
#define STR_TEMPERATURE_UNITS "Temperature Units"
#define STR_USER_THERMISTORS "User thermistors"
//
// Endstop Names used by Endstops::report_states
//
@ -287,7 +333,7 @@
#define STR_Z_PROBE "z_probe"
#define STR_PROBE_EN "probe_en"
#define STR_FILAMENT_RUNOUT_SENSOR "filament"
#define STR_FILAMENT "filament"
// General axis names
#define STR_X "X"

65
Marlin/src/core/macros.h

@ -33,32 +33,32 @@
#define _AXIS(A) (A##_AXIS)
#define _XMIN_ 100
#define _YMIN_ 200
#define _ZMIN_ 300
#define _IMIN_ 500
#define _JMIN_ 600
#define _KMIN_ 700
#define _XMAX_ 101
#define _YMAX_ 201
#define _ZMAX_ 301
#define _IMAX_ 501
#define _JMAX_ 601
#define _KMAX_ 701
#define _XDIAG_ 102
#define _YDIAG_ 202
#define _ZDIAG_ 302
#define _IDIAG_ 502
#define _JDIAG_ 602
#define _KDIAG_ 702
#define _E0DIAG_ 400
#define _E1DIAG_ 401
#define _E2DIAG_ 402
#define _E3DIAG_ 403
#define _E4DIAG_ 404
#define _E5DIAG_ 405
#define _E6DIAG_ 406
#define _E7DIAG_ 407
#define _XMIN_ 0x11
#define _YMIN_ 0x12
#define _ZMIN_ 0x13
#define _IMIN_ 0x14
#define _JMIN_ 0x15
#define _KMIN_ 0x16
#define _XMAX_ 0x21
#define _YMAX_ 0x22
#define _ZMAX_ 0x23
#define _IMAX_ 0x24
#define _JMAX_ 0x25
#define _KMAX_ 0x26
#define _XDIAG_ 0x31
#define _YDIAG_ 0x32
#define _ZDIAG_ 0x33
#define _IDIAG_ 0x34
#define _JDIAG_ 0x35
#define _KDIAG_ 0x36
#define _E0DIAG_ 0xE0
#define _E1DIAG_ 0xE1
#define _E2DIAG_ 0xE2
#define _E3DIAG_ 0xE3
#define _E4DIAG_ 0xE4
#define _E5DIAG_ 0xE5
#define _E6DIAG_ 0xE6
#define _E7DIAG_ 0xE7
#define _FORCE_INLINE_ __attribute__((__always_inline__)) __inline__
#define FORCE_INLINE __attribute__((always_inline)) inline
@ -251,6 +251,8 @@
memcpy(&a[0],&b[0],_MIN(sizeof(a),sizeof(b))); \
}while(0)
#define CODE_11( A,B,C,D,E,F,G,H,I,J,K,...) A; B; C; D; E; F; G; H; I; J; K
#define CODE_10( A,B,C,D,E,F,G,H,I,J,...) A; B; C; D; E; F; G; H; I; J
#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
@ -260,6 +262,7 @@
#define CODE_3( A,B,C,...) A; B; C
#define CODE_2( A,B,...) A; B
#define CODE_1( A,...) A
#define CODE_0(...)
#define _CODE_N(N,V...) CODE_##N(V)
#define CODE_N(N,V...) _CODE_N(N,V)
@ -279,11 +282,16 @@
#define GANG_3( A,B,C,...) A B C
#define GANG_2( A,B,...) A B
#define GANG_1( A,...) A
#define GANG_0(...)
#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_20(A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T,...) A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,T
#define LIST_19(A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S,...) A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,S
#define LIST_18(A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R,...) A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,R
#define LIST_17(A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q,...) A,B,C,D,E,F,G,H,I,J,K,L,M,N,O,P,Q
#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
#define LIST_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
@ -500,6 +508,11 @@
#define INC_13 14
#define INC_14 15
#define INC_15 16
#define INC_16 17
#define INC_17 18
#define INC_18 19
#define INC_19 20
#define INC_20 21
#define INCREMENT_(n) INC_##n
#define INCREMENT(n) INCREMENT_(n)

62
Marlin/src/core/multi_language.h

@ -1,28 +1,35 @@
/********************
* multi_language.h *
********************/
/****************************************************************************
* Written By Marcio Teixeira 2019 - Aleph Objects, Inc. *
* *
* 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. *
* *
* To view a copy of the GNU General Public License, go to the following *
* location: <https://www.gnu.org/licenses/>. *
****************************************************************************/
/**
* Marlin 3D Printer Firmware
* Copyright (c) 2020 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
/*******************************************************
* multi_language.h *
* By Marcio Teixeira 2019 for Aleph Objects *
*******************************************************/
#include "../inc/MarlinConfigPre.h"
typedef const char Language_Str[];
#define LSTR PROGMEM Language_Str
#ifdef LCD_LANGUAGE_5
#define NUM_LANGUAGES 5
@ -36,9 +43,8 @@ typedef const char Language_Str[];
#define NUM_LANGUAGES 1
#endif
// Setting the unused languages equal to each other allows
// the compiler to optimize away the conditionals
// Set unused languages equal to each other so the
// compiler can optimize away the conditionals.
#ifndef LCD_LANGUAGE_2
#define LCD_LANGUAGE_2 LCD_LANGUAGE
#endif
@ -58,11 +64,11 @@ typedef const char Language_Str[];
#if NUM_LANGUAGES > 1
#define HAS_MULTI_LANGUAGE 1
#define GET_TEXT(MSG) ( \
ui.language == 0 ? GET_LANG(LCD_LANGUAGE )::MSG : \
ui.language == 1 ? GET_LANG(LCD_LANGUAGE_2)::MSG : \
ui.language == 2 ? GET_LANG(LCD_LANGUAGE_3)::MSG : \
ui.language == 4 ? GET_LANG(LCD_LANGUAGE_5)::MSG : \
ui.language == 3 ? GET_LANG(LCD_LANGUAGE_4)::MSG : \
GET_LANG(LCD_LANGUAGE_5)::MSG )
ui.language == 2 ? GET_LANG(LCD_LANGUAGE_3)::MSG : \
ui.language == 1 ? GET_LANG(LCD_LANGUAGE_2)::MSG : \
GET_LANG(LCD_LANGUAGE )::MSG )
#define MAX_LANG_CHARSIZE _MAX(GET_LANG(LCD_LANGUAGE )::CHARSIZE, \
GET_LANG(LCD_LANGUAGE_2)::CHARSIZE, \
GET_LANG(LCD_LANGUAGE_3)::CHARSIZE, \
@ -72,7 +78,7 @@ typedef const char Language_Str[];
#define GET_TEXT(MSG) GET_LANG(LCD_LANGUAGE)::MSG
#define MAX_LANG_CHARSIZE LANG_CHARSIZE
#endif
#define GET_TEXT_F(MSG) (const __FlashStringHelper*)GET_TEXT(MSG)
#define GET_TEXT_F(MSG) FPSTR(GET_TEXT(MSG))
#define GET_LANGUAGE_NAME(INDEX) GET_LANG(LCD_LANGUAGE_##INDEX)::LANGUAGE
#define LANG_CHARSIZE GET_TEXT(CHARSIZE)

2
Marlin/src/core/serial.cpp

@ -96,7 +96,7 @@ void print_bin(uint16_t val) {
void print_pos(LINEAR_AXIS_ARGS(const_float_t), PGM_P const prefix/*=nullptr*/, PGM_P const suffix/*=nullptr*/) {
if (prefix) serialprintPGM(prefix);
SERIAL_ECHOPAIR_P(
SERIAL_ECHOPGM_P(
LIST_N(DOUBLE(LINEAR_AXES), SP_X_STR, x, SP_Y_STR, y, SP_Z_STR, z, SP_I_STR, i, SP_J_STR, j, SP_K_STR, k)
);
if (suffix) serialprintPGM(suffix); else SERIAL_EOL();

38
Marlin/src/core/serial.h

@ -88,7 +88,7 @@ extern uint8_t marlin_debug_flags;
#if HAS_MULTI_SERIAL
#define _PORT_REDIRECT(n,p) REMEMBER(n,multiSerial.portMask,p)
#define _PORT_RESTORE(n,p) RESTORE(n)
#define SERIAL_ASSERT(P) if(multiSerial.portMask!=(P)){ debugger(); }
#define SERIAL_ASSERT(P) if (multiSerial.portMask!=(P)) { debugger(); }
// If we have a catchall, use that directly
#ifdef SERIAL_CATCHALL
#define _SERIAL_LEAF_2 SERIAL_CATCHALL
@ -188,44 +188,44 @@ inline void SERIAL_FLUSHTX() { SERIAL_IMPL.flushTX(); }
void serialprintPGM(PGM_P str);
//
// SERIAL_ECHOPAIR... macros are used to output string-value pairs.
// SERIAL_ECHOPGM... 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_1(s) serialprintPGM(PSTR(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)
#define SERIAL_ECHOPGM(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_1(s) serialprintPGM(PSTR(s "\n"));
#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)
#define SERIAL_ECHOLNPGM(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)
#define _SEP_1_P(p) serialprintPGM(p);
#define _SEP_2_P(p,v) serial_echopair_PGM(p,v);
#define _SEP_3_P(p,v,V...) _SEP_2_P(p,v); DEFER2(_SEP_N_P_REF)()(TWO_ARGS(V),V);
#define SERIAL_ECHOPGM_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)
#define _SELP_1_P(p) { serialprintPGM(p); SERIAL_EOL(); }
#define _SELP_2_P(p,v) { serial_echopair_PGM(p,v); SERIAL_EOL(); }
#define _SELP_3_P(p,v,V...) { _SEP_2_P(p,v); DEFER2(_SELP_N_P_REF)()(TWO_ARGS(V),V); }
#define SERIAL_ECHOLNPGM_P(V...) do{ EVAL(_SELP_N_P(TWO_ARGS(V),V)); }while(0)
#ifdef AllowDifferentTypeInList
@ -261,12 +261,6 @@ void serialprintPGM(PGM_P str);
#endif
#define SERIAL_ECHOPGM_P(P) (serialprintPGM(P))
#define SERIAL_ECHOLNPGM_P(P) do{ serialprintPGM(P); SERIAL_EOL(); }while(0)
#define SERIAL_ECHOPGM(S) (serialprintPGM(PSTR(S)))
#define SERIAL_ECHOLNPGM(S) (serialprintPGM(PSTR(S "\n")))
#define SERIAL_ECHOPAIR_F_P(P,V...) do{ serialprintPGM(P); SERIAL_ECHO_F(V); }while(0)
#define SERIAL_ECHOLNPAIR_F_P(V...) do{ SERIAL_ECHOPAIR_F_P(V); SERIAL_EOL(); }while(0)
@ -277,8 +271,8 @@ void serialprintPGM(PGM_P str);
#define SERIAL_ERROR_START() serial_error_start()
#define SERIAL_EOL() SERIAL_CHAR('\n')
#define SERIAL_ECHO_MSG(V...) do{ SERIAL_ECHO_START(); SERIAL_ECHOLNPAIR(V); }while(0)
#define SERIAL_ERROR_MSG(V...) do{ SERIAL_ERROR_START(); SERIAL_ECHOLNPAIR(V); }while(0)
#define SERIAL_ECHO_MSG(V...) do{ SERIAL_ECHO_START(); SERIAL_ECHOLNPGM(V); }while(0)
#define SERIAL_ERROR_MSG(V...) do{ SERIAL_ERROR_START(); SERIAL_ECHOLNPGM(V); }while(0)
#define SERIAL_ECHO_SP(C) serial_spaces(C)

8
Marlin/src/core/types.h

@ -27,7 +27,11 @@
#include "../inc/MarlinConfigPre.h"
class __FlashStringHelper;
typedef const __FlashStringHelper *progmem_str;
typedef const __FlashStringHelper* FSTR_P;
#ifndef FPSTR
#define FPSTR(S) (reinterpret_cast<FSTR_P>(S))
#endif
#define FTOP(S) (reinterpret_cast<const char*>(S))
//
// Conditional type assignment magic. For example...
@ -55,6 +59,8 @@ struct IF<true, L, R> { typedef L type; };
#define LOGICAL_AXIS_ELEM(O) LOGICAL_AXIS_LIST(O.e, O.x, O.y, O.z, O.i, O.j, O.k)
#define LOGICAL_AXIS_DECL(T,V) LOGICAL_AXIS_LIST(T e=V, T x=V, T y=V, T z=V, T i=V, T j=V, T k=V)
#define LOGICAL_AXES_STRING LOGICAL_AXIS_GANG("E", "X", "Y", "Z", AXIS4_STR, AXIS5_STR, AXIS6_STR)
#if HAS_EXTRUDERS
#define LIST_ITEM_E(N) , N
#define CODE_ITEM_E(N) ; N

12
Marlin/src/core/utility.cpp

@ -79,9 +79,9 @@ void safe_delay(millis_t ms) {
#if HAS_BED_PROBE
#if !HAS_PROBE_XY_OFFSET
SERIAL_ECHOPAIR("Probe Offset X0 Y0 Z", probe.offset.z, " (");
SERIAL_ECHOPGM("Probe Offset X0 Y0 Z", probe.offset.z, " (");
#else
SERIAL_ECHOPAIR_P(PSTR("Probe Offset X"), probe.offset_xy.x, SP_Y_STR, probe.offset_xy.y, SP_Z_STR, probe.offset.z);
SERIAL_ECHOPGM_P(PSTR("Probe Offset X"), probe.offset_xy.x, SP_Y_STR, probe.offset_xy.y, SP_Z_STR, probe.offset.z);
if (probe.offset_xy.x > 0)
SERIAL_ECHOPGM(" (Right");
else if (probe.offset_xy.x < 0)
@ -119,7 +119,7 @@ void safe_delay(millis_t ms) {
SERIAL_ECHOLNPGM(" (enabled)");
#if ENABLED(ENABLE_LEVELING_FADE_HEIGHT)
if (planner.z_fade_height)
SERIAL_ECHOLNPAIR("Z Fade: ", planner.z_fade_height);
SERIAL_ECHOLNPGM("Z Fade: ", planner.z_fade_height);
#endif
#if ABL_PLANAR
SERIAL_ECHOPGM("ABL Adjustment");
@ -140,7 +140,7 @@ void safe_delay(millis_t ms) {
SERIAL_ECHO(ftostr43sign(rz, '+'));
#if ENABLED(ENABLE_LEVELING_FADE_HEIGHT)
if (planner.z_fade_height) {
SERIAL_ECHOPAIR(" (", ftostr43sign(rz * planner.fade_scaling_factor_for_z(current_position.z), '+'));
SERIAL_ECHOPGM(" (", ftostr43sign(rz * planner.fade_scaling_factor_for_z(current_position.z), '+'));
SERIAL_CHAR(')');
}
#endif
@ -156,10 +156,10 @@ void safe_delay(millis_t ms) {
SERIAL_ECHOPGM("Mesh Bed Leveling");
if (planner.leveling_active) {
SERIAL_ECHOLNPGM(" (enabled)");
SERIAL_ECHOPAIR("MBL Adjustment Z", ftostr43sign(mbl.get_z(current_position), '+'));
SERIAL_ECHOPGM("MBL Adjustment Z", ftostr43sign(mbl.get_z(current_position), '+'));
#if ENABLED(ENABLE_LEVELING_FADE_HEIGHT)
if (planner.z_fade_height) {
SERIAL_ECHOPAIR(" (", ftostr43sign(
SERIAL_ECHOPGM(" (", ftostr43sign(
mbl.get_z(current_position, planner.fade_scaling_factor_for_z(current_position.z)), '+'
));
SERIAL_CHAR(')');

10
Marlin/src/feature/backlash.cpp

@ -60,9 +60,9 @@ Backlash backlash;
* spread over multiple segments, smoothing out artifacts even more.
*/
void Backlash::add_correction_steps(const int32_t &da, const int32_t &db, const int32_t &dc, const uint8_t dm, block_t * const block) {
static uint8_t last_direction_bits;
uint8_t changed_dir = last_direction_bits ^ dm;
void Backlash::add_correction_steps(const int32_t &da, const int32_t &db, const int32_t &dc, const axis_bits_t dm, block_t * const block) {
static axis_bits_t last_direction_bits;
axis_bits_t changed_dir = last_direction_bits ^ dm;
// Ignore direction change unless steps are taken in that direction
#if DISABLED(CORE_BACKLASH) || ENABLED(MARKFORGED_XY)
if (!da) CBI(changed_dir, X_AXIS);
@ -134,12 +134,12 @@ void Backlash::add_correction_steps(const int32_t &da, const int32_t &db, const
switch (axis) {
case CORE_AXIS_1:
//block->steps[CORE_AXIS_2] += influence_distance_mm[axis] * planner.settings.axis_steps_per_mm[CORE_AXIS_2];
//SERIAL_ECHOLNPAIR("CORE_AXIS_1 dir change. distance=", distance_mm[axis], " r.err=", residual_error[axis],
//SERIAL_ECHOLNPGM("CORE_AXIS_1 dir change. distance=", distance_mm[axis], " r.err=", residual_error[axis],
// " da=", da, " db=", db, " block->steps[axis]=", block->steps[axis], " err_corr=", error_correction);
break;
case CORE_AXIS_2:
//block->steps[CORE_AXIS_1] += influence_distance_mm[axis] * planner.settings.axis_steps_per_mm[CORE_AXIS_1];;
//SERIAL_ECHOLNPAIR("CORE_AXIS_2 dir change. distance=", distance_mm[axis], " r.err=", residual_error[axis],
//SERIAL_ECHOLNPGM("CORE_AXIS_2 dir change. distance=", distance_mm[axis], " r.err=", residual_error[axis],
// " da=", da, " db=", db, " block->steps[axis]=", block->steps[axis], " err_corr=", error_correction);
break;
case NORMAL_AXIS: break;

2
Marlin/src/feature/backlash.h

@ -71,7 +71,7 @@ public:
return has_measurement(X_AXIS) || has_measurement(Y_AXIS) || has_measurement(Z_AXIS);
}
void add_correction_steps(const int32_t &da, const int32_t &db, const int32_t &dc, const uint8_t dm, block_t * const block);
void add_correction_steps(const int32_t &da, const int32_t &db, const int32_t &dc, const axis_bits_t dm, block_t * const block);
};
extern Backlash backlash;

10
Marlin/src/feature/bedlevel/abl/abl.cpp

@ -336,11 +336,11 @@ float bilinear_z_offset(const xy_pos_t &raw) {
/*
static float last_offset = 0;
if (ABS(last_offset - offset) > 0.2) {
SERIAL_ECHOLNPAIR("Sudden Shift at x=", rel.x, " / ", bilinear_grid_spacing.x, " -> thisg.x=", thisg.x);
SERIAL_ECHOLNPAIR(" y=", rel.y, " / ", bilinear_grid_spacing.y, " -> thisg.y=", thisg.y);
SERIAL_ECHOLNPAIR(" ratio.x=", ratio.x, " ratio.y=", ratio.y);
SERIAL_ECHOLNPAIR(" z1=", z1, " z2=", z2, " z3=", z3, " z4=", z4);
SERIAL_ECHOLNPAIR(" L=", L, " R=", R, " offset=", offset);
SERIAL_ECHOLNPGM("Sudden Shift at x=", rel.x, " / ", bilinear_grid_spacing.x, " -> thisg.x=", thisg.x);
SERIAL_ECHOLNPGM(" y=", rel.y, " / ", bilinear_grid_spacing.y, " -> thisg.y=", thisg.y);
SERIAL_ECHOLNPGM(" ratio.x=", ratio.x, " ratio.y=", ratio.y);
SERIAL_ECHOLNPGM(" z1=", z1, " z2=", z2, " z3=", z3, " z4=", z4);
SERIAL_ECHOLNPGM(" L=", L, " R=", R, " offset=", offset);
}
last_offset = offset;
//*/

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

@ -51,7 +51,7 @@ void unified_bed_leveling::report_current_mesh() {
GRID_LOOP(x, y)
if (!isnan(z_values[x][y])) {
SERIAL_ECHO_START();
SERIAL_ECHOPAIR(" M421 I", x, " J", y);
SERIAL_ECHOPGM(" M421 I", x, " J", y);
SERIAL_ECHOLNPAIR_F_P(SP_Z_STR, z_values[x][y], 4);
serial_delay(75); // Prevent Printrun from exploding
}

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

@ -208,7 +208,7 @@ public:
if (DEBUGGING(LEVELING)) {
if (WITHIN(x1_i, 0, (GRID_MAX_POINTS_X) - 1)) DEBUG_ECHOPGM("yi"); else DEBUG_ECHOPGM("x1_i");
DEBUG_ECHOLNPAIR(" out of bounds in z_correction_for_x_on_horizontal_mesh_line(rx0=", rx0, ",x1_i=", x1_i, ",yi=", yi, ")");
DEBUG_ECHOLNPGM(" out of bounds in z_correction_for_x_on_horizontal_mesh_line(rx0=", rx0, ",x1_i=", x1_i, ",yi=", yi, ")");
}
// The requested location is off the mesh. Return UBL_Z_RAISE_WHEN_OFF_MESH or NAN.
@ -231,7 +231,7 @@ public:
if (DEBUGGING(LEVELING)) {
if (WITHIN(xi, 0, (GRID_MAX_POINTS_X) - 1)) DEBUG_ECHOPGM("y1_i"); else DEBUG_ECHOPGM("xi");
DEBUG_ECHOLNPAIR(" out of bounds in z_correction_for_y_on_vertical_mesh_line(ry0=", ry0, ", xi=", xi, ", y1_i=", y1_i, ")");
DEBUG_ECHOLNPGM(" out of bounds in z_correction_for_y_on_vertical_mesh_line(ry0=", ry0, ", xi=", xi, ", y1_i=", y1_i, ")");
}
// The requested location is off the mesh. Return UBL_Z_RAISE_WHEN_OFF_MESH or NAN.
@ -275,11 +275,11 @@ public:
// because part of the Mesh is undefined and we don't have the
// information we need to complete the height correction.
if (DEBUGGING(MESH_ADJUST)) DEBUG_ECHOLNPAIR("??? Yikes! NAN in ");
if (DEBUGGING(MESH_ADJUST)) DEBUG_ECHOLNPGM("??? Yikes! NAN in ");
}
if (DEBUGGING(MESH_ADJUST)) {
DEBUG_ECHOPAIR("get_z_correction(", rx0, ", ", ry0);
DEBUG_ECHOPGM("get_z_correction(", rx0, ", ", ry0);
DEBUG_ECHOLNPAIR_F(") => ", z0, 6);
}

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

@ -428,7 +428,7 @@ void unified_bed_leveling::G29() {
SERIAL_ECHOLNPGM("Mesh invalidated. Probing mesh.");
}
if (param.V_verbosity > 1) {
SERIAL_ECHOPAIR("Probing around (", param.XY_pos.x);
SERIAL_ECHOPGM("Probing around (", param.XY_pos.x);
SERIAL_CHAR(',');
SERIAL_DECIMAL(param.XY_pos.y);
SERIAL_ECHOLNPGM(").\n");
@ -602,14 +602,14 @@ void unified_bed_leveling::G29() {
}
if (!WITHIN(param.KLS_storage_slot, 0, a - 1)) {
SERIAL_ECHOLNPAIR("?Invalid storage slot.\n?Use 0 to ", a - 1);
SERIAL_ECHOLNPGM("?Invalid storage slot.\n?Use 0 to ", a - 1);
return;
}
settings.load_mesh(param.KLS_storage_slot);
storage_slot = param.KLS_storage_slot;
SERIAL_ECHOLNPGM("Done.");
SERIAL_ECHOLNPGM(STR_DONE);
}
//
@ -630,14 +630,14 @@ void unified_bed_leveling::G29() {
}
if (!WITHIN(param.KLS_storage_slot, 0, a - 1)) {
SERIAL_ECHOLNPAIR("?Invalid storage slot.\n?Use 0 to ", a - 1);
SERIAL_ECHOLNPGM("?Invalid storage slot.\n?Use 0 to ", a - 1);
goto LEAVE;
}
settings.store_mesh(param.KLS_storage_slot);
storage_slot = param.KLS_storage_slot;
SERIAL_ECHOLNPGM("Done.");
SERIAL_ECHOLNPGM(STR_DONE);
}
if (parser.seen_test('T'))
@ -653,7 +653,7 @@ void unified_bed_leveling::G29() {
#endif
#ifdef Z_PROBE_END_SCRIPT
if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("Z Probe End Script: ", Z_PROBE_END_SCRIPT);
if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("Z Probe End Script: ", Z_PROBE_END_SCRIPT);
if (probe_deployed) {
planner.synchronize();
gcode.process_subcommands_now_P(PSTR(Z_PROBE_END_SCRIPT));
@ -690,7 +690,7 @@ void unified_bed_leveling::adjust_mesh_to_mean(const bool cflag, const_float_t o
if (!isnan(z_values[x][y]))
sum_of_diff_squared += sq(z_values[x][y] - mean);
SERIAL_ECHOLNPAIR("# of samples: ", n);
SERIAL_ECHOLNPGM("# of samples: ", n);
SERIAL_ECHOLNPAIR_F("Mean Mesh Height: ", mean, 6);
const float sigma = SQRT(sum_of_diff_squared / (n + 1));
@ -735,8 +735,8 @@ void unified_bed_leveling::shift_mesh_height() {
if (do_ubl_mesh_map) display_map(param.T_map_type);
const uint8_t point_num = (GRID_MAX_POINTS - count) + 1;
SERIAL_ECHOLNPAIR("Probing mesh point ", point_num, "/", GRID_MAX_POINTS, ".");
TERN_(HAS_STATUS_MESSAGE, ui.status_printf_P(0, PSTR(S_FMT " %i/%i"), GET_TEXT(MSG_PROBING_MESH), point_num, int(GRID_MAX_POINTS)));
SERIAL_ECHOLNPGM("Probing mesh point ", point_num, "/", GRID_MAX_POINTS, ".");
TERN_(HAS_STATUS_MESSAGE, ui.status_printf_P(0, PSTR(S_FMT " %i/%i"), GET_TEXT(MSG_PROBING_POINT), point_num, int(GRID_MAX_POINTS)));
#if HAS_LCD_MENU
if (ui.button_pressed()) {
@ -1450,7 +1450,7 @@ void unified_bed_leveling::smart_fill_mesh() {
#endif
if (param.V_verbosity > 3) {
serial_spaces(16);
SERIAL_ECHOLNPAIR("Corrected_Z=", measured_z);
SERIAL_ECHOLNPGM("Corrected_Z=", measured_z);
}
incremental_LSF(&lsf_results, points[0], measured_z);
}
@ -1469,7 +1469,7 @@ void unified_bed_leveling::smart_fill_mesh() {
measured_z -= get_z_correction(points[1]);
if (param.V_verbosity > 3) {
serial_spaces(16);
SERIAL_ECHOLNPAIR("Corrected_Z=", measured_z);
SERIAL_ECHOLNPGM("Corrected_Z=", measured_z);
}
incremental_LSF(&lsf_results, points[1], measured_z);
}
@ -1479,7 +1479,7 @@ void unified_bed_leveling::smart_fill_mesh() {
SERIAL_ECHOLNPGM("Tilting mesh (3/3)");
TERN_(HAS_STATUS_MESSAGE, ui.status_printf_P(0, PSTR(S_FMT " 3/3"), GET_TEXT(MSG_LCD_TILTING_MESH)));
measured_z = probe.probe_at_point(points[2], PROBE_PT_STOW, param.V_verbosity);
measured_z = probe.probe_at_point(points[2], PROBE_PT_LAST_STOW, param.V_verbosity);
#ifdef VALIDATE_MESH_TILT
z3 = measured_z;
#endif
@ -1489,7 +1489,7 @@ void unified_bed_leveling::smart_fill_mesh() {
measured_z -= get_z_correction(points[2]);
if (param.V_verbosity > 3) {
serial_spaces(16);
SERIAL_ECHOLNPAIR("Corrected_Z=", measured_z);
SERIAL_ECHOLNPGM("Corrected_Z=", measured_z);
}
incremental_LSF(&lsf_results, points[2], measured_z);
}
@ -1517,7 +1517,7 @@ void unified_bed_leveling::smart_fill_mesh() {
rpos.y = y_min + dy * (zig_zag ? param.J_grid_size - 1 - iy : iy);
if (!abort_flag) {
SERIAL_ECHOLNPAIR("Tilting mesh point ", point_num, "/", total_points, "\n");
SERIAL_ECHOLNPGM("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_test('E') ? PROBE_PT_STOW : PROBE_PT_RAISE, param.V_verbosity); // TODO: Needs error handling
@ -1545,7 +1545,7 @@ void unified_bed_leveling::smart_fill_mesh() {
if (param.V_verbosity > 3) {
serial_spaces(16);
SERIAL_ECHOLNPAIR("Corrected_Z=", measured_z);
SERIAL_ECHOLNPGM("Corrected_Z=", measured_z);
}
incremental_LSF(&lsf_results, rpos, measured_z);
}
@ -1648,7 +1648,7 @@ void unified_bed_leveling::smart_fill_mesh() {
DEBUG_ECHOLNPAIR_F("0 : ", normed(safe_homing_xy, 0), 6);
d_from(); DEBUG_ECHOPGM("safe home with Z=");
DEBUG_ECHOLNPAIR_F("mesh value ", normed(safe_homing_xy, get_z_correction(safe_homing_xy)), 6);
DEBUG_ECHOPAIR(" Z error = (", Z_SAFE_HOMING_X_POINT, ",", Z_SAFE_HOMING_Y_POINT);
DEBUG_ECHOPGM(" Z error = (", Z_SAFE_HOMING_X_POINT, ",", Z_SAFE_HOMING_Y_POINT);
DEBUG_ECHOLNPAIR_F(") = ", get_z_correction(safe_homing_xy), 6);
#endif
} // DEBUGGING(LEVELING)
@ -1722,7 +1722,7 @@ void unified_bed_leveling::smart_fill_mesh() {
if (storage_slot == -1)
SERIAL_ECHOPGM("No Mesh Loaded.");
else
SERIAL_ECHOPAIR("Mesh ", storage_slot, " Loaded.");
SERIAL_ECHOPGM("Mesh ", storage_slot, " Loaded.");
SERIAL_EOL();
serial_delay(50);
@ -1736,14 +1736,14 @@ void unified_bed_leveling::smart_fill_mesh() {
SERIAL_ECHOLNPAIR_F("Probe Offset M851 Z", probe.offset.z, 7);
#endif
SERIAL_ECHOLNPAIR("MESH_MIN_X " STRINGIFY(MESH_MIN_X) "=", MESH_MIN_X); serial_delay(50);
SERIAL_ECHOLNPAIR("MESH_MIN_Y " STRINGIFY(MESH_MIN_Y) "=", MESH_MIN_Y); serial_delay(50);
SERIAL_ECHOLNPAIR("MESH_MAX_X " STRINGIFY(MESH_MAX_X) "=", MESH_MAX_X); serial_delay(50);
SERIAL_ECHOLNPAIR("MESH_MAX_Y " STRINGIFY(MESH_MAX_Y) "=", MESH_MAX_Y); serial_delay(50);
SERIAL_ECHOLNPAIR("GRID_MAX_POINTS_X ", GRID_MAX_POINTS_X); serial_delay(50);
SERIAL_ECHOLNPAIR("GRID_MAX_POINTS_Y ", GRID_MAX_POINTS_Y); serial_delay(50);
SERIAL_ECHOLNPAIR("MESH_X_DIST ", MESH_X_DIST);
SERIAL_ECHOLNPAIR("MESH_Y_DIST ", MESH_Y_DIST); serial_delay(50);
SERIAL_ECHOLNPGM("MESH_MIN_X " STRINGIFY(MESH_MIN_X) "=", MESH_MIN_X); serial_delay(50);
SERIAL_ECHOLNPGM("MESH_MIN_Y " STRINGIFY(MESH_MIN_Y) "=", MESH_MIN_Y); serial_delay(50);
SERIAL_ECHOLNPGM("MESH_MAX_X " STRINGIFY(MESH_MAX_X) "=", MESH_MAX_X); serial_delay(50);
SERIAL_ECHOLNPGM("MESH_MAX_Y " STRINGIFY(MESH_MAX_Y) "=", MESH_MAX_Y); serial_delay(50);
SERIAL_ECHOLNPGM("GRID_MAX_POINTS_X ", GRID_MAX_POINTS_X); serial_delay(50);
SERIAL_ECHOLNPGM("GRID_MAX_POINTS_Y ", GRID_MAX_POINTS_Y); serial_delay(50);
SERIAL_ECHOLNPGM("MESH_X_DIST ", MESH_X_DIST);
SERIAL_ECHOLNPGM("MESH_Y_DIST ", MESH_Y_DIST); serial_delay(50);
SERIAL_ECHOPGM("X-Axis Mesh Points at: ");
LOOP_L_N(i, GRID_MAX_POINTS_X) {
@ -1762,27 +1762,27 @@ void unified_bed_leveling::smart_fill_mesh() {
SERIAL_EOL();
#if HAS_KILL
SERIAL_ECHOLNPAIR("Kill pin on :", KILL_PIN, " state:", kill_state());
SERIAL_ECHOLNPGM("Kill pin on :", KILL_PIN, " state:", kill_state());
#endif
SERIAL_EOL();
serial_delay(50);
#if ENABLED(UBL_DEVEL_DEBUGGING)
SERIAL_ECHOLNPAIR("ubl_state_at_invocation :", ubl_state_at_invocation, "\nubl_state_recursion_chk :", ubl_state_recursion_chk);
SERIAL_ECHOLNPGM("ubl_state_at_invocation :", ubl_state_at_invocation, "\nubl_state_recursion_chk :", ubl_state_recursion_chk);
serial_delay(50);
SERIAL_ECHOLNPAIR("Meshes go from ", hex_address((void*)settings.meshes_start_index()), " to ", hex_address((void*)settings.meshes_end_index()));
SERIAL_ECHOLNPGM("Meshes go from ", hex_address((void*)settings.meshes_start_index()), " to ", hex_address((void*)settings.meshes_end_index()));
serial_delay(50);
SERIAL_ECHOLNPAIR("sizeof(ubl) : ", sizeof(ubl)); SERIAL_EOL();
SERIAL_ECHOLNPAIR("z_value[][] size: ", sizeof(z_values)); SERIAL_EOL();
SERIAL_ECHOLNPGM("sizeof(ubl) : ", sizeof(ubl)); SERIAL_EOL();
SERIAL_ECHOLNPGM("z_value[][] size: ", sizeof(z_values)); SERIAL_EOL();
serial_delay(25);
SERIAL_ECHOLNPAIR("EEPROM free for UBL: ", hex_address((void*)(settings.meshes_end_index() - settings.meshes_start_index())));
SERIAL_ECHOLNPGM("EEPROM free for UBL: ", hex_address((void*)(settings.meshes_end_index() - settings.meshes_start_index())));
serial_delay(50);
SERIAL_ECHOLNPAIR("EEPROM can hold ", settings.calc_num_meshes(), " meshes.\n");
SERIAL_ECHOLNPGM("EEPROM can hold ", settings.calc_num_meshes(), " meshes.\n");
serial_delay(25);
#endif // UBL_DEVEL_DEBUGGING
@ -1829,7 +1829,7 @@ void unified_bed_leveling::smart_fill_mesh() {
}
if (!parser.has_value() || !WITHIN(parser.value_int(), 0, a - 1)) {
SERIAL_ECHOLNPAIR("?Invalid storage slot.\n?Use 0 to ", a - 1);
SERIAL_ECHOLNPGM("?Invalid storage slot.\n?Use 0 to ", a - 1);
return;
}
@ -1838,7 +1838,7 @@ void unified_bed_leveling::smart_fill_mesh() {
float tmp_z_values[GRID_MAX_POINTS_X][GRID_MAX_POINTS_Y];
settings.load_mesh(param.KLS_storage_slot, &tmp_z_values);
SERIAL_ECHOLNPAIR("Subtracting mesh in slot ", param.KLS_storage_slot, " from current mesh.");
SERIAL_ECHOLNPGM("Subtracting mesh in slot ", param.KLS_storage_slot, " from current mesh.");
GRID_LOOP(x, y) {
z_values[x][y] -= tmp_z_values[x][y];

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

@ -19,6 +19,7 @@
* along with this program. If not, see <https://www.gnu.org/licenses/>.
*
*/
#include "../../../inc/MarlinConfig.h"
#if ENABLED(AUTO_BED_LEVELING_UBL)
@ -323,6 +324,8 @@
#define DELTA_SEGMENT_MIN_LENGTH 0.25 // SCARA minimum segment size is 0.25mm
#elif ENABLED(DELTA)
#define DELTA_SEGMENT_MIN_LENGTH 0.10 // mm (still subject to DELTA_SEGMENTS_PER_SECOND)
#elif ENABLED(POLARGRAPH)
#define DELTA_SEGMENT_MIN_LENGTH 0.10 // mm (still subject to DELTA_SEGMENTS_PER_SECOND)
#else // CARTESIAN
#ifdef LEVELED_SEGMENT_LENGTH
#define DELTA_SEGMENT_MIN_LENGTH LEVELED_SEGMENT_LENGTH

14
Marlin/src/feature/binary_stream.h

@ -146,9 +146,9 @@ public:
transfer_timeout = millis() + TIMEOUT;
switch (static_cast<FileTransfer>(packet_type)) {
case FileTransfer::QUERY:
SERIAL_ECHOPAIR("PFT:version:", VERSION_MAJOR, ".", VERSION_MINOR, ".", VERSION_PATCH);
SERIAL_ECHOPGM("PFT:version:", VERSION_MAJOR, ".", VERSION_MINOR, ".", VERSION_PATCH);
#if ENABLED(BINARY_STREAM_COMPRESSION)
SERIAL_ECHOLNPAIR(":compression:heatshrink,", HEATSHRINK_STATIC_WINDOW_BITS, ",", HEATSHRINK_STATIC_LOOKAHEAD_BITS);
SERIAL_ECHOLNPGM(":compression:heatshrink,", HEATSHRINK_STATIC_WINDOW_BITS, ",", HEATSHRINK_STATIC_LOOKAHEAD_BITS);
#else
SERIAL_ECHOLNPGM(":compression:none");
#endif
@ -322,7 +322,7 @@ public:
if (packet.header.checksum == packet.header_checksum) {
// The SYNC control packet is a special case in that it doesn't require the stream sync to be correct
if (static_cast<Protocol>(packet.header.protocol()) == Protocol::CONTROL && static_cast<ProtocolControl>(packet.header.type()) == ProtocolControl::SYNC) {
SERIAL_ECHOLNPAIR("ss", sync, ",", buffer_size, ",", VERSION_MAJOR, ".", VERSION_MINOR, ".", VERSION_PATCH);
SERIAL_ECHOLNPGM("ss", sync, ",", buffer_size, ",", VERSION_MAJOR, ".", VERSION_MINOR, ".", VERSION_PATCH);
stream_state = StreamState::PACKET_RESET;
break;
}
@ -337,7 +337,7 @@ public:
stream_state = StreamState::PACKET_PROCESS;
}
else if (packet.header.sync == sync - 1) { // ok response must have been lost
SERIAL_ECHOLNPAIR("ok", packet.header.sync); // transmit valid packet received and drop the payload
SERIAL_ECHOLNPGM("ok", packet.header.sync); // transmit valid packet received and drop the payload
stream_state = StreamState::PACKET_RESET;
}
else if (packet_retries) {
@ -393,7 +393,7 @@ public:
packet_retries = 0;
bytes_received += packet.header.size;
SERIAL_ECHOLNPAIR("ok", packet.header.sync); // transmit valid packet received
SERIAL_ECHOLNPGM("ok", packet.header.sync); // transmit valid packet received
dispatch();
stream_state = StreamState::PACKET_RESET;
break;
@ -402,7 +402,7 @@ public:
packet_retries++;
stream_state = StreamState::PACKET_RESET;
SERIAL_ECHO_MSG("Resend request ", packet_retries);
SERIAL_ECHOLNPAIR("rs", sync);
SERIAL_ECHOLNPGM("rs", sync);
}
else
stream_state = StreamState::PACKET_ERROR;
@ -412,7 +412,7 @@ public:
stream_state = StreamState::PACKET_RESEND;
break;
case StreamState::PACKET_ERROR:
SERIAL_ECHOLNPAIR("fe", packet.header.sync);
SERIAL_ECHOLNPGM("fe", packet.header.sync);
reset(); // reset everything, resync required
stream_state = StreamState::PACKET_RESET;
break;

8
Marlin/src/feature/bltouch.cpp

@ -39,7 +39,7 @@ void stop();
#include "../core/debug_out.h"
bool BLTouch::command(const BLTCommand cmd, const millis_t &ms) {
if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPAIR("BLTouch Command :", cmd);
if (DEBUGGING(LEVELING)) SERIAL_ECHOLNPGM("BLTouch Command :", cmd);
MOVE_SERVO(Z_PROBE_SERVO_NR, cmd);
safe_delay(_MAX(ms, (uint32_t)BLTOUCH_DELAY)); // BLTOUCH_DELAY is also the *minimum* delay
return triggered();
@ -64,7 +64,7 @@ void BLTouch::init(const bool set_voltage/*=false*/) {
#else
if (DEBUGGING(LEVELING)) {
DEBUG_ECHOLNPAIR("last_written_mode - ", last_written_mode);
DEBUG_ECHOLNPGM("last_written_mode - ", last_written_mode);
DEBUG_ECHOLNPGM("config mode - "
#if ENABLED(BLTOUCH_SET_5V_MODE)
"BLTOUCH_SET_5V_MODE"
@ -175,7 +175,7 @@ bool BLTouch::status_proc() {
_set_SW_mode(); // Incidentally, _set_SW_mode() will also RESET any active alarm
const bool tr = triggered(); // If triggered in SW mode, the pin is up, it is STOWED
if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("BLTouch is ", tr);
if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("BLTouch is ", tr);
if (tr) _stow(); else _deploy(); // Turn off SW mode, reset any trigger, honor pin state
return !tr;
@ -187,7 +187,7 @@ void BLTouch::mode_conv_proc(const bool M5V) {
* BLTOUCH V3.0: This will set the mode (twice) and sadly, a STOW is needed at the end, because of the deploy
* BLTOUCH V3.1: This will set the mode and store it in the eeprom. The STOW is not needed but does not hurt
*/
if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPAIR("BLTouch Set Mode - ", M5V);
if (DEBUGGING(LEVELING)) DEBUG_ECHOLNPGM("BLTouch Set Mode - ", M5V);
_deploy();
if (M5V) _set_5V_mode(); else _set_OD_mode();
_mode_store();

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

Loading…
Cancel
Save