From 6ae2cde6637282b431b90c92cad7e3de6587affc Mon Sep 17 00:00:00 2001 From: ellensp <530024+ellensp@users.noreply.github.com> Date: Wed, 22 Nov 2023 06:43:08 +1300 Subject: [PATCH 01/77] =?UTF-8?q?=F0=9F=90=9BFix=20GT2560=5FV41b=20Z2=20pi?= =?UTF-8?q?n=20(#26370)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit * Update pins_GT2560_V41b.h Fix Z2_STOP_PIN * use mega2560ext when board has pins > D69 * Allow overrides, consistent with other pins in this file --------- Co-authored-by: Jason Smith --- Marlin/src/pins/mega/pins_GT2560_V41b.h | 7 ++++--- Marlin/src/pins/pins.h | 2 +- 2 files changed, 5 insertions(+), 4 deletions(-) diff --git a/Marlin/src/pins/mega/pins_GT2560_V41b.h b/Marlin/src/pins/mega/pins_GT2560_V41b.h index ce0adc2a396f..d4891d9e2ef5 100644 --- a/Marlin/src/pins/mega/pins_GT2560_V41b.h +++ b/Marlin/src/pins/mega/pins_GT2560_V41b.h @@ -51,15 +51,13 @@ * X AXIS Y AXIS Z1 AXIS Z0 AXIS * --- --- --- --- * | 1 | 5V | 1 | 5V | 1 | 5V | 1 | 5V - * | 2 | 24 X_MIN | 2 | 28 Y_MIN | 2 | PE7 Z1_MIN | 2 | 30 Z0_MIN + * | 2 | 24 X_MIN | 2 | 28 Y_MIN | 2 | 80 Z1_MIN | 2 | 30 Z0_MIN * | 3 | GND | 3 | GND | 3 | GND | 3 | GND * --- --- --- --- * J3 J4 J5 J6 * */ -//#define Z1_MIN PE7 // Number?? - #ifndef X_STOP_PIN #ifndef X_MIN_PIN #define X_MIN_PIN 24 @@ -84,6 +82,9 @@ #define Z_MAX_PIN 32 #endif #endif +#ifndef Z2_STOP_PIN + #define Z2_STOP_PIN 80 // PE7 - Extended mega2560 pin +#endif /** Filament Runout Sensors * diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index f9c2d08ba2b7..6b44d68445c5 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -349,7 +349,7 @@ #elif MB(WEEDO_62A) #include "mega/pins_WEEDO_62A.h" // ATmega2560 env:mega2560 #elif MB(GT2560_V41B) - #include "mega/pins_GT2560_V41b.h" // ATmega2560 env:mega2560 + #include "mega/pins_GT2560_V41b.h" // ATmega2560 env:mega2560ext // // ATmega1281, ATmega2561 From 2b1666fcb0834dbdae4030f464778e0a7c391d57 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 21 Nov 2023 13:59:30 -0600 Subject: [PATCH 02/77] =?UTF-8?q?=E2=9C=8F=EF=B8=8F=20GT2560=5FV41b=20foll?= =?UTF-8?q?owup?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/mega/pins_GT2560_V41b.h | 2 +- Marlin/src/pins/samd/pins_MINITRONICS20.h | 29 ++++++++++------------- 2 files changed, 14 insertions(+), 17 deletions(-) diff --git a/Marlin/src/pins/mega/pins_GT2560_V41b.h b/Marlin/src/pins/mega/pins_GT2560_V41b.h index d4891d9e2ef5..e74b2994840f 100644 --- a/Marlin/src/pins/mega/pins_GT2560_V41b.h +++ b/Marlin/src/pins/mega/pins_GT2560_V41b.h @@ -51,7 +51,7 @@ * X AXIS Y AXIS Z1 AXIS Z0 AXIS * --- --- --- --- * | 1 | 5V | 1 | 5V | 1 | 5V | 1 | 5V - * | 2 | 24 X_MIN | 2 | 28 Y_MIN | 2 | 80 Z1_MIN | 2 | 30 Z0_MIN + * | 2 | 24 X_MIN | 2 | 28 Y_MIN | 2 | 80 Z1_MIN | 2 | 30 Z0_MIN * | 3 | GND | 3 | GND | 3 | GND | 3 | GND * --- --- --- --- * J3 J4 J5 J6 diff --git a/Marlin/src/pins/samd/pins_MINITRONICS20.h b/Marlin/src/pins/samd/pins_MINITRONICS20.h index 8c0daa497b01..2a450698d12a 100644 --- a/Marlin/src/pins/samd/pins_MINITRONICS20.h +++ b/Marlin/src/pins/samd/pins_MINITRONICS20.h @@ -60,8 +60,9 @@ #define Z_STOP_PIN 4 /** - * NOTE: Useful if extra TMC2209 are to be used as independent axes. - * We need to configure the new digital PIN, for this we could configure on the board the extra pin of this stepper, for example as a MIN_PIN/MAX_PIN. This pin is the D14. + * NOTE: For extra TMC2209 used as independent axes a new digital PIN is needed. + * We can configure on the board the extra pin of this stepper, + * e.g., as a MIN_PIN/MAX_PIN. This pin is D14. */ //#define Z2_STOP_PIN 14 //#define X2_STOP_PIN 14 @@ -105,7 +106,7 @@ // This board have the option to use an extra TMC2209 stepper, one of the use could be as a second extruder. #if EXTRUDERS < 2 - // TODO: Corregir aquí que cuando tenemos dos extrusores o lo que sea, utiliza los endstop que le sobran, osea los max, no hay Z2_endstop + // TODO: Correct here that when we have two extruders (or whatever), use the extra endstops. i.e., The max, there is no Z2_endstop. #if NUM_Z_STEPPERS > 1 #define Z2_STOP_PIN 14 #endif @@ -117,8 +118,8 @@ #undef Z3_DRIVER_TYPE #undef Z4_DRIVER_TYPE - // Si tenemos más de un extrusor lo que hacemos es definir el nuevo extrusor así como sus pines - // Acordarse de definir el #define TEMP_SENSOR_1, ya que este contiene el tipo de sonda del extrusor E1 + // For more than one extruder define the new extruder and its pins. + // Remember to #define TEMP_SENSOR_1, since this contains the E1 sensor type. #define FIL_RUNOUT2_PIN 14 @@ -166,13 +167,9 @@ #define EXP3_08_PIN EXP1_08_PIN #endif -/************************************/ -/***** Configurations Section ******/ -/************************************/ - /** - * This sections starts with the pins_RAMPS_144.h as example, after if you need any new - * display, you could use normal duponts and connect it with with the scheme showed before. + * This section is based on pins_RAMPS_144.h. To use a new display, you + * could use normal duponts and connect with the scheme shown before. * Tested: * - Ender-3 Old display (Character LCD) * - Ender-3 New Serial DWING Display @@ -427,7 +424,7 @@ // TO TEST //#define BEEPER_PIN EXP2_05_PIN // not connected to a pin - //#define LCD_BACKLIGHT_PIN 57 // backlight LED on A11/D? (Mega/Due:65 - AGCM4:57) + //#define LCD_BACKLIGHT_PIN 57 // Backlight LED on A11/D? (Mega/Due:65 - AGCM4:57) //#define DOGLCD_A0 EXP2_07_PIN //#define DOGLCD_CS 58 // Mega/Due:66 - AGCM4:58 @@ -502,8 +499,8 @@ #if HAS_TMC_UART /** - * Address for the UART Configuration of the TMC2209. Override in Configuration files. - * To test TMC2209 Steppers enable TMC_DEBUG in Configuration_adv.h and test the M122 command with voltage on the steppers. + * TMC2209 UART Address. Override in Configuration files. + * To test TMC2209 Steppers enable TMC_DEBUG and test M122 with voltage on the steppers. */ #ifndef X_SLAVE_ADDRESS #define X_SLAVE_ADDRESS 0b00 @@ -523,8 +520,8 @@ /** * TMC2208/TMC2209 stepper drivers - * It seems to work perfectly fine on Software Serial, if an advanced user wants to test, you could use the SAMD51 Serial1 and Serial 2. Be careful with the Sercom configurations. - * Steppers 1,2,3,4 (X,Y,Z,E0) are on the Serial1, Sercom (RX = 0, TX = 1), extra stepper 5 (E1 or any axis you want) is on Serial2, Sercom (RX = 17, TX = 16) + * Seems to work fine with Software Serial. If you want to test, use SAMD51 Serial1 and Serial2. Be careful with the Sercom configurations. + * Steppers 1,2,3,4 (X,Y,Z,E0) are on Serial1, Sercom (RX=0, TX=1), extra stepper 5 (E1 or any axis you want) is on Serial2, Sercom (RX=17, TX=16) */ //#define X_HARDWARE_SERIAL Serial1 From 61cb98dc0fc7b97915c839eafcafeeff6838eee5 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Wed, 22 Nov 2023 00:21:52 +0000 Subject: [PATCH 03/77] [cron] Bump distribution date (2023-11-22) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 8e91cf147e8b..c1709b501dca 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2023-11-21" +//#define STRING_DISTRIBUTION_DATE "2023-11-22" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index c01fb95d549f..bcbcd4df2624 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2023-11-21" + #define STRING_DISTRIBUTION_DATE "2023-11-22" #endif /** From 8322848c35364afa23caa283e5bbe513f4aba0e8 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 22 Nov 2023 01:35:46 -0600 Subject: [PATCH 04/77] =?UTF-8?q?=E2=9C=85=20Smarter=20use=5Fexample=5Fcon?= =?UTF-8?q?figs?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- buildroot/bin/use_example_configs | 21 +++++++++++++++------ 1 file changed, 15 insertions(+), 6 deletions(-) diff --git a/buildroot/bin/use_example_configs b/buildroot/bin/use_example_configs index 1fdab1de6c5b..282e057dde46 100755 --- a/buildroot/bin/use_example_configs +++ b/buildroot/bin/use_example_configs @@ -8,28 +8,37 @@ # use_example_configs release-2.0.9.4:Creality/CR-10/CrealityV1 # # If a configpath has spaces (or quotes) escape them or enquote the path +# If no branch: prefix is given use configs based on the current branch name. +# e.g., For `latest-2.1.x` name the working branch something like "my_work-2.1.x." +# The branch or tag must first exist at MarlinFirmware/Configurations. +# The fallback branch is bugfix-2.1.x. # which curl >/dev/null && TOOL='curl -L -s -S -f -o wgot' which wget >/dev/null && TOOL='wget -q -O wgot' CURR=$(git branch 2>/dev/null | grep ^* | sed 's/\* //g') -[[ $CURR == "bugfix-2.0.x" ]] && BRANCH=bugfix-2.0.x || BRANCH=bugfix-2.1.x - -REPO=$BRANCH +case "$CURR" in + bugfix-2.*.x ) BRANCH=$CURR ;; + *-2.1.x|2.1.x ) BRANCH=latest-2.1.x ;; + *-2.0.x|2.0.x ) BRANCH=latest-2.0.x ;; + *-1.1.x|1.1.x ) BRANCH=latest-1.1.x ;; + *-1.0.x|1.0.x ) BRANCH=latest-1.0.x ;; + * ) BRANCH=bugfix-2.1.x ;; +esac if [[ $# > 0 ]]; then IFS=: read -r PART1 PART2 <<< "$@" - [[ -n $PART2 ]] && { UDIR="$PART2" ; REPO="$PART1" ; } \ + [[ -n $PART2 ]] && { UDIR="$PART2" ; BRANCH="$PART1" ; } \ || { UDIR="$PART1" ; } RDIR="${UDIR// /%20}" - echo "Fetching $UDIR configurations from $REPO..." + echo "Fetching $UDIR configurations from $BRANCH..." EXAMPLES="examples/$RDIR" else EXAMPLES="default" fi -CONFIGS="https://raw.githubusercontent.com/MarlinFirmware/Configurations/$REPO/config/${EXAMPLES}" +CONFIGS="https://raw.githubusercontent.com/MarlinFirmware/Configurations/$BRANCH/config/${EXAMPLES}" restore_configs From c5b267162cf00feb965154b9d96e21bef61a9336 Mon Sep 17 00:00:00 2001 From: Andrew <18502096+classicrocker883@users.noreply.github.com> Date: Wed, 22 Nov 2023 03:07:44 -0500 Subject: [PATCH 05/77] =?UTF-8?q?=F0=9F=8C=90=20Regenerate=20Russian=20fon?= =?UTF-8?q?t=20data=20(#26428)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/dogm/fontdata/langdata_ro.h | 8 +++++++- 1 file changed, 7 insertions(+), 1 deletion(-) diff --git a/Marlin/src/lcd/dogm/fontdata/langdata_ro.h b/Marlin/src/lcd/dogm/fontdata/langdata_ro.h index 6be486355314..bdd4795f8ba2 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata_ro.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata_ro.h @@ -7,4 +7,10 @@ #include "langdata.h" -static const uxg_fontinfo_t g_fontinfo_ro[] PROGMEM = {}; +const u8g_fntpgm_uint8_t fontpage_2_131_131[31] U8G_FONT_SECTION("fontpage_2_131_131") = { + 0x00,0x0C,0x0F,0x00,0xFE,0x00,0x00,0x00,0x00,0x00,0x83,0x83,0x00,0x08,0x00,0x00, + 0x00,0x05,0x08,0x08,0x06,0x00,0x00,0x88,0x70,0x00,0x70,0x08,0x78,0x88,0x78}; + +static const uxg_fontinfo_t g_fontinfo_ro[] PROGMEM = { + FONTDATA_ITEM(2, 131, 131, fontpage_2_131_131), // 'ă' -- 'ă' +}; From f3473495d0ecc61e4d768e88759e9a7f9a263770 Mon Sep 17 00:00:00 2001 From: Andrew <18502096+classicrocker883@users.noreply.github.com> Date: Wed, 22 Nov 2023 03:19:29 -0500 Subject: [PATCH 06/77] =?UTF-8?q?=F0=9F=9A=B8=20Fixes=20for=20ProUI=20popu?= =?UTF-8?q?p,=20abort=20(#26308)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/core/serial_hook.h | 4 ++-- Marlin/src/lcd/e3v2/proui/dwin.cpp | 15 ++++++++++++++- Marlin/src/lcd/e3v2/proui/dwin_popup.h | 8 +++++++- Marlin/src/lcd/e3v2/proui/menus.h | 2 +- Marlin/src/sd/usb_flashdrive/lib-uhs2/Usb.cpp | 2 +- .../src/sd/usb_flashdrive/lib-uhs2/parsetools.h | 2 +- buildroot/tests/STM32F103RE_creality | 2 +- 7 files changed, 27 insertions(+), 8 deletions(-) diff --git a/Marlin/src/core/serial_hook.h b/Marlin/src/core/serial_hook.h index 65c553c70259..06efce1dc5fe 100644 --- a/Marlin/src/core/serial_hook.h +++ b/Marlin/src/core/serial_hook.h @@ -179,7 +179,7 @@ struct RuntimeSerial : public SerialBase< RuntimeSerial >, public Seria // Append Hookable for this class SerialFeature features(serial_index_t index) const { return SerialFeature::Hookable | CALL_IF_EXISTS(SerialFeature, static_cast(this), features, index); } - void setHook(WriteHook writeHook = 0, EndOfMessageHook eofHook = 0, void * userPointer = 0) { + void setHook(WriteHook writeHook=0, EndOfMessageHook eofHook=0, void * userPointer=0) { // Order is important here as serial code can be called inside interrupts // When setting a hook, the user pointer must be set first so if writeHook is called as soon as it's set, it'll be valid if (userPointer) this->userPointer = userPointer; @@ -292,7 +292,7 @@ struct MultiSerial : public SerialBase< MultiSerial< REPEAT(NUM_SERIAL, _S_NAME) #define _S_REFS(N) Serial##N##T & serial##N, #define _S_INIT(N) ,serial##N (serial##N) - MultiSerial(REPEAT(NUM_SERIAL, _S_REFS) const SerialMask mask = ALL, const bool e = false) + MultiSerial(REPEAT(NUM_SERIAL, _S_REFS) const SerialMask mask=ALL, const bool e=false) : BaseClassT(e), portMask(mask) REPEAT(NUM_SERIAL, _S_INIT) {} }; diff --git a/Marlin/src/lcd/e3v2/proui/dwin.cpp b/Marlin/src/lcd/e3v2/proui/dwin.cpp index a6cc1613ef09..341521ee84f2 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin.cpp @@ -1713,6 +1713,18 @@ void dwinPrintFinished() { // Print was aborted void dwinPrintAborted() { + #ifndef EVENT_GCODE_SD_ABORT + if (all_axes_homed()) { + queue.inject( + #if ENABLED(NOZZLE_PARK_FEATURE) + F("G27") + #else + TS(F("G0Z"), float(_MIN(current_position.z + (Z_POST_CLEARANCE), Z_MAX_POS)), F("\nG0F2000Y"), Y_MAX_POS); + #endif + ); + } + #endif + hostui.notify("Print Aborted"); dwinPrintFinished(); } @@ -2226,7 +2238,8 @@ void setMoveZ() { hmiValue.axis = Z_AXIS; setPFloatOnClick(Z_MIN_POS, Z_MAX_POS, #endif #if LCD_BACKLIGHT_TIMEOUT_MINS - void setTimer() { setPIntOnClick(ui.backlight_timeout_min, ui.backlight_timeout_max); } + void applyTimer() { ui.backlight_timeout_minutes = menuData.value; } + void setTimer() { setIntOnClick(ui.backlight_timeout_min, ui.backlight_timeout_max, ui.backlight_timeout_minutes, applyTimer); } #endif #if HAS_FILAMENT_SENSOR diff --git a/Marlin/src/lcd/e3v2/proui/dwin_popup.h b/Marlin/src/lcd/e3v2/proui/dwin_popup.h index ee8664e874dd..d970cbfef475 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin_popup.h +++ b/Marlin/src/lcd/e3v2/proui/dwin_popup.h @@ -50,9 +50,15 @@ inline void drawPopupBkgd() { template void dwinDrawPopup(const uint8_t icon, T amsg1=nullptr, U amsg2=nullptr, uint8_t button=0) { + xy_uint8_t pos; + switch (icon) { + default: pos.set(81, 90); break; // Icon 1 - 8, 90 - 91; (110 x 100) + case 17 ... 24: pos.set(96, 90); break; // Icon 17 - 24; ( 80 x 100) + case 78 ... 81: pos.set(100, 107); break; // Icon 78 - 81; ( 73 x 66) + } DWINUI::clearMainArea(); drawPopupBkgd(); - if (icon) DWINUI::drawIcon(icon, 101, 105); + if (icon) DWINUI::drawIcon(icon, pos.x, pos.y); if (amsg1) DWINUI::drawCenteredString(hmiData.colorPopupTxt, 210, amsg1); if (amsg2) DWINUI::drawCenteredString(hmiData.colorPopupTxt, 240, amsg2); if (button) DWINUI::drawButton(button, 86, 280); diff --git a/Marlin/src/lcd/e3v2/proui/menus.h b/Marlin/src/lcd/e3v2/proui/menus.h index be0c88176006..d1f5cdb698ba 100644 --- a/Marlin/src/lcd/e3v2/proui/menus.h +++ b/Marlin/src/lcd/e3v2/proui/menus.h @@ -93,7 +93,7 @@ class MenuItem: public CustomMenuItem { MenuItem(uint8_t cicon, const char * const text=nullptr, OnDrawItem ondraw=nullptr, OnClickItem onclick=nullptr); MenuItem(uint8_t cicon, uint8_t id, uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2, OnDrawItem ondraw=nullptr, OnClickItem onclick=nullptr); void setFrame(uint8_t id, uint16_t x1, uint16_t y1, uint16_t x2, uint16_t y2); - void setCaption(const char * const text = nullptr); + void setCaption(const char * const text=nullptr); }; class MenuItemPtr: public MenuItem { diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs2/Usb.cpp b/Marlin/src/sd/usb_flashdrive/lib-uhs2/Usb.cpp index 75421f4482a8..889b8560aa01 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs2/Usb.cpp +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs2/Usb.cpp @@ -215,7 +215,7 @@ uint8_t USB::inTransfer(uint8_t addr, uint8_t ep, uint16_t *nbytesptr, uint8_t * return InTransfer(pep, nak_limit, nbytesptr, data, bInterval); } -uint8_t USB::InTransfer(EpInfo *pep, uint16_t nak_limit, uint16_t *nbytesptr, uint8_t *data, uint8_t bInterval /*= 0*/) { +uint8_t USB::InTransfer(EpInfo *pep, uint16_t nak_limit, uint16_t *nbytesptr, uint8_t *data, uint8_t bInterval/*=0*/) { uint8_t rcode = 0; uint8_t pktsize; diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs2/parsetools.h b/Marlin/src/sd/usb_flashdrive/lib-uhs2/parsetools.h index 403766da8ff1..21c6cd495178 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs2/parsetools.h +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs2/parsetools.h @@ -141,5 +141,5 @@ class PTPListParser { theParser.Initialize(p); } - bool Parse(uint8_t **pp, uint16_t *pcntdn, PTP_ARRAY_EL_FUNC pf, const void *me = nullptr); + bool Parse(uint8_t **pp, uint16_t *pcntdn, PTP_ARRAY_EL_FUNC pf, const void *me=nullptr); }; diff --git a/buildroot/tests/STM32F103RE_creality b/buildroot/tests/STM32F103RE_creality index 09206c10503f..ad80605e61fa 100755 --- a/buildroot/tests/STM32F103RE_creality +++ b/buildroot/tests/STM32F103RE_creality @@ -24,7 +24,7 @@ opt_enable DWIN_MARLINUI_LANDSCAPE LCD_ENDSTOP_TEST AUTO_BED_LEVELING_UBL BLTOUC exec_test $1 $2 "Ender-3 v2 - MarlinUI (UBL+BLTOUCH, MPCTEMP, LCD_ENDSTOP_TEST)" "$3" use_example_configs "Creality/Ender-3 S1/STM32F1" -opt_disable DWIN_CREALITY_LCD Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN AUTO_BED_LEVELING_BILINEAR CANCEL_OBJECTS FWRETRACT +opt_disable DWIN_CREALITY_LCD Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN AUTO_BED_LEVELING_BILINEAR CANCEL_OBJECTS FWRETRACT EVENT_GCODE_SD_ABORT opt_enable DWIN_LCD_PROUI INDIVIDUAL_AXIS_HOMING_SUBMENU SET_PROGRESS_MANUALLY SET_PROGRESS_PERCENT STATUS_MESSAGE_SCROLLING \ SOUND_MENU_ITEM PRINTCOUNTER NOZZLE_PARK_FEATURE ADVANCED_PAUSE_FEATURE FILAMENT_RUNOUT_SENSOR \ BLTOUCH Z_SAFE_HOMING AUTO_BED_LEVELING_UBL MESH_EDIT_MENU LCD_BED_TRAMMING \ From c2376d62e232b952923cdda55bdb0bbc3c59063c Mon Sep 17 00:00:00 2001 From: Andrew <18502096+classicrocker883@users.noreply.github.com> Date: Wed, 22 Nov 2023 03:40:50 -0500 Subject: [PATCH 07/77] =?UTF-8?q?=F0=9F=A9=B9=20Fix=20JyersUI/ProUI=20narr?= =?UTF-8?q?owing=20(#26453)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/src/lcd/e3v2/jyersui/dwin.cpp | 2 +- Marlin/src/lcd/e3v2/proui/bedlevel_tools.cpp | 8 ++++---- 2 files changed, 5 insertions(+), 5 deletions(-) diff --git a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp index cf78bdd7c6a5..6e7898a389f9 100644 --- a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp @@ -389,7 +389,7 @@ class TextScroller { // Draw value text on if (viewer_print_value) { - xy_int_t offset { 0, cell_height_px / 2 - 6 }; + xy_uint_t offset { 0, cell_height_px / 2 - 6 }; if (isnan(bedlevel.z_values[x][y])) { // undefined dwinDrawString(false, font6x12, COLOR_WHITE, COLOR_BG_BLUE, start_x_px + cell_width_px / 2 - 5, start_y_px + offset.y, F("X")); } diff --git a/Marlin/src/lcd/e3v2/proui/bedlevel_tools.cpp b/Marlin/src/lcd/e3v2/proui/bedlevel_tools.cpp index eea4ac97f0cc..f2fe008667c6 100644 --- a/Marlin/src/lcd/e3v2/proui/bedlevel_tools.cpp +++ b/Marlin/src/lcd/e3v2/proui/bedlevel_tools.cpp @@ -211,9 +211,9 @@ bool BedLevelTools::meshValidate() { void BedLevelTools::drawBedMesh(int16_t selected/*=-1*/, uint8_t gridline_width/*=1*/, uint16_t padding_x/*=8*/, uint16_t padding_y_top/*=(40 + 53 - 7)*/) { drawing_mesh = true; - const uint16_t total_width_px = DWIN_WIDTH - padding_x - padding_x; - const uint16_t cell_width_px = total_width_px / (GRID_MAX_POINTS_X); - const uint16_t cell_height_px = total_width_px / (GRID_MAX_POINTS_Y); + const uint16_t total_width_px = DWIN_WIDTH - padding_x - padding_x, + cell_width_px = total_width_px / (GRID_MAX_POINTS_X), + cell_height_px = total_width_px / (GRID_MAX_POINTS_Y); const float v_max = abs(getMaxValue()), v_min = abs(getMinValue()), rmax = _MAX(v_min, v_max); // Clear background from previous selection and select new square @@ -247,7 +247,7 @@ bool BedLevelTools::meshValidate() { // Draw value text on const uint8_t fs = DWINUI::fontWidth(meshfont); if (viewer_print_value) { - xy_int_t offset { 0, cell_height_px / 2 - fs }; + xy_uint_t offset { 0, cell_height_px / 2 - fs }; if (isnan(bedlevel.z_values[x][y])) { // undefined dwinDrawString(false, meshfont, COLOR_WHITE, COLOR_BG_BLUE, start_x_px + cell_width_px / 2 - 5, start_y_px + offset.y, F("X")); } From 993cc9463ebb7e9c46696e50469bbd69a72eabb0 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Thu, 23 Nov 2023 00:21:17 +0000 Subject: [PATCH 08/77] [cron] Bump distribution date (2023-11-23) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index c1709b501dca..963a0ca362b0 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2023-11-22" +//#define STRING_DISTRIBUTION_DATE "2023-11-23" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index bcbcd4df2624..4cb1853c0ff2 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2023-11-22" + #define STRING_DISTRIBUTION_DATE "2023-11-23" #endif /** From 2d9262cc5a9b24d5900126f3498da7f3a8f31e66 Mon Sep 17 00:00:00 2001 From: Erkan Ozgur Yilmaz Date: Thu, 23 Nov 2023 02:39:40 +0000 Subject: [PATCH 09/77] =?UTF-8?q?=E2=9A=A1=EF=B8=8F=20Fix=20MMU2=20sscanf?= =?UTF-8?q?=20bug,=20optimize=20(#26449)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/src/feature/mmu/mmu2.cpp | 23 +++++++++++------------ Marlin/src/feature/mmu/mmu2.h | 5 ++--- 2 files changed, 13 insertions(+), 15 deletions(-) diff --git a/Marlin/src/feature/mmu/mmu2.cpp b/Marlin/src/feature/mmu/mmu2.cpp index dbf8171a276e..5ef56c7eacfc 100644 --- a/Marlin/src/feature/mmu/mmu2.cpp +++ b/Marlin/src/feature/mmu/mmu2.cpp @@ -76,7 +76,7 @@ MMU2 mmu2; #define MMU2_NO_TOOL 99 #define MMU_BAUD 115200 -bool MMU2::_enabled, MMU2::ready, MMU2::mmu_print_saved; +bool MMU2::_enabled, MMU2::ready; #if HAS_PRUSA_MMU2S bool MMU2::mmu2s_triggered; #endif @@ -84,7 +84,6 @@ uint8_t MMU2::cmd, MMU2::cmd_arg, MMU2::last_cmd, MMU2::extruder; int8_t MMU2::state = 0; volatile int8_t MMU2::finda = 1; volatile bool MMU2::finda_runout_valid; -uint16_t MMU2::version = 0, MMU2::buildnr = 0; millis_t MMU2::prev_request, MMU2::prev_P0_request; char MMU2::rx_buffer[MMU_RX_SIZE], MMU2::tx_buffer[MMU_TX_SIZE]; @@ -146,6 +145,7 @@ void mmu2_attn_buzz(const bool two=false) { if (two) { BUZZ(10, 0); BUZZ(200, 404); } } +// Avoiding sscanf significantly reduces build size void MMU2::mmu_loop() { switch (state) { @@ -168,7 +168,7 @@ void MMU2::mmu_loop() { case -2: if (rx_ok()) { - sscanf(rx_buffer, "%huok\n", &version); + const uint16_t version = uint16_t(strtoul(rx_buffer, nullptr, 10)); DEBUG_ECHOLNPGM("MMU => ", version, "\nMMU <= 'S2'"); MMU2_SEND("S2"); // Read Build Number state = -3; @@ -177,17 +177,15 @@ void MMU2::mmu_loop() { case -3: if (rx_ok()) { - sscanf(rx_buffer, "%huok\n", &buildnr); - + const uint16_t buildnr = uint16_t(strtoul(rx_buffer, nullptr, 10)); DEBUG_ECHOLNPGM("MMU => ", buildnr); - check_version(); + check_version(buildnr); #if ENABLED(MMU2_MODE_12V) DEBUG_ECHOLNPGM("MMU <= 'M1'"); MMU2_SEND("M1"); // Stealth Mode state = -5; - #else DEBUG_ECHOLNPGM("MMU <= 'P0'"); MMU2_SEND("P0"); // Read FINDA @@ -210,7 +208,8 @@ void MMU2::mmu_loop() { case -4: if (rx_ok()) { - sscanf(rx_buffer, "%hhuok\n", &finda); + const uint8_t findex = uint8_t(rx_buffer[0] - '0'); + if (findex <= 1) finda = findex; DEBUG_ECHOLNPGM("MMU => ", finda, "\nMMU - ENABLED"); @@ -283,7 +282,8 @@ void MMU2::mmu_loop() { case 2: // response to command P0 if (rx_ok()) { - sscanf(rx_buffer, "%hhuok\n", &finda); + const uint8_t findex = uint8_t(rx_buffer[0] - '0'); + if (findex <= 1) finda = findex; // This is super annoying. Only activate if necessary //if (finda_runout_valid) DEBUG_ECHOLNPGM("MMU <= 'P0'\nMMU => ", p_float_t(finda, 6)); @@ -439,7 +439,7 @@ bool MMU2::rx_ok() { /** * Check if MMU has compatible firmware */ -void MMU2::check_version() { +void MMU2::check_version(const uint16_t buildnr) { if (buildnr < MMU_REQUIRED_FW_BUILDNR) { SERIAL_ERROR_MSG("Invalid MMU2 firmware. Version >= " STRINGIFY(MMU_REQUIRED_FW_BUILDNR) " required."); kill(GET_TEXT_F(MSG_KILL_MMU2_FIRMWARE)); @@ -801,8 +801,7 @@ bool MMU2::get_response() { void MMU2::manage_response(const bool move_axes, const bool turn_off_nozzle) { constexpr xyz_pos_t park_point = NOZZLE_PARK_POINT; - bool response = false; - mmu_print_saved = false; + bool response = false, mmu_print_saved = false; xyz_pos_t resume_position; celsius_t resume_hotend_temp = thermalManager.degTargetHotend(active_extruder); diff --git a/Marlin/src/feature/mmu/mmu2.h b/Marlin/src/feature/mmu/mmu2.h index bebbae667e12..2c9fd3308d97 100644 --- a/Marlin/src/feature/mmu/mmu2.h +++ b/Marlin/src/feature/mmu/mmu2.h @@ -64,7 +64,7 @@ class MMU2 { static bool rx_ok(); static bool rx_start(); - static void check_version(); + static void check_version(const uint16_t buildnr); static void command(const uint8_t cmd); static bool get_response(); @@ -90,13 +90,12 @@ class MMU2 { static void mmu_continue_loading(); #endif - static bool _enabled, ready, mmu_print_saved; + static bool _enabled, ready; static uint8_t cmd, cmd_arg, last_cmd, extruder; static int8_t state; static volatile int8_t finda; static volatile bool finda_runout_valid; - static uint16_t version, buildnr; static millis_t prev_request, prev_P0_request; static char rx_buffer[MMU_RX_SIZE], tx_buffer[MMU_TX_SIZE]; From bf61e5239083fad148c84b7a3bce355c9e32ec6a Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 22 Nov 2023 21:06:47 -0600 Subject: [PATCH 10/77] =?UTF-8?q?=E2=9A=A1=EF=B8=8F=20Tiny=20string=20opti?= =?UTF-8?q?mization?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/core/serial.h | 6 +++--- Marlin/src/lcd/menu/menu_ubl.cpp | 18 +++++++++++++----- 2 files changed, 16 insertions(+), 8 deletions(-) diff --git a/Marlin/src/core/serial.h b/Marlin/src/core/serial.h index 6b91371170f6..721d27211b88 100644 --- a/Marlin/src/core/serial.h +++ b/Marlin/src/core/serial.h @@ -276,13 +276,13 @@ class SString : public MString { SString& set() { super::set(); return *this; } template - SString& setf_P(PGM_P const fmt, Args... more) { snprintf_P(str, SIZE, fmt, more...); debug(F("setf_P")); return *this; } + SString& setf_P(PGM_P const fmt, Args... more) { super::setf_P(fmt, more...); return *this; } template - SString& setf(const char *fmt, Args... more) { snprintf(str, SIZE, fmt, more...); debug(F("setf")); return *this; } + SString& setf(const char *fmt, Args... more) { super::setf(fmt, more...); return *this; } template - SString& setf(FSTR_P const fmt, Args... more) { return setf_P(FTOP(fmt), more...); } + SString& setf(FSTR_P const fmt, Args... more) { super::setf(fmt, more...); return *this; } template SString& set(const T &v) { super::set(v); return *this; } diff --git a/Marlin/src/lcd/menu/menu_ubl.cpp b/Marlin/src/lcd/menu/menu_ubl.cpp index dc2e1761adbc..701d2ae97a54 100644 --- a/Marlin/src/lcd/menu/menu_ubl.cpp +++ b/Marlin/src/lcd/menu/menu_ubl.cpp @@ -376,11 +376,19 @@ void _lcd_ubl_storage_mesh() { * UBL LCD "radar" map point editing */ void _lcd_ubl_map_edit_cmd() { - char ubl_lcd_gcode[50], str[10], str2[10]; - dtostrf(bedlevel.get_mesh_x(x_plot), 0, 2, str); - dtostrf(bedlevel.get_mesh_y(y_plot), 0, 2, str2); - snprintf_P(ubl_lcd_gcode, sizeof(ubl_lcd_gcode), PSTR("G29P4X%sY%sR%i"), str, str2, int(n_edit_pts)); - queue.inject(ubl_lcd_gcode); + #if ENABLED(POWER_LOSS_RECOVERY) + // Costs 198 bytes on AVR with PLR disabled, but saves 60 bytes with PLR enabled + queue.inject(TS(F("G29P4X"), x_plot, 'Y', y_plot, 'R', n_edit_pts)); + #else + char ubl_lcd_gcode[50], str1[10], str2[10]; + snprintf_P(ubl_lcd_gcode, sizeof(ubl_lcd_gcode), + PSTR("G29P4X%sY%sR%i"), + dtostrf(bedlevel.get_mesh_x(x_plot), 0, 2, str1), + dtostrf(bedlevel.get_mesh_y(y_plot), 0, 2, str2), + int(n_edit_pts) + ); + queue.inject(ubl_lcd_gcode); + #endif } /** From ded942a4e4d116b36177993371b0ddaa4b14bf4c Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 22 Nov 2023 22:18:41 -0600 Subject: [PATCH 11/77] =?UTF-8?q?=F0=9F=90=9B=20Fix=20expand=5Fu8str=5FP?= =?UTF-8?q?=20string=20substitution?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Fixes #26424 --- Marlin/src/lcd/language/language_en.h | 2 +- Marlin/src/lcd/lcdprint.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index ad49906dd023..8c9dd08d07da 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -352,7 +352,7 @@ namespace LanguageNarrow_en { LSTR MSG_LCD_ON = _UxGT("On"); LSTR MSG_LCD_OFF = _UxGT("Off"); LSTR MSG_PID_AUTOTUNE = _UxGT("PID Autotune"); - LSTR MSG_PID_AUTOTUNE_E = _UxGT("PID Autotune *"); + LSTR MSG_PID_AUTOTUNE_E = _UxGT("Autotune * PID"); LSTR MSG_PID_CYCLE = _UxGT("PID Cycles"); LSTR MSG_PID_AUTOTUNE_DONE = _UxGT("PID tuning done"); LSTR MSG_PID_AUTOTUNE_FAILED = _UxGT("Autotune failed!"); diff --git a/Marlin/src/lcd/lcdprint.cpp b/Marlin/src/lcd/lcdprint.cpp index 8642d84315f3..f559272f7ed2 100644 --- a/Marlin/src/lcd/lcdprint.cpp +++ b/Marlin/src/lcd/lcdprint.cpp @@ -68,7 +68,7 @@ lcd_uint_t expand_u8str_P(char * const outstr, PGM_P const ptpl, const int8_t in else { PGM_P const b = ind == -2 ? GET_TEXT(MSG_CHAMBER) : GET_TEXT(MSG_BED); strncpy_P(o, b, n); - n -= utf8_strlen_P(b); + n -= utf8_strlen(o); o += strlen(o); } if (n > 0) { From 1bee537a09376da015dfa63ed0a74b948cef3e24 Mon Sep 17 00:00:00 2001 From: Jason Smith Date: Thu, 23 Nov 2023 10:17:41 -0800 Subject: [PATCH 12/77] =?UTF-8?q?=F0=9F=A7=91=E2=80=8D=F0=9F=92=BB=20Add?= =?UTF-8?q?=20sim=20launch=20example=20for=20Windows=20(#26456)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- buildroot/share/PlatformIO/debugging/launch.json | 9 +++++++++ 1 file changed, 9 insertions(+) diff --git a/buildroot/share/PlatformIO/debugging/launch.json b/buildroot/share/PlatformIO/debugging/launch.json index f9936ebcedf9..ddd9ba7483a3 100644 --- a/buildroot/share/PlatformIO/debugging/launch.json +++ b/buildroot/share/PlatformIO/debugging/launch.json @@ -45,6 +45,15 @@ //"program": "${workspaceRoot}/.pio/build/simulator_windows/MarlinSimulator", //"targetArchitecture": "arm64", "MIMode": "lldb" + }, + { + "name": "Launch Sim (Windows gdb)", + "request": "launch", + "type": "cppdbg", + "cwd": "${workspaceRoot}", + "program": "${workspaceRoot}/.pio/build/simulator_windows/debug/MarlinSimulator.exe", + "MIMode": "gdb", + "miDebuggerPath": "C:/msys64/mingw64/bin/gdb.exe" } ] } From fd3de02a37cec8fc5395a2d486fd229a2b71e8a9 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Fri, 24 Nov 2023 00:20:39 +0000 Subject: [PATCH 13/77] [cron] Bump distribution date (2023-11-24) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 963a0ca362b0..a33fa5f92e46 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2023-11-23" +//#define STRING_DISTRIBUTION_DATE "2023-11-24" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 4cb1853c0ff2..2447f9a9c7e4 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2023-11-23" + #define STRING_DISTRIBUTION_DATE "2023-11-24" #endif /** From bd872a7a98528da6e1fab95382488ce703fe24c1 Mon Sep 17 00:00:00 2001 From: Vovodroid Date: Fri, 24 Nov 2023 21:03:06 +0200 Subject: [PATCH 14/77] =?UTF-8?q?=F0=9F=94=A7=20Configurable=20FR/Flow=20e?= =?UTF-8?q?dit=20ranges=20(#26446)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/Configuration_adv.h | 11 +- Marlin/src/inc/Conditionals_LCD.h | 1799 ++++++++++++------------ Marlin/src/lcd/e3v2/creality/dwin.cpp | 6 +- Marlin/src/lcd/e3v2/proui/dwin.cpp | 24 +- Marlin/src/lcd/extui/malyan/malyan.cpp | 2 +- Marlin/src/lcd/marlinui.cpp | 2 +- Marlin/src/lcd/menu/menu_item.h | 6 +- Marlin/src/lcd/menu/menu_tune.cpp | 6 +- Marlin/src/lcd/tft/touch.cpp | 6 +- 9 files changed, 937 insertions(+), 925 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 275bcaa66926..b72f7d8da11b 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1254,7 +1254,7 @@ */ //#define XY_FREQUENCY_LIMIT 10 // (Hz) Maximum frequency of small zigzag infill moves. Set with M201 F. #ifdef XY_FREQUENCY_LIMIT - #define XY_FREQUENCY_MIN_PERCENT 5 // (percent) Minimum FR percentage to apply. Set with M201 G. + #define XY_FREQUENCY_MIN_PERCENT 5 // (%) Minimum FR percentage to apply. Set with M201 G. #endif // @@ -1625,6 +1625,15 @@ #endif // HAS_DISPLAY +#if HAS_FEEDRATE_EDIT + #define SPEED_EDIT_MIN 10 // (%) Feedrate percentage edit range minimum + #define SPEED_EDIT_MAX 999 // (%) Feedrate percentage edit range maximum +#endif +#if HAS_FLOW_EDIT + #define FLOW_EDIT_MIN 10 // (%) Flow percentage edit range minimum + #define FLOW_EDIT_MAX 999 // (%) Flow percentage edit range maximum +#endif + // Add 'M73' to set print job progress, overrides Marlin's built-in estimate //#define SET_PROGRESS_MANUALLY #if ENABLED(SET_PROGRESS_MANUALLY) diff --git a/Marlin/src/inc/Conditionals_LCD.h b/Marlin/src/inc/Conditionals_LCD.h index a252edfb4a56..955b8fd960f4 100644 --- a/Marlin/src/inc/Conditionals_LCD.h +++ b/Marlin/src/inc/Conditionals_LCD.h @@ -26,1093 +26,1089 @@ * Conditionals that need to be set before Configuration_adv.h or pins.h */ -#if ENABLED(SDSUPPORT) - #define HAS_MEDIA 1 +/** + * Extruders have some combination of stepper motors and hotends + * so we separate these concepts into the defines: + * + * EXTRUDERS - Number of Selectable Tools + * HOTENDS - Number of hotends, whether connected or separate + * E_STEPPERS - Number of actual E stepper motors + * E_MANUAL - Number of E steppers for LCD move options + * + * These defines must be simple constants for use in REPEAT, etc. + */ +#if EXTRUDERS + #define HAS_EXTRUDERS 1 + #if EXTRUDERS > 1 + #define HAS_MULTI_EXTRUDER 1 + #endif + #define E_AXIS_N(E) AxisEnum(E_AXIS + E_INDEX_N(E)) +#else + #undef EXTRUDERS + #define EXTRUDERS 0 + #undef TEMP_SENSOR_0 + #undef TEMP_SENSOR_1 + #undef TEMP_SENSOR_2 + #undef TEMP_SENSOR_3 + #undef TEMP_SENSOR_4 + #undef TEMP_SENSOR_5 + #undef TEMP_SENSOR_6 + #undef TEMP_SENSOR_7 + #undef SINGLENOZZLE + #undef SWITCHING_EXTRUDER + #undef MECHANICAL_SWITCHING_EXTRUDER + #undef SWITCHING_NOZZLE + #undef MECHANICAL_SWITCHING_NOZZLE + #undef MIXING_EXTRUDER + #undef HOTEND_IDLE_TIMEOUT + #undef DISABLE_E + #undef PREVENT_LENGTHY_EXTRUDE + #undef FILAMENT_RUNOUT_SENSOR + #undef FILAMENT_RUNOUT_DISTANCE_MM + #undef DISABLE_OTHER_EXTRUDERS #endif -// MKS_LCD12864A/B is a variant of MKS_MINI_12864 -#if ANY(MKS_LCD12864A, MKS_LCD12864B) - #define MKS_MINI_12864 -#endif +#define E_OPTARG(N) OPTARG(HAS_MULTI_EXTRUDER, N) +#define E_TERN_(N) TERN_(HAS_MULTI_EXTRUDER, N) +#define E_TERN0(N) TERN0(HAS_MULTI_EXTRUDER, N) -// MKS_MINI_12864_V3 and BTT_MINI_12864 have identical pinouts to FYSETC_MINI_12864_2_1 -#if ANY(MKS_MINI_12864_V3, BTT_MINI_12864) - #define FYSETC_MINI_12864_2_1 +#if ANY(SWITCHING_EXTRUDER, MECHANICAL_SWITCHING_EXTRUDER) + #define HAS_SWITCHING_EXTRUDER 1 #endif - -// Old settings are now conditional on DGUS_LCD_UI -#if DGUS_UI_IS(ORIGIN) - #define DGUS_LCD_UI_ORIGIN 1 -#elif DGUS_UI_IS(FYSETC) - #define DGUS_LCD_UI_FYSETC 1 -#elif DGUS_UI_IS(HIPRECY) - #define DGUS_LCD_UI_HIPRECY 1 -#elif DGUS_UI_IS(MKS) - #define DGUS_LCD_UI_MKS 1 -#elif DGUS_UI_IS(RELOADED) - #define DGUS_LCD_UI_RELOADED 1 -#elif DGUS_UI_IS(IA_CREALITY) - #define DGUS_LCD_UI_IA_CREALITY 1 -#elif DGUS_UI_IS(E3S1PRO) - #define DGUS_LCD_UI_E3S1PRO 1 +#if ANY(SWITCHING_NOZZLE, MECHANICAL_SWITCHING_NOZZLE) + #define HAS_SWITCHING_NOZZLE 1 #endif /** - * General Flags that may be set below by specific LCDs - * - * DOGLCD : Run a Graphical LCD through U8GLib (with MarlinUI) - * IS_ULTIPANEL : Define LCD_PINS_D5/6/7 for direct-connected "Ultipanel" LCDs - * HAS_WIRED_LCD : Ultra LCD, not necessarily Ultipanel. - * IS_RRD_SC : Common RRD Smart Controller digital interface pins - * IS_RRD_FG_SC : Common RRD Full Graphical Smart Controller digital interface pins - * IS_U8GLIB_ST7920 : Most common DOGM display SPI interface, supporting a "lightweight" display mode. - * U8GLIB_SH1106 : SH1106 OLED with I2C interface via U8GLib - * IS_U8GLIB_SSD1306 : SSD1306 OLED with I2C interface via U8GLib (U8GLIB_SSD1306) - * U8GLIB_SSD1309 : SSD1309 OLED with I2C interface via U8GLib (HAS_U8GLIB_I2C_OLED, HAS_WIRED_LCD, DOGLCD) - * IS_U8GLIB_ST7565_64128N : ST7565 128x64 LCD with SPI interface via U8GLib - * IS_U8GLIB_LM6059_AF : LM6059 with Hardware SPI via U8GLib + * Multi-Material-Unit supported models */ -#if ANY(MKS_MINI_12864, ENDER2_STOCKDISPLAY) - - #define MINIPANEL - -#elif ENABLED(YHCB2004) - - #define IS_ULTIPANEL 1 - -#elif ENABLED(CARTESIO_UI) - - #define DOGLCD - #define IS_ULTIPANEL 1 - -#elif ANY(DWIN_MARLINUI_PORTRAIT, DWIN_MARLINUI_LANDSCAPE) - - #define IS_DWIN_MARLINUI 1 - #define IS_ULTIPANEL 1 - -#elif ENABLED(ZONESTAR_LCD) - - #define HAS_ADC_BUTTONS 1 - #define REPRAPWORLD_KEYPAD_MOVE_STEP 10.0 - #define ADC_KEY_NUM 8 - #define IS_ULTIPANEL 1 - - // This helps to implement HAS_ADC_BUTTONS menus - #define REVERSE_MENU_DIRECTION - #define STD_ENCODER_PULSES_PER_STEP 1 - #define STD_ENCODER_STEPS_PER_MENU_ITEM 1 - #define ENCODER_FEEDRATE_DEADZONE 2 - -#elif ENABLED(ZONESTAR_12864LCD) - #define DOGLCD - #define IS_RRD_SC 1 - #define IS_U8GLIB_ST7920 1 +#define PRUSA_MMU1 1 +#define PRUSA_MMU2 2 +#define PRUSA_MMU2S 3 +#define EXTENDABLE_EMU_MMU2 12 +#define EXTENDABLE_EMU_MMU2S 13 -#elif ENABLED(ZONESTAR_12864OLED) - #define IS_RRD_SC 1 - #define U8GLIB_SH1106 +#ifdef MMU_MODEL + #define HAS_MMU 1 + #define SINGLENOZZLE + #if MMU_MODEL == PRUSA_MMU1 + #define HAS_PRUSA_MMU1 1 + #elif MMU_MODEL % 10 == PRUSA_MMU2 + #define HAS_PRUSA_MMU2 1 + #elif MMU_MODEL % 10 == PRUSA_MMU2S + #define HAS_PRUSA_MMU2 1 + #define HAS_PRUSA_MMU2S 1 + #endif + #if MMU_MODEL >= EXTENDABLE_EMU_MMU2 + #define HAS_EXTENDABLE_MMU 1 + #endif +#endif -#elif ENABLED(ZONESTAR_12864OLED_SSD1306) - #define IS_RRD_SC 1 - #define IS_U8GLIB_SSD1306 +#undef PRUSA_MMU1 +#undef PRUSA_MMU2 +#undef PRUSA_MMU2S +#undef EXTENDABLE_EMU_MMU2 +#undef EXTENDABLE_EMU_MMU2S -#elif ENABLED(RADDS_DISPLAY) - #define IS_ULTIPANEL 1 - #define STD_ENCODER_PULSES_PER_STEP 2 +#if ENABLED(E_DUAL_STEPPER_DRIVERS) // E0/E1 steppers act in tandem as E0 -#elif ANY(miniVIKI, VIKI2, WYH_L12864, ELB_FULL_GRAPHIC_CONTROLLER, AZSMZ_12864, EMOTION_TECH_LCD) + #define E_STEPPERS 2 + #define E_MANUAL 1 - #define DOGLCD - #define IS_DOGM_12864 1 - #define IS_ULTIPANEL 1 +#elif HAS_SWITCHING_EXTRUDER // One stepper for every two EXTRUDERS - #if ENABLED(miniVIKI) - #define IS_U8GLIB_ST7565_64128N 1 - #elif ENABLED(VIKI2) - #define IS_U8GLIB_ST7565_64128N 1 - #elif ENABLED(WYH_L12864) - #define IS_U8GLIB_ST7565_64128N 1 - #define ST7565_XOFFSET 0x04 - #elif ENABLED(ELB_FULL_GRAPHIC_CONTROLLER) - #define IS_U8GLIB_LM6059_AF 1 - #elif ENABLED(AZSMZ_12864) - #define IS_U8GLIB_ST7565_64128N 1 - #elif ENABLED(EMOTION_TECH_LCD) - #define IS_U8GLIB_ST7565_64128N 1 - #define ST7565_VOLTAGE_DIVIDER_VALUE 0x07 + #if EXTRUDERS > 4 + #define E_STEPPERS 3 + #elif EXTRUDERS > 2 + #define E_STEPPERS 2 + #else + #define E_STEPPERS 1 #endif -#elif ENABLED(OLED_PANEL_TINYBOY2) - - #define IS_U8GLIB_SSD1306 - #define IS_ULTIPANEL 1 - -#elif ENABLED(RA_CONTROL_PANEL) +#elif ENABLED(MIXING_EXTRUDER) // Multiple feeds are mixed proportionally - #define LCD_I2C_TYPE_PCA8574 - #define LCD_I2C_ADDRESS 0x27 // I2C Address of the port expander - #define IS_ULTIPANEL 1 + #define E_STEPPERS MIXING_STEPPERS + #define E_MANUAL 1 + #if MIXING_STEPPERS == 2 + #define HAS_DUAL_MIXING 1 + #endif -#elif ENABLED(REPRAPWORLD_GRAPHICAL_LCD) +#elif ENABLED(SWITCHING_TOOLHEAD) // Toolchanger - #define DOGLCD - #define IS_U8GLIB_ST7920 1 - #define IS_ULTIPANEL 1 - #define ENCODER_PULSES_PER_STEP 2 + #define E_STEPPERS EXTRUDERS + #define E_MANUAL EXTRUDERS -#elif ENABLED(MKS_12864OLED) +#elif HAS_PRUSA_MMU2 // Průša Multi-Material Unit v2 - #define IS_RRD_SC 1 - #define U8GLIB_SH1106 + #define E_STEPPERS 1 + #define E_MANUAL 1 -#elif ENABLED(MKS_12864OLED_SSD1306) +#endif - #define IS_RRD_SC 1 - #define IS_U8GLIB_SSD1306 +// Default E steppers / manual motion is one per extruder +#ifndef E_STEPPERS + #define E_STEPPERS EXTRUDERS +#endif +#ifndef E_MANUAL + #define E_MANUAL EXTRUDERS +#endif -#elif ENABLED(SAV_3DGLCD) +// Number of hotends... +#if ANY(SINGLENOZZLE, MIXING_EXTRUDER) // Only one for singlenozzle or mixing extruder + #define HOTENDS 1 +#elif HAS_SWITCHING_EXTRUDER && !HAS_SWITCHING_NOZZLE // One for each pair of abstract "extruders" + #define HOTENDS E_STEPPERS +#elif TEMP_SENSOR_0 + #define HOTENDS EXTRUDERS // One per extruder if at least one heater exists +#else + #define HOTENDS 0 // A machine with no hotends at all can still extrude +#endif - #ifdef U8GLIB_SSD1306 - #define IS_U8GLIB_SSD1306 // Allow for U8GLIB_SSD1306 + SAV_3DGLCD +// At least one hotend... +#if HOTENDS + #define HAS_HOTEND 1 + #ifndef HOTEND_OVERSHOOT + #define HOTEND_OVERSHOOT 15 #endif - #define IS_NEWPANEL 1 - -#elif ENABLED(FYSETC_242_OLED_12864) - - #define IS_RRD_SC 1 - #define U8GLIB_SH1106 +#endif - #ifndef NEOPIXEL_BRIGHTNESS - #define NEOPIXEL_BRIGHTNESS 127 +// More than one hotend... +#if HOTENDS > 1 + #define HAS_MULTI_HOTEND 1 + #define HAS_HOTEND_OFFSET 1 + #ifndef HOTEND_OFFSET_X + #define HOTEND_OFFSET_X { 0 } // X offsets for each extruder #endif + #ifndef HOTEND_OFFSET_Y + #define HOTEND_OFFSET_Y { 0 } // Y offsets for each extruder + #endif + #ifndef HOTEND_OFFSET_Z + #define HOTEND_OFFSET_Z { 0 } // Z offsets for each extruder + #endif +#else + #undef HOTEND_OFFSET_X + #undef HOTEND_OFFSET_Y + #undef HOTEND_OFFSET_Z +#endif -#elif ANY(FYSETC_MINI_12864_X_X, FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0, FYSETC_MINI_12864_2_1, FYSETC_GENERIC_12864_1_1) - - #define FYSETC_MINI_12864 - #define DOGLCD - #define IS_ULTIPANEL 1 - #define LED_COLORS_REDUCE_GREEN - - // Require LED backlighting enabled - #if ENABLED(FYSETC_MINI_12864_2_1) - #ifndef NEOPIXEL_BRIGHTNESS - #define NEOPIXEL_BRIGHTNESS 127 +// Clean up E-stepper-based settings... +#if E_STEPPERS <= 7 + #undef INVERT_E7_DIR + #undef E7_DRIVER_TYPE + #if E_STEPPERS <= 6 + #undef INVERT_E6_DIR + #undef E6_DRIVER_TYPE + #if E_STEPPERS <= 5 + #undef INVERT_E5_DIR + #undef E5_DRIVER_TYPE + #if E_STEPPERS <= 4 + #undef INVERT_E4_DIR + #undef E4_DRIVER_TYPE + #if E_STEPPERS <= 3 + #undef INVERT_E3_DIR + #undef E3_DRIVER_TYPE + #if E_STEPPERS <= 2 + #undef INVERT_E2_DIR + #undef E2_DRIVER_TYPE + #if E_STEPPERS <= 1 + #undef INVERT_E1_DIR + #undef E1_DRIVER_TYPE + #if E_STEPPERS == 0 + #undef INVERT_E0_DIR + #undef E0_DRIVER_TYPE + #endif + #endif + #endif + #endif + #endif #endif - //#define NEOPIXEL_STARTUP_TEST #endif +#endif -#elif ENABLED(ULTI_CONTROLLER) +/** + * Number of Linear Axes (e.g., XYZIJKUVW) + * All the logical axes except for the tool (E) axis + */ +#ifdef NUM_AXES + #undef NUM_AXES + #define NUM_AXES_WARNING 1 +#endif - #define IS_ULTIPANEL 1 - #define U8GLIB_SSD1309 - #define LCD_RESET_PIN LCD_PINS_D6 // This controller need a reset pin - #define STD_ENCODER_PULSES_PER_STEP 4 - #define STD_ENCODER_STEPS_PER_MENU_ITEM 1 - #ifndef PCA9632 - #define PCA9632 +#ifdef W_DRIVER_TYPE + #define NUM_AXES 9 +#elif defined(V_DRIVER_TYPE) + #define NUM_AXES 8 +#elif defined(U_DRIVER_TYPE) + #define NUM_AXES 7 +#elif defined(K_DRIVER_TYPE) + #define NUM_AXES 6 +#elif defined(J_DRIVER_TYPE) + #define NUM_AXES 5 +#elif defined(I_DRIVER_TYPE) + #define NUM_AXES 4 +#elif defined(Z_DRIVER_TYPE) + #define NUM_AXES 3 +#elif defined(Y_DRIVER_TYPE) + #define NUM_AXES 2 +#elif defined(X_DRIVER_TYPE) + #define NUM_AXES 1 +#else + #define NUM_AXES 0 +#endif +#if NUM_AXES >= 1 + #define HAS_X_AXIS 1 + #if NUM_AXES >= XY + #define HAS_Y_AXIS 1 + #if NUM_AXES >= XYZ + #define HAS_Z_AXIS 1 + #if NUM_AXES >= 4 + #define HAS_I_AXIS 1 + #if NUM_AXES >= 5 + #define HAS_J_AXIS 1 + #if NUM_AXES >= 6 + #define HAS_K_AXIS 1 + #if NUM_AXES >= 7 + #define HAS_U_AXIS 1 + #if NUM_AXES >= 8 + #define HAS_V_AXIS 1 + #if NUM_AXES >= 9 + #define HAS_W_AXIS 1 + #endif + #endif + #endif + #endif + #endif + #endif + #endif #endif +#endif -#elif ENABLED(MAKEBOARD_MINI_2_LINE_DISPLAY_1602) - - #define IS_RRD_SC 1 - #define LCD_WIDTH 16 - #define LCD_HEIGHT 2 - -#elif ANY(TFTGLCD_PANEL_SPI, TFTGLCD_PANEL_I2C) +#if !HAS_X_AXIS + #undef AVOID_OBSTACLES + #undef ENDSTOPPULLUP_XMIN + #undef ENDSTOPPULLUP_XMAX + #undef X_MIN_ENDSTOP_HIT_STATE + #undef X_MAX_ENDSTOP_HIT_STATE + #undef X2_DRIVER_TYPE + #undef X_ENABLE_ON + #undef DISABLE_X + #undef INVERT_X_DIR + #undef X_HOME_DIR + #undef X_MIN_POS + #undef X_MAX_POS + #undef MANUAL_X_HOME_POS + #undef MIN_SOFTWARE_ENDSTOPS + #undef MAX_SOFTWARE_ENDSTOPS +#endif - #define IS_TFTGLCD_PANEL 1 - #define IS_ULTIPANEL 1 // Note that IS_ULTIPANEL leads to HAS_WIRED_LCD +#if !HAS_Y_AXIS + #undef AVOID_OBSTACLES + #undef ENDSTOPPULLUP_YMIN + #undef ENDSTOPPULLUP_YMAX + #undef Y_MIN_ENDSTOP_HIT_STATE + #undef Y_MAX_ENDSTOP_HIT_STATE + #undef Y2_DRIVER_TYPE + #undef Y_ENABLE_ON + #undef DISABLE_Y + #undef INVERT_Y_DIR + #undef Y_HOME_DIR + #undef Y_MIN_POS + #undef Y_MAX_POS + #undef MANUAL_Y_HOME_POS + #undef MIN_SOFTWARE_ENDSTOP_Y + #undef MAX_SOFTWARE_ENDSTOP_Y +#endif - #if HAS_MEDIA && DISABLED(LCD_PROGRESS_BAR) - #define LCD_PROGRESS_BAR - #endif - #if ENABLED(TFTGLCD_PANEL_I2C) - #define LCD_I2C_ADDRESS 0x33 // Must be 0x33 for STM32 main boards and equal to panel's I2C slave address +#if HAS_Z_AXIS + #ifdef Z4_DRIVER_TYPE + #define NUM_Z_STEPPERS 4 + #elif defined(Z3_DRIVER_TYPE) + #define NUM_Z_STEPPERS 3 + #elif defined(Z2_DRIVER_TYPE) + #define NUM_Z_STEPPERS 2 + #else + #define NUM_Z_STEPPERS 1 #endif - #define LCD_USE_I2C_BUZZER // Enable buzzer on LCD, used for both I2C and SPI buses (LiquidTWI2 not required) - #define STD_ENCODER_PULSES_PER_STEP 2 - #define STD_ENCODER_STEPS_PER_MENU_ITEM 1 - #define LCD_WIDTH 20 // 20 or 24 chars in line - #define LCD_HEIGHT 10 // Character lines - #define LCD_CONTRAST_MIN 127 - #define LCD_CONTRAST_MAX 255 - #define LCD_CONTRAST_DEFAULT 250 - #define CONVERT_TO_EXT_ASCII // Use extended 128-255 symbols from ASCII table. - // At this time present conversion only for cyrillic - bg, ru and uk languages. - // First 7 ASCII symbols in panel font must be replaced with Marlin's special symbols. - -#elif ENABLED(CR10_STOCKDISPLAY) - - #define IS_RRD_FG_SC 1 - #define LCD_ST7920_DELAY_1 125 - #define LCD_ST7920_DELAY_2 125 - #define LCD_ST7920_DELAY_3 125 - -#elif ANY(ANET_FULL_GRAPHICS_LCD, ANET_FULL_GRAPHICS_LCD_ALT_WIRING) - - #define IS_RRD_FG_SC 1 - #define LCD_ST7920_DELAY_1 150 - #define LCD_ST7920_DELAY_2 150 - #define LCD_ST7920_DELAY_3 150 - -#elif ANY(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER, BQ_LCD_SMART_CONTROLLER, K3D_FULL_GRAPHIC_SMART_CONTROLLER) - - #define IS_RRD_FG_SC 1 - -#elif ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) - - #define IS_RRD_SC 1 // RepRapDiscount LCD or Graphical LCD with rotary click encoder +#else + #undef ENDSTOPPULLUP_ZMIN + #undef ENDSTOPPULLUP_ZMAX + #undef Z_MIN_ENDSTOP_HIT_STATE + #undef Z_MAX_ENDSTOP_HIT_STATE + #undef Z2_DRIVER_TYPE + #undef Z3_DRIVER_TYPE + #undef Z4_DRIVER_TYPE + #undef Z_ENABLE_ON + #undef DISABLE_Z + #undef INVERT_Z_DIR + #undef Z_HOME_DIR + #undef Z_MIN_POS + #undef Z_MAX_POS + #undef MANUAL_Z_HOME_POS + #undef Z_SAFE_HOMING + #undef MIN_SOFTWARE_ENDSTOP_Z + #undef MAX_SOFTWARE_ENDSTOP_Z +#endif -#elif ENABLED(K3D_242_OLED_CONTROLLER) +#if !HAS_I_AXIS + #undef ENDSTOPPULLUP_IMIN + #undef ENDSTOPPULLUP_IMAX + #undef I_MIN_ENDSTOP_HIT_STATE + #undef I_MAX_ENDSTOP_HIT_STATE + #undef I_ENABLE_ON + #undef DISABLE_I + #undef INVERT_I_DIR + #undef I_HOME_DIR + #undef I_MIN_POS + #undef I_MAX_POS + #undef MANUAL_I_HOME_POS + #undef MIN_SOFTWARE_ENDSTOP_I + #undef MAX_SOFTWARE_ENDSTOP_I +#endif - #define IS_RRD_SC 1 - #define U8GLIB_SSD1309 +#if !HAS_J_AXIS + #undef ENDSTOPPULLUP_JMIN + #undef ENDSTOPPULLUP_JMAX + #undef J_MIN_ENDSTOP_HIT_STATE + #undef J_MAX_ENDSTOP_HIT_STATE + #undef J_ENABLE_ON + #undef DISABLE_J + #undef INVERT_J_DIR + #undef J_HOME_DIR + #undef J_MIN_POS + #undef J_MAX_POS + #undef MANUAL_J_HOME_POS + #undef MIN_SOFTWARE_ENDSTOP_J + #undef MAX_SOFTWARE_ENDSTOP_J +#endif +#if !HAS_K_AXIS + #undef ENDSTOPPULLUP_KMIN + #undef ENDSTOPPULLUP_KMAX + #undef K_MIN_ENDSTOP_HIT_STATE + #undef K_MAX_ENDSTOP_HIT_STATE + #undef K_ENABLE_ON + #undef DISABLE_K + #undef INVERT_K_DIR + #undef K_HOME_DIR + #undef K_MIN_POS + #undef K_MAX_POS + #undef MANUAL_K_HOME_POS + #undef MIN_SOFTWARE_ENDSTOP_K + #undef MAX_SOFTWARE_ENDSTOP_K #endif -// ST7920-based graphical displays -#if ANY(IS_RRD_FG_SC, LCD_FOR_MELZI, SILVER_GATE_GLCD_CONTROLLER) - #define DOGLCD - #define IS_U8GLIB_ST7920 1 - #define IS_RRD_SC 1 +#if !HAS_U_AXIS + #undef ENDSTOPPULLUP_UMIN + #undef ENDSTOPPULLUP_UMAX + #undef U_MIN_ENDSTOP_HIT_STATE + #undef U_MAX_ENDSTOP_HIT_STATE + #undef U_ENABLE_ON + #undef DISABLE_U + #undef INVERT_U_DIR + #undef U_HOME_DIR + #undef U_MIN_POS + #undef U_MAX_POS + #undef MANUAL_U_HOME_POS + #undef MIN_SOFTWARE_ENDSTOP_U + #undef MAX_SOFTWARE_ENDSTOP_U #endif -// ST7565 / 64128N graphical displays -#if ANY(MAKRPANEL, MINIPANEL) - #define IS_ULTIPANEL 1 - #define DOGLCD - #if ENABLED(MAKRPANEL) - #define IS_U8GLIB_ST7565_64128N 1 - #endif +#if !HAS_V_AXIS + #undef ENDSTOPPULLUP_VMIN + #undef ENDSTOPPULLUP_VMAX + #undef V_MIN_ENDSTOP_HIT_STATE + #undef V_MAX_ENDSTOP_HIT_STATE + #undef V_ENABLE_ON + #undef DISABLE_V + #undef INVERT_V_DIR + #undef V_HOME_DIR + #undef V_MIN_POS + #undef V_MAX_POS + #undef MANUAL_V_HOME_POS + #undef MIN_SOFTWARE_ENDSTOP_V + #undef MAX_SOFTWARE_ENDSTOP_V #endif -#if ENABLED(IS_U8GLIB_SSD1306) - #define U8GLIB_SSD1306 +#if !HAS_W_AXIS + #undef ENDSTOPPULLUP_WMIN + #undef ENDSTOPPULLUP_WMAX + #undef W_MIN_ENDSTOP_HIT_STATE + #undef W_MAX_ENDSTOP_HIT_STATE + #undef W_ENABLE_ON + #undef DISABLE_W + #undef INVERT_W_DIR + #undef W_HOME_DIR + #undef W_MIN_POS + #undef W_MAX_POS + #undef MANUAL_W_HOME_POS + #undef MIN_SOFTWARE_ENDSTOP_W + #undef MAX_SOFTWARE_ENDSTOP_W #endif -#if ENABLED(OVERLORD_OLED) - #define IS_ULTIPANEL 1 - #define U8GLIB_SH1106 - /** - * PCA9632 for buzzer and LEDs via i2c - * No auto-inc, red and green leds switched, buzzer - */ - #define PCA9632 - #define PCA9632_NO_AUTO_INC - #define PCA9632_GRN 0x00 - #define PCA9632_RED 0x02 - #define PCA9632_BUZZER - #define PCA9632_BUZZER_DATA { 0x09, 0x02 } +#define _OR_HAS_DA(A) ENABLED(DISABLE_##A) || +#if MAP(_OR_HAS_DA, X, Y, Z, I, J, K, U, V, W) 0 + #define HAS_DISABLE_MAIN_AXES 1 +#endif +#if HAS_DISABLE_MAIN_AXES || ENABLED(DISABLE_E) + #define HAS_DISABLE_AXES 1 +#endif +#undef _OR_HAS_DA - #define STD_ENCODER_PULSES_PER_STEP 1 // Overlord uses buttons - #define STD_ENCODER_STEPS_PER_MENU_ITEM 1 +#ifdef X2_DRIVER_TYPE + #define HAS_X2_STEPPER 1 +#endif +#ifdef Y2_DRIVER_TYPE + #define HAS_Y2_STEPPER 1 #endif -// 128x64 I2C OLED LCDs - SSD1306/SSD1309/SH1106 -#if ANY(U8GLIB_SSD1306, U8GLIB_SSD1309, U8GLIB_SH1106) - #define HAS_U8GLIB_I2C_OLED 1 - #define HAS_WIRED_LCD 1 - #define DOGLCD +/** + * Number of Primary Linear Axes (e.g., XYZ) + * X, XY, or XYZ axes. Excluding duplicate axes (X2, Y2, Z2, Z3, Z4) + */ +#if NUM_AXES >= 3 + #define PRIMARY_LINEAR_AXES 3 +#else + #define PRIMARY_LINEAR_AXES NUM_AXES #endif /** - * SPI Ultipanels + * Number of Secondary Axes (e.g., IJKUVW) + * All linear/rotational axes between XYZ and E. */ +#define SECONDARY_AXES SUB3(NUM_AXES) -// Basic Ultipanel-like displays -#if ANY(ULTIMAKERCONTROLLER, IS_RRD_SC, G3D_PANEL, RIGIDBOT_PANEL, PANEL_ONE, U8GLIB_SH1106) - #define IS_ULTIPANEL 1 +/** + * Number of Rotational Axes (e.g., IJK) + * All axes for which AXIS*_ROTATES is defined. + * For these axes, positions are specified in angular degrees. + */ +#if ENABLED(AXIS9_ROTATES) + #define ROTATIONAL_AXES 6 +#elif ENABLED(AXIS8_ROTATES) + #define ROTATIONAL_AXES 5 +#elif ENABLED(AXIS7_ROTATES) + #define ROTATIONAL_AXES 4 +#elif ENABLED(AXIS6_ROTATES) + #define ROTATIONAL_AXES 3 +#elif ENABLED(AXIS5_ROTATES) + #define ROTATIONAL_AXES 2 +#elif ENABLED(AXIS4_ROTATES) + #define ROTATIONAL_AXES 1 +#else + #define ROTATIONAL_AXES 0 #endif -// Einstart OLED has Cardinal nav via pins defined in pins_EINSTART-S.h -#if ENABLED(U8GLIB_SH1106_EINSTART) - #define DOGLCD - #define IS_ULTIPANEL 1 +/** + * Number of Secondary Linear Axes (e.g., UVW) + * All secondary axes for which AXIS*_ROTATES is not defined. + * Excluding primary axes and excluding duplicate axes (X2, Y2, Z2, Z3, Z4) + */ +#define SECONDARY_LINEAR_AXES (NUM_AXES - PRIMARY_LINEAR_AXES - ROTATIONAL_AXES) + +/** + * Number of Logical Axes (e.g., XYZIJKUVWE) + * All logical axes that can be commanded directly by G-code. + * Delta maps stepper-specific values to ABC steppers. + */ +#if HAS_EXTRUDERS + #define LOGICAL_AXES INCREMENT(NUM_AXES) +#else + #define LOGICAL_AXES NUM_AXES #endif -// TFT Legacy options masquerade as TFT_GENERIC -#if ANY(FSMC_GRAPHICAL_TFT, SPI_GRAPHICAL_TFT, TFT_320x240, TFT_480x320, TFT_320x240_SPI, TFT_480x320_SPI, TFT_LVGL_UI_FSMC, TFT_LVGL_UI_SPI) - #define IS_LEGACY_TFT 1 - #define TFT_GENERIC - #if ANY(FSMC_GRAPHICAL_TFT, TFT_320x240, TFT_480x320, TFT_LVGL_UI_FSMC) - #define TFT_INTERFACE_FSMC - #elif ANY(SPI_GRAPHICAL_TFT, TFT_320x240_SPI, TFT_480x320_SPI, TFT_LVGL_UI_SPI) - #define TFT_INTERFACE_SPI - #endif - #if ANY(FSMC_GRAPHICAL_TFT, SPI_GRAPHICAL_TFT) - #define TFT_CLASSIC_UI - #elif ANY(TFT_320x240, TFT_480x320, TFT_320x240_SPI, TFT_480x320_SPI) - #define TFT_COLOR_UI - #elif ANY(TFT_LVGL_UI_FSMC, TFT_LVGL_UI_SPI) - #define TFT_LVGL_UI - #endif +/** + * DISTINCT_E_FACTORS is set to give extruders (some) individual settings. + * + * DISTINCT_AXES is the number of distinct addressable axes (not steppers). + * Includes all linear axes plus all distinguished extruders. + * The default behavior is to treat all extruders as a single E axis + * with shared motion and temperature settings. + * + * DISTINCT_E is the number of distinguished extruders. By default this + * will be 1 which indicates all extruders share the same settings. + * + * E_INDEX_N(E) should be used to get the E index of any item that might be + * distinguished. + */ +#if ENABLED(DISTINCT_E_FACTORS) && E_STEPPERS > 1 + #define DISTINCT_AXES (NUM_AXES + E_STEPPERS) + #define DISTINCT_E E_STEPPERS + #define E_INDEX_N(E) (E) +#else + #undef DISTINCT_E_FACTORS + #define DISTINCT_AXES LOGICAL_AXES + #define DISTINCT_E 1 + #define E_INDEX_N(E) 0 #endif -// FSMC/SPI TFT Panels (LVGL) -#if ENABLED(TFT_LVGL_UI) - #define HAS_TFT_LVGL_UI 1 - #define SERIAL_RUNTIME_HOOK 1 +// Helper macros for extruder and hotend arrays +#define _EXTRUDER_LOOP(E) for (int8_t E = 0; E < EXTRUDERS; E++) +#define EXTRUDER_LOOP() _EXTRUDER_LOOP(e) +#define _HOTEND_LOOP(H) for (int8_t H = 0; H < HOTENDS; H++) +#define HOTEND_LOOP() _HOTEND_LOOP(e) + +#define ARRAY_BY_EXTRUDERS(V...) ARRAY_N(EXTRUDERS, V) +#define ARRAY_BY_EXTRUDERS1(v1) ARRAY_N_1(EXTRUDERS, v1) +#define ARRAY_BY_HOTENDS(V...) ARRAY_N(HOTENDS, V) +#define ARRAY_BY_HOTENDS1(v1) ARRAY_N_1(HOTENDS, v1) + +// Support for SD Card and other file storage +#if ENABLED(SDSUPPORT) + #define HAS_MEDIA 1 #endif -// FSMC/SPI TFT Panels -#if ENABLED(TFT_CLASSIC_UI) - #define TFT_SCALED_DOGLCD 1 +/** + * Conditionals for the configured LCD / Controller + */ + +// MKS_LCD12864A/B is a variant of MKS_MINI_12864 +#if ANY(MKS_LCD12864A, MKS_LCD12864B) + #define MKS_MINI_12864 #endif -#if TFT_SCALED_DOGLCD - #define DOGLCD - #define IS_ULTIPANEL 1 - #define DELAYED_BACKLIGHT_INIT -#elif HAS_TFT_LVGL_UI - #define DELAYED_BACKLIGHT_INIT +// MKS_MINI_12864_V3 and BTT_MINI_12864 have identical pinouts to FYSETC_MINI_12864_2_1 +#if ANY(MKS_MINI_12864_V3, BTT_MINI_12864) + #define FYSETC_MINI_12864_2_1 #endif -// Color UI -#if ENABLED(TFT_COLOR_UI) - #define HAS_GRAPHICAL_TFT 1 - #define IS_ULTIPANEL 1 +// Old settings are now conditional on DGUS_LCD_UI +#if DGUS_UI_IS(ORIGIN) + #define DGUS_LCD_UI_ORIGIN 1 +#elif DGUS_UI_IS(FYSETC) + #define DGUS_LCD_UI_FYSETC 1 +#elif DGUS_UI_IS(HIPRECY) + #define DGUS_LCD_UI_HIPRECY 1 +#elif DGUS_UI_IS(MKS) + #define DGUS_LCD_UI_MKS 1 +#elif DGUS_UI_IS(RELOADED) + #define DGUS_LCD_UI_RELOADED 1 +#elif DGUS_UI_IS(IA_CREALITY) + #define DGUS_LCD_UI_IA_CREALITY 1 +#elif DGUS_UI_IS(E3S1PRO) + #define DGUS_LCD_UI_E3S1PRO 1 #endif /** - * I2C Panels + * General Flags that may be set below by specific LCDs + * + * DOGLCD : Run a Graphical LCD through U8GLib (with MarlinUI) + * IS_ULTIPANEL : Define LCD_PINS_D5/6/7 for direct-connected "Ultipanel" LCDs + * HAS_WIRED_LCD : Ultra LCD, not necessarily Ultipanel. + * IS_RRD_SC : Common RRD Smart Controller digital interface pins + * IS_RRD_FG_SC : Common RRD Full Graphical Smart Controller digital interface pins + * IS_U8GLIB_ST7920 : Most common DOGM display SPI interface, supporting a "lightweight" display mode. + * U8GLIB_SH1106 : SH1106 OLED with I2C interface via U8GLib + * IS_U8GLIB_SSD1306 : SSD1306 OLED with I2C interface via U8GLib (U8GLIB_SSD1306) + * U8GLIB_SSD1309 : SSD1309 OLED with I2C interface via U8GLib (HAS_U8GLIB_I2C_OLED, HAS_WIRED_LCD, DOGLCD) + * IS_U8GLIB_ST7565_64128N : ST7565 128x64 LCD with SPI interface via U8GLib + * IS_U8GLIB_LM6059_AF : LM6059 with Hardware SPI via U8GLib */ +#if ANY(MKS_MINI_12864, ENDER2_STOCKDISPLAY) -#if ANY(IS_RRD_SC, IS_DOGM_12864, OLED_PANEL_TINYBOY2, LCD_I2C_PANELOLU2) + #define MINIPANEL - #define STD_ENCODER_PULSES_PER_STEP 4 - #define STD_ENCODER_STEPS_PER_MENU_ITEM 1 +#elif ENABLED(YHCB2004) - #if ENABLED(LCD_I2C_PANELOLU2) // PANELOLU2 LCD with status LEDs, separate encoder and click inputs - #define LCD_I2C_TYPE_MCP23017 // I2C Character-based 12864 display - #define LCD_I2C_ADDRESS 0x20 // I2C Address of the port expander - #define LCD_USE_I2C_BUZZER // Enable buzzer on LCD (optional) - #define IS_ULTIPANEL 1 - #endif + #define IS_ULTIPANEL 1 -#elif ANY(LCD_SAINSMART_I2C_1602, LCD_SAINSMART_I2C_2004) +#elif ENABLED(CARTESIO_UI) - #define LCD_I2C_TYPE_PCF8575 // I2C Character-based 12864 display - #define LCD_I2C_ADDRESS 0x27 // I2C Address of the port expander + #define DOGLCD #define IS_ULTIPANEL 1 - #if ENABLED(LCD_SAINSMART_I2C_2004) - #define LCD_WIDTH 20 - #define LCD_HEIGHT 4 - #endif - -#elif ENABLED(LCD_I2C_VIKI) +#elif ANY(DWIN_MARLINUI_PORTRAIT, DWIN_MARLINUI_LANDSCAPE) - /** - * Panucatt VIKI LCD with status LEDs, integrated click & L/R/U/P buttons, separate encoder inputs - * - * This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 ) - * Make sure the LiquidTWI2 directory is placed in the Arduino or Sketchbook libraries subdirectory. - * Note: The pause/stop/resume LCD button pin should be connected to the Arduino - * BTN_ENC pin (or set BTN_ENC to -1 if not used) - */ - #define LCD_I2C_TYPE_MCP23017 - #define LCD_I2C_ADDRESS 0x20 // I2C Address of the port expander - #define LCD_USE_I2C_BUZZER // Enable buzzer on LCD (requires LiquidTWI2 v1.2.3 or later) + #define IS_DWIN_MARLINUI 1 #define IS_ULTIPANEL 1 - #define ENCODER_FEEDRATE_DEADZONE 4 +#elif ENABLED(ZONESTAR_LCD) + + #define HAS_ADC_BUTTONS 1 + #define REPRAPWORLD_KEYPAD_MOVE_STEP 10.0 + #define ADC_KEY_NUM 8 + #define IS_ULTIPANEL 1 + // This helps to implement HAS_ADC_BUTTONS menus + #define REVERSE_MENU_DIRECTION #define STD_ENCODER_PULSES_PER_STEP 1 - #define STD_ENCODER_STEPS_PER_MENU_ITEM 2 + #define STD_ENCODER_STEPS_PER_MENU_ITEM 1 + #define ENCODER_FEEDRATE_DEADZONE 2 -#elif ENABLED(G3D_PANEL) +#elif ENABLED(ZONESTAR_12864LCD) + #define DOGLCD + #define IS_RRD_SC 1 + #define IS_U8GLIB_ST7920 1 + +#elif ENABLED(ZONESTAR_12864OLED) + #define IS_RRD_SC 1 + #define U8GLIB_SH1106 + +#elif ENABLED(ZONESTAR_12864OLED_SSD1306) + #define IS_RRD_SC 1 + #define IS_U8GLIB_SSD1306 +#elif ENABLED(RADDS_DISPLAY) + #define IS_ULTIPANEL 1 #define STD_ENCODER_PULSES_PER_STEP 2 - #define STD_ENCODER_STEPS_PER_MENU_ITEM 1 -#endif +#elif ANY(miniVIKI, VIKI2, WYH_L12864, ELB_FULL_GRAPHIC_CONTROLLER, AZSMZ_12864, EMOTION_TECH_LCD) -#if ANY(LCD_I2C_TYPE_MCP23017, LCD_I2C_TYPE_MCP23008) && DISABLED(NO_LCD_DETECT) - #define DETECT_I2C_LCD_DEVICE 1 -#endif + #define DOGLCD + #define IS_DOGM_12864 1 + #define IS_ULTIPANEL 1 -#ifndef STD_ENCODER_PULSES_PER_STEP - #if ENABLED(TOUCH_SCREEN) - #define STD_ENCODER_PULSES_PER_STEP 2 - #else - #define STD_ENCODER_PULSES_PER_STEP 5 + #if ENABLED(miniVIKI) + #define IS_U8GLIB_ST7565_64128N 1 + #elif ENABLED(VIKI2) + #define IS_U8GLIB_ST7565_64128N 1 + #elif ENABLED(WYH_L12864) + #define IS_U8GLIB_ST7565_64128N 1 + #define ST7565_XOFFSET 0x04 + #elif ENABLED(ELB_FULL_GRAPHIC_CONTROLLER) + #define IS_U8GLIB_LM6059_AF 1 + #elif ENABLED(AZSMZ_12864) + #define IS_U8GLIB_ST7565_64128N 1 + #elif ENABLED(EMOTION_TECH_LCD) + #define IS_U8GLIB_ST7565_64128N 1 + #define ST7565_VOLTAGE_DIVIDER_VALUE 0x07 #endif -#endif -#ifndef STD_ENCODER_STEPS_PER_MENU_ITEM - #define STD_ENCODER_STEPS_PER_MENU_ITEM 1 -#endif -#ifndef ENCODER_PULSES_PER_STEP - #define ENCODER_PULSES_PER_STEP STD_ENCODER_PULSES_PER_STEP -#endif -#ifndef ENCODER_STEPS_PER_MENU_ITEM - #define ENCODER_STEPS_PER_MENU_ITEM STD_ENCODER_STEPS_PER_MENU_ITEM -#endif -#ifndef ENCODER_FEEDRATE_DEADZONE - #define ENCODER_FEEDRATE_DEADZONE 6 -#endif -// Shift register panels -// --------------------- -// 2 wire Non-latching LCD SR from: -// https://github.com/fmalpartida/New-LiquidCrystal/wiki/schematics#user-content-ShiftRegister_connection -#if ENABLED(FF_INTERFACEBOARD) - #define SR_LCD_3W_NL // Non latching 3 wire shift register - #define IS_ULTIPANEL 1 -#elif ENABLED(SAV_3DLCD) - #define SR_LCD_2W_NL // Non latching 2 wire shift register - #define IS_ULTIPANEL 1 -#elif ENABLED(ULTIPANEL) +#elif ENABLED(OLED_PANEL_TINYBOY2) + + #define IS_U8GLIB_SSD1306 #define IS_ULTIPANEL 1 -#endif -#if ANY(IS_ULTIPANEL, ULTRA_LCD) - #define HAS_WIRED_LCD 1 -#endif +#elif ENABLED(RA_CONTROL_PANEL) -#if ANY(IS_ULTIPANEL, REPRAPWORLD_KEYPAD) - #define IS_NEWPANEL 1 -#endif + #define LCD_I2C_TYPE_PCA8574 + #define LCD_I2C_ADDRESS 0x27 // I2C Address of the port expander + #define IS_ULTIPANEL 1 -#if ANY(ZONESTAR_LCD, REPRAPWORLD_KEYPAD) - #define IS_RRW_KEYPAD 1 - #ifndef REPRAPWORLD_KEYPAD_MOVE_STEP - #define REPRAPWORLD_KEYPAD_MOVE_STEP 1.0 - #endif -#endif +#elif ENABLED(REPRAPWORLD_GRAPHICAL_LCD) -// Aliases for LCD features -#if !DGUS_UI_IS(NONE) || ENABLED(ANYCUBIC_LCD_VYPER) - #define HAS_DGUS_LCD 1 - #if DGUS_UI_IS(ORIGIN, FYSETC, HIPRECY, MKS) - #define HAS_DGUS_LCD_CLASSIC 1 - #endif -#endif + #define DOGLCD + #define IS_U8GLIB_ST7920 1 + #define IS_ULTIPANEL 1 + #define ENCODER_PULSES_PER_STEP 2 -// Extensible UI serial touch screens. (See src/lcd/extui) -#if ANY(HAS_DGUS_LCD, MALYAN_LCD, ANYCUBIC_LCD_I3MEGA, ANYCUBIC_LCD_CHIRON, NEXTION_TFT, TOUCH_UI_FTDI_EVE) - #define IS_EXTUI 1 // Just for sanity check. - #define EXTENSIBLE_UI -#endif +#elif ENABLED(MKS_12864OLED) -// Aliases for LCD features -#if ANY(DWIN_CREALITY_LCD, DWIN_LCD_PROUI) - #define HAS_DWIN_E3V2_BASIC 1 -#endif -#if ANY(HAS_DWIN_E3V2_BASIC, DWIN_CREALITY_LCD_JYERSUI) - #define HAS_DWIN_E3V2 1 -#endif + #define IS_RRD_SC 1 + #define U8GLIB_SH1106 -// E3V2 extras -#if HAS_DWIN_E3V2 || IS_DWIN_MARLINUI - #define SERIAL_CATCHALL 0 - #define HAS_LCD_BRIGHTNESS 1 - #define LCD_BRIGHTNESS_MAX 250 -#endif +#elif ENABLED(MKS_12864OLED_SSD1306) -#if ENABLED(DWIN_LCD_PROUI) - #define DO_LIST_BIN_FILES 1 - #define LCD_BRIGHTNESS_DEFAULT 127 -#endif + #define IS_RRD_SC 1 + #define IS_U8GLIB_SSD1306 -// Serial Controllers require LCD_SERIAL_PORT -#if ANY(IS_DWIN_MARLINUI, HAS_DWIN_E3V2, HAS_DGUS_LCD, MALYAN_LCD, ANYCUBIC_LCD_I3MEGA, ANYCUBIC_LCD_CHIRON, NEXTION_TFT) - #define LCD_IS_SERIAL_HOST 1 -#endif +#elif ENABLED(SAV_3DGLCD) -#if HAS_WIRED_LCD - #if ENABLED(DOGLCD) - #define HAS_MARLINUI_U8GLIB 1 - #elif IS_TFTGLCD_PANEL - // Neither DOGM nor HD44780. Fully customized interface. - #elif IS_DWIN_MARLINUI - // Since HAS_MARLINUI_U8GLIB refers to U8G displays - // the DWIN display can define its own flags - #elif !HAS_GRAPHICAL_TFT - #define HAS_MARLINUI_HD44780 1 + #ifdef U8GLIB_SSD1306 + #define IS_U8GLIB_SSD1306 // Allow for U8GLIB_SSD1306 + SAV_3DGLCD #endif -#endif + #define IS_NEWPANEL 1 -#if ANY(HAS_WIRED_LCD, EXTENSIBLE_UI, DWIN_LCD_PROUI, DWIN_CREALITY_LCD_JYERSUI) - /** - * HAS_DISPLAY indicates the display uses these MarlinUI methods... - * - update - * - abort_print - * - pause_print - * - resume_print - * - poweroff (for PSU_CONTROL and HAS_MARLINUI_MENU) - * - * ...and implements these MarlinUI methods: - * - zoffset_overlay (if BABYSTEP_GFX_OVERLAY or MESH_EDIT_GFX_OVERLAY are supported) - * - draw_kill_screen - * - kill_screen - * - draw_status_message - */ - #define HAS_DISPLAY 1 -#endif +#elif ENABLED(FYSETC_242_OLED_12864) -#if HAS_WIRED_LCD && !HAS_GRAPHICAL_TFT && !IS_DWIN_MARLINUI - #define HAS_LCDPRINT 1 -#endif + #define IS_RRD_SC 1 + #define U8GLIB_SH1106 -#if HAS_DISPLAY || HAS_LCDPRINT - #define HAS_UTF8_UTILS 1 -#endif + #ifndef NEOPIXEL_BRIGHTNESS + #define NEOPIXEL_BRIGHTNESS 127 + #endif -#if ANY(HAS_DISPLAY, HAS_DWIN_E3V2) - #define HAS_STATUS_MESSAGE 1 -#endif +#elif ANY(FYSETC_MINI_12864_X_X, FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0, FYSETC_MINI_12864_2_1, FYSETC_GENERIC_12864_1_1) -#if IS_ULTIPANEL && DISABLED(NO_LCD_MENUS) - #define HAS_MARLINUI_MENU 1 -#endif + #define FYSETC_MINI_12864 + #define DOGLCD + #define IS_ULTIPANEL 1 + #define LED_COLORS_REDUCE_GREEN + + // Require LED backlighting enabled + #if ENABLED(FYSETC_MINI_12864_2_1) + #ifndef NEOPIXEL_BRIGHTNESS + #define NEOPIXEL_BRIGHTNESS 127 + #endif + //#define NEOPIXEL_STARTUP_TEST + #endif -#if ANY(HAS_MARLINUI_MENU, EXTENSIBLE_UI, HAS_DWIN_E3V2) - #define HAS_MANUAL_MOVE_MENU 1 -#endif +#elif ENABLED(ULTI_CONTROLLER) -#if HAS_MARLINUI_U8GLIB - #ifndef LCD_PIXEL_WIDTH - #define LCD_PIXEL_WIDTH 128 - #endif - #ifndef LCD_PIXEL_HEIGHT - #define LCD_PIXEL_HEIGHT 64 + #define IS_ULTIPANEL 1 + #define U8GLIB_SSD1309 + #define LCD_RESET_PIN LCD_PINS_D6 // This controller need a reset pin + #define STD_ENCODER_PULSES_PER_STEP 4 + #define STD_ENCODER_STEPS_PER_MENU_ITEM 1 + #ifndef PCA9632 + #define PCA9632 #endif -#endif -/** - * Multi-Material-Unit supported models - */ -#define PRUSA_MMU1 1 -#define PRUSA_MMU2 2 -#define PRUSA_MMU2S 3 -#define EXTENDABLE_EMU_MMU2 12 -#define EXTENDABLE_EMU_MMU2S 13 +#elif ENABLED(MAKEBOARD_MINI_2_LINE_DISPLAY_1602) -#ifdef MMU_MODEL - #define HAS_MMU 1 - #if MMU_MODEL == PRUSA_MMU1 - #define HAS_PRUSA_MMU1 1 - #elif MMU_MODEL % 10 == PRUSA_MMU2 - #define HAS_PRUSA_MMU2 1 - #elif MMU_MODEL % 10 == PRUSA_MMU2S - #define HAS_PRUSA_MMU2 1 - #define HAS_PRUSA_MMU2S 1 - #endif - #if MMU_MODEL >= EXTENDABLE_EMU_MMU2 - #define HAS_EXTENDABLE_MMU 1 - #endif -#endif + #define IS_RRD_SC 1 + #define LCD_WIDTH 16 + #define LCD_HEIGHT 2 -#undef PRUSA_MMU1 -#undef PRUSA_MMU2 -#undef PRUSA_MMU2S -#undef EXTENDABLE_EMU_MMU2 -#undef EXTENDABLE_EMU_MMU2S +#elif ANY(TFTGLCD_PANEL_SPI, TFTGLCD_PANEL_I2C) -/** - * Extruders have some combination of stepper motors and hotends - * so we separate these concepts into the defines: - * - * EXTRUDERS - Number of Selectable Tools - * HOTENDS - Number of hotends, whether connected or separate - * E_STEPPERS - Number of actual E stepper motors - * E_MANUAL - Number of E steppers for LCD move options - * - * These defines must be simple constants for use in REPEAT, etc. - */ -#if EXTRUDERS - #define HAS_EXTRUDERS 1 - #if EXTRUDERS > 1 - #define HAS_MULTI_EXTRUDER 1 + #define IS_TFTGLCD_PANEL 1 + #define IS_ULTIPANEL 1 // Note that IS_ULTIPANEL leads to HAS_WIRED_LCD + + #if HAS_MEDIA && DISABLED(LCD_PROGRESS_BAR) + #define LCD_PROGRESS_BAR #endif - #define E_AXIS_N(E) AxisEnum(E_AXIS + E_INDEX_N(E)) -#else - #undef EXTRUDERS - #define EXTRUDERS 0 - #undef TEMP_SENSOR_0 - #undef TEMP_SENSOR_1 - #undef TEMP_SENSOR_2 - #undef TEMP_SENSOR_3 - #undef TEMP_SENSOR_4 - #undef TEMP_SENSOR_5 - #undef TEMP_SENSOR_6 - #undef TEMP_SENSOR_7 - #undef SINGLENOZZLE - #undef SWITCHING_EXTRUDER - #undef MECHANICAL_SWITCHING_EXTRUDER - #undef SWITCHING_NOZZLE - #undef MECHANICAL_SWITCHING_NOZZLE - #undef MIXING_EXTRUDER - #undef HOTEND_IDLE_TIMEOUT - #undef DISABLE_E - #undef PREVENT_LENGTHY_EXTRUDE - #undef FILAMENT_RUNOUT_SENSOR - #undef FILAMENT_RUNOUT_DISTANCE_MM - #undef DISABLE_OTHER_EXTRUDERS -#endif + #if ENABLED(TFTGLCD_PANEL_I2C) + #define LCD_I2C_ADDRESS 0x33 // Must be 0x33 for STM32 main boards and equal to panel's I2C slave address + #endif + #define LCD_USE_I2C_BUZZER // Enable buzzer on LCD, used for both I2C and SPI buses (LiquidTWI2 not required) + #define STD_ENCODER_PULSES_PER_STEP 2 + #define STD_ENCODER_STEPS_PER_MENU_ITEM 1 + #define LCD_WIDTH 20 // 20 or 24 chars in line + #define LCD_HEIGHT 10 // Character lines + #define LCD_CONTRAST_MIN 127 + #define LCD_CONTRAST_MAX 255 + #define LCD_CONTRAST_DEFAULT 250 + #define CONVERT_TO_EXT_ASCII // Use extended 128-255 symbols from ASCII table. + // At this time present conversion only for cyrillic - bg, ru and uk languages. + // First 7 ASCII symbols in panel font must be replaced with Marlin's special symbols. -#define E_OPTARG(N) OPTARG(HAS_MULTI_EXTRUDER, N) -#define E_TERN_(N) TERN_(HAS_MULTI_EXTRUDER, N) -#define E_TERN0(N) TERN0(HAS_MULTI_EXTRUDER, N) +#elif ENABLED(CR10_STOCKDISPLAY) -#if ANY(SWITCHING_EXTRUDER, MECHANICAL_SWITCHING_EXTRUDER) - #define HAS_SWITCHING_EXTRUDER 1 -#endif -#if ANY(SWITCHING_NOZZLE, MECHANICAL_SWITCHING_NOZZLE) - #define HAS_SWITCHING_NOZZLE 1 -#endif + #define IS_RRD_FG_SC 1 + #define LCD_ST7920_DELAY_1 125 + #define LCD_ST7920_DELAY_2 125 + #define LCD_ST7920_DELAY_3 125 -#if ENABLED(E_DUAL_STEPPER_DRIVERS) // E0/E1 steppers act in tandem as E0 +#elif ANY(ANET_FULL_GRAPHICS_LCD, ANET_FULL_GRAPHICS_LCD_ALT_WIRING) - #define E_STEPPERS 2 - #define E_MANUAL 1 + #define IS_RRD_FG_SC 1 + #define LCD_ST7920_DELAY_1 150 + #define LCD_ST7920_DELAY_2 150 + #define LCD_ST7920_DELAY_3 150 -#elif HAS_SWITCHING_EXTRUDER // One stepper for every two EXTRUDERS +#elif ANY(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER, BQ_LCD_SMART_CONTROLLER, K3D_FULL_GRAPHIC_SMART_CONTROLLER) - #if EXTRUDERS > 4 - #define E_STEPPERS 3 - #elif EXTRUDERS > 2 - #define E_STEPPERS 2 - #else - #define E_STEPPERS 1 - #endif + #define IS_RRD_FG_SC 1 -#elif ENABLED(MIXING_EXTRUDER) // Multiple feeds are mixed proportionally +#elif ENABLED(REPRAP_DISCOUNT_SMART_CONTROLLER) - #define E_STEPPERS MIXING_STEPPERS - #define E_MANUAL 1 - #if MIXING_STEPPERS == 2 - #define HAS_DUAL_MIXING 1 - #endif + #define IS_RRD_SC 1 // RepRapDiscount LCD or Graphical LCD with rotary click encoder -#elif ENABLED(SWITCHING_TOOLHEAD) // Toolchanger +#elif ENABLED(K3D_242_OLED_CONTROLLER) - #define E_STEPPERS EXTRUDERS - #define E_MANUAL EXTRUDERS + #define IS_RRD_SC 1 + #define U8GLIB_SSD1309 -#elif HAS_PRUSA_MMU2 // Průša Multi-Material Unit v2 +#endif - #define E_STEPPERS 1 - #define E_MANUAL 1 +// ST7920-based graphical displays +#if ANY(IS_RRD_FG_SC, LCD_FOR_MELZI, SILVER_GATE_GLCD_CONTROLLER) + #define DOGLCD + #define IS_U8GLIB_ST7920 1 + #define IS_RRD_SC 1 +#endif +// ST7565 / 64128N graphical displays +#if ANY(MAKRPANEL, MINIPANEL) + #define IS_ULTIPANEL 1 + #define DOGLCD + #if ENABLED(MAKRPANEL) + #define IS_U8GLIB_ST7565_64128N 1 + #endif #endif -// No inactive extruders with SWITCHING_NOZZLE or Průša MMU1 or just 1 E stepper exists -#if HAS_SWITCHING_NOZZLE || HAS_PRUSA_MMU1 || E_STEPPERS < 2 - #undef DISABLE_OTHER_EXTRUDERS +#if ENABLED(IS_U8GLIB_SSD1306) + #define U8GLIB_SSD1306 #endif -// Průša MMU1, MMU(S) 2.0 and EXTENDABLE_EMU_MMU2(S) force SINGLENOZZLE -#if HAS_MMU - #define SINGLENOZZLE +#if ENABLED(OVERLORD_OLED) + #define IS_ULTIPANEL 1 + #define U8GLIB_SH1106 + /** + * PCA9632 for buzzer and LEDs via i2c + * No auto-inc, red and green leds switched, buzzer + */ + #define PCA9632 + #define PCA9632_NO_AUTO_INC + #define PCA9632_GRN 0x00 + #define PCA9632_RED 0x02 + #define PCA9632_BUZZER + #define PCA9632_BUZZER_DATA { 0x09, 0x02 } + + #define STD_ENCODER_PULSES_PER_STEP 1 // Overlord uses buttons + #define STD_ENCODER_STEPS_PER_MENU_ITEM 1 #endif -// Default E steppers / manual motion is one per extruder -#ifndef E_STEPPERS - #define E_STEPPERS EXTRUDERS +// 128x64 I2C OLED LCDs - SSD1306/SSD1309/SH1106 +#if ANY(U8GLIB_SSD1306, U8GLIB_SSD1309, U8GLIB_SH1106) + #define HAS_U8GLIB_I2C_OLED 1 + #define HAS_WIRED_LCD 1 + #define DOGLCD #endif -#ifndef E_MANUAL - #define E_MANUAL EXTRUDERS + +/** + * SPI Ultipanels + */ + +// Basic Ultipanel-like displays +#if ANY(ULTIMAKERCONTROLLER, IS_RRD_SC, G3D_PANEL, RIGIDBOT_PANEL, PANEL_ONE, U8GLIB_SH1106) + #define IS_ULTIPANEL 1 #endif -// Number of hotends... -#if ANY(SINGLENOZZLE, MIXING_EXTRUDER) // Only one for singlenozzle or mixing extruder - #define HOTENDS 1 -#elif HAS_SWITCHING_EXTRUDER && !HAS_SWITCHING_NOZZLE // One for each pair of abstract "extruders" - #define HOTENDS E_STEPPERS -#elif TEMP_SENSOR_0 - #define HOTENDS EXTRUDERS // One per extruder if at least one heater exists -#else - #define HOTENDS 0 // A machine with no hotends at all can still extrude +// Einstart OLED has Cardinal nav via pins defined in pins_EINSTART-S.h +#if ENABLED(U8GLIB_SH1106_EINSTART) + #define DOGLCD + #define IS_ULTIPANEL 1 #endif -// More than one hotend... -#if HOTENDS > 1 - #define HAS_MULTI_HOTEND 1 - #define HAS_HOTEND_OFFSET 1 - #ifndef HOTEND_OFFSET_X - #define HOTEND_OFFSET_X { 0 } // X offsets for each extruder - #endif - #ifndef HOTEND_OFFSET_Y - #define HOTEND_OFFSET_Y { 0 } // Y offsets for each extruder +// TFT Legacy options masquerade as TFT_GENERIC +#if ANY(FSMC_GRAPHICAL_TFT, SPI_GRAPHICAL_TFT, TFT_320x240, TFT_480x320, TFT_320x240_SPI, TFT_480x320_SPI, TFT_LVGL_UI_FSMC, TFT_LVGL_UI_SPI) + #define IS_LEGACY_TFT 1 + #define TFT_GENERIC + #if ANY(FSMC_GRAPHICAL_TFT, TFT_320x240, TFT_480x320, TFT_LVGL_UI_FSMC) + #define TFT_INTERFACE_FSMC + #elif ANY(SPI_GRAPHICAL_TFT, TFT_320x240_SPI, TFT_480x320_SPI, TFT_LVGL_UI_SPI) + #define TFT_INTERFACE_SPI #endif - #ifndef HOTEND_OFFSET_Z - #define HOTEND_OFFSET_Z { 0 } // Z offsets for each extruder + #if ANY(FSMC_GRAPHICAL_TFT, SPI_GRAPHICAL_TFT) + #define TFT_CLASSIC_UI + #elif ANY(TFT_320x240, TFT_480x320, TFT_320x240_SPI, TFT_480x320_SPI) + #define TFT_COLOR_UI + #elif ANY(TFT_LVGL_UI_FSMC, TFT_LVGL_UI_SPI) + #define TFT_LVGL_UI #endif -#else - #undef HOTEND_OFFSET_X - #undef HOTEND_OFFSET_Y - #undef HOTEND_OFFSET_Z #endif -// At least one hotend... -#if HOTENDS - #define HAS_HOTEND 1 - #ifndef HOTEND_OVERSHOOT - #define HOTEND_OVERSHOOT 15 - #endif +// FSMC/SPI TFT Panels (LVGL) +#if ENABLED(TFT_LVGL_UI) + #define HAS_TFT_LVGL_UI 1 + #define SERIAL_RUNTIME_HOOK 1 +#endif + +// FSMC/SPI TFT Panels +#if ENABLED(TFT_CLASSIC_UI) + #define TFT_SCALED_DOGLCD 1 #endif -// Clean up E-stepper-based settings... -#if E_STEPPERS <= 7 - #undef INVERT_E7_DIR - #undef E7_DRIVER_TYPE - #if E_STEPPERS <= 6 - #undef INVERT_E6_DIR - #undef E6_DRIVER_TYPE - #if E_STEPPERS <= 5 - #undef INVERT_E5_DIR - #undef E5_DRIVER_TYPE - #if E_STEPPERS <= 4 - #undef INVERT_E4_DIR - #undef E4_DRIVER_TYPE - #if E_STEPPERS <= 3 - #undef INVERT_E3_DIR - #undef E3_DRIVER_TYPE - #if E_STEPPERS <= 2 - #undef INVERT_E2_DIR - #undef E2_DRIVER_TYPE - #if E_STEPPERS <= 1 - #undef INVERT_E1_DIR - #undef E1_DRIVER_TYPE - #if E_STEPPERS == 0 - #undef INVERT_E0_DIR - #undef E0_DRIVER_TYPE - #endif - #endif - #endif - #endif - #endif - #endif - #endif +#if TFT_SCALED_DOGLCD + #define DOGLCD + #define IS_ULTIPANEL 1 + #define DELAYED_BACKLIGHT_INIT +#elif HAS_TFT_LVGL_UI + #define DELAYED_BACKLIGHT_INIT +#endif + +// Color UI +#if ENABLED(TFT_COLOR_UI) + #define HAS_GRAPHICAL_TFT 1 + #define IS_ULTIPANEL 1 #endif /** - * Number of Linear Axes (e.g., XYZIJKUVW) - * All the logical axes except for the tool (E) axis + * I2C Panels */ -#ifdef NUM_AXES - #undef NUM_AXES - #define NUM_AXES_WARNING 1 -#endif -#ifdef W_DRIVER_TYPE - #define NUM_AXES 9 -#elif defined(V_DRIVER_TYPE) - #define NUM_AXES 8 -#elif defined(U_DRIVER_TYPE) - #define NUM_AXES 7 -#elif defined(K_DRIVER_TYPE) - #define NUM_AXES 6 -#elif defined(J_DRIVER_TYPE) - #define NUM_AXES 5 -#elif defined(I_DRIVER_TYPE) - #define NUM_AXES 4 -#elif defined(Z_DRIVER_TYPE) - #define NUM_AXES 3 -#elif defined(Y_DRIVER_TYPE) - #define NUM_AXES 2 -#elif defined(X_DRIVER_TYPE) - #define NUM_AXES 1 -#else - #define NUM_AXES 0 -#endif -#if NUM_AXES >= 1 - #define HAS_X_AXIS 1 - #if NUM_AXES >= XY - #define HAS_Y_AXIS 1 - #if NUM_AXES >= XYZ - #define HAS_Z_AXIS 1 - #if NUM_AXES >= 4 - #define HAS_I_AXIS 1 - #if NUM_AXES >= 5 - #define HAS_J_AXIS 1 - #if NUM_AXES >= 6 - #define HAS_K_AXIS 1 - #if NUM_AXES >= 7 - #define HAS_U_AXIS 1 - #if NUM_AXES >= 8 - #define HAS_V_AXIS 1 - #if NUM_AXES >= 9 - #define HAS_W_AXIS 1 - #endif - #endif - #endif - #endif - #endif - #endif - #endif +#if ANY(IS_RRD_SC, IS_DOGM_12864, OLED_PANEL_TINYBOY2, LCD_I2C_PANELOLU2) + + #define STD_ENCODER_PULSES_PER_STEP 4 + #define STD_ENCODER_STEPS_PER_MENU_ITEM 1 + + #if ENABLED(LCD_I2C_PANELOLU2) // PANELOLU2 LCD with status LEDs, separate encoder and click inputs + #define LCD_I2C_TYPE_MCP23017 // I2C Character-based 12864 display + #define LCD_I2C_ADDRESS 0x20 // I2C Address of the port expander + #define LCD_USE_I2C_BUZZER // Enable buzzer on LCD (optional) + #define IS_ULTIPANEL 1 #endif -#endif -#if !HAS_X_AXIS - #undef AVOID_OBSTACLES - #undef ENDSTOPPULLUP_XMIN - #undef ENDSTOPPULLUP_XMAX - #undef X_MIN_ENDSTOP_HIT_STATE - #undef X_MAX_ENDSTOP_HIT_STATE - #undef X2_DRIVER_TYPE - #undef X_ENABLE_ON - #undef DISABLE_X - #undef INVERT_X_DIR - #undef X_HOME_DIR - #undef X_MIN_POS - #undef X_MAX_POS - #undef MANUAL_X_HOME_POS - #undef MIN_SOFTWARE_ENDSTOPS - #undef MAX_SOFTWARE_ENDSTOPS +#elif ANY(LCD_SAINSMART_I2C_1602, LCD_SAINSMART_I2C_2004) + + #define LCD_I2C_TYPE_PCF8575 // I2C Character-based 12864 display + #define LCD_I2C_ADDRESS 0x27 // I2C Address of the port expander + #define IS_ULTIPANEL 1 + + #if ENABLED(LCD_SAINSMART_I2C_2004) + #define LCD_WIDTH 20 + #define LCD_HEIGHT 4 + #endif + +#elif ENABLED(LCD_I2C_VIKI) + + /** + * Panucatt VIKI LCD with status LEDs, integrated click & L/R/U/P buttons, separate encoder inputs + * + * This uses the LiquidTWI2 library v1.2.3 or later ( https://github.com/lincomatic/LiquidTWI2 ) + * Make sure the LiquidTWI2 directory is placed in the Arduino or Sketchbook libraries subdirectory. + * Note: The pause/stop/resume LCD button pin should be connected to the Arduino + * BTN_ENC pin (or set BTN_ENC to -1 if not used) + */ + #define LCD_I2C_TYPE_MCP23017 + #define LCD_I2C_ADDRESS 0x20 // I2C Address of the port expander + #define LCD_USE_I2C_BUZZER // Enable buzzer on LCD (requires LiquidTWI2 v1.2.3 or later) + #define IS_ULTIPANEL 1 + + #define ENCODER_FEEDRATE_DEADZONE 4 + + #define STD_ENCODER_PULSES_PER_STEP 1 + #define STD_ENCODER_STEPS_PER_MENU_ITEM 2 + +#elif ENABLED(G3D_PANEL) + + #define STD_ENCODER_PULSES_PER_STEP 2 + #define STD_ENCODER_STEPS_PER_MENU_ITEM 1 + #endif -#if !HAS_Y_AXIS - #undef AVOID_OBSTACLES - #undef ENDSTOPPULLUP_YMIN - #undef ENDSTOPPULLUP_YMAX - #undef Y_MIN_ENDSTOP_HIT_STATE - #undef Y_MAX_ENDSTOP_HIT_STATE - #undef Y2_DRIVER_TYPE - #undef Y_ENABLE_ON - #undef DISABLE_Y - #undef INVERT_Y_DIR - #undef Y_HOME_DIR - #undef Y_MIN_POS - #undef Y_MAX_POS - #undef MANUAL_Y_HOME_POS - #undef MIN_SOFTWARE_ENDSTOP_Y - #undef MAX_SOFTWARE_ENDSTOP_Y +#if ANY(LCD_I2C_TYPE_MCP23017, LCD_I2C_TYPE_MCP23008) && DISABLED(NO_LCD_DETECT) + #define DETECT_I2C_LCD_DEVICE 1 #endif -#if HAS_Z_AXIS - #ifdef Z4_DRIVER_TYPE - #define NUM_Z_STEPPERS 4 - #elif defined(Z3_DRIVER_TYPE) - #define NUM_Z_STEPPERS 3 - #elif defined(Z2_DRIVER_TYPE) - #define NUM_Z_STEPPERS 2 +#ifndef STD_ENCODER_PULSES_PER_STEP + #if ENABLED(TOUCH_SCREEN) + #define STD_ENCODER_PULSES_PER_STEP 2 #else - #define NUM_Z_STEPPERS 1 + #define STD_ENCODER_PULSES_PER_STEP 5 #endif -#else - #undef ENDSTOPPULLUP_ZMIN - #undef ENDSTOPPULLUP_ZMAX - #undef Z_MIN_ENDSTOP_HIT_STATE - #undef Z_MAX_ENDSTOP_HIT_STATE - #undef Z2_DRIVER_TYPE - #undef Z3_DRIVER_TYPE - #undef Z4_DRIVER_TYPE - #undef Z_ENABLE_ON - #undef DISABLE_Z - #undef INVERT_Z_DIR - #undef Z_HOME_DIR - #undef Z_MIN_POS - #undef Z_MAX_POS - #undef MANUAL_Z_HOME_POS - #undef Z_SAFE_HOMING - #undef MIN_SOFTWARE_ENDSTOP_Z - #undef MAX_SOFTWARE_ENDSTOP_Z +#endif +#ifndef STD_ENCODER_STEPS_PER_MENU_ITEM + #define STD_ENCODER_STEPS_PER_MENU_ITEM 1 +#endif +#ifndef ENCODER_PULSES_PER_STEP + #define ENCODER_PULSES_PER_STEP STD_ENCODER_PULSES_PER_STEP +#endif +#ifndef ENCODER_STEPS_PER_MENU_ITEM + #define ENCODER_STEPS_PER_MENU_ITEM STD_ENCODER_STEPS_PER_MENU_ITEM +#endif +#ifndef ENCODER_FEEDRATE_DEADZONE + #define ENCODER_FEEDRATE_DEADZONE 6 #endif -#if !HAS_I_AXIS - #undef ENDSTOPPULLUP_IMIN - #undef ENDSTOPPULLUP_IMAX - #undef I_MIN_ENDSTOP_HIT_STATE - #undef I_MAX_ENDSTOP_HIT_STATE - #undef I_ENABLE_ON - #undef DISABLE_I - #undef INVERT_I_DIR - #undef I_HOME_DIR - #undef I_MIN_POS - #undef I_MAX_POS - #undef MANUAL_I_HOME_POS - #undef MIN_SOFTWARE_ENDSTOP_I - #undef MAX_SOFTWARE_ENDSTOP_I +// Shift register panels +// --------------------- +// 2 wire Non-latching LCD SR from: +// https://github.com/fmalpartida/New-LiquidCrystal/wiki/schematics#user-content-ShiftRegister_connection +#if ENABLED(FF_INTERFACEBOARD) + #define SR_LCD_3W_NL // Non latching 3 wire shift register + #define IS_ULTIPANEL 1 +#elif ENABLED(SAV_3DLCD) + #define SR_LCD_2W_NL // Non latching 2 wire shift register + #define IS_ULTIPANEL 1 +#elif ENABLED(ULTIPANEL) + #define IS_ULTIPANEL 1 #endif -#if !HAS_J_AXIS - #undef ENDSTOPPULLUP_JMIN - #undef ENDSTOPPULLUP_JMAX - #undef J_MIN_ENDSTOP_HIT_STATE - #undef J_MAX_ENDSTOP_HIT_STATE - #undef J_ENABLE_ON - #undef DISABLE_J - #undef INVERT_J_DIR - #undef J_HOME_DIR - #undef J_MIN_POS - #undef J_MAX_POS - #undef MANUAL_J_HOME_POS - #undef MIN_SOFTWARE_ENDSTOP_J - #undef MAX_SOFTWARE_ENDSTOP_J +#if ANY(IS_ULTIPANEL, ULTRA_LCD) + #define HAS_WIRED_LCD 1 #endif -#if !HAS_K_AXIS - #undef ENDSTOPPULLUP_KMIN - #undef ENDSTOPPULLUP_KMAX - #undef K_MIN_ENDSTOP_HIT_STATE - #undef K_MAX_ENDSTOP_HIT_STATE - #undef K_ENABLE_ON - #undef DISABLE_K - #undef INVERT_K_DIR - #undef K_HOME_DIR - #undef K_MIN_POS - #undef K_MAX_POS - #undef MANUAL_K_HOME_POS - #undef MIN_SOFTWARE_ENDSTOP_K - #undef MAX_SOFTWARE_ENDSTOP_K +#if ANY(IS_ULTIPANEL, REPRAPWORLD_KEYPAD) + #define IS_NEWPANEL 1 #endif -#if !HAS_U_AXIS - #undef ENDSTOPPULLUP_UMIN - #undef ENDSTOPPULLUP_UMAX - #undef U_MIN_ENDSTOP_HIT_STATE - #undef U_MAX_ENDSTOP_HIT_STATE - #undef U_ENABLE_ON - #undef DISABLE_U - #undef INVERT_U_DIR - #undef U_HOME_DIR - #undef U_MIN_POS - #undef U_MAX_POS - #undef MANUAL_U_HOME_POS - #undef MIN_SOFTWARE_ENDSTOP_U - #undef MAX_SOFTWARE_ENDSTOP_U +#if ANY(ZONESTAR_LCD, REPRAPWORLD_KEYPAD) + #define IS_RRW_KEYPAD 1 + #ifndef REPRAPWORLD_KEYPAD_MOVE_STEP + #define REPRAPWORLD_KEYPAD_MOVE_STEP 1.0 + #endif #endif -#if !HAS_V_AXIS - #undef ENDSTOPPULLUP_VMIN - #undef ENDSTOPPULLUP_VMAX - #undef V_MIN_ENDSTOP_HIT_STATE - #undef V_MAX_ENDSTOP_HIT_STATE - #undef V_ENABLE_ON - #undef DISABLE_V - #undef INVERT_V_DIR - #undef V_HOME_DIR - #undef V_MIN_POS - #undef V_MAX_POS - #undef MANUAL_V_HOME_POS - #undef MIN_SOFTWARE_ENDSTOP_V - #undef MAX_SOFTWARE_ENDSTOP_V +// Aliases for LCD features +#if !DGUS_UI_IS(NONE) || ENABLED(ANYCUBIC_LCD_VYPER) + #define HAS_DGUS_LCD 1 + #if DGUS_UI_IS(ORIGIN, FYSETC, HIPRECY, MKS) + #define HAS_DGUS_LCD_CLASSIC 1 + #endif #endif -#if !HAS_W_AXIS - #undef ENDSTOPPULLUP_WMIN - #undef ENDSTOPPULLUP_WMAX - #undef W_MIN_ENDSTOP_HIT_STATE - #undef W_MAX_ENDSTOP_HIT_STATE - #undef W_ENABLE_ON - #undef DISABLE_W - #undef INVERT_W_DIR - #undef W_HOME_DIR - #undef W_MIN_POS - #undef W_MAX_POS - #undef MANUAL_W_HOME_POS - #undef MIN_SOFTWARE_ENDSTOP_W - #undef MAX_SOFTWARE_ENDSTOP_W +// Extensible UI serial touch screens. (See src/lcd/extui) +#if ANY(HAS_DGUS_LCD, MALYAN_LCD, ANYCUBIC_LCD_I3MEGA, ANYCUBIC_LCD_CHIRON, NEXTION_TFT, TOUCH_UI_FTDI_EVE) + #define IS_EXTUI 1 // Just for sanity check. + #define EXTENSIBLE_UI #endif -#define _OR_HAS_DA(A) ENABLED(DISABLE_##A) || -#if MAP(_OR_HAS_DA, X, Y, Z, I, J, K, U, V, W) 0 - #define HAS_DISABLE_MAIN_AXES 1 +// Aliases for LCD features +#if ANY(DWIN_CREALITY_LCD, DWIN_LCD_PROUI) + #define HAS_DWIN_E3V2_BASIC 1 #endif -#if HAS_DISABLE_MAIN_AXES || ENABLED(DISABLE_E) - #define HAS_DISABLE_AXES 1 +#if ANY(HAS_DWIN_E3V2_BASIC, DWIN_CREALITY_LCD_JYERSUI) + #define HAS_DWIN_E3V2 1 #endif -#undef _OR_HAS_DA -#ifdef X2_DRIVER_TYPE - #define HAS_X2_STEPPER 1 +// E3V2 extras +#if HAS_DWIN_E3V2 || IS_DWIN_MARLINUI + #define SERIAL_CATCHALL 0 + #define HAS_LCD_BRIGHTNESS 1 + #define LCD_BRIGHTNESS_MAX 250 #endif -#ifdef Y2_DRIVER_TYPE - #define HAS_Y2_STEPPER 1 + +#if ENABLED(DWIN_LCD_PROUI) + #define DO_LIST_BIN_FILES 1 + #define LCD_BRIGHTNESS_DEFAULT 127 #endif -/** - * Number of Primary Linear Axes (e.g., XYZ) - * X, XY, or XYZ axes. Excluding duplicate axes (X2, Y2, Z2, Z3, Z4) - */ -#if NUM_AXES >= 3 - #define PRIMARY_LINEAR_AXES 3 -#else - #define PRIMARY_LINEAR_AXES NUM_AXES +// Serial Controllers require LCD_SERIAL_PORT +#if ANY(IS_DWIN_MARLINUI, HAS_DWIN_E3V2, HAS_DGUS_LCD, MALYAN_LCD, ANYCUBIC_LCD_I3MEGA, ANYCUBIC_LCD_CHIRON, NEXTION_TFT) + #define LCD_IS_SERIAL_HOST 1 #endif -/** - * Number of Secondary Axes (e.g., IJKUVW) - * All linear/rotational axes between XYZ and E. - */ -#define SECONDARY_AXES SUB3(NUM_AXES) +#if HAS_WIRED_LCD + #if ENABLED(DOGLCD) + #define HAS_MARLINUI_U8GLIB 1 + #elif IS_TFTGLCD_PANEL + // Neither DOGM nor HD44780. Fully customized interface. + #elif IS_DWIN_MARLINUI + // Since HAS_MARLINUI_U8GLIB refers to U8G displays + // the DWIN display can define its own flags + #elif !HAS_GRAPHICAL_TFT + #define HAS_MARLINUI_HD44780 1 + #endif +#endif -/** - * Number of Rotational Axes (e.g., IJK) - * All axes for which AXIS*_ROTATES is defined. - * For these axes, positions are specified in angular degrees. - */ -#if ENABLED(AXIS9_ROTATES) - #define ROTATIONAL_AXES 6 -#elif ENABLED(AXIS8_ROTATES) - #define ROTATIONAL_AXES 5 -#elif ENABLED(AXIS7_ROTATES) - #define ROTATIONAL_AXES 4 -#elif ENABLED(AXIS6_ROTATES) - #define ROTATIONAL_AXES 3 -#elif ENABLED(AXIS5_ROTATES) - #define ROTATIONAL_AXES 2 -#elif ENABLED(AXIS4_ROTATES) - #define ROTATIONAL_AXES 1 -#else - #define ROTATIONAL_AXES 0 +#if ANY(HAS_WIRED_LCD, EXTENSIBLE_UI, DWIN_LCD_PROUI, DWIN_CREALITY_LCD_JYERSUI) + /** + * HAS_DISPLAY indicates the display uses these MarlinUI methods... + * - update + * - abort_print + * - pause_print + * - resume_print + * - poweroff (for PSU_CONTROL and HAS_MARLINUI_MENU) + * + * ...and implements these MarlinUI methods: + * - zoffset_overlay (if BABYSTEP_GFX_OVERLAY or MESH_EDIT_GFX_OVERLAY are supported) + * - draw_kill_screen + * - kill_screen + * - draw_status_message + */ + #define HAS_DISPLAY 1 #endif -/** - * Number of Secondary Linear Axes (e.g., UVW) - * All secondary axes for which AXIS*_ROTATES is not defined. - * Excluding primary axes and excluding duplicate axes (X2, Y2, Z2, Z3, Z4) - */ -#define SECONDARY_LINEAR_AXES (NUM_AXES - PRIMARY_LINEAR_AXES - ROTATIONAL_AXES) +#if HAS_WIRED_LCD && !HAS_GRAPHICAL_TFT && !IS_DWIN_MARLINUI + #define HAS_LCDPRINT 1 +#endif -/** - * Number of Logical Axes (e.g., XYZIJKUVWE) - * All logical axes that can be commanded directly by G-code. - * Delta maps stepper-specific values to ABC steppers. - */ -#if HAS_EXTRUDERS - #define LOGICAL_AXES INCREMENT(NUM_AXES) -#else - #define LOGICAL_AXES NUM_AXES +#if HAS_DISPLAY || HAS_LCDPRINT + #define HAS_UTF8_UTILS 1 #endif -/** - * DISTINCT_E_FACTORS is set to give extruders (some) individual settings. - * - * DISTINCT_AXES is the number of distinct addressable axes (not steppers). - * Includes all linear axes plus all distinguished extruders. - * The default behavior is to treat all extruders as a single E axis - * with shared motion and temperature settings. - * - * DISTINCT_E is the number of distinguished extruders. By default this - * will be 1 which indicates all extruders share the same settings. - * - * E_INDEX_N(E) should be used to get the E index of any item that might be - * distinguished. - */ -#if ENABLED(DISTINCT_E_FACTORS) && E_STEPPERS > 1 - #define DISTINCT_AXES (NUM_AXES + E_STEPPERS) - #define DISTINCT_E E_STEPPERS - #define E_INDEX_N(E) (E) -#else - #undef DISTINCT_E_FACTORS - #define DISTINCT_AXES LOGICAL_AXES - #define DISTINCT_E 1 - #define E_INDEX_N(E) 0 +#if ANY(HAS_DISPLAY, HAS_DWIN_E3V2) + #define HAS_STATUS_MESSAGE 1 #endif -// Helper macros for extruder and hotend arrays -#define _EXTRUDER_LOOP(E) for (int8_t E = 0; E < EXTRUDERS; E++) -#define EXTRUDER_LOOP() _EXTRUDER_LOOP(e) -#define _HOTEND_LOOP(H) for (int8_t H = 0; H < HOTENDS; H++) -#define HOTEND_LOOP() _HOTEND_LOOP(e) +#if IS_ULTIPANEL && DISABLED(NO_LCD_MENUS) + #define HAS_MARLINUI_MENU 1 +#endif -#define ARRAY_BY_EXTRUDERS(V...) ARRAY_N(EXTRUDERS, V) -#define ARRAY_BY_EXTRUDERS1(v1) ARRAY_N_1(EXTRUDERS, v1) -#define ARRAY_BY_HOTENDS(V...) ARRAY_N(HOTENDS, V) -#define ARRAY_BY_HOTENDS1(v1) ARRAY_N_1(HOTENDS, v1) +#if ANY(HAS_MARLINUI_MENU, EXTENSIBLE_UI, HAS_DWIN_E3V2) + #define HAS_MANUAL_MOVE_MENU 1 +#endif + +#if HAS_MARLINUI_U8GLIB + #ifndef LCD_PIXEL_WIDTH + #define LCD_PIXEL_WIDTH 128 + #endif + #ifndef LCD_PIXEL_HEIGHT + #define LCD_PIXEL_HEIGHT 64 + #endif +#endif /** * Disable unused SINGLENOZZLE sub-options @@ -1124,6 +1120,11 @@ #undef SINGLENOZZLE_STANDBY_FAN #endif +// No inactive extruders with SWITCHING_NOZZLE or Průša MMU1 or just 1 E stepper exists +#if HAS_SWITCHING_NOZZLE || HAS_PRUSA_MMU1 || E_STEPPERS < 2 + #undef DISABLE_OTHER_EXTRUDERS +#endif + // Switching extruder has its own servo? #if ENABLED(SWITCHING_EXTRUDER) && (!HAS_SWITCHING_NOZZLE || SWITCHING_EXTRUDER_SERVO_NR != SWITCHING_NOZZLE_SERVO_NR) #define DO_SWITCH_EXTRUDER 1 @@ -1553,6 +1554,14 @@ #define BOOT_MARLIN_LOGO_SMALL #endif +// Flow and feedrate editing +#if HAS_EXTRUDERS && ANY(HAS_MARLINUI_MENU, DWIN_CREALITY_LCD, DWIN_LCD_PROUI, MALYAN_LCD, TOUCH_SCREEN) + #define HAS_FLOW_EDIT 1 +#endif +#if ANY(HAS_MARLINUI_MENU, ULTIPANEL_FEEDMULTIPLY, DWIN_CREALITY_LCD, DWIN_LCD_PROUI, MALYAN_LCD, TOUCH_SCREEN) + #define HAS_FEEDRATE_EDIT 1 +#endif + /** * CoreXY, CoreXZ, and CoreYZ - and their reverse */ diff --git a/Marlin/src/lcd/e3v2/creality/dwin.cpp b/Marlin/src/lcd/e3v2/creality/dwin.cpp index c71ab8cff280..f3935f39dd5e 100644 --- a/Marlin/src/lcd/e3v2/creality/dwin.cpp +++ b/Marlin/src/lcd/e3v2/creality/dwin.cpp @@ -97,10 +97,6 @@ #define MENU_CHAR_LIMIT 24 #define STATUS_Y 354 -// Print speed limit -#define MIN_PRINT_SPEED 10 -#define MAX_PRINT_SPEED 999 - #define FEEDRATE_E (60) // Minimum unit (0.1) : multiple (10) @@ -1559,7 +1555,7 @@ void hmiPrintSpeed() { return; } // printSpeed limit - LIMIT(hmiValues.printSpeed, MIN_PRINT_SPEED, MAX_PRINT_SPEED); + LIMIT(hmiValues.printSpeed, SPEED_EDIT_MIN, SPEED_EDIT_MAX); // printSpeed value drawEditInteger3(select_tune.now + MROWS - index_tune, hmiValues.printSpeed, true); } diff --git a/Marlin/src/lcd/e3v2/proui/dwin.cpp b/Marlin/src/lcd/e3v2/proui/dwin.cpp index 341521ee84f2..366ecffbd9b2 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin.cpp @@ -135,16 +135,14 @@ #define PAUSE_HEAT -// Print speed limit -#define MIN_PRINT_SPEED 10 -#define MAX_PRINT_SPEED 999 - -// Print flow limit -#define MIN_PRINT_FLOW 10 -#define MAX_PRINT_FLOW 299 - // Load and Unload limits -#define MAX_LOAD_UNLOAD 500 +#ifndef EXTRUDE_MAXLENGTH + #ifdef FILAMENT_CHANGE_UNLOAD_LENGTH + #define EXTRUDE_MAXLENGTH (FILAMENT_CHANGE_UNLOAD_LENGTH + 10) + #else + #define EXTRUDE_MAXLENGTH 500 + #endif +#endif // Juntion deviation limits #define MIN_JD_MM 0.001 @@ -2254,8 +2252,8 @@ void setMoveZ() { hmiValue.axis = Z_AXIS; setPFloatOnClick(Z_MIN_POS, Z_MAX_POS, #endif #if ENABLED(ADVANCED_PAUSE_FEATURE) - void setFilLoad() { setPFloatOnClick(0, MAX_LOAD_UNLOAD, UNITFDIGITS); } - void setFilUnload() { setPFloatOnClick(0, MAX_LOAD_UNLOAD, UNITFDIGITS); } + void setFilLoad() { setPFloatOnClick(0, EXTRUDE_MAXLENGTH, UNITFDIGITS); } + void setFilUnload() { setPFloatOnClick(0, EXTRUDE_MAXLENGTH, UNITFDIGITS); } #endif #if ENABLED(PREVENT_COLD_EXTRUSION) @@ -2263,7 +2261,7 @@ void setMoveZ() { hmiValue.axis = Z_AXIS; setPFloatOnClick(Z_MIN_POS, Z_MAX_POS, void setExtMinT() { setPIntOnClick(MIN_ETEMP, MAX_ETEMP, applyExtMinT); } #endif -void setSpeed() { setPIntOnClick(MIN_PRINT_SPEED, MAX_PRINT_SPEED); } +void setSpeed() { setPIntOnClick(SPEED_EDIT_MIN, SPEED_EDIT_MAX); } #if HAS_HOTEND void applyHotendTemp() { thermalManager.setTargetHotend(menuData.value, 0); } @@ -2308,7 +2306,7 @@ void setSpeed() { setPIntOnClick(MIN_PRINT_SPEED, MAX_PRINT_SPEED); } #endif // ADVANCED_PAUSE_FEATURE -void setFlow() { setPIntOnClick(MIN_PRINT_FLOW, MAX_PRINT_FLOW, []{ planner.refresh_e_factor(0); }); } +void setFlow() { setPIntOnClick(FLOW_EDIT_MIN, FLOW_EDIT_MAX, []{ planner.refresh_e_factor(0); }); } // Bed Tramming diff --git a/Marlin/src/lcd/extui/malyan/malyan.cpp b/Marlin/src/lcd/extui/malyan/malyan.cpp index d1c2387682ff..c2e6bcdb7dd1 100644 --- a/Marlin/src/lcd/extui/malyan/malyan.cpp +++ b/Marlin/src/lcd/extui/malyan/malyan.cpp @@ -130,7 +130,7 @@ void process_lcd_c_command(const char *command) { case 'C': // Cope with both V1 early rev and later LCDs. case 'S': feedrate_percentage = target_val * 10; - LIMIT(feedrate_percentage, 10, 999); + LIMIT(feedrate_percentage, SPEED_EDIT_MIN, SPEED_EDIT_MAX); break; case 'T': diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index 49b9fecad8ae..178f0b74ecc5 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -695,7 +695,7 @@ void MarlinUI::init() { else if ((old_frm < 100 && new_frm > 100) || (old_frm > 100 && new_frm < 100)) new_frm = 100; - LIMIT(new_frm, 10, 999); + LIMIT(new_frm, SPEED_EDIT_MIN, SPEED_EDIT_MAX); if (old_frm != new_frm) { feedrate_percentage = new_frm; diff --git a/Marlin/src/lcd/menu/menu_item.h b/Marlin/src/lcd/menu/menu_item.h index ea26b48907a2..4d3e33db4c5a 100644 --- a/Marlin/src/lcd/menu/menu_item.h +++ b/Marlin/src/lcd/menu/menu_item.h @@ -264,9 +264,9 @@ class MenuItem_bool : public MenuEditItemBase { * MenuItem_function::action(flabel, lcd_sdcard_pause) * MenuItem_function::draw(sel, row, flabel, lcd_sdcard_pause) * - * EDIT_ITEM(int3, MSG_SPEED, &feedrate_percentage, 10, 999) - * MenuItem_int3::action(flabel, &feedrate_percentage, 10, 999) - * MenuItem_int3::draw(sel, row, flabel, &feedrate_percentage, 10, 999) + * EDIT_ITEM(int3, MSG_SPEED, &feedrate_percentage, SPEED_EDIT_MIN, SPEED_EDIT_MAX) + * MenuItem_int3::action(flabel, &feedrate_percentage, SPEED_EDIT_MIN, SPEED_EDIT_MAX) + * MenuItem_int3::draw(sel, row, flabel, &feedrate_percentage, SPEED_EDIT_MIN, SPEED_EDIT_MAX) */ #if ENABLED(ENCODER_RATE_MULTIPLIER) diff --git a/Marlin/src/lcd/menu/menu_tune.cpp b/Marlin/src/lcd/menu/menu_tune.cpp index c36ac013b86f..ecd4e5f342fc 100644 --- a/Marlin/src/lcd/menu/menu_tune.cpp +++ b/Marlin/src/lcd/menu/menu_tune.cpp @@ -114,7 +114,7 @@ void menu_tune() { // // Speed: // - EDIT_ITEM(int3, MSG_SPEED, &feedrate_percentage, 10, 999); + EDIT_ITEM(int3, MSG_SPEED, &feedrate_percentage, SPEED_EDIT_MIN, SPEED_EDIT_MAX); // // Manual bed leveling, Bed Z: @@ -198,11 +198,11 @@ void menu_tune() { // Flow: // #if HAS_EXTRUDERS - EDIT_ITEM(int3, MSG_FLOW, &planner.flow_percentage[active_extruder], 10, 999, []{ planner.refresh_e_factor(active_extruder); }); + EDIT_ITEM(int3, MSG_FLOW, &planner.flow_percentage[active_extruder], FLOW_EDIT_MIN, FLOW_EDIT_MAX, []{ planner.refresh_e_factor(active_extruder); }); // Flow En: #if HAS_MULTI_EXTRUDER EXTRUDER_LOOP() - EDIT_ITEM_N(int3, e, MSG_FLOW_N, &planner.flow_percentage[e], 10, 999, []{ planner.refresh_e_factor(MenuItemBase::itemIndex); }); + EDIT_ITEM_N(int3, e, MSG_FLOW_N, &planner.flow_percentage[e], FLOW_EDIT_MIN, FLOW_EDIT_MAX, []{ planner.refresh_e_factor(MenuItemBase::itemIndex); }); #endif #endif diff --git a/Marlin/src/lcd/tft/touch.cpp b/Marlin/src/lcd/tft/touch.cpp index 4d5056183bb9..8e79e397adea 100644 --- a/Marlin/src/lcd/tft/touch.cpp +++ b/Marlin/src/lcd/tft/touch.cpp @@ -220,7 +220,7 @@ void Touch::touch(touch_control_t *control) { break; case FEEDRATE: ui.clear_lcd(); - MenuItem_int3::action(GET_TEXT_F(MSG_SPEED), &feedrate_percentage, 10, 999); + MenuItem_int3::action(GET_TEXT_F(MSG_SPEED), &feedrate_percentage, SPEED_EDIT_MIN, SPEED_EDIT_MAX); break; #if HAS_EXTRUDERS @@ -228,9 +228,9 @@ void Touch::touch(touch_control_t *control) { ui.clear_lcd(); MenuItemBase::itemIndex = control->data; #if EXTRUDERS == 1 - MenuItem_int3::action(GET_TEXT_F(MSG_FLOW), &planner.flow_percentage[MenuItemBase::itemIndex], 10, 999, []{ planner.refresh_e_factor(MenuItemBase::itemIndex); }); + MenuItem_int3::action(GET_TEXT_F(MSG_FLOW), &planner.flow_percentage[MenuItemBase::itemIndex], FLOW_EDIT_MIN, FLOW_EDIT_MAX, []{ planner.refresh_e_factor(MenuItemBase::itemIndex); }); #else - MenuItem_int3::action(GET_TEXT_F(MSG_FLOW_N), &planner.flow_percentage[MenuItemBase::itemIndex], 10, 999, []{ planner.refresh_e_factor(MenuItemBase::itemIndex); }); + MenuItem_int3::action(GET_TEXT_F(MSG_FLOW_N), &planner.flow_percentage[MenuItemBase::itemIndex], FLOW_EDIT_MIN, FLOW_EDIT_MAX, []{ planner.refresh_e_factor(MenuItemBase::itemIndex); }); #endif break; #endif From e98e307d17cccddc35b7af364c1198e448891518 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sat, 25 Nov 2023 00:20:09 +0000 Subject: [PATCH 15/77] [cron] Bump distribution date (2023-11-25) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index a33fa5f92e46..adcf430114a3 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2023-11-24" +//#define STRING_DISTRIBUTION_DATE "2023-11-25" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 2447f9a9c7e4..962149506937 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2023-11-24" + #define STRING_DISTRIBUTION_DATE "2023-11-25" #endif /** From ae695e83093d234aecf6849c5107b0bc29bd687b Mon Sep 17 00:00:00 2001 From: ellensp <530024+ellensp@users.noreply.github.com> Date: Sat, 25 Nov 2023 16:27:55 +1300 Subject: [PATCH 16/77] =?UTF-8?q?=F0=9F=91=BD=EF=B8=8F=20Update=20Teensy?= =?UTF-8?q?=204.0/4.1=20Serial=20(#26457)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/TEENSY40_41/HAL.cpp | 12 +++++++++++- Marlin/src/HAL/TEENSY40_41/HAL.h | 16 ++++++++++++++-- 2 files changed, 25 insertions(+), 3 deletions(-) diff --git a/Marlin/src/HAL/TEENSY40_41/HAL.cpp b/Marlin/src/HAL/TEENSY40_41/HAL.cpp index 1d02ab8575c3..4dd5c3678d78 100644 --- a/Marlin/src/HAL/TEENSY40_41/HAL.cpp +++ b/Marlin/src/HAL/TEENSY40_41/HAL.cpp @@ -39,9 +39,19 @@ #define _IMPLEMENT_SERIAL(X) DefaultSerial##X MSerial##X(false, Serial##X) #define IMPLEMENT_SERIAL(X) _IMPLEMENT_SERIAL(X) -#if WITHIN(SERIAL_PORT, 0, 3) +#if WITHIN(SERIAL_PORT, 0, 8) IMPLEMENT_SERIAL(SERIAL_PORT); #endif +#ifdef SERIAL_PORT_2 + #if WITHIN(SERIAL_PORT_2, 0, 8) + IMPLEMENT_SERIAL(SERIAL_PORT_2); + #endif +#endif +#ifdef SERIAL_PORT_3 + #if WITHIN(SERIAL_PORT_3, 0, 8) + IMPLEMENT_SERIAL(SERIAL_PORT_3); + #endif +#endif USBSerialType USBSerial(false, SerialUSB); // ------------------------ diff --git a/Marlin/src/HAL/TEENSY40_41/HAL.h b/Marlin/src/HAL/TEENSY40_41/HAL.h index 84c584767705..ddda9be65f1a 100644 --- a/Marlin/src/HAL/TEENSY40_41/HAL.h +++ b/Marlin/src/HAL/TEENSY40_41/HAL.h @@ -80,7 +80,7 @@ extern USBSerialType USBSerial; #define MSERIAL(X) _MSERIAL(X) #if SERIAL_PORT == -1 - #define MYSERIAL1 SerialUSB + #define MYSERIAL1 USBSerial #elif WITHIN(SERIAL_PORT, 0, 8) DECLARE_SERIAL(SERIAL_PORT); #define MYSERIAL1 MSERIAL(SERIAL_PORT) @@ -90,16 +90,28 @@ extern USBSerialType USBSerial; #ifdef SERIAL_PORT_2 #if SERIAL_PORT_2 == -1 - #define MYSERIAL2 usbSerial + #define MYSERIAL2 USBSerial #elif SERIAL_PORT_2 == -2 #define MYSERIAL2 ethernet.telnetClient #elif WITHIN(SERIAL_PORT_2, 0, 8) + DECLARE_SERIAL(SERIAL_PORT_2); #define MYSERIAL2 MSERIAL(SERIAL_PORT_2) #else #error "SERIAL_PORT_2 must be from 0 to 8, or -1 for Native USB, or -2 for Ethernet." #endif #endif +#ifdef SERIAL_PORT_3 + #if SERIAL_PORT_3 == -1 + #define MYSERIAL3 USBSerial + #elif WITHIN(SERIAL_PORT_3, 0, 8) + DECLARE_SERIAL(SERIAL_PORT_3); + #define MYSERIAL3 MSERIAL(SERIAL_PORT_3) + #else + #error "SERIAL_PORT_3 must be from 0 to 8, or -1 for Native USB." + #endif +#endif + // ------------------------ // Types // ------------------------ From 8ff937c7d861d72da46fb10ce29e28b44b49cc2c Mon Sep 17 00:00:00 2001 From: Jason Smith Date: Fri, 24 Nov 2023 23:26:02 -0800 Subject: [PATCH 17/77] =?UTF-8?q?=F0=9F=90=9B=20Fix=20PANDA=20ZHU=20missin?= =?UTF-8?q?g=20#endif=20(#26460)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/esp32/pins_PANDA_ZHU.h | 1 + 1 file changed, 1 insertion(+) diff --git a/Marlin/src/pins/esp32/pins_PANDA_ZHU.h b/Marlin/src/pins/esp32/pins_PANDA_ZHU.h index f2a5f440f674..36a589b60035 100644 --- a/Marlin/src/pins/esp32/pins_PANDA_ZHU.h +++ b/Marlin/src/pins/esp32/pins_PANDA_ZHU.h @@ -29,6 +29,7 @@ #if E_STEPPERS > 5 #error "PANDA ZHU supports up to 5 E steppers." +#endif #if HAS_MULTI_HOTEND #error "PANDA ZHU only supports 1 hotend." #endif From 924d7769ec3dd65f89b53b45b94998c5d5cb1748 Mon Sep 17 00:00:00 2001 From: Keith Bennett <13375512+thisiskeithb@users.noreply.github.com> Date: Sat, 25 Nov 2023 14:31:53 -0800 Subject: [PATCH 18/77] =?UTF-8?q?=E2=9C=A8=20BD=5FSENSOR=5FPROBE=5FNO=5FST?= =?UTF-8?q?OP=20(#26353)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration.h | 3 +++ 1 file changed, 3 insertions(+) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 6374760db54a..406c42f21f81 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -1430,6 +1430,9 @@ * Uses I2C port, so it requires I2C library markyue/Panda_SoftMasterI2C. */ //#define BD_SENSOR +#if ENABLED(BD_SENSOR) + //#define BD_SENSOR_PROBE_NO_STOP // Probe bed without stopping at each probe point +#endif // A probe that is deployed and stowed with a solenoid pin (SOL1_PIN) //#define SOLENOID_PROBE From 20a26d5053b15e44d2be86c24ec074b43f159074 Mon Sep 17 00:00:00 2001 From: Andrew <18502096+classicrocker883@users.noreply.github.com> Date: Sat, 25 Nov 2023 17:45:39 -0500 Subject: [PATCH 19/77] =?UTF-8?q?=F0=9F=A7=91=E2=80=8D=F0=9F=92=BB=20Use?= =?UTF-8?q?=20ftpl=20for=20item=20strings=20(#26462)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/menu/menu.h | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/Marlin/src/lcd/menu/menu.h b/Marlin/src/lcd/menu/menu.h index 3f95d08effbe..de9e4d5086a1 100644 --- a/Marlin/src/lcd/menu/menu.h +++ b/Marlin/src/lcd/menu/menu.h @@ -65,11 +65,11 @@ class MenuItemBase { // Implementation-specific: // Draw an item either selected (pre_char) or not (space) with post_char // Menus may set up itemIndex, itemStringC/F and pass them to string-building or string-emitting functions - static void _draw(const bool sel, const uint8_t row, FSTR_P const fstr, const char pre_char, const char post_char); + static void _draw(const bool sel, const uint8_t row, FSTR_P const ftpl, const char pre_char, const char post_char); // Draw an item either selected ('>') or not (space) with post_char - FORCE_INLINE static void _draw(const bool sel, const uint8_t row, FSTR_P const fstr, const char post_char) { - _draw(sel, row, fstr, '>', post_char); + FORCE_INLINE static void _draw(const bool sel, const uint8_t row, FSTR_P const ftpl, const char post_char) { + _draw(sel, row, ftpl, '>', post_char); } }; @@ -82,8 +82,8 @@ class MenuItem_static : public MenuItemBase { // BACK_ITEM(LABEL) class MenuItem_back : public MenuItemBase { public: - FORCE_INLINE static void draw(const bool sel, const uint8_t row, FSTR_P const fstr) { - _draw(sel, row, fstr, LCD_STR_UPLEVEL[0], LCD_STR_UPLEVEL[0]); + FORCE_INLINE static void draw(const bool sel, const uint8_t row, FSTR_P const ftpl) { + _draw(sel, row, ftpl, LCD_STR_UPLEVEL[0], LCD_STR_UPLEVEL[0]); } // Back Item action goes back one step in history FORCE_INLINE static void action(FSTR_P const=nullptr) { ui.go_back(); } From e41df97c42e1be0b0c2b7bfbef2664a32cdf577b Mon Sep 17 00:00:00 2001 From: ellensp <530024+ellensp@users.noreply.github.com> Date: Sun, 26 Nov 2023 12:15:38 +1300 Subject: [PATCH 20/77] =?UTF-8?q?=F0=9F=94=A7=20Pins=20for=20FYSETC=20Spid?= =?UTF-8?q?er=20King=204.07=20(#26461)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../pins/stm32f1/pins_KEDI_CONTROLLER_V1_2.h | 12 +- .../pins/stm32f4/pins_FYSETC_SPIDER_KING407.h | 371 ++++++++++++++++++ 2 files changed, 377 insertions(+), 6 deletions(-) create mode 100644 Marlin/src/pins/stm32f4/pins_FYSETC_SPIDER_KING407.h diff --git a/Marlin/src/pins/stm32f1/pins_KEDI_CONTROLLER_V1_2.h b/Marlin/src/pins/stm32f1/pins_KEDI_CONTROLLER_V1_2.h index c29afb3ce4c7..4ac0a24d1c4d 100644 --- a/Marlin/src/pins/stm32f1/pins_KEDI_CONTROLLER_V1_2.h +++ b/Marlin/src/pins/stm32f1/pins_KEDI_CONTROLLER_V1_2.h @@ -82,14 +82,14 @@ // TMC2130 on SPI // SPI Pins (Shared for all drivers) #if ENABLED(TMC_USE_SW_SPI) // Shared with EXP2 - #ifndef TMC_SW_SCK - #define TMC_SW_SCK PB3 + #ifndef TMC_SPI_SCK + #define TMC_SPI_SCK PB3 #endif - #ifndef TMC_SW_MISO - #define TMC_SW_MISO PB4 + #ifndef TMC_SPI_MISO + #define TMC_SPI_MISO PB4 #endif - #ifndef TMC_SW_MOSI - #define TMC_SW_MOSI PB5 + #ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI PB5 #endif #endif diff --git a/Marlin/src/pins/stm32f4/pins_FYSETC_SPIDER_KING407.h b/Marlin/src/pins/stm32f4/pins_FYSETC_SPIDER_KING407.h new file mode 100644 index 000000000000..c79a4f5eb545 --- /dev/null +++ b/Marlin/src/pins/stm32f4/pins_FYSETC_SPIDER_KING407.h @@ -0,0 +1,371 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 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 . + * + */ +#pragma once + +#include "env_validate.h" + +#if HOTENDS > 5 || E_STEPPERS > 5 + #error "FYSETC SPIDER KING supports up to 5 hotends / E-steppers." +#endif + +#ifndef BOARD_INFO_NAME + #define BOARD_INFO_NAME "FYSETC SPIDER KING" +#endif +#ifndef DEFAULT_MACHINE_NAME + #define DEFAULT_MACHINE_NAME BOARD_INFO_NAME +#endif + +// +// EEPROM Emulation +// +#if NO_EEPROM_SELECTED + #undef NO_EEPROM_SELECTED + //#define FLASH_EEPROM_EMULATION + //#define SRAM_EEPROM_EMULATION + #define I2C_EEPROM +#endif + +#if ENABLED(I2C_EEPROM) + #define I2C_EEPROM + #define I2C_SCL_PIN PF1 + #define I2C_SDA_PIN PF0 + #define MARLIN_EEPROM_SIZE 0x1000 // 4KB +#endif + +// +// Servos +// +#define SERVO0_PIN PA1 + +// +// Software SPI pins for TMC2130 stepper drivers +// +#define TMC_USE_SW_SPI +#if ENABLED(TMC_USE_SW_SPI) + #ifndef TMC_SPI_MOSI + #define TMC_SPI_MOSI PE14 + #endif + #ifndef TMC_SPI_MISO + #define TMC_SPI_MISO PE13 + #endif + #ifndef TMC_SPI_SCK + #define TMC_SPI_SCK PE12 + #endif +#endif + +// +// Limit Switches +// +#define X_MIN_PIN PC5 +#define Y_MIN_PIN PC4 +#define Z_MIN_PIN PB6 +#define X_MAX_PIN PB5 +#define Y_MAX_PIN PF13 +#define Z_MAX_PIN PF14 + +#ifndef Z_MIN_PROBE_PIN + #define Z_MIN_PROBE_PIN PA0 +#endif + +// +// Steppers +// +#define X_STEP_PIN PG7 // "MOT1" +#define X_DIR_PIN PG6 +#define X_ENABLE_PIN PE11 +#define X_CS_PIN PD2 + +#define X2_STEP_PIN PD11 // "MOT2" +#define X2_DIR_PIN PD10 +#define X2_ENABLE_PIN PG10 +#define X2_CS_PIN PE15 + +#define Y_STEP_PIN PG14 // "MOT3" +#define Y_DIR_PIN PG12 +#define Y_ENABLE_PIN PG15 +#define Y_CS_PIN PD8 + +#define Z_STEP_PIN PD4 // "MOT4" +#define Z_DIR_PIN PD6 +#define Z_ENABLE_PIN PD5 +#define Z_CS_PIN PD7 + +#define Z2_STEP_PIN PE5 // "MOT5" +#define Z2_DIR_PIN PC13 +#define Z2_ENABLE_PIN PE6 +#define Z2_CS_PIN PC14 + +#define E0_STEP_PIN PE3 // "MOT6" +#define E0_DIR_PIN PE4 +#define E0_ENABLE_PIN PE2 +#define E0_CS_PIN PC15 + +#define E1_STEP_PIN PG13 // "MOT7" +#define E1_DIR_PIN PG8 +#define E1_ENABLE_PIN PG9 +#define E1_CS_PIN PG3 + +#define E2_STEP_PIN PE1 // "MOT8" +#define E2_DIR_PIN PE0 +#define E2_ENABLE_PIN PB2 +#define E2_CS_PIN PD9 + +#define E3_STEP_PIN PF4 // "MOT9" +#define E3_DIR_PIN PF3 +#define E3_ENABLE_PIN PF2 +#define E3_CS_PIN PF5 + +#define E4_STEP_PIN PF15 // "MOT10" +#define E4_DIR_PIN PG0 +#define E4_ENABLE_PIN PG5 +#define E4_CS_PIN PG11 + +#if HAS_TMC_UART + // + // TMC2208/TMC2209 stepper drivers + // + #define X_SERIAL_TX_PIN PD2 + #define X_SERIAL_RX_PIN PD2 + + #define X2_SERIAL_TX_PIN PE15 + #define X2_SERIAL_RX_PIN PE15 + + #define Y_SERIAL_TX_PIN PD8 + #define Y_SERIAL_RX_PIN PD8 + + #define Z_SERIAL_TX_PIN PD7 + #define Z_SERIAL_RX_PIN PD7 + + #define Z2_SERIAL_TX_PIN PC14 + #define Z2_SERIAL_RX_PIN PC14 + + #define E0_SERIAL_TX_PIN PC15 + #define E0_SERIAL_RX_PIN PC15 + + #define E1_SERIAL_TX_PIN PG3 + #define E1_SERIAL_RX_PIN PG3 + + #define E2_SERIAL_TX_PIN PD9 + #define E2_SERIAL_RX_PIN PD9 + + #define E3_SERIAL_TX_PIN PF5 + #define E3_SERIAL_RX_PIN PF5 + + #define E4_SERIAL_TX_PIN PG11 + #define E4_SERIAL_RX_PIN PG11 + + // Reduce baud rate to improve software serial reliability + #define TMC_BAUD_RATE 19200 +#endif + +// +// Temperature Sensors +// +#define TEMP_0_PIN PC1 +#define TEMP_1_PIN PF9 +#define TEMP_2_PIN PC3 +#define TEMP_3_PIN PC2 +#define TEMP_4_PIN PC0 +//#define TEMP_CHAMBER_PIN PC0 +#ifndef TEMP_BED_PIN + #define TEMP_BED_PIN PF10 +#endif + +// +// Heaters / Fans +// +#ifndef HEATER_0_PIN + #define HEATER_0_PIN PB4 +#endif +#ifndef HEATER_1_PIN + #define HEATER_1_PIN PB0 +#endif +#ifndef HEATER_2_PIN + #define HEATER_2_PIN PD13 +#endif +#ifndef HEATER_3_PIN + #define HEATER_3_PIN PC8 +#endif +#ifndef HEATER_4_PIN + #define HEATER_4_PIN PA15 +#endif +#ifndef HEATER_BED_PIN + #define HEATER_BED_PIN PE10 +#endif + +#ifndef FAN0_PIN + #define FAN0_PIN PE8 +#endif +#ifndef FAN1_PIN + #define FAN1_PIN PE9 +#endif +#ifndef FAN2_PIN + #define FAN2_PIN PD15 +#endif +#ifndef FAN3_PIN + #define FAN3_PIN PD12 +#endif +#ifndef FAN4_PIN + #define FAN4_PIN PD14 +#endif + +/** + * ------ ------ ------ + * PA2 |10 9 | PA3 PA6 |10 9 | PA5 PC9 |10 9 | PA8 + * -1 | 8 7 | PB10 PC6 | 8 7 | PA4 PC12 | 8 7 | PD0 + * PA6 6 5 | PA7 PC7 | 6 5 PA7 PC10 | 6 5 PC11 + * PA5 | 4 3 | PA4 PB10 | 4 3 | RESET PG4 | 4 3 | PE7 + * GND | 2 1 | 5V GND | 2 1 | 5V GND | 2 1 | 5V + * ------ ------ ------ + * EXP3 EXP2 EXP1 + */ +#define EXP1_03_PIN PE7 // LCD_D7 +#define EXP1_04_PIN PG4 // LCD_D6 +#define EXP1_05_PIN PC11 // LCD_D5 +#define EXP1_06_PIN PC10 // LCD_D4 +#define EXP1_07_PIN PD0 // LCD_RS +#define EXP1_08_PIN PC12 // LCD_EN +#define EXP1_09_PIN PA8 // BTN_ENC +#define EXP1_10_PIN PC9 // BEEP + +#define EXP2_03_PIN -1 // RESET +#define EXP2_04_PIN PB10 // CD +#define EXP2_05_PIN PA7 // MOSI +#define EXP2_06_PIN PC7 // BTN_EN2 +#define EXP2_07_PIN PA4 // SS +#define EXP2_08_PIN PC6 // BTN_EN1 +#define EXP2_09_PIN PA5 // SCK +#define EXP2_10_PIN PA6 // MISO + +#define EXP3_03_PIN PA4 // SS +#define EXP3_04_PIN PA5 // SCK +#define EXP3_05_PIN PA7 // MOSI +#define EXP3_06_PIN PA6 // MISO +#define EXP3_07_PIN PB10 // CD +#define EXP3_08_PIN -1 // 3V3 +#define EXP3_09_PIN PA3 // LCD_RX/RX +#define EXP3_10_PIN PA2 // LCD_TX/TX + +// +// SPI / SD Card +// +#define SD_SCK_PIN EXP2_09_PIN +#define SD_MISO_PIN EXP2_10_PIN +#define SD_MOSI_PIN EXP2_05_PIN + +#define SDSS EXP2_07_PIN +#define SD_DETECT_PIN EXP2_04_PIN + +// +// LCD / Controller +// +#if ENABLED(FYSETC_242_OLED_12864) + + #define BEEPER_PIN EXP2_08_PIN + + #define BTN_EN1 EXP1_10_PIN + #define BTN_EN2 EXP1_03_PIN + #define BTN_ENC EXP1_09_PIN + + #define LCD_PINS_DC EXP1_05_PIN + #define LCD_PINS_RS EXP2_06_PIN // LCD_RST + #define DOGLCD_CS EXP1_07_PIN + #define DOGLCD_MOSI EXP1_06_PIN + #define DOGLCD_SCK EXP1_08_PIN + #define DOGLCD_A0 LCD_PINS_DC + #define FORCE_SOFT_SPI + + //#define KILL_PIN -1 // NC + #define NEOPIXEL_PIN EXP1_04_PIN + +#elif HAS_WIRED_LCD + + #define BEEPER_PIN EXP1_10_PIN + #define BTN_ENC EXP1_09_PIN + + #define LCD_PINS_RS EXP1_07_PIN + + #define BTN_EN1 EXP2_08_PIN + #define BTN_EN2 EXP2_06_PIN + + #define LCD_SDSS EXP2_07_PIN + + #define LCD_PINS_ENABLE EXP1_08_PIN + #define LCD_PINS_D4 EXP1_06_PIN + + #if ENABLED(FYSETC_MINI_12864) + // See https://wiki.fysetc.com/Mini12864_Panel + #define DOGLCD_CS EXP1_08_PIN + #define DOGLCD_A0 EXP1_07_PIN + #if ENABLED(FYSETC_GENERIC_12864_1_1) + #define LCD_BACKLIGHT_PIN EXP1_04_PIN + #endif + #define LCD_RESET_PIN EXP1_06_PIN // Must be high or open for LCD to operate normally. + #if ANY(FYSETC_MINI_12864_1_2, FYSETC_MINI_12864_2_0) + #ifndef RGB_LED_R_PIN + #define RGB_LED_R_PIN EXP1_05_PIN + #endif + #ifndef RGB_LED_G_PIN + #define RGB_LED_G_PIN EXP1_04_PIN + #endif + #ifndef RGB_LED_B_PIN + #define RGB_LED_B_PIN EXP1_03_PIN + #endif + #elif ENABLED(FYSETC_MINI_12864_2_1) + #define NEOPIXEL_PIN EXP1_05_PIN + #endif + #endif + + #if IS_ULTIPANEL + #define LCD_PINS_D5 EXP1_05_PIN + #define LCD_PINS_D6 EXP1_04_PIN + #define LCD_PINS_D7 EXP1_03_PIN + #if ENABLED(REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER) + #define BTN_ENC_EN LCD_PINS_D7 // Detect the presence of the encoder + #endif + #endif + +#endif // HAS_WIRED_LCD + +// Alter timing for graphical display +#if IS_U8GLIB_ST7920 + #define BOARD_ST7920_DELAY_1 96 + #define BOARD_ST7920_DELAY_2 48 + #define BOARD_ST7920_DELAY_3 640 +#endif + +// +// Wifi module +// +#define ESP_WIFI_MODULE_COM 1 // Set either SERIAL_PORT or SERIAL_PORT_2 to this +#define ESP_WIFI_MODULE_BAUDRATE BAUDRATE // Use the same BAUDRATE as SERIAL_PORT or SERIAL_PORT_2 +#define ESP_WIFI_MODULE_RESET_PIN PB3 +#define ESP_WIFI_MODULE_ENABLE_PIN PD1 // PC8 +#define ESP_WIFI_MODULE_GPIO0_PIN PG2 // PB4 +#define ESP_WIFI_MODULE_GPIO4_PIN PG1 // PB7 + +// +// NeoPixel LED +// +#ifndef NEOPIXEL_PIN + #define NEOPIXEL_PIN PD3 +#endif From e7cf0e12ea2f122b80e5567e878e8f545eb37bee Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sun, 26 Nov 2023 00:27:32 +0000 Subject: [PATCH 21/77] [cron] Bump distribution date (2023-11-26) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index adcf430114a3..f9da779f1cff 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2023-11-25" +//#define STRING_DISTRIBUTION_DATE "2023-11-26" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 962149506937..fd5cac89d3af 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2023-11-25" + #define STRING_DISTRIBUTION_DATE "2023-11-26" #endif /** From 0a86a5f39c560f324e65b539b5be8da1ed91c60a Mon Sep 17 00:00:00 2001 From: David Buezas Date: Sun, 26 Nov 2023 02:55:51 +0100 Subject: [PATCH 22/77] =?UTF-8?q?=E2=9C=A8=20MAX=20Thermocouples=20for=20H?= =?UTF-8?q?eated=20Bed=20(#26441)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/Configuration.h | 6 +- Marlin/src/MarlinCore.cpp | 6 + Marlin/src/inc/Conditionals_adv.h | 56 +++++--- Marlin/src/inc/Conditionals_post.h | 20 ++- Marlin/src/inc/SanityCheck.h | 6 +- Marlin/src/inc/Warnings.cpp | 3 + Marlin/src/module/temperature.cpp | 223 ++++++++++++++++++++++++----- Marlin/src/module/temperature.h | 9 +- 8 files changed, 258 insertions(+), 71 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 406c42f21f81..0639f432c518 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -513,10 +513,10 @@ * ================================================================ * SPI RTD/Thermocouple Boards * ================================================================ - * -5 : MAX31865 with Pt100/Pt1000, 2, 3, or 4-wire (only for sensors 0-1) + * -5 : MAX31865 with Pt100/Pt1000, 2, 3, or 4-wire (only for sensors 0-2 and bed) * NOTE: You must uncomment/set the MAX31865_*_OHMS_n defines below. - * -3 : MAX31855 with Thermocouple, -200°C to +700°C (only for sensors 0-1) - * -2 : MAX6675 with Thermocouple, 0°C to +700°C (only for sensors 0-1) + * -3 : MAX31855 with Thermocouple, -200°C to +700°C (only for sensors 0-2 and bed) + * -2 : MAX6675 with Thermocouple, 0°C to +700°C (only for sensors 0-2 and bed) * * NOTE: Ensure TEMP_n_CS_PIN is set in your pins file for each TEMP_SENSOR_n using an SPI Thermocouple. By default, * Hardware SPI on the default serial bus is used. If you have also set TEMP_n_SCK_PIN and TEMP_n_MISO_PIN, diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 312e6c2cee92..1dcee50d12c9 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -1219,6 +1219,12 @@ void setup() { #if TEMP_SENSOR_IS_MAX_TC(1) || (TEMP_SENSOR_IS_MAX_TC(REDUNDANT) && REDUNDANT_TEMP_MATCH(SOURCE, E1)) OUT_WRITE(TEMP_1_CS_PIN, HIGH); #endif + #if TEMP_SENSOR_IS_MAX_TC(2) || (TEMP_SENSOR_IS_MAX_TC(REDUNDANT) && REDUNDANT_TEMP_MATCH(SOURCE, E2)) + OUT_WRITE(TEMP_2_CS_PIN, HIGH); + #endif + #if TEMP_SENSOR_IS_MAX_TC(BED) + OUT_WRITE(TEMP_BED_CS_PIN, HIGH); + #endif #if ENABLED(DUET_SMART_EFFECTOR) && PIN_EXISTS(SMART_EFFECTOR_MOD) OUT_WRITE(SMART_EFFECTOR_MOD_PIN, LOW); // Put Smart Effector into NORMAL mode diff --git a/Marlin/src/inc/Conditionals_adv.h b/Marlin/src/inc/Conditionals_adv.h index 9e4cc0d04625..7fc6050f0db9 100644 --- a/Marlin/src/inc/Conditionals_adv.h +++ b/Marlin/src/inc/Conditionals_adv.h @@ -507,33 +507,35 @@ #endif #if TEMP_SENSOR_IS_MAX_TC(REDUNDANT) + #define _REDUNDANT_E (REDUNDANT_TEMP_MATCH(SOURCE, E0) || REDUNDANT_TEMP_MATCH(SOURCE, E1) || REDUNDANT_TEMP_MATCH(SOURCE, E2)) #if TEMP_SENSOR_REDUNDANT == -5 - #if !REDUNDANT_TEMP_MATCH(SOURCE, E0) && !REDUNDANT_TEMP_MATCH(SOURCE, E1) && !REDUNDANT_TEMP_MATCH(SOURCE, E2) - #error "MAX31865 Thermocouples (-5) not supported for TEMP_SENSOR_REDUNDANT_SOURCE other than TEMP_SENSOR_0/TEMP_SENSOR_1/TEMP_SENSOR_2 (0/1/2)." + #if !_REDUNDANT_E + #error "MAX31865 Thermocouples (-5) not supported for TEMP_SENSOR_REDUNDANT_SOURCE other than TEMP_SENSOR_[0-2]." #endif #define TEMP_SENSOR_REDUNDANT_IS_MAX31865 1 #define TEMP_SENSOR_REDUNDANT_MAX_TC_TMIN 0 #define TEMP_SENSOR_REDUNDANT_MAX_TC_TMAX 1024 #elif TEMP_SENSOR_REDUNDANT == -3 - #if !REDUNDANT_TEMP_MATCH(SOURCE, E0) && !REDUNDANT_TEMP_MATCH(SOURCE, E1) && !REDUNDANT_TEMP_MATCH(SOURCE, E2) - #error "MAX31855 Thermocouples (-3) not supported for TEMP_SENSOR_REDUNDANT_SOURCE other than TEMP_SENSOR_0/TEMP_SENSOR_1/TEMP_SENSOR_2 (0/1/2)." + #if !_REDUNDANT_E + #error "MAX31855 Thermocouples (-3) not supported for TEMP_SENSOR_REDUNDANT_SOURCE other than TEMP_SENSOR_[0-2]." #endif #define TEMP_SENSOR_REDUNDANT_IS_MAX31855 1 #define TEMP_SENSOR_REDUNDANT_MAX_TC_TMIN -270 #define TEMP_SENSOR_REDUNDANT_MAX_TC_TMAX 1800 #elif TEMP_SENSOR_REDUNDANT == -2 - #if !REDUNDANT_TEMP_MATCH(SOURCE, E0) && !REDUNDANT_TEMP_MATCH(SOURCE, E1) && !REDUNDANT_TEMP_MATCH(SOURCE, E2) - #error "MAX6675 Thermocouples (-2) not supported for TEMP_SENSOR_REDUNDANT_SOURCE other than TEMP_SENSOR_0/TEMP_SENSOR_1/TEMP_SENSOR_2 (0/1/2)." + #if !_REDUNDANT_E + #error "MAX6675 Thermocouples (-2) not supported for TEMP_SENSOR_REDUNDANT_SOURCE other than TEMP_SENSOR_[0-2]." #endif #define TEMP_SENSOR_REDUNDANT_IS_MAX6675 1 #define TEMP_SENSOR_REDUNDANT_MAX_TC_TMIN 0 #define TEMP_SENSOR_REDUNDANT_MAX_TC_TMAX 1024 #endif + #undef _REDUNDANT_E - // mimic setting up the source TEMP_SENSOR + // Mimic setting up the source TEMP_SENSOR #if REDUNDANT_TEMP_MATCH(SOURCE, E0) #define TEMP_SENSOR_0_MAX_TC_TMIN TEMP_SENSOR_REDUNDANT_MAX_TC_TMIN #define TEMP_SENSOR_0_MAX_TC_TMAX TEMP_SENSOR_REDUNDANT_MAX_TC_TMAX @@ -556,11 +558,11 @@ #if (TEMP_SENSOR_IS_MAX_TC(0) && TEMP_SENSOR_REDUNDANT != TEMP_SENSOR_0) || (TEMP_SENSOR_IS_MAX_TC(1) && TEMP_SENSOR_REDUNDANT != TEMP_SENSOR_1) || (TEMP_SENSOR_IS_MAX_TC(2) && TEMP_SENSOR_REDUNDANT != TEMP_SENSOR_2) #if TEMP_SENSOR_REDUNDANT == -5 - #error "If MAX31865 Thermocouple (-5) is used for TEMP_SENSOR_0/TEMP_SENSOR_1/TEMP_SENSOR_2 then TEMP_SENSOR_REDUNDANT must match." + #error "If MAX31865 Thermocouple (-5) is used for TEMP_SENSOR_[0-2] then TEMP_SENSOR_REDUNDANT must match." #elif TEMP_SENSOR_REDUNDANT == -3 - #error "If MAX31855 Thermocouple (-3) is used for TEMP_SENSOR_0/TEMP_SENSOR_1/TEMP_SENSOR_2 then TEMP_SENSOR_REDUNDANT must match." + #error "If MAX31855 Thermocouple (-3) is used for TEMP_SENSOR_[0-2] then TEMP_SENSOR_REDUNDANT must match." #elif TEMP_SENSOR_REDUNDANT == -2 - #error "If MAX6675 Thermocouple (-2) is used for TEMP_SENSOR_0/TEMP_SENSOR_1/TEMP_SENSOR_2 then TEMP_SENSOR_REDUNDANT must match." + #error "If MAX6675 Thermocouple (-2) is used for TEMP_SENSOR_[0-2] then TEMP_SENSOR_REDUNDANT must match." #endif #endif #elif TEMP_SENSOR_REDUNDANT == -4 @@ -576,16 +578,16 @@ #endif #endif -#if TEMP_SENSOR_IS_MAX_TC(0) || TEMP_SENSOR_IS_MAX_TC(1) || TEMP_SENSOR_IS_MAX_TC(2) || TEMP_SENSOR_IS_MAX_TC(REDUNDANT) +#if TEMP_SENSOR_IS_MAX_TC(0) || TEMP_SENSOR_IS_MAX_TC(1) || TEMP_SENSOR_IS_MAX_TC(2) || TEMP_SENSOR_IS_MAX_TC(BED) || TEMP_SENSOR_IS_MAX_TC(REDUNDANT) #define HAS_MAX_TC 1 #endif -#if TEMP_SENSOR_0_IS_MAX6675 || TEMP_SENSOR_1_IS_MAX6675 || TEMP_SENSOR_2_IS_MAX6675 || TEMP_SENSOR_REDUNDANT_IS_MAX6675 +#if TEMP_SENSOR_0_IS_MAX6675 || TEMP_SENSOR_1_IS_MAX6675 || TEMP_SENSOR_2_IS_MAX6675 || TEMP_SENSOR_BED_IS_MAX6675 || TEMP_SENSOR_REDUNDANT_IS_MAX6675 #define HAS_MAX6675 1 #endif -#if TEMP_SENSOR_0_IS_MAX31855 || TEMP_SENSOR_1_IS_MAX31855 || TEMP_SENSOR_2_IS_MAX31855 || TEMP_SENSOR_REDUNDANT_IS_MAX31855 +#if TEMP_SENSOR_0_IS_MAX31855 || TEMP_SENSOR_1_IS_MAX31855 || TEMP_SENSOR_2_IS_MAX31855 || TEMP_SENSOR_BED_IS_MAX31855 || TEMP_SENSOR_REDUNDANT_IS_MAX31855 #define HAS_MAX31855 1 #endif -#if TEMP_SENSOR_0_IS_MAX31865 || TEMP_SENSOR_1_IS_MAX31865 || TEMP_SENSOR_2_IS_MAX31865 || TEMP_SENSOR_REDUNDANT_IS_MAX31865 +#if TEMP_SENSOR_0_IS_MAX31865 || TEMP_SENSOR_1_IS_MAX31865 || TEMP_SENSOR_2_IS_MAX31865 || TEMP_SENSOR_BED_IS_MAX31865 || TEMP_SENSOR_REDUNDANT_IS_MAX31865 #define HAS_MAX31865 1 #endif @@ -674,12 +676,28 @@ #endif #endif -#if TEMP_SENSOR_BED == -4 +#if TEMP_SENSOR_IS_MAX_TC(BED) + #if TEMP_SENSOR_BED == -5 + #define TEMP_SENSOR_BED_IS_MAX31865 1 + #define TEMP_SENSOR_BED_MAX_TC_TMIN 0 + #define TEMP_SENSOR_BED_MAX_TC_TMAX 1024 + #ifndef MAX31865_SENSOR_WIRES_BED + #define MAX31865_SENSOR_WIRES_BED 2 + #endif + #ifndef MAX31865_WIRE_OHMS_BED + #define MAX31865_WIRE_OHMS_BED 0.0f + #endif + #elif TEMP_SENSOR_BED == -3 + #define TEMP_SENSOR_BED_IS_MAX31855 1 + #define TEMP_SENSOR_BED_MAX_TC_TMIN -270 + #define TEMP_SENSOR_BED_MAX_TC_TMAX 1800 + #elif TEMP_SENSOR_BED == -2 + #define TEMP_SENSOR_BED_IS_MAX6675 1 + #define TEMP_SENSOR_BED_MAX_TC_TMIN 0 + #define TEMP_SENSOR_BED_MAX_TC_TMAX 1024 + #endif +#elif TEMP_SENSOR_BED == -4 #define TEMP_SENSOR_BED_IS_AD8495 1 -#elif TEMP_SENSOR_BED == -3 - #error "MAX31855 Thermocouples (-3) not supported for TEMP_SENSOR_BED." -#elif TEMP_SENSOR_BED == -2 - #error "MAX6675 Thermocouples (-2) not supported for TEMP_SENSOR_BED." #elif TEMP_SENSOR_BED == -1 #define TEMP_SENSOR_BED_IS_AD595 1 #elif TEMP_SENSOR_BED > 0 diff --git a/Marlin/src/inc/Conditionals_post.h b/Marlin/src/inc/Conditionals_post.h index b98ca4d371f8..09e020dab885 100644 --- a/Marlin/src/inc/Conditionals_post.h +++ b/Marlin/src/inc/Conditionals_post.h @@ -697,11 +697,13 @@ /** * Compatibility layer for MAX (SPI) temp boards */ + +#define TEMP_SENSOR_IS_ANY_MAX_TC(n) (TEMP_SENSOR_IS_MAX_TC(n) || (TEMP_SENSOR_IS_MAX_TC(REDUNDANT) && REDUNDANT_TEMP_MATCH(SOURCE, E##n))) + #if HAS_MAX_TC // Software SPI - enable if MISO/SCK are defined. - #if (TEMP_SENSOR_IS_MAX_TC(0) || (TEMP_SENSOR_IS_MAX_TC(REDUNDANT) && REDUNDANT_TEMP_MATCH(SOURCE, E1))) \ - && PIN_EXISTS(TEMP_0_MISO) && PIN_EXISTS(TEMP_0_SCK) && DISABLED(TEMP_SENSOR_0_FORCE_HW_SPI) + #if TEMP_SENSOR_IS_ANY_MAX_TC(0) && DISABLED(TEMP_SENSOR_0_FORCE_HW_SPI) && PINS_EXIST(TEMP_0_MISO, TEMP_0_SCK) #if TEMP_SENSOR_0_IS_MAX31865 && !PIN_EXISTS(TEMP_0_MOSI) #error "TEMP_SENSOR_0 MAX31865 requires TEMP_0_MOSI_PIN defined for Software SPI. To use Hardware SPI instead, undefine MISO/SCK or enable TEMP_SENSOR_0_FORCE_HW_SPI." #else @@ -709,8 +711,7 @@ #endif #endif - #if (TEMP_SENSOR_IS_MAX_TC(1) || (TEMP_SENSOR_IS_MAX_TC(REDUNDANT) && REDUNDANT_TEMP_MATCH(SOURCE, E1))) \ - && PIN_EXISTS(TEMP_1_MISO) && PIN_EXISTS(TEMP_1_SCK) && DISABLED(TEMP_SENSOR_1_FORCE_HW_SPI) + #if TEMP_SENSOR_IS_ANY_MAX_TC(1) && DISABLED(TEMP_SENSOR_1_FORCE_HW_SPI) && PINS_EXIST(TEMP_1_MISO, TEMP_1_SCK) #if TEMP_SENSOR_1_IS_MAX31865 && !PIN_EXISTS(TEMP_1_MOSI) #error "TEMP_SENSOR_1 MAX31865 requires TEMP_1_MOSI_PIN defined for Software SPI. To use Hardware SPI instead, undefine MISO/SCK or enable TEMP_SENSOR_1_FORCE_HW_SPI." #else @@ -718,8 +719,7 @@ #endif #endif - #if (TEMP_SENSOR_IS_MAX_TC(2) || (TEMP_SENSOR_IS_MAX_TC(REDUNDANT) && REDUNDANT_TEMP_MATCH(SOURCE, E2))) \ - && PIN_EXISTS(TEMP_2_MISO) && PIN_EXISTS(TEMP_2_SCK) && DISABLED(TEMP_SENSOR_2_FORCE_HW_SPI) + #if TEMP_SENSOR_IS_ANY_MAX_TC(2) && DISABLED(TEMP_SENSOR_2_FORCE_HW_SPI) && PINS_EXIST(TEMP_2_MISO, TEMP_2_SCK) #if TEMP_SENSOR_2_IS_MAX31865 && !PIN_EXISTS(TEMP_2_MOSI) #error "TEMP_SENSOR_2 MAX31865 requires TEMP_2_MOSI_PIN defined for Software SPI. To use Hardware SPI instead, undefine MISO/SCK or enable TEMP_SENSOR_2_FORCE_HW_SPI." #else @@ -727,6 +727,14 @@ #endif #endif + #if (TEMP_SENSOR_IS_MAX_TC(BED)) && DISABLED(TEMP_SENSOR_BED_FORCE_HW_SPI) && PINS_EXIST(TEMP_BED_MISO, TEMP_BED_SCK) + #if TEMP_SENSOR_BED_IS_MAX31865 && !PIN_EXISTS(TEMP_BED_MOSI) + #error "TEMP_SENSOR_BED MAX31865 requires TEMP_BED_MOSI_PIN defined for Software SPI. To use Hardware SPI instead, undefine MISO/SCK or enable TEMP_SENSOR_BED_FORCE_HW_SPI." + #else + #define TEMP_SENSOR_BED_HAS_SPI_PINS 1 + #endif + #endif + // // User-defined thermocouple libraries // diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 3b08e6635f33..00e90b618356 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -2057,6 +2057,8 @@ static_assert(COUNT(arm) == LOGICAL_AXES, "AXIS_RELATIVE_MODES must contain " _L #error "TEMP_SENSOR_REDUNDANT MAX Thermocouple with TEMP_SENSOR_REDUNDANT_SOURCE E0 requires TEMP_0_CS_PIN." #elif TEMP_SENSOR_IS_MAX_TC(REDUNDANT) && REDUNDANT_TEMP_MATCH(SOURCE, E1) && !PIN_EXISTS(TEMP_1_CS) #error "TEMP_SENSOR_REDUNDANT MAX Thermocouple with TEMP_SENSOR_REDUNDANT_SOURCE E1 requires TEMP_1_CS_PIN." + #elif TEMP_SENSOR_IS_MAX_TC(REDUNDANT) && REDUNDANT_TEMP_MATCH(SOURCE, E2) && !PIN_EXISTS(TEMP_2_CS) + #error "TEMP_SENSOR_REDUNDANT MAX Thermocouple with TEMP_SENSOR_REDUNDANT_SOURCE E2 requires TEMP_2_CS_PIN." #endif #endif @@ -2089,7 +2091,9 @@ static_assert(COUNT(arm) == LOGICAL_AXES, "AXIS_RELATIVE_MODES must contain " _L #error "TEMP_1_PIN or TEMP_1_CS_PIN not defined for this board." #endif #if HOTENDS > 2 - #if TEMP_SENSOR_2 == 100 + #if TEMP_SENSOR_IS_MAX_TC(2) && !PIN_EXISTS(TEMP_2_CS) + #error "TEMP_SENSOR_2 MAX thermocouple requires TEMP_2_CS_PIN." + #elif TEMP_SENSOR_2 == 100 #error "TEMP_SENSOR_2 can't use Soc temperature sensor." #elif TEMP_SENSOR_2 == 0 #error "TEMP_SENSOR_2 is required with 3 or more HOTENDS." diff --git a/Marlin/src/inc/Warnings.cpp b/Marlin/src/inc/Warnings.cpp index a8820af179a7..26ecfbf533a5 100644 --- a/Marlin/src/inc/Warnings.cpp +++ b/Marlin/src/inc/Warnings.cpp @@ -59,6 +59,9 @@ #if HAS_COOLER && DISABLED(THERMAL_PROTECTION_COOLER) #warning "Safety Alert! Enable THERMAL_PROTECTION_COOLER for the final build!" #endif +#if ENABLED(IGNORE_THERMOCOUPLE_ERRORS) + #warning "Safety Alert! Disable IGNORE_THERMOCOUPLE_ERRORS for the final build!" +#endif #if ANY_THERMISTOR_IS(998) || ANY_THERMISTOR_IS(999) #warning "Warning! Don't use dummy thermistors (998/999) for final build!" #endif diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index 2f8761ec39f3..fc9e08fe7cac 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -74,7 +74,6 @@ // MAX TC related macros #define TEMP_SENSOR_IS_MAX(n, M) (ENABLED(TEMP_SENSOR_##n##_IS_MAX##M) || (ENABLED(TEMP_SENSOR_REDUNDANT_IS_MAX##M) && REDUNDANT_TEMP_MATCH(SOURCE, E##n))) -#define TEMP_SENSOR_IS_ANY_MAX_TC(n) (TEMP_SENSOR_IS_MAX_TC(n) || (TEMP_SENSOR_IS_MAX_TC(REDUNDANT) && REDUNDANT_TEMP_MATCH(SOURCE, E##n))) // LIB_MAX6675 can be added to the build_flags in platformio.ini to use a user-defined library // If LIB_MAX6675 is not on the build_flags then raw SPI reads will be used. @@ -121,6 +120,9 @@ #if TEMP_SENSOR_IS_ANY_MAX_TC(2) && TEMP_SENSOR_2_HAS_SPI_PINS && DISABLED(TEMP_SENSOR_FORCE_HW_SPI) #define TEMP_SENSOR_2_USES_SW_SPI 1 #endif +#if TEMP_SENSOR_IS_ANY_MAX_TC(BED) && TEMP_SENSOR_0_HAS_SPI_PINS && DISABLED(TEMP_SENSOR_FORCE_HW_SPI) + #define TEMP_SENSOR_BED_USES_SW_SPI 1 +#endif #if (TEMP_SENSOR_0_USES_SW_SPI || TEMP_SENSOR_1_USES_SW_SPI || TEMP_SENSOR_2_USES_SW_SPI) && !HAS_MAXTC_LIBRARIES #include "../libs/private_spi.h" @@ -259,6 +261,7 @@ PGMSTR(str_t_heating_failed, STR_T_HEATING_FAILED); #define _MAX31865_0_SW TEMP_SENSOR_0_USES_SW_SPI #define _MAX31865_1_SW TEMP_SENSOR_1_USES_SW_SPI #define _MAX31865_2_SW TEMP_SENSOR_2_USES_SW_SPI + #define _MAX31865_BED_SW TEMP_SENSOR_BED_USES_SW_SPI #if TEMP_SENSOR_IS_MAX(0, 31865) MAXTC_INIT(0, 31865); @@ -269,10 +272,14 @@ PGMSTR(str_t_heating_failed, STR_T_HEATING_FAILED); #if TEMP_SENSOR_IS_MAX(2, 31865) MAXTC_INIT(2, 31865); #endif + #if TEMP_SENSOR_IS_MAX(BED, 31865) + MAXTC_INIT(BED, 31865); + #endif #undef _MAX31865_0_SW #undef _MAX31865_1_SW #undef _MAX31865_2_SW + #undef _MAX31865_BED_SW #endif #undef MAXTC_INIT @@ -2089,33 +2096,38 @@ void Temperature::task() { #if TEMP_SENSOR_IS_MAX_TC(0) { const auto deg = degHotend(0); - if (deg > _MIN(HEATER_0_MAXTEMP, TEMP_SENSOR_0_MAX_TC_TMAX - 1.0)) MAXTEMP_ERROR(H_E0, deg); - if (deg < _MAX(HEATER_0_MINTEMP, TEMP_SENSOR_0_MAX_TC_TMIN + .01)) MINTEMP_ERROR(H_E0, deg); + if (deg > _MIN(HEATER_0_MAXTEMP, TEMP_SENSOR_0_MAX_TC_TMAX - 1.00f)) MAXTEMP_ERROR(H_E0, deg); + if (deg < _MAX(HEATER_0_MINTEMP, TEMP_SENSOR_0_MAX_TC_TMIN + 0.01f)) MINTEMP_ERROR(H_E0, deg); } #endif #if TEMP_SENSOR_IS_MAX_TC(1) { const auto deg = degHotend(1); - if (deg > _MIN(HEATER_1_MAXTEMP, TEMP_SENSOR_1_MAX_TC_TMAX - 1.0)) MAXTEMP_ERROR(H_E1, deg); - if (deg < _MAX(HEATER_1_MINTEMP, TEMP_SENSOR_1_MAX_TC_TMIN + .01)) MINTEMP_ERROR(H_E1, deg); + if (deg > _MIN(HEATER_1_MAXTEMP, TEMP_SENSOR_1_MAX_TC_TMAX - 1.00f)) MAXTEMP_ERROR(H_E1, deg); + if (deg < _MAX(HEATER_1_MINTEMP, TEMP_SENSOR_1_MAX_TC_TMIN + 0.01f)) MINTEMP_ERROR(H_E1, deg); } #endif #if TEMP_SENSOR_IS_MAX_TC(2) { const auto deg = degHotend(2); - if (deg > _MIN(HEATER_2_MAXTEMP, TEMP_SENSOR_2_MAX_TC_TMAX - 1.0)) MAXTEMP_ERROR(H_E2, deg); - if (deg < _MAX(HEATER_2_MINTEMP, TEMP_SENSOR_2_MAX_TC_TMIN + .01)) MINTEMP_ERROR(H_E2, deg); + if (deg > _MIN(HEATER_2_MAXTEMP, TEMP_SENSOR_2_MAX_TC_TMAX - 1.00f)) MAXTEMP_ERROR(H_E2, deg); + if (deg < _MAX(HEATER_2_MINTEMP, TEMP_SENSOR_2_MAX_TC_TMIN + 0.01f)) MINTEMP_ERROR(H_E2, deg); } #endif #if TEMP_SENSOR_IS_MAX_TC(REDUNDANT) { const auto deg = degRedundant(); - if (deg > TEMP_SENSOR_REDUNDANT_MAX_TC_TMAX - 1.0) MAXTEMP_ERROR(H_REDUNDANT, deg); - if (deg < TEMP_SENSOR_REDUNDANT_MAX_TC_TMIN + .01) MINTEMP_ERROR(H_REDUNDANT, deg); + if (deg > TEMP_SENSOR_REDUNDANT_MAX_TC_TMAX - 1.00f) MAXTEMP_ERROR(H_REDUNDANT, deg); + if (deg < TEMP_SENSOR_REDUNDANT_MAX_TC_TMIN + 0.01f) MINTEMP_ERROR(H_REDUNDANT, deg); + } + #endif + #if TEMP_SENSOR_IS_MAX_TC(BED) + { + const auto deg = degBed(); + if (deg > _MIN(BED_MAXTEMP, TEMP_SENSOR_BED_MAX_TC_TMAX - 1.00f)) MAXTEMP_ERROR(H_BED, deg); + if (deg < _MAX(BED_MINTEMP, TEMP_SENSOR_BED_MAX_TC_TMIN + 0.01f)) MINTEMP_ERROR(H_BED, deg); } #endif - #else - #warning "Safety Alert! Disable IGNORE_THERMOCOUPLE_ERRORS for the final build!" #endif const millis_t ms = millis(); @@ -2329,7 +2341,7 @@ void Temperature::task() { max31865_0.temperature(MAX31865_SENSOR_OHMS_0, MAX31865_CALIBRATION_OHMS_0) ); #else - return (int16_t)raw * 0.25; + return (int16_t)raw * 0.25f; #endif #elif TEMP_SENSOR_0_IS_AD595 return TEMP_AD595(raw); @@ -2348,7 +2360,7 @@ void Temperature::task() { max31865_1.temperature(MAX31865_SENSOR_OHMS_1, MAX31865_CALIBRATION_OHMS_1) ); #else - return (int16_t)raw * 0.25; + return (int16_t)raw * 0.25f; #endif #elif TEMP_SENSOR_1_IS_AD595 return TEMP_AD595(raw); @@ -2367,7 +2379,7 @@ void Temperature::task() { max31865_2.temperature(MAX31865_SENSOR_OHMS_2, MAX31865_CALIBRATION_OHMS_2) ); #else - return (int16_t)raw * 0.25; + return (int16_t)raw * 0.25f; #endif #elif TEMP_SENSOR_2_IS_AD595 return TEMP_AD595(raw); @@ -2444,6 +2456,15 @@ void Temperature::task() { celsius_float_t Temperature::analog_to_celsius_bed(const raw_adc_t raw) { #if TEMP_SENSOR_BED_IS_CUSTOM return user_thermistor_to_deg_c(CTI_BED, raw); + #elif TEMP_SENSOR_IS_MAX_TC(BED) + #if TEMP_SENSOR_BED_IS_MAX31865 + return TERN(LIB_INTERNAL_MAX31865, + max31865_BED.temperature(raw), + max31865_BED.temperature(MAX31865_SENSOR_OHMS_BED, MAX31865_CALIBRATION_OHMS_BED) + ); + #else + return (int16_t)raw * 0.25f; + #endif #elif TEMP_SENSOR_BED_IS_THERMISTOR SCAN_THERMISTOR_TABLE(TEMPTABLE_BED, TEMPTABLE_BED_LEN); #elif TEMP_SENSOR_BED_IS_AD595 @@ -2549,11 +2570,11 @@ void Temperature::task() { #if TEMP_SENSOR_REDUNDANT_IS_CUSTOM return user_thermistor_to_deg_c(CTI_REDUNDANT, raw); #elif TEMP_SENSOR_IS_MAX_TC(REDUNDANT) && REDUNDANT_TEMP_MATCH(SOURCE, E0) - return TERN(TEMP_SENSOR_REDUNDANT_IS_MAX31865, max31865_0.temperature(raw), (int16_t)raw * 0.25); + return TERN(TEMP_SENSOR_REDUNDANT_IS_MAX31865, max31865_0.temperature(raw), (int16_t)raw * 0.25f); #elif TEMP_SENSOR_IS_MAX_TC(REDUNDANT) && REDUNDANT_TEMP_MATCH(SOURCE, E1) - return TERN(TEMP_SENSOR_REDUNDANT_IS_MAX31865, max31865_1.temperature(raw), (int16_t)raw * 0.25); + return TERN(TEMP_SENSOR_REDUNDANT_IS_MAX31865, max31865_1.temperature(raw), (int16_t)raw * 0.25f); #elif TEMP_SENSOR_IS_MAX_TC(REDUNDANT) && REDUNDANT_TEMP_MATCH(SOURCE, E2) - return TERN(TEMP_SENSOR_REDUNDANT_IS_MAX31865, max31865_2.temperature(raw), (int16_t)raw * 0.25); + return TERN(TEMP_SENSOR_REDUNDANT_IS_MAX31865, max31865_2.temperature(raw), (int16_t)raw * 0.25f); #elif TEMP_SENSOR_REDUNDANT_IS_THERMISTOR SCAN_THERMISTOR_TABLE(TEMPTABLE_REDUNDANT, TEMPTABLE_REDUNDANT_LEN); #elif TEMP_SENSOR_REDUNDANT_IS_AD595 @@ -2595,6 +2616,9 @@ void Temperature::updateTemperaturesFromRawValues() { #if TEMP_SENSOR_IS_MAX_TC(REDUNDANT) temp_redundant.setraw(READ_MAX_TC(HEATER_ID(TEMP_SENSOR_REDUNDANT_SOURCE))); #endif + #if TEMP_SENSOR_IS_MAX_TC(BED) + temp_bed.setraw(read_max_tc_bed()); + #endif #if HAS_HOTEND HOTEND_LOOP() temp_hotend[e].celsius = analog_to_celsius_hotend(temp_hotend[e].getraw(), e); @@ -2763,6 +2787,17 @@ void Temperature::init() { ); #endif + #if TEMP_SENSOR_IS_MAX(BED, 6675) && HAS_MAX6675_LIBRARY + max6675_BED.begin(); + #elif TEMP_SENSOR_IS_MAX(BED, 31855) && HAS_MAX31855_LIBRARY + max31855_BED.begin(); + #elif TEMP_SENSOR_IS_MAX(BED, 31865) + max31865_BED.begin( + MAX31865_WIRES(MAX31865_SENSOR_WIRES_BED) // MAX31865_BEDWIRE, MAX31865_3WIRE, MAX31865_4WIRE + OPTARG(LIB_INTERNAL_MAX31865, MAX31865_SENSOR_OHMS_BED, MAX31865_CALIBRATION_OHMS_BED, MAX31865_WIRE_OHMS_BED) + ); + #endif + #undef MAX31865_WIRES #undef _MAX31865_WIRES #endif @@ -3321,6 +3356,8 @@ void Temperature::disable_all_heaters() { #if HAS_MAX_TC + typedef TERN(HAS_MAX31855, uint32_t, uint16_t) max_tc_temp_t; + #ifndef THERMOCOUPLE_MAX_ERRORS #define THERMOCOUPLE_MAX_ERRORS 15 #endif @@ -3420,12 +3457,10 @@ void Temperature::disable_all_heaters() { MAX6675 &max6675ref = THERMO_SEL(max6675_0, max6675_1, max6675_2); max_tc_temp = max6675ref.readRaw16(); #endif - #if HAS_MAX31855_LIBRARY MAX31855 &max855ref = THERMO_SEL(max31855_0, max31855_1, max31855_2); max_tc_temp = max855ref.readRaw32(); #endif - #if HAS_MAX31865 MAX31865 &max865ref = THERMO_SEL(max31865_0, max31865_1, max31865_2); max_tc_temp = TERN(LIB_INTERNAL_MAX31865, max865ref.readRaw(), max865ref.readRTD_with_Fault()); @@ -3442,30 +3477,21 @@ void Temperature::disable_all_heaters() { SERIAL_ECHOPGM("Temp measurement error! "); #if HAS_MAX31855 SERIAL_ECHOPGM("MAX31855 Fault: (", max_tc_temp & 0x7, ") >> "); - if (max_tc_temp & 0x1) - SERIAL_ECHOLNPGM("Open Circuit"); - else if (max_tc_temp & 0x2) - SERIAL_ECHOLNPGM("Short to GND"); - else if (max_tc_temp & 0x4) - SERIAL_ECHOLNPGM("Short to VCC"); + if (max_tc_temp & 0x1) SERIAL_ECHOLNPGM("Open Circuit"); + else if (max_tc_temp & 0x2) SERIAL_ECHOLNPGM("Short to GND"); + else if (max_tc_temp & 0x4) SERIAL_ECHOLNPGM("Short to VCC"); #elif HAS_MAX31865 const uint8_t fault_31865 = max865ref.readFault(); max865ref.clearFault(); if (fault_31865) { SERIAL_EOL(); SERIAL_ECHOLNPGM("\nMAX31865 Fault: (", fault_31865, ") >>"); - if (fault_31865 & MAX31865_FAULT_HIGHTHRESH) - SERIAL_ECHOLNPGM("RTD High Threshold"); - if (fault_31865 & MAX31865_FAULT_LOWTHRESH) - SERIAL_ECHOLNPGM("RTD Low Threshold"); - if (fault_31865 & MAX31865_FAULT_REFINLOW) - SERIAL_ECHOLNPGM("REFIN- > 0.85 x V bias"); - if (fault_31865 & MAX31865_FAULT_REFINHIGH) - SERIAL_ECHOLNPGM("REFIN- < 0.85 x V bias (FORCE- open)"); - if (fault_31865 & MAX31865_FAULT_RTDINLOW) - SERIAL_ECHOLNPGM("REFIN- < 0.85 x V bias (FORCE- open)"); - if (fault_31865 & MAX31865_FAULT_OVUV) - SERIAL_ECHOLNPGM("Under/Over voltage"); + if (fault_31865 & MAX31865_FAULT_HIGHTHRESH) SERIAL_ECHOLNPGM("RTD High Threshold"); + if (fault_31865 & MAX31865_FAULT_LOWTHRESH) SERIAL_ECHOLNPGM("RTD Low Threshold"); + if (fault_31865 & MAX31865_FAULT_REFINLOW) SERIAL_ECHOLNPGM("REFIN- > 0.85 x V bias"); + if (fault_31865 & MAX31865_FAULT_REFINHIGH) SERIAL_ECHOLNPGM("REFIN- < 0.85 x V bias (FORCE- open)"); + if (fault_31865 & MAX31865_FAULT_RTDINLOW) SERIAL_ECHOLNPGM("REFIN- < 0.85 x V bias (FORCE- open)"); + if (fault_31865 & MAX31865_FAULT_OVUV) SERIAL_ECHOLNPGM("Under/Over voltage"); } #else // MAX6675 SERIAL_ECHOLNPGM("MAX6675 Fault: Open Circuit"); @@ -3493,6 +3519,124 @@ void Temperature::disable_all_heaters() { #endif // HAS_MAX_TC +#if TEMP_SENSOR_IS_MAX_TC(BED) + /** + * @brief Read MAX Thermocouple temperature. + * + * Reads the thermocouple board via HW or SW SPI, using a library (LIB_USR_x) or raw SPI reads. + * Doesn't strictly return a temperature; returns an "ADC Value" (i.e. raw register content). + * + * @return integer representing the board's buffer, to be converted later if needed + */ + raw_adc_t Temperature::read_max_tc_bed() { + #define MAXTC_HEAT_INTERVAL 250UL + + #if TEMP_SENSOR_BED_IS_MAX31855 + #define BED_MAX_TC_ERROR_MASK 7 // D2-0: SCV, SCG, OC + #define BED_MAX_TC_DISCARD_BITS 18 // Data D31-18; sign bit D31 + #define BED_MAX_TC_SPEED_BITS 3 // ~1MHz + #elif TEMP_SENSOR_BED_IS_MAX31865 + #define BED_MAX_TC_ERROR_MASK 1 // D0 Bit on fault only + #define BED_MAX_TC_DISCARD_BITS 1 // Data is in D15-D1 + #define BED_MAX_TC_SPEED_BITS 3 // ~1MHz + #else // MAX6675 + #define BED_MAX_TC_ERROR_MASK 3 // D2 only; 1 = open circuit + #define BED_MAX_TC_DISCARD_BITS 3 // Data D15-D1 + #define BED_MAX_TC_SPEED_BITS 2 // ~2MHz + #endif + + static max_tc_temp_t max_tc_temp = TEMP_SENSOR_BED_MAX_TC_TMAX; + + static uint8_t max_tc_errors = 0; + static millis_t next_max_tc_ms = 0; + + // Return last-read value between readings + const millis_t ms = millis(); + if (PENDING(ms, next_max_tc_ms)) return max_tc_temp; + next_max_tc_ms = ms + MAXTC_HEAT_INTERVAL; + + #if !HAS_MAXTC_LIBRARIES + max_tc_temp = 0; + + #if !HAS_MAXTC_SW_SPI + // Initialize SPI using the default Hardware SPI bus. + // FIXME: spiBegin, spiRec and spiInit doesn't work when soft spi is used. + spiBegin(); + spiInit(BED_MAX_TC_SPEED_BITS); + #endif + + WRITE(TEMP_BED_CS_PIN, LOW); // Enable MAXTC + DELAY_NS(100); // Ensure 100ns delay + + // Read a big-endian temperature value without using a library + for (uint8_t i = sizeof(max_tc_temp); i--;) { + max_tc_temp |= TERN(HAS_MAXTC_SW_SPI, max_tc_spi.receive(), spiRec()); + if (i > 0) max_tc_temp <<= 8; // shift left if not the last byte + } + + WRITE(TEMP_BED_CS_PIN, HIGH); // Disable MAXTC + + #elif ALL(TEMP_SENSOR_BED_IS_MAX6675, HAS_MAX6675_LIBRARY) + MAX6675 &max6675ref = max6675_BED; + max_tc_temp = max6675ref.readRaw16(); + #elif ALL(TEMP_SENSOR_BED_IS_MAX31855, HAS_MAX31855_LIBRARY) + MAX31855 &max855ref = max31855_BED; + max_tc_temp = max855ref.readRaw32(); + #elif TEMP_SENSOR_BED_IS_MAX31865 + MAX31865 &max865ref = max31865_BED; + max_tc_temp = TERN(LIB_INTERNAL_MAX31865, max865ref.readRaw(), max865ref.readRTD_with_Fault()); + #endif + + // Handle an error. If there have been more than THERMOCOUPLE_MAX_ERRORS, send an error over serial. + // Either way, return the TMAX for the thermocouple to trigger a maxtemp_error() + if (max_tc_temp & BED_MAX_TC_ERROR_MASK) { + max_tc_errors++; + + if (max_tc_errors > THERMOCOUPLE_MAX_ERRORS) { + SERIAL_ERROR_START(); + SERIAL_ECHOPGM("Bed temp measurement error! "); + #if TEMP_SENSOR_BED_IS_MAX31855 + SERIAL_ECHOPGM("MAX31855 Fault: (", max_tc_temp & 0x7, ") >> "); + if (max_tc_temp & 0x1) SERIAL_ECHOLNPGM("Open Circuit"); + else if (max_tc_temp & 0x2) SERIAL_ECHOLNPGM("Short to GND"); + else if (max_tc_temp & 0x4) SERIAL_ECHOLNPGM("Short to VCC"); + #elif TEMP_SENSOR_BED_IS_MAX31865 + const uint8_t fault_31865 = max865ref.readFault(); + max865ref.clearFault(); + if (fault_31865) { + SERIAL_EOL(); + SERIAL_ECHOLNPGM("\nMAX31865 Fault: (", fault_31865, ") >>"); + if (fault_31865 & MAX31865_FAULT_HIGHTHRESH) SERIAL_ECHOLNPGM("RTD High Threshold"); + if (fault_31865 & MAX31865_FAULT_LOWTHRESH) SERIAL_ECHOLNPGM("RTD Low Threshold"); + if (fault_31865 & MAX31865_FAULT_REFINLOW) SERIAL_ECHOLNPGM("REFIN- > 0.85 x V bias"); + if (fault_31865 & MAX31865_FAULT_REFINHIGH) SERIAL_ECHOLNPGM("REFIN- < 0.85 x V bias (FORCE- open)"); + if (fault_31865 & MAX31865_FAULT_RTDINLOW) SERIAL_ECHOLNPGM("REFIN- < 0.85 x V bias (FORCE- open)"); + if (fault_31865 & MAX31865_FAULT_OVUV) SERIAL_ECHOLNPGM("Under/Over voltage"); + } + #else // MAX6675 + SERIAL_ECHOLNPGM("MAX6675 Fault: Open Circuit"); + #endif + + // Set thermocouple above max temperature (TMAX) + max_tc_temp = TEMP_SENSOR_BED_MAX_TC_TMAX << (BED_MAX_TC_DISCARD_BITS + 1); + } + } + else { + max_tc_errors = 0; // No error bit, reset error count + } + + max_tc_temp >>= BED_MAX_TC_DISCARD_BITS; + + #if TEMP_SENSOR_BED_IS_MAX31855 + // Support negative temperature for MAX38155 + if (max_tc_temp & 0x00002000) max_tc_temp |= 0xFFFFC000; + #endif + + return max_tc_temp; + } + +#endif // TEMP_SENSOR_IS_MAX_TC(BED) + /** * Update raw temperatures * @@ -3518,13 +3662,16 @@ void Temperature::update_raw_temperatures() { temp_redundant.update(); #endif + #if HAS_TEMP_ADC_BED && !TEMP_SENSOR_IS_MAX_TC(BED) + temp_bed.update(); + #endif + TERN_(HAS_TEMP_ADC_2, temp_hotend[2].update()); TERN_(HAS_TEMP_ADC_3, temp_hotend[3].update()); TERN_(HAS_TEMP_ADC_4, temp_hotend[4].update()); TERN_(HAS_TEMP_ADC_5, temp_hotend[5].update()); TERN_(HAS_TEMP_ADC_6, temp_hotend[6].update()); TERN_(HAS_TEMP_ADC_7, temp_hotend[7].update()); - TERN_(HAS_TEMP_ADC_BED, temp_bed.update()); TERN_(HAS_TEMP_ADC_CHAMBER, temp_chamber.update()); TERN_(HAS_TEMP_ADC_PROBE, temp_probe.update()); TERN_(HAS_TEMP_ADC_COOLER, temp_cooler.update()); diff --git a/Marlin/src/module/temperature.h b/Marlin/src/module/temperature.h index d5a27a8671c6..d174bfd11dbd 100644 --- a/Marlin/src/module/temperature.h +++ b/Marlin/src/module/temperature.h @@ -1335,15 +1335,16 @@ class Temperature { // MAX Thermocouples #if HAS_MAX_TC - #define MAX_TC_COUNT TEMP_SENSOR_IS_MAX_TC(0) + TEMP_SENSOR_IS_MAX_TC(1) + TEMP_SENSOR_IS_MAX_TC(REDUNDANT) + #define MAX_TC_COUNT TEMP_SENSOR_IS_MAX_TC(0) + TEMP_SENSOR_IS_MAX_TC(1) + TEMP_SENSOR_IS_MAX_TC(2) + TEMP_SENSOR_IS_MAX_TC(REDUNDANT) #if MAX_TC_COUNT > 1 #define HAS_MULTI_MAX_TC 1 - #define READ_MAX_TC(N) read_max_tc(N) - #else - #define READ_MAX_TC(N) read_max_tc() #endif + #define READ_MAX_TC(N) read_max_tc(TERN_(HAS_MULTI_MAX_TC, N)) static raw_adc_t read_max_tc(TERN_(HAS_MULTI_MAX_TC, const uint8_t hindex=0)); #endif + #if TEMP_SENSOR_IS_MAX_TC(BED) + static raw_adc_t read_max_tc_bed(); + #endif #if HAS_AUTO_FAN #if ENABLED(POWER_OFF_WAIT_FOR_COOLDOWN) From 7d334775d0d7f038c03afe5f93d8befd34d12dcb Mon Sep 17 00:00:00 2001 From: ellensp <530024+ellensp@users.noreply.github.com> Date: Sun, 26 Nov 2023 23:05:50 +1300 Subject: [PATCH 23/77] Update MinSerial.cpp Add missing commas --- Marlin/src/HAL/STM32/MinSerial.cpp | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/Marlin/src/HAL/STM32/MinSerial.cpp b/Marlin/src/HAL/STM32/MinSerial.cpp index f1fc806acb2c..4f2033299a24 100644 --- a/Marlin/src/HAL/STM32/MinSerial.cpp +++ b/Marlin/src/HAL/STM32/MinSerial.cpp @@ -53,9 +53,9 @@ struct USARTMin { 0x40004800, // USART3 0x40004C00, // UART4_BASE 0x40005000, // UART5_BASE - 0x40011400 // USART6 - 0x40007800 // UART7_BASE - 0x40007C00 // UART8_BASE + 0x40011400, // USART6 + 0x40007800, // UART7_BASE + 0x40007C00, // UART8_BASE 0x40011800 // UART9_BASE }; static USARTMin * regs = (USARTMin*)regsAddr[SERIAL_PORT - 1]; From 9a12f06f199e86ca18ff2d40119805330c4ff6c6 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 25 Nov 2023 21:17:18 -0600 Subject: [PATCH 24/77] =?UTF-8?q?=F0=9F=8E=A8=20Update=20file=20headers?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Marlin is collectively © by the Organization, with individual contributors having © on their original work as documented in the commit history. --- Marlin/src/HAL/AVR/HAL.h | 4 +++- Marlin/src/HAL/AVR/timers.h | 4 +++- Marlin/src/HAL/DUE/HAL.cpp | 4 +++- Marlin/src/HAL/DUE/HAL.h | 6 +++--- Marlin/src/HAL/DUE/eeprom_flash.cpp | 7 +++---- Marlin/src/HAL/DUE/eeprom_wired.cpp | 7 +++---- Marlin/src/HAL/DUE/timers.cpp | 6 +++--- Marlin/src/HAL/DUE/timers.h | 5 +++-- Marlin/src/HAL/ESP32/HAL.h | 4 +++- Marlin/src/HAL/ESP32/HAL_SPI.cpp | 1 - Marlin/src/HAL/ESP32/ota.cpp | 4 +++- Marlin/src/HAL/ESP32/ota.h | 4 +++- Marlin/src/HAL/LINUX/HAL.h | 6 +++--- Marlin/src/HAL/LINUX/timers.cpp | 6 +++--- Marlin/src/HAL/LINUX/timers.h | 5 +++-- Marlin/src/HAL/LPC1768/HAL.h | 6 +++--- Marlin/src/HAL/LPC1768/timers.cpp | 6 +++--- Marlin/src/HAL/LPC1768/timers.h | 5 +++-- Marlin/src/HAL/NATIVE_SIM/HAL.h | 6 +++--- Marlin/src/HAL/NATIVE_SIM/MarlinSPI.h | 6 +++--- Marlin/src/HAL/NATIVE_SIM/pinsDebug.cpp | 3 +++ Marlin/src/HAL/NATIVE_SIM/pinsDebug.h | 3 +++ Marlin/src/HAL/NATIVE_SIM/tft/xpt2046.h | 3 +++ Marlin/src/HAL/NATIVE_SIM/timers.h | 5 +++-- Marlin/src/HAL/SAMD21/inc/Conditionals_LCD.h | 1 - Marlin/src/HAL/STM32/HAL.cpp | 7 +++---- Marlin/src/HAL/STM32/HAL.h | 7 +++---- Marlin/src/HAL/STM32/HAL_SPI.cpp | 1 - Marlin/src/HAL/STM32/MinSerial.cpp | 1 - Marlin/src/HAL/STM32/Servo.cpp | 1 - Marlin/src/HAL/STM32/Servo.h | 1 - Marlin/src/HAL/STM32/eeprom_flash.cpp | 7 +++---- Marlin/src/HAL/STM32/eeprom_sram.cpp | 7 +++---- Marlin/src/HAL/STM32/eeprom_wired.cpp | 7 +++---- Marlin/src/HAL/STM32/endstop_interrupts.h | 1 - Marlin/src/HAL/STM32/fastio.cpp | 1 - Marlin/src/HAL/STM32/fastio.h | 1 - Marlin/src/HAL/STM32/msc_sd.cpp | 9 ++++++++- Marlin/src/HAL/STM32/msc_sd.h | 9 ++++++++- Marlin/src/HAL/STM32/timers.cpp | 6 +++--- Marlin/src/HAL/STM32/timers.h | 6 +++--- Marlin/src/HAL/STM32F1/HAL.cpp | 7 +++---- Marlin/src/HAL/STM32F1/HAL.h | 7 +++---- Marlin/src/HAL/STM32F1/HAL_SPI.cpp | 1 - Marlin/src/HAL/STM32F1/MinSerial.cpp | 1 - Marlin/src/HAL/STM32F1/Servo.cpp | 1 - Marlin/src/HAL/STM32F1/Servo.h | 1 - Marlin/src/HAL/STM32F1/eeprom_flash.cpp | 7 +++---- Marlin/src/HAL/STM32F1/endstop_interrupts.h | 1 - Marlin/src/HAL/STM32F1/fastio.h | 1 - Marlin/src/HAL/STM32F1/msc_sd.cpp | 9 ++++++++- Marlin/src/HAL/STM32F1/msc_sd.h | 9 ++++++++- Marlin/src/HAL/STM32F1/onboard_sd.cpp | 3 +++ Marlin/src/HAL/STM32F1/sdio.cpp | 1 - Marlin/src/HAL/STM32F1/sdio.h | 6 +++--- Marlin/src/HAL/STM32F1/timers.cpp | 6 +++--- Marlin/src/HAL/STM32F1/timers.h | 6 +++--- Marlin/src/HAL/TEENSY31_32/HAL.h | 6 +++--- Marlin/src/HAL/TEENSY35_36/HAL.h | 6 +++--- Marlin/src/HAL/TEENSY35_36/eeprom.cpp | 7 +++---- Marlin/src/HAL/TEENSY35_36/timers.h | 5 +++-- Marlin/src/HAL/TEENSY40_41/HAL.h | 6 +++--- Marlin/src/HAL/TEENSY40_41/eeprom.cpp | 7 +++---- Marlin/src/HAL/TEENSY40_41/fastio.h | 1 - Marlin/src/HAL/TEENSY40_41/timers.h | 5 +++-- Marlin/src/HAL/shared/cpu_exception/exception_arm.cpp | 1 - Marlin/src/HAL/shared/eeprom_api.cpp | 7 +++---- Marlin/src/HAL/shared/eeprom_api.h | 7 +++---- Marlin/src/HAL/shared/eeprom_if.h | 6 +++--- Marlin/src/lcd/dogm/fontdata/langdata.h | 3 +++ .../cocoa_press/_bootscreen_landscape.h | 1 - Marlin/src/lcd/tft/images/time_elapsed_32x32x4.cpp | 3 +++ Marlin/src/lcd/tft/images/time_remaining_32x32x4.cpp | 3 +++ Marlin/src/pins/mega/pins_WEEDO_62A.h | 1 - Marlin/src/sd/usb_flashdrive/lib-uhs2/masstorage.h | 1 - Marlin/src/sd/usb_flashdrive/lib-uhs2/settings.h | 1 - 76 files changed, 182 insertions(+), 151 deletions(-) diff --git a/Marlin/src/HAL/AVR/HAL.h b/Marlin/src/HAL/AVR/HAL.h index 7d5e1000d797..3c883b645c20 100644 --- a/Marlin/src/HAL/AVR/HAL.h +++ b/Marlin/src/HAL/AVR/HAL.h @@ -1,7 +1,9 @@ /** * Marlin 3D Printer Firmware * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.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 diff --git a/Marlin/src/HAL/AVR/timers.h b/Marlin/src/HAL/AVR/timers.h index d9cdfc4f0131..94b17f310270 100644 --- a/Marlin/src/HAL/AVR/timers.h +++ b/Marlin/src/HAL/AVR/timers.h @@ -1,7 +1,9 @@ /** * Marlin 3D Printer Firmware * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.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 diff --git a/Marlin/src/HAL/DUE/HAL.cpp b/Marlin/src/HAL/DUE/HAL.cpp index 1b57bdb2fad4..763091cb009a 100644 --- a/Marlin/src/HAL/DUE/HAL.cpp +++ b/Marlin/src/HAL/DUE/HAL.cpp @@ -1,7 +1,9 @@ /** * Marlin 3D Printer Firmware * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.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 diff --git a/Marlin/src/HAL/DUE/HAL.h b/Marlin/src/HAL/DUE/HAL.h index 7b9285488fd9..49a8be3fe7bb 100644 --- a/Marlin/src/HAL/DUE/HAL.h +++ b/Marlin/src/HAL/DUE/HAL.h @@ -1,9 +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 + * + * 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 diff --git a/Marlin/src/HAL/DUE/eeprom_flash.cpp b/Marlin/src/HAL/DUE/eeprom_flash.cpp index 607764155b0a..a0ed6cc84347 100644 --- a/Marlin/src/HAL/DUE/eeprom_flash.cpp +++ b/Marlin/src/HAL/DUE/eeprom_flash.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 diff --git a/Marlin/src/HAL/DUE/eeprom_wired.cpp b/Marlin/src/HAL/DUE/eeprom_wired.cpp index 557a2f2cffa5..24f8c06d2e1b 100644 --- a/Marlin/src/HAL/DUE/eeprom_wired.cpp +++ b/Marlin/src/HAL/DUE/eeprom_wired.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 diff --git a/Marlin/src/HAL/DUE/timers.cpp b/Marlin/src/HAL/DUE/timers.cpp index e5647817b6f0..e388255c0808 100644 --- a/Marlin/src/HAL/DUE/timers.cpp +++ b/Marlin/src/HAL/DUE/timers.cpp @@ -1,9 +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 + * + * 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 diff --git a/Marlin/src/HAL/DUE/timers.h b/Marlin/src/HAL/DUE/timers.h index dc35c77e6384..db5d83a06f74 100644 --- a/Marlin/src/HAL/DUE/timers.h +++ b/Marlin/src/HAL/DUE/timers.h @@ -1,8 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.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 diff --git a/Marlin/src/HAL/ESP32/HAL.h b/Marlin/src/HAL/ESP32/HAL.h index 97ed4d1e4f0b..0acb3676a2f9 100644 --- a/Marlin/src/HAL/ESP32/HAL.h +++ b/Marlin/src/HAL/ESP32/HAL.h @@ -1,7 +1,9 @@ /** * Marlin 3D Printer Firmware * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.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 diff --git a/Marlin/src/HAL/ESP32/HAL_SPI.cpp b/Marlin/src/HAL/ESP32/HAL_SPI.cpp index 6dc540864eec..e5302bb90553 100644 --- a/Marlin/src/HAL/ESP32/HAL_SPI.cpp +++ b/Marlin/src/HAL/ESP32/HAL_SPI.cpp @@ -4,7 +4,6 @@ * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * Copyright (c) 2017 Victor Perez * * 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 diff --git a/Marlin/src/HAL/ESP32/ota.cpp b/Marlin/src/HAL/ESP32/ota.cpp index c5c3082c30cb..01f5924871ff 100644 --- a/Marlin/src/HAL/ESP32/ota.cpp +++ b/Marlin/src/HAL/ESP32/ota.cpp @@ -1,7 +1,9 @@ /** * Marlin 3D Printer Firmware * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.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 diff --git a/Marlin/src/HAL/ESP32/ota.h b/Marlin/src/HAL/ESP32/ota.h index 546ace82dbb8..a91d04dbb742 100644 --- a/Marlin/src/HAL/ESP32/ota.h +++ b/Marlin/src/HAL/ESP32/ota.h @@ -1,7 +1,9 @@ /** * Marlin 3D Printer Firmware * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.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 diff --git a/Marlin/src/HAL/LINUX/HAL.h b/Marlin/src/HAL/LINUX/HAL.h index d1c0cbe7ae36..e84516d4dca9 100644 --- a/Marlin/src/HAL/LINUX/HAL.h +++ b/Marlin/src/HAL/LINUX/HAL.h @@ -1,9 +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 + * + * 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 diff --git a/Marlin/src/HAL/LINUX/timers.cpp b/Marlin/src/HAL/LINUX/timers.cpp index 66d80f25185a..a8ab40319773 100644 --- a/Marlin/src/HAL/LINUX/timers.cpp +++ b/Marlin/src/HAL/LINUX/timers.cpp @@ -1,9 +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 + * + * 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 diff --git a/Marlin/src/HAL/LINUX/timers.h b/Marlin/src/HAL/LINUX/timers.h index 2d2a95774c1b..2b29edce0bb4 100644 --- a/Marlin/src/HAL/LINUX/timers.h +++ b/Marlin/src/HAL/LINUX/timers.h @@ -1,8 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.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 diff --git a/Marlin/src/HAL/LPC1768/HAL.h b/Marlin/src/HAL/LPC1768/HAL.h index c9b7a0739479..ab28e06eb89e 100644 --- a/Marlin/src/HAL/LPC1768/HAL.h +++ b/Marlin/src/HAL/LPC1768/HAL.h @@ -1,9 +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 + * + * 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 diff --git a/Marlin/src/HAL/LPC1768/timers.cpp b/Marlin/src/HAL/LPC1768/timers.cpp index bbb13f81da05..b541ab6e6a25 100644 --- a/Marlin/src/HAL/LPC1768/timers.cpp +++ b/Marlin/src/HAL/LPC1768/timers.cpp @@ -1,9 +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 + * + * 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 diff --git a/Marlin/src/HAL/LPC1768/timers.h b/Marlin/src/HAL/LPC1768/timers.h index c6d7bc632e2e..bae01703ed85 100644 --- a/Marlin/src/HAL/LPC1768/timers.h +++ b/Marlin/src/HAL/LPC1768/timers.h @@ -1,8 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.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 diff --git a/Marlin/src/HAL/NATIVE_SIM/HAL.h b/Marlin/src/HAL/NATIVE_SIM/HAL.h index 58f084af8529..8e88e5023026 100644 --- a/Marlin/src/HAL/NATIVE_SIM/HAL.h +++ b/Marlin/src/HAL/NATIVE_SIM/HAL.h @@ -1,9 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.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 diff --git a/Marlin/src/HAL/NATIVE_SIM/MarlinSPI.h b/Marlin/src/HAL/NATIVE_SIM/MarlinSPI.h index b5cc6f02a45a..0c447ba4cb3d 100644 --- a/Marlin/src/HAL/NATIVE_SIM/MarlinSPI.h +++ b/Marlin/src/HAL/NATIVE_SIM/MarlinSPI.h @@ -1,9 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com - * Copyright (c) 2015-2016 Nico Tonnhofer wurstnase.reprap@gmail.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 diff --git a/Marlin/src/HAL/NATIVE_SIM/pinsDebug.cpp b/Marlin/src/HAL/NATIVE_SIM/pinsDebug.cpp index e75826c58a8c..c4d56c6c218d 100644 --- a/Marlin/src/HAL/NATIVE_SIM/pinsDebug.cpp +++ b/Marlin/src/HAL/NATIVE_SIM/pinsDebug.cpp @@ -2,6 +2,9 @@ * 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 diff --git a/Marlin/src/HAL/NATIVE_SIM/pinsDebug.h b/Marlin/src/HAL/NATIVE_SIM/pinsDebug.h index 28821acbd07c..3321d1484dbe 100644 --- a/Marlin/src/HAL/NATIVE_SIM/pinsDebug.h +++ b/Marlin/src/HAL/NATIVE_SIM/pinsDebug.h @@ -2,6 +2,9 @@ * 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 diff --git a/Marlin/src/HAL/NATIVE_SIM/tft/xpt2046.h b/Marlin/src/HAL/NATIVE_SIM/tft/xpt2046.h index 43a0791e0a23..d37f74c7744b 100644 --- a/Marlin/src/HAL/NATIVE_SIM/tft/xpt2046.h +++ b/Marlin/src/HAL/NATIVE_SIM/tft/xpt2046.h @@ -2,6 +2,9 @@ * 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 diff --git a/Marlin/src/HAL/NATIVE_SIM/timers.h b/Marlin/src/HAL/NATIVE_SIM/timers.h index be38d583b686..d46e8e7b9402 100644 --- a/Marlin/src/HAL/NATIVE_SIM/timers.h +++ b/Marlin/src/HAL/NATIVE_SIM/timers.h @@ -1,8 +1,9 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.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 diff --git a/Marlin/src/HAL/SAMD21/inc/Conditionals_LCD.h b/Marlin/src/HAL/SAMD21/inc/Conditionals_LCD.h index 9d58e454327f..570baf7e95e5 100644 --- a/Marlin/src/HAL/SAMD21/inc/Conditionals_LCD.h +++ b/Marlin/src/HAL/SAMD21/inc/Conditionals_LCD.h @@ -19,5 +19,4 @@ * along with this program. If not, see . * */ - #pragma once diff --git a/Marlin/src/HAL/STM32/HAL.cpp b/Marlin/src/HAL/STM32/HAL.cpp index ce49f27a8ed2..610bd0b243bd 100644 --- a/Marlin/src/HAL/STM32/HAL.cpp +++ b/Marlin/src/HAL/STM32/HAL.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) 2017 Victor Perez + * + * 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 diff --git a/Marlin/src/HAL/STM32/HAL.h b/Marlin/src/HAL/STM32/HAL.h index 37a718b08dbe..b3430f333987 100644 --- a/Marlin/src/HAL/STM32/HAL.h +++ b/Marlin/src/HAL/STM32/HAL.h @@ -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) 2017 Victor Perez + * + * 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 diff --git a/Marlin/src/HAL/STM32/HAL_SPI.cpp b/Marlin/src/HAL/STM32/HAL_SPI.cpp index 278d209c47cb..cc035ecffabc 100644 --- a/Marlin/src/HAL/STM32/HAL_SPI.cpp +++ b/Marlin/src/HAL/STM32/HAL_SPI.cpp @@ -4,7 +4,6 @@ * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * Copyright (c) 2017 Victor Perez * * 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 diff --git a/Marlin/src/HAL/STM32/MinSerial.cpp b/Marlin/src/HAL/STM32/MinSerial.cpp index 4f2033299a24..a27bc35a146b 100644 --- a/Marlin/src/HAL/STM32/MinSerial.cpp +++ b/Marlin/src/HAL/STM32/MinSerial.cpp @@ -4,7 +4,6 @@ * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * Copyright (c) 2017 Victor Perez * * 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 diff --git a/Marlin/src/HAL/STM32/Servo.cpp b/Marlin/src/HAL/STM32/Servo.cpp index a00186e0e79e..4f026ffc6df4 100644 --- a/Marlin/src/HAL/STM32/Servo.cpp +++ b/Marlin/src/HAL/STM32/Servo.cpp @@ -4,7 +4,6 @@ * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * Copyright (c) 2017 Victor Perez * * 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 diff --git a/Marlin/src/HAL/STM32/Servo.h b/Marlin/src/HAL/STM32/Servo.h index 1527e753b661..95ecb5d97762 100644 --- a/Marlin/src/HAL/STM32/Servo.h +++ b/Marlin/src/HAL/STM32/Servo.h @@ -4,7 +4,6 @@ * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * Copyright (c) 2017 Victor Perez * * 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 diff --git a/Marlin/src/HAL/STM32/eeprom_flash.cpp b/Marlin/src/HAL/STM32/eeprom_flash.cpp index 6bd519877d53..69511c6de40c 100644 --- a/Marlin/src/HAL/STM32/eeprom_flash.cpp +++ b/Marlin/src/HAL/STM32/eeprom_flash.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 diff --git a/Marlin/src/HAL/STM32/eeprom_sram.cpp b/Marlin/src/HAL/STM32/eeprom_sram.cpp index 687e7f55c226..9bd84ff4fe27 100644 --- a/Marlin/src/HAL/STM32/eeprom_sram.cpp +++ b/Marlin/src/HAL/STM32/eeprom_sram.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 diff --git a/Marlin/src/HAL/STM32/eeprom_wired.cpp b/Marlin/src/HAL/STM32/eeprom_wired.cpp index cf0468151e5e..6fb9d9b51b7b 100644 --- a/Marlin/src/HAL/STM32/eeprom_wired.cpp +++ b/Marlin/src/HAL/STM32/eeprom_wired.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 diff --git a/Marlin/src/HAL/STM32/endstop_interrupts.h b/Marlin/src/HAL/STM32/endstop_interrupts.h index 0c92053d4219..ab86bf29c220 100644 --- a/Marlin/src/HAL/STM32/endstop_interrupts.h +++ b/Marlin/src/HAL/STM32/endstop_interrupts.h @@ -4,7 +4,6 @@ * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * Copyright (c) 2017 Victor Perez * * 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 diff --git a/Marlin/src/HAL/STM32/fastio.cpp b/Marlin/src/HAL/STM32/fastio.cpp index a4b3ba70c923..f8501545a078 100644 --- a/Marlin/src/HAL/STM32/fastio.cpp +++ b/Marlin/src/HAL/STM32/fastio.cpp @@ -4,7 +4,6 @@ * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * Copyright (c) 2017 Victor Perez * * 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 diff --git a/Marlin/src/HAL/STM32/fastio.h b/Marlin/src/HAL/STM32/fastio.h index 4a489544716f..af2941c49c1a 100644 --- a/Marlin/src/HAL/STM32/fastio.h +++ b/Marlin/src/HAL/STM32/fastio.h @@ -4,7 +4,6 @@ * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * Copyright (c) 2017 Victor Perez * * 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 diff --git a/Marlin/src/HAL/STM32/msc_sd.cpp b/Marlin/src/HAL/STM32/msc_sd.cpp index d7652abdc2ea..5c8bee9c62bc 100644 --- a/Marlin/src/HAL/STM32/msc_sd.cpp +++ b/Marlin/src/HAL/STM32/msc_sd.cpp @@ -1,14 +1,21 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * Copyright (c) 2019 BigTreeTech [https://github.com/bigtreetech] * + * 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 . * diff --git a/Marlin/src/HAL/STM32/msc_sd.h b/Marlin/src/HAL/STM32/msc_sd.h index a8e5349f7cd3..20e738223cd2 100644 --- a/Marlin/src/HAL/STM32/msc_sd.h +++ b/Marlin/src/HAL/STM32/msc_sd.h @@ -1,14 +1,21 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2021 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * Copyright (c) 2019 BigTreeTech [https://github.com/bigtreetech] * + * 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 . * diff --git a/Marlin/src/HAL/STM32/timers.cpp b/Marlin/src/HAL/STM32/timers.cpp index 54506cb4513f..10e0dc43a436 100644 --- a/Marlin/src/HAL/STM32/timers.cpp +++ b/Marlin/src/HAL/STM32/timers.cpp @@ -1,9 +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 + * + * 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 diff --git a/Marlin/src/HAL/STM32/timers.h b/Marlin/src/HAL/STM32/timers.h index 6828998198af..180e24031471 100644 --- a/Marlin/src/HAL/STM32/timers.h +++ b/Marlin/src/HAL/STM32/timers.h @@ -1,9 +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) 2017 Victor Perez + * + * 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 diff --git a/Marlin/src/HAL/STM32F1/HAL.cpp b/Marlin/src/HAL/STM32F1/HAL.cpp index 373116ba39fb..a83c3a23bf7d 100644 --- a/Marlin/src/HAL/STM32F1/HAL.cpp +++ b/Marlin/src/HAL/STM32F1/HAL.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) 2017 Victor Perez + * + * 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 diff --git a/Marlin/src/HAL/STM32F1/HAL.h b/Marlin/src/HAL/STM32F1/HAL.h index a6f8036906f6..c4b90db68a19 100644 --- a/Marlin/src/HAL/STM32F1/HAL.h +++ b/Marlin/src/HAL/STM32F1/HAL.h @@ -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) 2017 Victor Perez + * + * 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 diff --git a/Marlin/src/HAL/STM32F1/HAL_SPI.cpp b/Marlin/src/HAL/STM32F1/HAL_SPI.cpp index abb348d743c5..b5b57536f3f8 100644 --- a/Marlin/src/HAL/STM32F1/HAL_SPI.cpp +++ b/Marlin/src/HAL/STM32F1/HAL_SPI.cpp @@ -4,7 +4,6 @@ * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * Copyright (c) 2017 Victor Perez * * 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 diff --git a/Marlin/src/HAL/STM32F1/MinSerial.cpp b/Marlin/src/HAL/STM32F1/MinSerial.cpp index 6cf68d8d8f45..8fb913325496 100644 --- a/Marlin/src/HAL/STM32F1/MinSerial.cpp +++ b/Marlin/src/HAL/STM32F1/MinSerial.cpp @@ -4,7 +4,6 @@ * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * Copyright (c) 2017 Victor Perez * * 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 diff --git a/Marlin/src/HAL/STM32F1/Servo.cpp b/Marlin/src/HAL/STM32F1/Servo.cpp index 47ffb631cf8f..7aa8fe3d00df 100644 --- a/Marlin/src/HAL/STM32F1/Servo.cpp +++ b/Marlin/src/HAL/STM32F1/Servo.cpp @@ -4,7 +4,6 @@ * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * Copyright (c) 2017 Victor Perez * * 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 diff --git a/Marlin/src/HAL/STM32F1/Servo.h b/Marlin/src/HAL/STM32F1/Servo.h index 745a1c93f07d..ffafc23833e3 100644 --- a/Marlin/src/HAL/STM32F1/Servo.h +++ b/Marlin/src/HAL/STM32F1/Servo.h @@ -4,7 +4,6 @@ * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * Copyright (c) 2017 Victor Perez * * 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 diff --git a/Marlin/src/HAL/STM32F1/eeprom_flash.cpp b/Marlin/src/HAL/STM32F1/eeprom_flash.cpp index e7d9dd29e2c5..48fb2d286cc6 100644 --- a/Marlin/src/HAL/STM32F1/eeprom_flash.cpp +++ b/Marlin/src/HAL/STM32F1/eeprom_flash.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 diff --git a/Marlin/src/HAL/STM32F1/endstop_interrupts.h b/Marlin/src/HAL/STM32F1/endstop_interrupts.h index 6ed920183bb8..d11b3bf50503 100644 --- a/Marlin/src/HAL/STM32F1/endstop_interrupts.h +++ b/Marlin/src/HAL/STM32F1/endstop_interrupts.h @@ -4,7 +4,6 @@ * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * Copyright (c) 2017 Victor Perez * * 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 diff --git a/Marlin/src/HAL/STM32F1/fastio.h b/Marlin/src/HAL/STM32F1/fastio.h index e75254d6929e..5b3ebaa52c49 100644 --- a/Marlin/src/HAL/STM32F1/fastio.h +++ b/Marlin/src/HAL/STM32F1/fastio.h @@ -4,7 +4,6 @@ * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * Copyright (c) 2017 Victor Perez * * 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 diff --git a/Marlin/src/HAL/STM32F1/msc_sd.cpp b/Marlin/src/HAL/STM32F1/msc_sd.cpp index f490c83ed829..067b46eb8bad 100644 --- a/Marlin/src/HAL/STM32F1/msc_sd.cpp +++ b/Marlin/src/HAL/STM32F1/msc_sd.cpp @@ -1,14 +1,21 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * Copyright (c) 2019 BigTreeTech [https://github.com/bigtreetech] * + * 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 . * diff --git a/Marlin/src/HAL/STM32F1/msc_sd.h b/Marlin/src/HAL/STM32F1/msc_sd.h index f4636bdff702..371211efc68a 100644 --- a/Marlin/src/HAL/STM32F1/msc_sd.h +++ b/Marlin/src/HAL/STM32F1/msc_sd.h @@ -1,14 +1,21 @@ /** * Marlin 3D Printer Firmware - * * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * Copyright (c) 2019 BigTreeTech [https://github.com/bigtreetech] * + * 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 . * diff --git a/Marlin/src/HAL/STM32F1/onboard_sd.cpp b/Marlin/src/HAL/STM32F1/onboard_sd.cpp index a3d8dcb2d57e..df5549217d98 100644 --- a/Marlin/src/HAL/STM32F1/onboard_sd.cpp +++ b/Marlin/src/HAL/STM32F1/onboard_sd.cpp @@ -5,6 +5,9 @@ * Copyright (c) 2019 BigTreeTech [https://github.com/bigtreetech] * Copyright (C) 2015, ChaN, all right reserved. * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * * This software is a free software and there is NO WARRANTY. * No restriction on use. You can use, modify and redistribute it for * personal, non-profit or commercial products UNDER YOUR RESPONSIBILITY. diff --git a/Marlin/src/HAL/STM32F1/sdio.cpp b/Marlin/src/HAL/STM32F1/sdio.cpp index 1ab76440b7aa..23f984eff329 100644 --- a/Marlin/src/HAL/STM32F1/sdio.cpp +++ b/Marlin/src/HAL/STM32F1/sdio.cpp @@ -4,7 +4,6 @@ * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * Copyright (c) 2017 Victor Perez * * 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 diff --git a/Marlin/src/HAL/STM32F1/sdio.h b/Marlin/src/HAL/STM32F1/sdio.h index 8777299f01bc..2371601e9920 100644 --- a/Marlin/src/HAL/STM32F1/sdio.h +++ b/Marlin/src/HAL/STM32F1/sdio.h @@ -1,9 +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) 2017 Victor Perez + * + * 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 diff --git a/Marlin/src/HAL/STM32F1/timers.cpp b/Marlin/src/HAL/STM32F1/timers.cpp index 112c730b9acc..12477a458314 100644 --- a/Marlin/src/HAL/STM32F1/timers.cpp +++ b/Marlin/src/HAL/STM32F1/timers.cpp @@ -1,9 +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 + * + * 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 diff --git a/Marlin/src/HAL/STM32F1/timers.h b/Marlin/src/HAL/STM32F1/timers.h index 557522f336a2..f92c32c2a3ef 100644 --- a/Marlin/src/HAL/STM32F1/timers.h +++ b/Marlin/src/HAL/STM32F1/timers.h @@ -1,9 +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) 2017 Victor Perez + * + * 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 diff --git a/Marlin/src/HAL/TEENSY31_32/HAL.h b/Marlin/src/HAL/TEENSY31_32/HAL.h index fe913ed583f5..16594c16a821 100644 --- a/Marlin/src/HAL/TEENSY31_32/HAL.h +++ b/Marlin/src/HAL/TEENSY31_32/HAL.h @@ -1,9 +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 + * + * 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 diff --git a/Marlin/src/HAL/TEENSY35_36/HAL.h b/Marlin/src/HAL/TEENSY35_36/HAL.h index 24dcf2ebabbe..692133400390 100644 --- a/Marlin/src/HAL/TEENSY35_36/HAL.h +++ b/Marlin/src/HAL/TEENSY35_36/HAL.h @@ -1,9 +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 + * + * 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 diff --git a/Marlin/src/HAL/TEENSY35_36/eeprom.cpp b/Marlin/src/HAL/TEENSY35_36/eeprom.cpp index b80e93b536a5..a2afa4534345 100644 --- a/Marlin/src/HAL/TEENSY35_36/eeprom.cpp +++ b/Marlin/src/HAL/TEENSY35_36/eeprom.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 diff --git a/Marlin/src/HAL/TEENSY35_36/timers.h b/Marlin/src/HAL/TEENSY35_36/timers.h index 8af79d73928e..3536b62265f2 100644 --- a/Marlin/src/HAL/TEENSY35_36/timers.h +++ b/Marlin/src/HAL/TEENSY35_36/timers.h @@ -1,8 +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 + * + * 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 diff --git a/Marlin/src/HAL/TEENSY40_41/HAL.h b/Marlin/src/HAL/TEENSY40_41/HAL.h index ddda9be65f1a..fa5971a68102 100644 --- a/Marlin/src/HAL/TEENSY40_41/HAL.h +++ b/Marlin/src/HAL/TEENSY40_41/HAL.h @@ -1,9 +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 + * + * 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 diff --git a/Marlin/src/HAL/TEENSY40_41/eeprom.cpp b/Marlin/src/HAL/TEENSY40_41/eeprom.cpp index 3cd376edce62..87f7dd3cfce5 100644 --- a/Marlin/src/HAL/TEENSY40_41/eeprom.cpp +++ b/Marlin/src/HAL/TEENSY40_41/eeprom.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 diff --git a/Marlin/src/HAL/TEENSY40_41/fastio.h b/Marlin/src/HAL/TEENSY40_41/fastio.h index 52f991dfb85f..179f044c9b85 100644 --- a/Marlin/src/HAL/TEENSY40_41/fastio.h +++ b/Marlin/src/HAL/TEENSY40_41/fastio.h @@ -4,7 +4,6 @@ * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * Copyright (c) 2017 Victor Perez * * 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 diff --git a/Marlin/src/HAL/TEENSY40_41/timers.h b/Marlin/src/HAL/TEENSY40_41/timers.h index 77fe0953d3bd..3c7cda0b4e66 100644 --- a/Marlin/src/HAL/TEENSY40_41/timers.h +++ b/Marlin/src/HAL/TEENSY40_41/timers.h @@ -1,8 +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 + * + * 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 diff --git a/Marlin/src/HAL/shared/cpu_exception/exception_arm.cpp b/Marlin/src/HAL/shared/cpu_exception/exception_arm.cpp index 3c514f58a9c4..d478255678cf 100644 --- a/Marlin/src/HAL/shared/cpu_exception/exception_arm.cpp +++ b/Marlin/src/HAL/shared/cpu_exception/exception_arm.cpp @@ -4,7 +4,6 @@ * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * Copyright (c) 2020 Cyril Russo * * 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 diff --git a/Marlin/src/HAL/shared/eeprom_api.cpp b/Marlin/src/HAL/shared/eeprom_api.cpp index 083ccc70d7c9..62a8f2afbc75 100644 --- a/Marlin/src/HAL/shared/eeprom_api.cpp +++ b/Marlin/src/HAL/shared/eeprom_api.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 diff --git a/Marlin/src/HAL/shared/eeprom_api.h b/Marlin/src/HAL/shared/eeprom_api.h index cd744f82dc79..7be1e72f7ab5 100644 --- a/Marlin/src/HAL/shared/eeprom_api.h +++ b/Marlin/src/HAL/shared/eeprom_api.h @@ -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 diff --git a/Marlin/src/HAL/shared/eeprom_if.h b/Marlin/src/HAL/shared/eeprom_if.h index e496de2a03c6..8b9791e1f804 100644 --- a/Marlin/src/HAL/shared/eeprom_if.h +++ b/Marlin/src/HAL/shared/eeprom_if.h @@ -1,9 +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 + * + * 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 diff --git a/Marlin/src/lcd/dogm/fontdata/langdata.h b/Marlin/src/lcd/dogm/fontdata/langdata.h index 746a3bd0b451..a9e1b6cd94bd 100644 --- a/Marlin/src/lcd/dogm/fontdata/langdata.h +++ b/Marlin/src/lcd/dogm/fontdata/langdata.h @@ -2,6 +2,9 @@ * 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 diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/_bootscreen_landscape.h b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/_bootscreen_landscape.h index e7b06f7bd397..fed407326b17 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/_bootscreen_landscape.h +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/_bootscreen_landscape.h @@ -21,7 +21,6 @@ * 0x0000 and 0xFFFE. A single 0xFFFF in the data stream indicates the * start of a new closed path. */ - #pragma once constexpr float x_min = 0.000000; diff --git a/Marlin/src/lcd/tft/images/time_elapsed_32x32x4.cpp b/Marlin/src/lcd/tft/images/time_elapsed_32x32x4.cpp index b5d35e1dbc6c..74947f9ce527 100644 --- a/Marlin/src/lcd/tft/images/time_elapsed_32x32x4.cpp +++ b/Marlin/src/lcd/tft/images/time_elapsed_32x32x4.cpp @@ -2,6 +2,9 @@ * Marlin 3D Printer Firmware * Copyright (c) 2022 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 diff --git a/Marlin/src/lcd/tft/images/time_remaining_32x32x4.cpp b/Marlin/src/lcd/tft/images/time_remaining_32x32x4.cpp index 8b433cfbe8ba..aa3db491643a 100644 --- a/Marlin/src/lcd/tft/images/time_remaining_32x32x4.cpp +++ b/Marlin/src/lcd/tft/images/time_remaining_32x32x4.cpp @@ -2,6 +2,9 @@ * Marlin 3D Printer Firmware * Copyright (c) 2022 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 diff --git a/Marlin/src/pins/mega/pins_WEEDO_62A.h b/Marlin/src/pins/mega/pins_WEEDO_62A.h index d13de7ed3077..f3adf5eab8b8 100644 --- a/Marlin/src/pins/mega/pins_WEEDO_62A.h +++ b/Marlin/src/pins/mega/pins_WEEDO_62A.h @@ -25,7 +25,6 @@ * Copyright (c) 2019 WEEDO3D Perron * ATmega2560 */ - #pragma once #include "env_validate.h" diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs2/masstorage.h b/Marlin/src/sd/usb_flashdrive/lib-uhs2/masstorage.h index aafb91624b00..fa56b6857368 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs2/masstorage.h +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs2/masstorage.h @@ -22,7 +22,6 @@ * Web : https://www.circuitsathome.com * e-mail : support@circuitsathome.com */ - #pragma once // Cruft removal, makes driver smaller, faster. diff --git a/Marlin/src/sd/usb_flashdrive/lib-uhs2/settings.h b/Marlin/src/sd/usb_flashdrive/lib-uhs2/settings.h index 268c0e1d1dcd..1d46dc69b395 100644 --- a/Marlin/src/sd/usb_flashdrive/lib-uhs2/settings.h +++ b/Marlin/src/sd/usb_flashdrive/lib-uhs2/settings.h @@ -22,7 +22,6 @@ * Web : https://www.circuitsathome.com * e-mail : support@circuitsathome.com */ - #pragma once #include "../../../inc/MarlinConfig.h" From 8a110b80bf859a0e038a3a8f4e4febff48cb80e2 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 26 Nov 2023 14:26:20 -0600 Subject: [PATCH 25/77] =?UTF-8?q?=E2=9C=85=20Use=20Python=203.9=20for=20CI?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .github/workflows/test-builds.yml | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/.github/workflows/test-builds.yml b/.github/workflows/test-builds.yml index 44554f8b7a49..ca1fa12bbb46 100644 --- a/.github/workflows/test-builds.yml +++ b/.github/workflows/test-builds.yml @@ -144,7 +144,7 @@ jobs: steps: - name: Check out the PR - uses: actions/checkout@v3 + uses: actions/checkout@v4 - name: Cache pip uses: actions/cache@v3 @@ -160,11 +160,11 @@ jobs: path: ~/.platformio key: ${{ runner.os }}-${{ hashFiles('**/lockfiles') }} - - name: Select Python 3.7 - uses: actions/setup-python@v3 + - name: Select Python 3.9 + uses: actions/setup-python@v4 with: - python-version: '3.7' # Version range or exact version of a Python version to use, using semvers version range syntax. - architecture: 'x64' # optional x64 or x86. Defaults to x64 if not specified + python-version: '3.9' + architecture: 'x64' - name: Install PlatformIO run: | From 86338ca835540d522145a3f05e498518ecf90756 Mon Sep 17 00:00:00 2001 From: Chris <52449218+shadow578@users.noreply.github.com> Date: Mon, 27 Nov 2023 00:58:56 +0100 Subject: [PATCH 26/77] =?UTF-8?q?=E2=9C=A8=20HAL=20for=20HC32F460=20(#2641?= =?UTF-8?q?4)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .github/workflows/test-builds.yml | 3 + Marlin/src/HAL/HC32/HAL.cpp | 56 ++++ Marlin/src/HAL/HC32/HAL.h | 154 +++++++++++ Marlin/src/HAL/HC32/MarlinHAL.cpp | 278 ++++++++++++++++++++ Marlin/src/HAL/HC32/MarlinHAL.h | 133 ++++++++++ Marlin/src/HAL/HC32/MarlinSerial.cpp | 142 ++++++++++ Marlin/src/HAL/HC32/MarlinSerial.h | 56 ++++ Marlin/src/HAL/HC32/MinSerial.cpp | 151 +++++++++++ Marlin/src/HAL/HC32/README.md | 110 ++++++++ Marlin/src/HAL/HC32/Servo.cpp | 84 ++++++ Marlin/src/HAL/HC32/Servo.h | 97 +++++++ Marlin/src/HAL/HC32/eeprom_bl24cxx.cpp | 92 +++++++ Marlin/src/HAL/HC32/eeprom_if_iic.cpp | 51 ++++ Marlin/src/HAL/HC32/eeprom_sdcard.cpp | 98 +++++++ Marlin/src/HAL/HC32/eeprom_wired.cpp | 94 +++++++ Marlin/src/HAL/HC32/endstop_interrupts.cpp | 98 +++++++ Marlin/src/HAL/HC32/endstop_interrupts.h | 48 ++++ Marlin/src/HAL/HC32/fastio.h | 69 +++++ Marlin/src/HAL/HC32/inc/Conditionals_LCD.h | 22 ++ Marlin/src/HAL/HC32/inc/Conditionals_adv.h | 26 ++ Marlin/src/HAL/HC32/inc/Conditionals_post.h | 34 +++ Marlin/src/HAL/HC32/inc/SanityCheck.h | 78 ++++++ Marlin/src/HAL/HC32/pinsDebug.h | 174 ++++++++++++ Marlin/src/HAL/HC32/printf_retarget.cpp | 55 ++++ Marlin/src/HAL/HC32/sdio.cpp | 137 ++++++++++ Marlin/src/HAL/HC32/sdio.h | 28 ++ Marlin/src/HAL/HC32/spi_pins.h | 19 ++ Marlin/src/HAL/HC32/sysclock.cpp | 124 +++++++++ Marlin/src/HAL/HC32/timers.cpp | 54 ++++ Marlin/src/HAL/HC32/timers.h | 135 ++++++++++ Marlin/src/HAL/platforms.h | 2 + Marlin/src/HAL/shared/servo.h | 2 + Marlin/src/core/boards.h | 5 + Marlin/src/inc/Conditionals_adv.h | 2 +- Marlin/src/libs/BL24CXX.cpp | 2 +- Marlin/src/pins/hc32f4/env_validate.h | 26 ++ Marlin/src/pins/hc32f4/pins_AQUILA_101.h | 212 +++++++++++++++ Marlin/src/pins/mega/pins_GT2560_V41b.h | 2 +- Marlin/src/pins/pins.h | 6 + Marlin/src/pins/stm32f1/pins_MD_D301.h | 2 +- buildroot/tests/HC32F460C_aquila_101 | 15 ++ ini/hc32.ini | 88 +++++++ platformio.ini | 1 + 43 files changed, 3061 insertions(+), 4 deletions(-) create mode 100644 Marlin/src/HAL/HC32/HAL.cpp create mode 100644 Marlin/src/HAL/HC32/HAL.h create mode 100644 Marlin/src/HAL/HC32/MarlinHAL.cpp create mode 100644 Marlin/src/HAL/HC32/MarlinHAL.h create mode 100644 Marlin/src/HAL/HC32/MarlinSerial.cpp create mode 100644 Marlin/src/HAL/HC32/MarlinSerial.h create mode 100644 Marlin/src/HAL/HC32/MinSerial.cpp create mode 100644 Marlin/src/HAL/HC32/README.md create mode 100644 Marlin/src/HAL/HC32/Servo.cpp create mode 100644 Marlin/src/HAL/HC32/Servo.h create mode 100644 Marlin/src/HAL/HC32/eeprom_bl24cxx.cpp create mode 100644 Marlin/src/HAL/HC32/eeprom_if_iic.cpp create mode 100644 Marlin/src/HAL/HC32/eeprom_sdcard.cpp create mode 100644 Marlin/src/HAL/HC32/eeprom_wired.cpp create mode 100644 Marlin/src/HAL/HC32/endstop_interrupts.cpp create mode 100644 Marlin/src/HAL/HC32/endstop_interrupts.h create mode 100644 Marlin/src/HAL/HC32/fastio.h create mode 100644 Marlin/src/HAL/HC32/inc/Conditionals_LCD.h create mode 100644 Marlin/src/HAL/HC32/inc/Conditionals_adv.h create mode 100644 Marlin/src/HAL/HC32/inc/Conditionals_post.h create mode 100644 Marlin/src/HAL/HC32/inc/SanityCheck.h create mode 100644 Marlin/src/HAL/HC32/pinsDebug.h create mode 100644 Marlin/src/HAL/HC32/printf_retarget.cpp create mode 100644 Marlin/src/HAL/HC32/sdio.cpp create mode 100644 Marlin/src/HAL/HC32/sdio.h create mode 100644 Marlin/src/HAL/HC32/spi_pins.h create mode 100644 Marlin/src/HAL/HC32/sysclock.cpp create mode 100644 Marlin/src/HAL/HC32/timers.cpp create mode 100644 Marlin/src/HAL/HC32/timers.h create mode 100644 Marlin/src/pins/hc32f4/env_validate.h create mode 100644 Marlin/src/pins/hc32f4/pins_AQUILA_101.h create mode 100755 buildroot/tests/HC32F460C_aquila_101 create mode 100644 ini/hc32.ini diff --git a/.github/workflows/test-builds.yml b/.github/workflows/test-builds.yml index ca1fa12bbb46..057fa8b75f19 100644 --- a/.github/workflows/test-builds.yml +++ b/.github/workflows/test-builds.yml @@ -137,6 +137,9 @@ jobs: # STM32G0 - STM32G0B1RE_btt + # HC32 + - HC32F460C_aquila_101 + # LPC176x - Lengthy tests - LPC1768 - LPC1769 diff --git a/Marlin/src/HAL/HC32/HAL.cpp b/Marlin/src/HAL/HC32/HAL.cpp new file mode 100644 index 000000000000..a74d21e6fdb5 --- /dev/null +++ b/Marlin/src/HAL/HC32/HAL.cpp @@ -0,0 +1,56 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 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 . + * + */ + +#ifdef ARDUINO_ARCH_HC32 + +#include "HAL.h" +#include +#include + +// +// Emergency Parser +// +#if ENABLED(EMERGENCY_PARSER) + +extern "C" void core_hook_usart_rx_irq(uint8_t ch, uint8_t usart) { + // Only handle receive on host serial ports + if (false + #ifdef SERIAL_PORT + || usart != SERIAL_PORT + #endif + #ifdef SERIAL_PORT_2 + || usart != SERIAL_PORT_2 + #endif + #ifdef SERIAL_PORT_3 + || usart != SERIAL_PORT_3 + #endif + ) { + return; + } + + // Submit character to emergency parser + if (MYSERIAL1.emergency_parser_enabled()) + emergency_parser.update(MYSERIAL1.emergency_state, ch); +} + +#endif // EMERGENCY_PARSER +#endif // ARDUINO_ARCH_HC32 diff --git a/Marlin/src/HAL/HC32/HAL.h b/Marlin/src/HAL/HC32/HAL.h new file mode 100644 index 000000000000..dd02183dd0ea --- /dev/null +++ b/Marlin/src/HAL/HC32/HAL.h @@ -0,0 +1,154 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 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 . + * + */ + +/** + * HAL for HC32F460 based boards + * + * Note: MarlinHAL class is in MarlinHAL.h/cpp + */ + +#define CPU_32_BIT + +#include "../../inc/MarlinConfig.h" + +#include "../../core/macros.h" +#include "../shared/Marduino.h" +#include "../shared/math_32bit.h" +#include "../shared/HAL_SPI.h" + +#include "fastio.h" +#include "timers.h" +#include "MarlinSerial.h" + +#include + +// +// Serial Ports +// +#define _MSERIAL(X) MSerial##X +#define MSERIAL(X) _MSERIAL(X) +#define NUM_UARTS 4 + +#if SERIAL_PORT == -1 + #error "USB Serial is not supported on HC32F460" +#elif WITHIN(SERIAL_PORT, 1, NUM_UARTS) + #define MYSERIAL1 MSERIAL(SERIAL_PORT) +#else + #define MYSERIAL1 MSERIAL(1) // Dummy port + static_assert(false, "SERIAL_PORT must be from 1 to " STRINGIFY(NUM_UARTS) ".") +#endif + +#ifdef SERIAL_PORT_2 + #if SERIAL_PORT_2 == -1 + #error "USB Serial is not supported on HC32F460" + #elif WITHIN(SERIAL_PORT_2, 1, NUM_UARTS) + #define MYSERIAL2 MSERIAL(SERIAL_PORT_2) + #else + #define MYSERIAL2 MSERIAL(1) // Dummy port + static_assert(false, "SERIAL_PORT_2 must be from 1 to " STRINGIFY(NUM_UARTS) ".") + #endif +#endif + +#ifdef SERIAL_PORT_3 + #if SERIAL_PORT_3 == -1 + #error "USB Serial is not supported on HC32F460" + #elif WITHIN(SERIAL_PORT_3, 1, NUM_UARTS) + #define MYSERIAL3 MSERIAL(SERIAL_PORT_3) + #else + #define MYSERIAL3 MSERIAL(1) // Dummy port + static_assert(false, "SERIAL_PORT_3 must be from 1 to " STRINGIFY(NUM_UARTS) ".") + #endif +#endif + +#ifdef LCD_SERIAL_PORT + #if LCD_SERIAL_PORT == -1 + #error "USB Serial is not supported on HC32F460" + #elif WITHIN(LCD_SERIAL_PORT, 1, NUM_UARTS) + #define LCD_SERIAL MSERIAL(LCD_SERIAL_PORT) + #else + #define LCD_SERIAL MSERIAL(1) // Dummy port + static_assert(false, "LCD_SERIAL_PORT must be from 1 to " STRINGIFY(NUM_UARTS) ".") + #endif + + #if HAS_DGUS_LCD + #define LCD_SERIAL_TX_BUFFER_FREE() LCD_SERIAL.availableForWrite() + #endif +#endif + +// +// Emergency Parser +// +#if ENABLED(EMERGENCY_PARSER) + extern "C" void usart_rx_irq_hook(uint8_t ch, uint8_t usart); +#endif + +// +// Misc. Defines +// +#define square(x) ((x) * (x)) + +#ifndef strncpy_P + #define strncpy_P(dest, src, num) strncpy((dest), (src), (num)) +#endif + +// +// Misc. Functions +// +#ifndef analogInputToDigitalPin +#define analogInputToDigitalPin(p) (p) +#endif + +#define CRITICAL_SECTION_START \ + uint32_t primask = __get_PRIMASK(); \ + (void)__iCliRetVal() + +#define CRITICAL_SECTION_END \ + if (!primask) \ + (void)__iSeiRetVal() + +// Disable interrupts +#define cli() noInterrupts() + +// Enable interrupts +#define sei() interrupts() + +// bss_end alias +#define __bss_end __bss_end__ + +// Fix bug in pgm_read_ptr +#undef pgm_read_ptr +#define pgm_read_ptr(addr) (*(addr)) + +// +// ADC +// +#define HAL_ADC_VREF_MV 3300 +#define HAL_ADC_RESOLUTION 10 + +#define GET_PIN_MAP_PIN(index) index +#define GET_PIN_MAP_INDEX(pin) pin +#define PARSED_PIN_INDEX(code, dval) parser.intval(code, dval) + +// +// MarlinHAL implementation +// +#include "MarlinHAL.h" diff --git a/Marlin/src/HAL/HC32/MarlinHAL.cpp b/Marlin/src/HAL/HC32/MarlinHAL.cpp new file mode 100644 index 000000000000..1ab374fbf15c --- /dev/null +++ b/Marlin/src/HAL/HC32/MarlinHAL.cpp @@ -0,0 +1,278 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 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 . + * + */ + +/** + * HAL for HC32F460, based heavily on the legacy implementation and STM32F1 + */ +#ifdef ARDUINO_ARCH_HC32 + +#include "../../inc/MarlinConfig.h" + +#include "HAL.h" // Includes MarlinHAL.h +#include +#include + +#if TEMP_SENSOR_SOC + #include +#endif + +extern "C" char *_sbrk(int incr); + +#if ENABLED(POSTMORTEM_DEBUGGING) + // From MinSerial.cpp + extern void install_min_serial(); +#endif + +#if ENABLED(MARLIN_DEV_MODE) + inline void HAL_clock_frequencies_dump() { + // 1. dump all clock frequencies + update_system_clock_frequencies(); + SERIAL_ECHOPGM( + "-- clocks dump -- \nSYS=", SYSTEM_CLOCK_FREQUENCIES.system, + "\nHCLK=", SYSTEM_CLOCK_FREQUENCIES.hclk, + "\nPCLK0=", SYSTEM_CLOCK_FREQUENCIES.pclk0, + "\nPCLK1=", SYSTEM_CLOCK_FREQUENCIES.pclk1, + "\nPCLK2=", SYSTEM_CLOCK_FREQUENCIES.pclk2, + "\nPCLK3=", SYSTEM_CLOCK_FREQUENCIES.pclk3, + "\nPCLK4=", SYSTEM_CLOCK_FREQUENCIES.pclk4, + "\nEXCLK=", SYSTEM_CLOCK_FREQUENCIES.exclk, + "\nF_CPU=", F_CPU + ); + + // 2. dump current system clock source + en_clk_sys_source_t clkSrc = CLK_GetSysClkSource(); + SERIAL_ECHOPGM("\nSYSCLK="); + switch (clkSrc) { + case ClkSysSrcHRC: SERIAL_ECHOPGM("HRC"); break; + case ClkSysSrcMRC: SERIAL_ECHOPGM("MRC"); break; + case ClkSysSrcLRC: SERIAL_ECHOPGM("LRC"); break; + case ClkSysSrcXTAL: SERIAL_ECHOPGM("XTAL"); break; + case ClkSysSrcXTAL32: SERIAL_ECHOPGM("XTAL32"); break; + case CLKSysSrcMPLL: SERIAL_ECHOPGM("MPLL"); + + // 3. if MPLL is used, dump MPLL settings: + // (derived from CLK_SetPllSource and CLK_MpllConfig) + // source + switch (M4_SYSREG->CMU_PLLCFGR_f.PLLSRC) { + case ClkPllSrcXTAL: SERIAL_ECHOPGM(",XTAL"); break; + case ClkPllSrcHRC: SERIAL_ECHOPGM(",HRC"); break; + default: break; + } + + // PLL multipliers and dividers + SERIAL_ECHOPGM( + "\nP=", M4_SYSREG->CMU_PLLCFGR_f.MPLLP + 1UL, + "\nQ=", M4_SYSREG->CMU_PLLCFGR_f.MPLLQ + 1UL, + "\nR=", M4_SYSREG->CMU_PLLCFGR_f.MPLLR + 1UL, + "\nN=", M4_SYSREG->CMU_PLLCFGR_f.MPLLN + 1UL, + "\nM=", M4_SYSREG->CMU_PLLCFGR_f.MPLLM + 1UL + ); + break; + default: break; + } + + // Done + SERIAL_ECHOPGM("\n--\n"); + } +#endif // MARLIN_DEV_MODE + +// +// MarlinHAL class implementation +// + +pin_t MarlinHAL::last_adc_pin; + +#if TEMP_SENSOR_SOC + float MarlinHAL::soc_temp = 0; +#endif + +MarlinHAL::MarlinHAL() {} + +void MarlinHAL::watchdog_init() { + TERN_(USE_WATCHDOG, WDT.begin(5000)); // Reset on 5 second timeout +} + +void MarlinHAL::watchdog_refresh() { + TERN_(USE_WATCHDOG, WDT.reload()); +} + +void MarlinHAL::init() { + NVIC_SetPriorityGrouping(0x3); + + // Print clock frequencies to host serial + TERN_(MARLIN_DEV_MODE, HAL_clock_frequencies_dump()); + + // Register min serial + TERN_(POSTMORTEM_DEBUGGING, install_min_serial()); +} + +void MarlinHAL::init_board() {} + +void MarlinHAL::reboot() { + NVIC_SystemReset(); +} + +bool MarlinHAL::isr_state() { + return !__get_PRIMASK(); +} + +void MarlinHAL::isr_on() { + __enable_irq(); +} + +void MarlinHAL::isr_off() { + __disable_irq(); +} + +void MarlinHAL::delay_ms(const int ms) { + delay(ms); +} + +void MarlinHAL::idletask() {} + +uint8_t MarlinHAL::get_reset_source() { + // Query reset cause from RMU + stc_rmu_rstcause_t rstCause; + RMU_GetResetCause(&rstCause); + + // Map reset cause code to those expected by Marlin + // - Reset causes are flags, so multiple can be set + TERN_(MARLIN_DEV_MODE, printf("-- Reset Cause -- \n")); + uint8_t cause = 0; + #define MAP_CAUSE(from, to) \ + if (rstCause.from == Set) { \ + TERN_(MARLIN_DEV_MODE, printf(" - " STRINGIFY(from) "\n")); \ + cause |= to; \ + } + + // Power on + MAP_CAUSE(enPowerOn, RST_POWER_ON) // Power on reset + + // External + MAP_CAUSE(enRstPin, RST_EXTERNAL) // Reset pin + MAP_CAUSE(enPvd1, RST_EXTERNAL) // Program voltage detection reset + MAP_CAUSE(enPvd2, RST_EXTERNAL) // " + + // Brown out + MAP_CAUSE(enBrownOut, RST_BROWN_OUT) // Brown out reset + + // Wdt + MAP_CAUSE(enWdt, RST_WATCHDOG) // Watchdog reset + MAP_CAUSE(enSwdt, RST_WATCHDOG) // Special WDT reset + + // Software + MAP_CAUSE(enPowerDown, RST_SOFTWARE) // MCU power down (?) + MAP_CAUSE(enSoftware, RST_SOFTWARE) // Software reset (e.g. NVIC_SystemReset()) + + // Misc. + MAP_CAUSE(enMpuErr, RST_BACKUP) // MPU error + MAP_CAUSE(enRamParityErr, RST_BACKUP) // RAM parity error + MAP_CAUSE(enRamEcc, RST_BACKUP) // RAM ecc error + MAP_CAUSE(enClkFreqErr, RST_BACKUP) // Clock frequency failure + MAP_CAUSE(enXtalErr, RST_BACKUP) // XTAL failure + + #undef MAP_CAUSE + return cause; +} + +void MarlinHAL::clear_reset_source() { + RMU_ClrResetFlag(); +} + +int MarlinHAL::freeMemory() { + volatile char top; + return &top - _sbrk(0); +} + +void MarlinHAL::adc_init() {} + +void MarlinHAL::adc_enable(const pin_t pin) { + #if TEMP_SENSOR_SOC + if (pin == TEMP_SOC_PIN) { + // Start OTS, min. 1s between reads + ChipTemperature.begin(); + ChipTemperature.setMinimumReadDeltaMillis(1000); + return; + } + #endif + + // Just set pin mode to analog + pinMode(pin, INPUT_ANALOG); +} + +void MarlinHAL::adc_start(const pin_t pin) { + MarlinHAL::last_adc_pin = pin; + + #if TEMP_SENSOR_SOC + if (pin == TEMP_SOC_PIN) { + // Read OTS + float temp; + if (ChipTemperature.read(temp)) + MarlinHAL::soc_temp = temp; + return; + } + #endif + + CORE_ASSERT(IS_GPIO_PIN(pin), "adc_start: invalid pin") + + analogReadAsync(pin); +} + +bool MarlinHAL::adc_ready() { + #if TEMP_SENSOR_SOC + if (MarlinHAL::last_adc_pin == TEMP_SOC_PIN) return true; + #endif + + CORE_ASSERT(IS_GPIO_PIN(MarlinHAL::last_adc_pin), "adc_ready: invalid pin") + + return getAnalogReadComplete(MarlinHAL::last_adc_pin); +} + +uint16_t MarlinHAL::adc_value() { + #if TEMP_SENSOR_SOC + if (MarlinHAL::last_adc_pin == TEMP_SOC_PIN) + return OTS_FLOAT_TO_ADC_READING(MarlinHAL::soc_temp); + #endif + + // Read conversion result + CORE_ASSERT(IS_GPIO_PIN(MarlinHAL::last_adc_pin), "adc_value: invalid pin") + + return getAnalogReadValue(MarlinHAL::last_adc_pin); +} + +void MarlinHAL::set_pwm_duty(const pin_t pin, const uint16_t value, const uint16_t scale, const bool invert) { + // Invert value if requested + const uint16_t val = invert ? scale - value : value; + + // AnalogWrite the value, core handles the rest + // Pin mode should be set by Marlin by calling SET_PWM() before calling this function + analogWriteScaled(pin, val, scale); +} + +void MarlinHAL::set_pwm_frequency(const pin_t pin, const uint16_t f_desired) { + // TODO set_pwm_frequency is not implemented yet + panic("set_pwm_frequency is not implemented yet\n"); +} + +void flashFirmware(const int16_t) { MarlinHAL::reboot(); } + +#endif // ARDUINO_ARCH_HC32 diff --git a/Marlin/src/HAL/HC32/MarlinHAL.h b/Marlin/src/HAL/HC32/MarlinHAL.h new file mode 100644 index 000000000000..86dc3c7e53b1 --- /dev/null +++ b/Marlin/src/HAL/HC32/MarlinHAL.h @@ -0,0 +1,133 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 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 . + * + */ +#pragma once + +#include +#include + +typedef gpio_pin_t pin_t; + +#if TEMP_SENSOR_SOC + /** + * Convert ots measurement float to uint16_t for adc_value() + * + * @note returns float as integer in degrees C * 10, if T > 0 + */ + #define OTS_FLOAT_TO_ADC_READING(T) ((T) > 0 ? ((uint16_t)((T) * 10.0f)) : 0) + + /** + * Convert adc_value() uint16_t to ots measurement float + * + * @note see OTS_FLOAT_TO_ADC_READING for inverse + * + * @note RAW is oversampled by OVERSAMPLENR, so we need to divide first + */ + #define TEMP_SOC_SENSOR(RAW) ((float)(((RAW) / OVERSAMPLENR) / 10)) +#endif + +/** + * HAL class for Marlin on HC32F460 + */ +class MarlinHAL { +public: + // Earliest possible init, before setup() + MarlinHAL(); + + // Watchdog + static void watchdog_init(); + static void watchdog_refresh(); + + static void init(); // Called early in setup() + static void init_board(); // Called less early in setup() + static void reboot(); // Restart the firmware from 0x0 + + // Interrupts + static bool isr_state(); + static void isr_on(); + static void isr_off(); + + static void delay_ms(const int ms); + + // Tasks, called from idle() + static void idletask(); + + // Reset + static uint8_t get_reset_source(); + static void clear_reset_source(); + + // Free SRAM + static int freeMemory(); + + // + // ADC Methods + // + + // Called by Temperature::init once at startup + static void adc_init(); + + // Called by Temperature::init for each sensor at startup + static void adc_enable(const pin_t pin); + + // Begin ADC sampling on the given pin. Called from Temperature::isr! + static void adc_start(const pin_t pin); + + // Is the ADC ready for reading? + static bool adc_ready(); + + // The current value of the ADC register + static uint16_t adc_value(); + + /** + * Set the PWM duty cycle for the pin to the given value. + * Optionally invert the duty cycle [default = false] + * Optionally change the maximum size of the provided value to enable finer PWM duty control [default = 255] + * The timer must be pre-configured with set_pwm_frequency() if the default frequency is not desired. + */ + static void set_pwm_duty(const pin_t pin, const uint16_t value, const uint16_t scale = 255, const bool invert = false); + + /** + * Set the frequency of the timer for the given pin. + * All Timer PWM pins run at the same frequency. + */ + static void set_pwm_frequency(const pin_t pin, const uint16_t f_desired); + +private: + /** + * Pin number of the last pin that was used with adc_start() + */ + static pin_t last_adc_pin; + + #if TEMP_SENSOR_SOC + /** + * On-chip temperature sensor value + */ + static float soc_temp; + #endif +}; + +// M997: Trigger a firmware update from SD card (after upload). +// On HC32F460, a reboot is enough to do this. +#ifndef PLATFORM_M997_SUPPORT + #define PLATFORM_M997_SUPPORT +#endif + +void flashFirmware(const int16_t); diff --git a/Marlin/src/HAL/HC32/MarlinSerial.cpp b/Marlin/src/HAL/HC32/MarlinSerial.cpp new file mode 100644 index 000000000000..168533f66439 --- /dev/null +++ b/Marlin/src/HAL/HC32/MarlinSerial.cpp @@ -0,0 +1,142 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 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 . + * + */ +#ifdef ARDUINO_ARCH_HC32 + +#include "../../inc/MarlinConfig.h" +#include "MarlinSerial.h" +#include + +/** + * Not every MarlinSerial instance should handle emergency parsing, as + * it would not make sense to parse GCode from TMC responses + */ +constexpr bool serial_handles_emergency(int port) { + return false + #ifdef SERIAL_PORT + || (SERIAL_PORT) == port + #endif + #ifdef SERIAL_PORT_2 + || (SERIAL_PORT_2) == port + #endif + #ifdef LCD_SERIAL_PORT + || (LCD_SERIAL_PORT) == port + #endif + ; +} + +// +// Define serial ports +// +#define DEFINE_HWSERIAL_MARLIN(name, n) \ + MSerialT name(serial_handles_emergency(n), \ + &USART##n##_config, \ + BOARD_USART##n##_TX_PIN, \ + BOARD_USART##n##_RX_PIN); + +DEFINE_HWSERIAL_MARLIN(MSerial1, 1); +DEFINE_HWSERIAL_MARLIN(MSerial2, 2); + +// +// Serial port assertions +// + +// Check the type of each serial port by passing it to a template function. +// HardwareSerial is known to sometimes hang the controller when an error occurs, +// so this case will fail the static assert. All other classes are assumed to be ok. +template +constexpr bool IsSerialClassAllowed(const T &) { return true; } +constexpr bool IsSerialClassAllowed(const HardwareSerial &) { return false; } +constexpr bool IsSerialClassAllowed(const Usart &) { return false; } + +// If you encounter this error, replace SerialX with MSerialX, for example MSerial3. +#define CHECK_CFG_SERIAL(A) static_assert(IsSerialClassAllowed(A), STRINGIFY(A) " is defined incorrectly"); +#define CHECK_AXIS_SERIAL(A) static_assert(IsSerialClassAllowed(A##_HARDWARE_SERIAL), STRINGIFY(A) "_HARDWARE_SERIAL must be defined in the form MSerial1, rather than Serial1"); + +// Non-TMC ports were already validated in HAL.h, so do not require verbose error messages. +#ifdef MYSERIAL1 + CHECK_CFG_SERIAL(MYSERIAL1); +#endif +#ifdef MYSERIAL2 + CHECK_CFG_SERIAL(MYSERIAL2); +#endif +#ifdef LCD_SERIAL + CHECK_CFG_SERIAL(LCD_SERIAL); +#endif +#if AXIS_HAS_HW_SERIAL(X) + CHECK_AXIS_SERIAL(X); +#endif +#if AXIS_HAS_HW_SERIAL(X2) + CHECK_AXIS_SERIAL(X2); +#endif +#if AXIS_HAS_HW_SERIAL(Y) + CHECK_AXIS_SERIAL(Y); +#endif +#if AXIS_HAS_HW_SERIAL(Y2) + CHECK_AXIS_SERIAL(Y2); +#endif +#if AXIS_HAS_HW_SERIAL(Z) + CHECK_AXIS_SERIAL(Z); +#endif +#if AXIS_HAS_HW_SERIAL(Z2) + CHECK_AXIS_SERIAL(Z2); +#endif +#if AXIS_HAS_HW_SERIAL(Z3) + CHECK_AXIS_SERIAL(Z3); +#endif +#if AXIS_HAS_HW_SERIAL(Z4) + CHECK_AXIS_SERIAL(Z4); +#endif +#if AXIS_HAS_HW_SERIAL(I) + CHECK_AXIS_SERIAL(I); +#endif +#if AXIS_HAS_HW_SERIAL(J) + CHECK_AXIS_SERIAL(J); +#endif +#if AXIS_HAS_HW_SERIAL(K) + CHECK_AXIS_SERIAL(K); +#endif +#if AXIS_HAS_HW_SERIAL(E0) + CHECK_AXIS_SERIAL(E0); +#endif +#if AXIS_HAS_HW_SERIAL(E1) + CHECK_AXIS_SERIAL(E1); +#endif +#if AXIS_HAS_HW_SERIAL(E2) + CHECK_AXIS_SERIAL(E2); +#endif +#if AXIS_HAS_HW_SERIAL(E3) + CHECK_AXIS_SERIAL(E3); +#endif +#if AXIS_HAS_HW_SERIAL(E4) + CHECK_AXIS_SERIAL(E4); +#endif +#if AXIS_HAS_HW_SERIAL(E5) + CHECK_AXIS_SERIAL(E5); +#endif +#if AXIS_HAS_HW_SERIAL(E6) + CHECK_AXIS_SERIAL(E6); +#endif +#if AXIS_HAS_HW_SERIAL(E7) + CHECK_AXIS_SERIAL(E7); +#endif + +#endif // ARDUINO_ARCH_HC32 diff --git a/Marlin/src/HAL/HC32/MarlinSerial.h b/Marlin/src/HAL/HC32/MarlinSerial.h new file mode 100644 index 000000000000..08eeef43951e --- /dev/null +++ b/Marlin/src/HAL/HC32/MarlinSerial.h @@ -0,0 +1,56 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 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 . + * + */ +#pragma once + +#include "../../core/serial_hook.h" +#include + +// Optionally set uart IRQ priority to reduce overflow errors +// #define UART_IRQ_PRIO 1 + +struct MarlinSerial : public Usart { + MarlinSerial(struct usart_config_t *usart_device, gpio_pin_t tx_pin, gpio_pin_t rx_pin) : Usart(usart_device, tx_pin, rx_pin) {} + + #ifdef UART_IRQ_PRIO + void setPriority() { + NVIC_SetPriority(c_dev()->interrupts.rx_data_available.interrupt_number, UART_IRQ_PRIO); + NVIC_SetPriority(c_dev()->interrupts.rx_error.interrupt_number, UART_IRQ_PRIO); + NVIC_SetPriority(c_dev()->interrupts.tx_buffer_empty.interrupt_number, UART_IRQ_PRIO); + NVIC_SetPriority(c_dev()->interrupts.tx_complete.interrupt_number, UART_IRQ_PRIO); + } + + void begin(uint32_t baud) { + Usart::begin(baud); + setPriority(); + } + + void begin(uint32_t baud, uint8_t config) { + Usart::begin(baud, config); + setPriority(); + } + #endif +}; + +typedef Serial1Class MSerialT; + +extern MSerialT MSerial1; +extern MSerialT MSerial2; diff --git a/Marlin/src/HAL/HC32/MinSerial.cpp b/Marlin/src/HAL/HC32/MinSerial.cpp new file mode 100644 index 000000000000..93017ee0dfa2 --- /dev/null +++ b/Marlin/src/HAL/HC32/MinSerial.cpp @@ -0,0 +1,151 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 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 . + * + */ + +#ifdef ARDUINO_ARCH_HC32 + +#include "../../inc/MarlinConfig.h" +#include + +#if ANY(POSTMORTEM_DEBUGGING, PANIC_ENABLE) + +#include + +// +// Shared by both panic and PostMortem debugging +// +static void minserial_begin() { + #if !WITHIN(SERIAL_PORT, 1, 3) + #warning "MinSerial requires a physical UART port for output." + #warning "Disabling MinSerial because the used serial port is not a HW port." + #else + + // Prepare usart_sync configuration + const stc_usart_uart_init_t usart_config = { + .enClkMode = UsartIntClkCkNoOutput, + .enClkDiv = UsartClkDiv_1, + .enDataLength = UsartDataBits8, + .enDirection = UsartDataLsbFirst, + .enStopBit = UsartOneStopBit, + .enParity = UsartParityNone, + .enSampleMode = UsartSampleBit8, + .enDetectMode = UsartStartBitFallEdge, + .enHwFlow = UsartRtsEnable, + }; + + // Initializes usart_sync driver + #define __USART_SYNC_INIT(port_no, baud, config) \ + usart_sync_init(M4_USART##port_no, \ + BOARD_USART##port_no##_TX_PIN, \ + baud, \ + config); + #define USART_SYNC_INIT(port_no, baud, config) __USART_SYNC_INIT(port_no, baud, config) + + // This will reset the baudrate to what is defined in Configuration.h, + // ignoring any changes made with e.g. M575. + // keeping the dynamic baudrate would require re-calculating the baudrate + // using the register values, which is a pain... + + // TODO: retain dynamic baudrate in MinSerial init + // -> see USART_SetBaudrate(), needs to be inverted + USART_SYNC_INIT(SERIAL_PORT, BAUDRATE, &usart_config); + + #undef USART_SYNC_INIT + #undef __USART_SYNC_INIT + #endif +} + +static void minserial_putc(char c) { + #if WITHIN(SERIAL_PORT, 1, 3) + #define __USART_SYNC_PUTC(port_no, ch) usart_sync_putc(M4_USART##port_no, ch); + #define USART_SYNC_PUTC(port_no, ch) __USART_SYNC_PUTC(port_no, ch) + + USART_SYNC_PUTC(SERIAL_PORT, c); + + #undef USART_SYNC_PUTC + #undef __USART_SYNC_PUTC + #endif +} + +// +// Panic only +// +#ifdef PANIC_ENABLE + +void panic_begin() { + minserial_begin(); + panic_puts("\n\nPANIC:\n"); +} + +void panic_puts(const char *str) { + while (*str) minserial_putc(*str++); +} + +#endif // PANIC_ENABLE + +// +// PostMortem debugging only +// +#if ENABLED(POSTMORTEM_DEBUGGING) + +#include "../shared/MinSerial.h" +#include + +void fault_handlers_init() { + // Enable cpu traps: + // - Divide by zero + // - Unaligned access + SCB->CCR |= SCB_CCR_DIV_0_TRP_Msk; //| SCB_CCR_UNALIGN_TRP_Msk; +} + +void install_min_serial() { + HAL_min_serial_init = &minserial_begin; + HAL_min_serial_out = &minserial_putc; +} + +extern "C" { + __attribute__((naked)) void JumpHandler_ASM() { + __asm__ __volatile__( + "b CommonHandler_ASM\n"); + } + void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) HardFault_Handler(); + void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) BusFault_Handler(); + void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) UsageFault_Handler(); + void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) MemManage_Handler(); + void __attribute__((naked, alias("JumpHandler_ASM"), nothrow)) NMI_Handler(); +} + +#endif // POSTMORTEM_DEBUGGING +#endif // POSTMORTEM_DEBUGGING || PANIC_ENABLE + +// +// Panic_end is always required to print the '!!' to the host +// +void panic_end() { + // Print '!!' to signal error to host + // Do it 10x so it's not missed + for (uint_fast8_t i = 10; i--;) panic_printf("\n!!\n"); + + // Then, reset the board + NVIC_SystemReset(); +} + +#endif // ARDUINO_ARCH_HC32 diff --git a/Marlin/src/HAL/HC32/README.md b/Marlin/src/HAL/HC32/README.md new file mode 100644 index 000000000000..c9ae8a9a20ef --- /dev/null +++ b/Marlin/src/HAL/HC32/README.md @@ -0,0 +1,110 @@ +# HC32F460 HAL + +This document provides notes on the HAL for the HC32F460 MCU. + +## Adding support for a new board + +The HC32F460 HAL is designed to be generic enough for any HC32F460-based board. Adding support for a new HC32F460-based board will require the following steps: + +1. Follow [the usual instructions](https://marlinfw.org/docs/development/boards.html#adding-a-new-board) to add a new board to Marlin. (i.e., Add a pins file, edit `boards.h` and `pins.h`, etc.) +2. Determine the flash size your board uses: + - Examine the board's main processor. (Refer the naming key in `hc32.ini`.) + - Extend the `HC32F460C_common` base env for 256K, or `HC32F460E_common` for 512K. +3. Determine your board's application start address (see [below](#finding-the-application-start-address)) +4. Set `board_build.ld_args.flash_start` to the app start address once you've found it. If your board doesn't use a bootloader, you may be able to use the "ICSP" header or DFU. This document will be updated once we have more information about flashing without a bootloader. + +### Finding the application start address + +If the board contains a bootloader you'll need to find the application address. This is the address the bootloader jumps to after it's done. You can find this address in a few different ways: + +#### 1. Using log messages + +If you're lucky, the bootloader may print the app start address on the serial output during boot. To check for this, use your favorite serial monitor to observe the serial output when you power on the board. Look for a message like "Jumping to 0xC000" or "GotoApp->addr=0xC000". This line would be printed before Marlin's "start" message. + +Example: + +``` +[...] +version 1.2 +sdio init success! +Disk init +Tips ------ None Firmware file +GotoApp->addr=0xC000 + +start +[...] +``` + +#### 2. Using published source code + +If the vendor has published Marlin source code that includes the bootloader, you can search the bootloader source code for the address. Begin your search with the following steps: + +1. Find the code that sets the vector table offset + +The vector table offset is usually set using a line like this: + +```c +SCB->VTOR = ((uint32_t) APP_START_ADDRESS & SCB_VTOR_TBLOFF_Msk); +``` + +Just searching for `SCB->VTOR` should yield some results. From there, you just need to look at the value that's assigned to it. The example uses `APP_START_ADDRESS`. + +> [!NOTE] +> Some vendors publish incomplete source code. But they sometimes leave version control related files in the repo, which can contain previous version of files that were removed. Find these by including folders like `.git` or `.svn` in your search. + +> [!NOTE] +> The example is based on the [Voxelab-64/Aquila_X2](https://github.com/Voxelab-64/Aquila_X2/blob/d1f23adf96920996b979bc31023d1dce236d05db/firmware/Sources/.svn/pristine/ec/ec82bcb480b511906bc3e6658450e3a803ab9813.svn-base#L96) which actually includes deleted files in its repo. + +2. Using a linker script + +If the repository contains a linker script, look at the memory regions, specifically a region named `FLASH` or similar. The `ORIGIN` of that region will be the application start address. + +**Example:** + +```ld +MEMORY +{ + FLASH (rx): ORIGIN = 0x0000C000, LENGTH = 512K + OTP (rx): ORIGIN = 0x03000C00, LENGTH = 1020 + RAM (rwx): ORIGIN = 0x1FFF8000, LENGTH = 188K + RET_RAM (rwx): ORIGIN = 0x200F0000, LENGTH = 4K +} +``` + +> [!NOTE] +> This example is based on [Voxelab-64/Aquila_X2](https://github.com/Voxelab-64/Aquila_X2/blob/d1f23adf96920996b979bc31023d1dce236d05db/firmware/Sources/main/hdsc32core/hc32f46x_flash.ld#L55) + +## Documentation on the HC32F460 + +Due to uncertain licensing (w/r/t STMicro), documentation for the HC32F460 is only available upon request. Documentation includes the following: + +- Datasheet, user manual, reference manual +- Application notes for the DDL +- DDL source code +- IDE support packages (Keil, IAR, ...) including .svd files +- Programming software +- Emulator / debugger drivers +- Development board documentation and schematics +- Errata documents +- (Limited) sales information +- Full Voxelab firmware source code +- Documents in Chinese or English (machine translated) + +Contact me on Discord (@shadow578) if you need it. + +## Dependencies + +This HAL depends on the following projects: + +- [shadow578/platform-hc32f46x](https://github.com/shadow578/platform-hc32f46x) (PlatformIO platform for HC32F46x) +- [shadow578/framework-arduino-hc32f46x](https://github.com/shadow578/framework-arduino-hc32f46x) (Arduino framework for HC32F46x) +- [shadow578/framework-hc32f46x-ddl](https://github.com/shadow578/framework-hc32f46x-ddl) (HC32F46x DDL framework) + +## Credits + +This HAL wouldn't be possible without the following projects: + +- [Voxelab-64/Aquila_X2](https://github.com/Voxelab-64/Aquila_X2) (original implementation) +- [alexqzd/Marlin-H32](https://github.com/alexqzd/Marlin-H32) (misc. fixes to the original implementation) +- [kgoveas/Arduino-Core-Template](https://github.com/kgoveas/Arduino-Core-Template) (template for Arduino headers) +- [stm32duino/Arduino_Core_STM32](https://github.com/stm32duino/Arduino_Core_STM32) (misc. Arduino functions) diff --git a/Marlin/src/HAL/HC32/Servo.cpp b/Marlin/src/HAL/HC32/Servo.cpp new file mode 100644 index 000000000000..ce78572ef577 --- /dev/null +++ b/Marlin/src/HAL/HC32/Servo.cpp @@ -0,0 +1,84 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 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 . + * + */ + +#ifdef ARDUINO_ARCH_HC32 + +#include "../../inc/MarlinConfig.h" + +#if HAS_SERVOS + +#include "Servo.h" + +static uint8_t servoCount = 0; +static MarlinServo *servos[NUM_SERVOS] = {0}; + +constexpr uint32_t servoDelays[] = SERVO_DELAY; +static_assert(COUNT(servoDelays) == NUM_SERVOS, "SERVO_DELAY must be an array NUM_SERVOS long."); + +// +// MarlinServo impl +// +MarlinServo::MarlinServo() { + this->channel = servoCount++; + servos[this->channel] = this; +} + +int8_t MarlinServo::attach(const pin_t apin) { + // Use last pin if pin not given + if (apin >= 0) this->pin = apin; + + // If attached, do nothing but no fail + if (this->servo.attached()) return 0; + + // Attach + const uint8_t rc = this->servo.attach(this->pin); + return rc == INVALID_SERVO ? -1 : rc; +} + +void MarlinServo::detach() { + this->servo.detach(); +} + +bool MarlinServo::attached() { + return this->servo.attached(); +} + +void MarlinServo::write(servo_angle_t angle) { + this->angle = angle; + this->servo.write(angle); +} + +void MarlinServo::move(servo_angle_t angle) { + // Attach with pin=-1 to use last pin attach() was called with + if (attach(-1) < 0) return; // Attach failed + + write(angle); + safe_delay(servoDelays[this->channel]); + TERN_(DEACTIVATE_SERVOS_AFTER_MOVE, detach()); +} + +servo_angle_t MarlinServo::read() { + return TERN(OPTIMISTIC_SERVO_READ, this->angle, this->servo.read()); +} + +#endif // HAS_SERVOS +#endif // ARDUINO_ARCH_HC32 diff --git a/Marlin/src/HAL/HC32/Servo.h b/Marlin/src/HAL/HC32/Servo.h new file mode 100644 index 000000000000..db2f60d190b5 --- /dev/null +++ b/Marlin/src/HAL/HC32/Servo.h @@ -0,0 +1,97 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 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 . + * + */ + +#include "../../inc/MarlinConfigPre.h" + +#include + +/** + * return last written value in servo.read instead of calculated value + */ +#define OPTIMISTIC_SERVO_READ + +/** + * @brief servo lib wrapper for marlin + */ +class MarlinServo { +public: + MarlinServo(); + + /** + * @brief attach the pin to the servo, set pin mode, return channel number + * @param pin pin to attach to + * @return channel number, -1 if failed + */ + int8_t attach(const pin_t apin); + + /** + * @brief detach servo + */ + void detach(); + + /** + * @brief is servo attached? + */ + bool attached(); + + /** + * @brief set servo angle + * @param angle new angle + */ + void write(servo_angle_t angle); + + /** + * @brief attach servo, move to angle, delay then detach + * @param angle angle to move to + */ + void move(servo_angle_t angle); + + /** + * @brief read current angle + * @return current angle betwwne 0 and 180 degrees + */ + servo_angle_t read(); + +private: + /** + * @brief internal servo object, provided by arduino core + */ + Servo servo; + + /** + * @brief virtual servo channel + */ + uint8_t channel; + + /** + * @brief pin the servo attached to last + */ + pin_t pin; + + /** + * @brief last known servo angle + */ + servo_angle_t angle; +}; + +// Alias for marlin HAL +typedef MarlinServo hal_servo_t; diff --git a/Marlin/src/HAL/HC32/eeprom_bl24cxx.cpp b/Marlin/src/HAL/HC32/eeprom_bl24cxx.cpp new file mode 100644 index 000000000000..fe4a91384a28 --- /dev/null +++ b/Marlin/src/HAL/HC32/eeprom_bl24cxx.cpp @@ -0,0 +1,92 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 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 . + * + */ + +/** + * PersistentStore for Arduino-style EEPROM interface + * with simple implementations supplied by Marlin. + */ +#ifdef ARDUINO_ARCH_HC32 + +#include "../../inc/MarlinConfig.h" + +#if ENABLED(IIC_BL24CXX_EEPROM) + +#include "../shared/eeprom_api.h" +#include "../shared/eeprom_if.h" + +#ifndef MARLIN_EEPROM_SIZE + #error "MARLIN_EEPROM_SIZE is required for IIC_BL24CXX_EEPROM." +#endif + +size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; } + +bool PersistentStore::access_start() { + eeprom_init(); + return true; +} + +bool PersistentStore::access_finish() { return true; } + +bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { + while (size--) { + uint8_t v = *value; + uint8_t *const p = (uint8_t *const)pos; + + // EEPROM has only ~100,000 write cycles, + // so only write bytes that have changed! + if (v != eeprom_read_byte(p)) { + eeprom_write_byte(p, v); + delay(2); + if (eeprom_read_byte(p) != v) { + SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE); + return true; + } + } + + crc16(crc, &v, 1); + pos++; + value++; + } + + return false; +} + +bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, + uint16_t *crc, const bool writing /*=true*/) { + do { + uint8_t *const p = (uint8_t *const)pos; + uint8_t c = eeprom_read_byte(p); + if (writing) + { + *value = c; + } + + crc16(crc, &c, 1); + pos++; + value++; + } while (--size); + + return false; +} + +#endif // IIC_BL24CXX_EEPROM +#endif // ARDUINO_ARCH_HC32 diff --git a/Marlin/src/HAL/HC32/eeprom_if_iic.cpp b/Marlin/src/HAL/HC32/eeprom_if_iic.cpp new file mode 100644 index 000000000000..02b1d3fd54b9 --- /dev/null +++ b/Marlin/src/HAL/HC32/eeprom_if_iic.cpp @@ -0,0 +1,51 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 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 . + * + */ + +/** + * Platform-independent Arduino functions for I2C EEPROM. + * Enable USE_SHARED_EEPROM if not supplied by the framework. + */ +#ifdef ARDUINO_ARCH_HC32 + +#include "../../inc/MarlinConfig.h" + +#if ENABLED(IIC_BL24CXX_EEPROM) + +#include "../../libs/BL24CXX.h" +#include "../shared/eeprom_if.h" + +void eeprom_init() { + BL24CXX::init(); +} + +void eeprom_write_byte(uint8_t *pos, unsigned char value) { + const unsigned eeprom_address = (unsigned)pos; + return BL24CXX::writeOneByte(eeprom_address, value); +} + +uint8_t eeprom_read_byte(uint8_t *pos) { + const unsigned eeprom_address = (unsigned)pos; + return BL24CXX::readOneByte(eeprom_address); +} + +#endif // IIC_BL24CXX_EEPROM +#endif // ARDUINO_ARCH_HC32 diff --git a/Marlin/src/HAL/HC32/eeprom_sdcard.cpp b/Marlin/src/HAL/HC32/eeprom_sdcard.cpp new file mode 100644 index 000000000000..ec77c441a0b2 --- /dev/null +++ b/Marlin/src/HAL/HC32/eeprom_sdcard.cpp @@ -0,0 +1,98 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 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 . + * + */ + +/** + * Implementation of EEPROM settings in SD Card + */ +#ifdef ARDUINO_ARCH_HC32 + +#include "../../inc/MarlinConfig.h" + +#if ENABLED(SDCARD_EEPROM_EMULATION) + +#include "../shared/eeprom_api.h" +#include "../../sd/cardreader.h" + +#define EEPROM_FILENAME "eeprom.dat" + +#ifndef MARLIN_EEPROM_SIZE + #define MARLIN_EEPROM_SIZE 0x1000 // 4KB +#endif + +size_t PersistentStore::capacity() { + return MARLIN_EEPROM_SIZE; +} + +#define _ALIGN(x) __attribute__((aligned(x))) +static char _ALIGN(4) HAL_eeprom_data[MARLIN_EEPROM_SIZE]; + +bool PersistentStore::access_start() { + if (!card.isMounted()) return false; + + MediaFile file, root = card.getroot(); + if (!file.open(&root, EEPROM_FILENAME, O_RDONLY)) + return true; // False aborts the save + + int bytes_read = file.read(HAL_eeprom_data, MARLIN_EEPROM_SIZE); + if (bytes_read < 0) return false; + + for (; bytes_read < MARLIN_EEPROM_SIZE; bytes_read++) + HAL_eeprom_data[bytes_read] = 0xFF; + + file.close(); + return true; +} + +bool PersistentStore::access_finish() { + if (!card.isMounted()) return false; + + MediaFile file, root = card.getroot(); + int bytes_written = 0; + if (file.open(&root, EEPROM_FILENAME, O_CREAT | O_WRITE | O_TRUNC)) { + bytes_written = file.write(HAL_eeprom_data, MARLIN_EEPROM_SIZE); + file.close(); + } + + return (bytes_written == MARLIN_EEPROM_SIZE); +} + +bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { + for (size_t i = 0; i < size; i++) HAL_eeprom_data[pos + i] = value[i]; + + crc16(crc, value, size); + pos += size; + return false; +} + +bool PersistentStore::read_data(int &pos, uint8_t *value, const size_t size, uint16_t *crc, const bool writing /*=true*/) { + for (size_t i = 0; i < size; i++) { + uint8_t c = HAL_eeprom_data[pos + i]; + if (writing) value[i] = c; + crc16(crc, &c, 1); + } + + pos += size; + return false; +} + +#endif // SDCARD_EEPROM_EMULATION +#endif // ARDUINO_ARCH_HC32 diff --git a/Marlin/src/HAL/HC32/eeprom_wired.cpp b/Marlin/src/HAL/HC32/eeprom_wired.cpp new file mode 100644 index 000000000000..42c25635884d --- /dev/null +++ b/Marlin/src/HAL/HC32/eeprom_wired.cpp @@ -0,0 +1,94 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * 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 . + * + */ +#ifdef ARDUINO_ARCH_HC32 + +#include "../../inc/MarlinConfig.h" + +#if USE_WIRED_EEPROM + +#warning "SPI / I2C EEPROM has not been tested on HC32F460." + +/** + * PersistentStore for Arduino-style EEPROM interface + * with simple implementations supplied by Marlin. + */ + +#include "../shared/eeprom_if.h" +#include "../shared/eeprom_api.h" + +#ifndef MARLIN_EEPROM_SIZE + #error "MARLIN_EEPROM_SIZE is required for I2C / SPI EEPROM." +#endif +size_t PersistentStore::capacity() { return MARLIN_EEPROM_SIZE; } + +bool PersistentStore::access_finish() { return true; } + +bool PersistentStore::access_start() { + eeprom_init(); + #if ENABLED(SPI_EEPROM) + #if SPI_CHAN_EEPROM1 == 1 + SET_OUTPUT(BOARD_SPI1_SCK_PIN); + SET_OUTPUT(BOARD_SPI1_MOSI_PIN); + SET_INPUT(BOARD_SPI1_MISO_PIN); + SET_OUTPUT(SPI_EEPROM1_CS); + #endif + + spiInit(0); + #endif + return true; +} + +bool PersistentStore::write_data(int &pos, const uint8_t *value, size_t size, uint16_t *crc) { + while (size--) { + uint8_t *const p = (uint8_t *const)pos; + uint8_t v = *value; + // EEPROM has only ~100,000 write cycles, + // so only write bytes that have changed! + if (v != eeprom_read_byte(p)) { + eeprom_write_byte(p, v); + if (eeprom_read_byte(p) != v) { + SERIAL_ECHO_MSG(STR_ERR_EEPROM_WRITE); + return true; + } + } + crc16(crc, &v, 1); + pos++; + value++; + } + + return false; +} + +bool PersistentStore::read_data(int &pos, uint8_t *value, size_t size, uint16_t *crc, const bool writing /*=true*/) { + do { + uint8_t c = eeprom_read_byte((uint8_t *)pos); + if (writing && value) { + *value = c; + } + + crc16(crc, &c, 1); + pos++; + value++; + } while (--size); + + return false; +} + +#endif // USE_WIRED_EEPROM +#endif // ARDUINO_ARCH_HC32 diff --git a/Marlin/src/HAL/HC32/endstop_interrupts.cpp b/Marlin/src/HAL/HC32/endstop_interrupts.cpp new file mode 100644 index 000000000000..a976fa1d3c0d --- /dev/null +++ b/Marlin/src/HAL/HC32/endstop_interrupts.cpp @@ -0,0 +1,98 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 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 . + * + */ + +#ifdef ARDUINO_ARCH_HC32 + +#include "endstop_interrupts.h" +#include "../../module/endstops.h" +#include + +#define ENDSTOP_IRQ_PRIORITY DDL_IRQ_PRIORITY_06 + +// +// IRQ handler +// +void endstopIRQHandler() { + bool flag = false; + + // Check all irq flags + #define CHECK(name) TERN_(USE_##name, flag |= checkIRQFlag(name##_PIN, /*clear*/ true)) + + CHECK(X_MAX); + CHECK(X_MIN); + + CHECK(Y_MAX); + CHECK(Y_MIN); + + CHECK(Z_MAX); + CHECK(Z_MIN); + + CHECK(Z2_MAX); + CHECK(Z2_MIN); + + CHECK(Z3_MAX); + CHECK(Z3_MIN); + + CHECK(Z_MIN_PROBE); + + // Update endstops + if (flag) endstops.update(); + + #undef CHECK +} + +// +// HAL functions +// +void setup_endstop_interrupts() { + #define SETUP(name) TERN_(USE_##name, attachInterrupt(name##_PIN, endstopIRQHandler, CHANGE); setInterruptPriority(name##_PIN, ENDSTOP_IRQ_PRIORITY)) + + SETUP(X_MAX); + SETUP(X_MIN); + + SETUP(Y_MAX); + SETUP(Y_MIN); + + SETUP(Z_MAX); + SETUP(Z_MIN); + + SETUP(Z2_MAX); + SETUP(Z2_MIN); + + SETUP(Z3_MAX); + SETUP(Z3_MIN); + + SETUP(Z_MIN_PROBE); + + #undef SETUP +} + +// Ensure 1 - 10 IRQs are registered +// Disable some endstops if you encounter this error +#define ENDSTOPS_INTERRUPTS_COUNT COUNT_ENABLED(USE_X_MAX, USE_X_MIN, USE_Y_MAX, USE_Y_MIN, USE_Z_MAX, USE_Z_MIN, USE_Z2_MAX, USE_Z2_MIN, USE_Z3_MAX, USE_Z3_MIN, USE_Z_MIN_PROBE) +#if ENDSTOPS_INTERRUPTS_COUNT > 10 + #error "Too many endstop interrupts! HC32F460 only supports 10 endstop interrupts." +#elif ENDSTOPS_INTERRUPTS_COUNT == 0 + #error "No endstop interrupts are enabled! Comment out this line to continue." +#endif + +#endif // ARDUINO_ARCH_HC32 diff --git a/Marlin/src/HAL/HC32/endstop_interrupts.h b/Marlin/src/HAL/HC32/endstop_interrupts.h new file mode 100644 index 000000000000..124f6f1a1b95 --- /dev/null +++ b/Marlin/src/HAL/HC32/endstop_interrupts.h @@ -0,0 +1,48 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 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 . + * + */ +#pragma once + +/** + * Endstop interrupts for HC32F460 based targets. + * + * On HC32F460, all pins support external interrupt capability, with some restrictions. + * See the documentation of WInterrupts#attachInterrupt() for details. + * + * TL;DR + * any 16 pins can be used, but only one pin per EXTI line (so PA0 and PB0 are no-good). + */ + +/** + * Endstop Interrupts + * + * Without endstop interrupts the endstop pins must be polled continually in + * the temperature-ISR via endstops.update(), most of the time finding no change. + * With this feature endstops.update() is called only when we know that at + * least one endstop has changed state, saving valuable CPU cycles. + * + * This feature only works when all used endstop pins can generate an 'external interrupt'. + * + * Test whether pins issue interrupts on your board by flashing 'pin_interrupt_test.ino'. + * (Located in Marlin/buildroot/share/pin_interrupt_test/pin_interrupt_test.ino) + */ + +void setup_endstop_interrupts(); diff --git a/Marlin/src/HAL/HC32/fastio.h b/Marlin/src/HAL/HC32/fastio.h new file mode 100644 index 000000000000..af46866172c9 --- /dev/null +++ b/Marlin/src/HAL/HC32/fastio.h @@ -0,0 +1,69 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 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 . + * + */ +#pragma once + +/** + * Fast I/O interfaces for HC32F460 + * These use GPIO functions instead of Direct Port Manipulation. + */ +#include +#include +#include + +#define READ(IO) (GPIO_GetBit(IO) ? HIGH : LOW) +#define WRITE(IO, V) (((V) > 0) ? GPIO_SetBits(IO) : GPIO_ResetBits(IO)) +#define TOGGLE(IO) (GPIO_Toggle(IO)) + +#define _GET_MODE(IO) getPinMode(IO) +#define _SET_MODE(IO, M) pinMode(IO, M) +#define _SET_OUTPUT(IO) _SET_MODE(IO, OUTPUT) + +#define OUT_WRITE(IO, V) \ + do { \ + _SET_OUTPUT(IO); \ + WRITE(IO, V); \ + } while (0) + +#define SET_INPUT(IO) _SET_MODE(IO, INPUT_FLOATING) +#define SET_INPUT_PULLUP(IO) _SET_MODE(IO, INPUT_PULLUP) +#define SET_INPUT_PULLDOWN(IO) _SET_MODE(IO, INPUT_PULLDOWN) +#define SET_OUTPUT(IO) OUT_WRITE(IO, LOW) +#define SET_PWM(IO) _SET_MODE(IO, OUTPUT_PWM) + +#define IS_INPUT(IO) ( \ + _GET_MODE(IO) == INPUT || \ + _GET_MODE(IO) == INPUT_FLOATING || \ + _GET_MODE(IO) == INPUT_ANALOG || \ + _GET_MODE(IO) == INPUT_PULLUP || \ + _GET_MODE(IO) == INPUT_PULLDOWN) + +#define IS_OUTPUT(IO) ( \ + _GET_MODE(IO) == OUTPUT || \ + _GET_MODE(IO) == OUTPUT_PWM || \ + _GET_MODE(IO) == OUTPUT_OPEN_DRAIN) + +#define PWM_PIN(IO) isAnalogWritePin(IO) + +#define extDigitalRead(IO) digitalRead(IO) +#define extDigitalWrite(IO, V) digitalWrite(IO, V) + +#define NO_COMPILE_TIME_PWM // Can't check for PWM at compile time diff --git a/Marlin/src/HAL/HC32/inc/Conditionals_LCD.h b/Marlin/src/HAL/HC32/inc/Conditionals_LCD.h new file mode 100644 index 000000000000..5f1a94e9203a --- /dev/null +++ b/Marlin/src/HAL/HC32/inc/Conditionals_LCD.h @@ -0,0 +1,22 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 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 . + * + */ +#pragma once diff --git a/Marlin/src/HAL/HC32/inc/Conditionals_adv.h b/Marlin/src/HAL/HC32/inc/Conditionals_adv.h new file mode 100644 index 000000000000..06f15e51056f --- /dev/null +++ b/Marlin/src/HAL/HC32/inc/Conditionals_adv.h @@ -0,0 +1,26 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 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 . + * + */ +#pragma once + +#ifndef TEMP_SOC_PIN + #define TEMP_SOC_PIN 0xFF // Dummy that is not a valid GPIO, HAL checks for this +#endif diff --git a/Marlin/src/HAL/HC32/inc/Conditionals_post.h b/Marlin/src/HAL/HC32/inc/Conditionals_post.h new file mode 100644 index 000000000000..bcffd5a8d5e7 --- /dev/null +++ b/Marlin/src/HAL/HC32/inc/Conditionals_post.h @@ -0,0 +1,34 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 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 . + * + */ +#pragma once + +// If no real EEPROM, Flash emulation, or SRAM emulation is available fall back to SD emulation +#if USE_FALLBACK_EEPROM + #define SDCARD_EEPROM_EMULATION +#elif ANY(I2C_EEPROM, SPI_EEPROM) + #define USE_SHARED_EEPROM 1 +#endif + +// Allow SD support to be disabled +#if !HAS_MEDIA + #undef ONBOARD_SDIO +#endif diff --git a/Marlin/src/HAL/HC32/inc/SanityCheck.h b/Marlin/src/HAL/HC32/inc/SanityCheck.h new file mode 100644 index 000000000000..d7c6894039cb --- /dev/null +++ b/Marlin/src/HAL/HC32/inc/SanityCheck.h @@ -0,0 +1,78 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 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 . + * + */ +#pragma once + +#ifndef BOARD_XTAL_FREQUENCY + #error "BOARD_XTAL_FREQUENCY is required for HC32F460." +#endif + +#if ENABLED(FAST_PWM_FAN) + #error "FAST_PWM_FAN is not yet implemented for this platform." +#endif + +#if !defined(HAVE_SW_SERIAL) && HAS_TMC_SW_SERIAL + #error "Missing SoftwareSerial implementation." +#endif + +#if ENABLED(SDCARD_EEPROM_EMULATION) && !HAS_MEDIA + #undef SDCARD_EEPROM_EMULATION // Avoid additional error noise + #if USE_FALLBACK_EEPROM + #warning "EEPROM type not specified. Fallback is SDCARD_EEPROM_EMULATION." + #endif + + #error "SDCARD_EEPROM_EMULATION requires SDSUPPORT. Enable SDSUPPORT or choose another EEPROM emulation." +#endif + +#if ENABLED(SERIAL_STATS_MAX_RX_QUEUED) + #error "SERIAL_STATS_MAX_RX_QUEUED is not supported on this platform." +#elif ENABLED(SERIAL_STATS_DROPPED_RX) + #error "SERIAL_STATS_DROPPED_RX is not supported on this platform." +#endif + +#if ENABLED(NEOPIXEL_LED) && DISABLED(MKS_MINI_12864_V3) + #error "NEOPIXEL_LED (Adafruit NeoPixel) is not supported for HC32F460. Comment out this line to proceed at your own risk!" +#endif + +// Emergency Parser needs at least one serial with HardwareSerial. +#if ENABLED(EMERGENCY_PARSER) && ((SERIAL_PORT == -1 && !defined(SERIAL_PORT_2)) || (SERIAL_PORT_2 == -1 && !defined(SERIAL_PORT))) + #error "EMERGENCY_PARSER is only supported by HardwareSerial on HC32F460." +#endif + +#if TEMP_SENSOR_SOC + #if !defined(TEMP_SOC_PIN) + #error "TEMP_SOC_PIN must be defined to use TEMP_SENSOR_SOC." + #endif + + #if defined(TEMP_SOC_PIN) && IS_GPIO_PIN(TEMP_SOC_PIN) + #error "TEMP_SOC_PIN must not be a valid GPIO pin to avoid conflicts." + #endif +#endif + +#if ENABLED(POSTMORTEM_DEBUGGING) && !defined(CORE_DISABLE_FAULT_HANDLER) + #error "POSTMORTEM_DEBUGGING requires CORE_DISABLE_FAULT_HANDLER to be set." +#endif + +#if defined(PANIC_ENABLE) + #if defined(PANIC_USART1_TX_PIN) || defined(PANIC_USART2_TX_PIN) || defined(PANIC_USART3_TX_PIN) || defined(PANIC_USART3_TX_PIN) + #error "HC32 HAL uses a custom panic handler. Do not define PANIC_USARTx_TX_PIN." + #endif +#endif diff --git a/Marlin/src/HAL/HC32/pinsDebug.h b/Marlin/src/HAL/HC32/pinsDebug.h new file mode 100644 index 000000000000..1bee6ceb3e50 --- /dev/null +++ b/Marlin/src/HAL/HC32/pinsDebug.h @@ -0,0 +1,174 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * 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 . + * + */ +#pragma once + +#include "../../inc/MarlinConfig.h" +#include "fastio.h" +#include + +// +// Translation of routines & variables used by pinsDebug.h +// +#ifndef BOARD_NR_GPIO_PINS + #error "Expected BOARD_NR_GPIO_PINS not found." +#endif + +#define NUM_DIGITAL_PINS BOARD_NR_GPIO_PINS +#define NUMBER_PINS_TOTAL BOARD_NR_GPIO_PINS +#define VALID_PIN(pin) IS_GPIO_PIN(pin) + +// Note: pin_array is defined in `Marlin/src/pins/pinsDebug.h`, and since this file is included +// after it, it is available in this file as well. +#define GET_ARRAY_PIN(p) pin_t(pin_array[p].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 + +// +// Pins that will cause a hang / reset / disconnect in M43 Toggle and Watch utils +// +#ifndef M43_NEVER_TOUCH + // Don't touch any of the following pins: + // - Host serial pins, and + // - Pins that could be connected to oscillators (see datasheet, Table 2.1): + // - XTAL = PH0, PH1 + // - XTAL32 = PC14, PC15 + #define IS_HOST_USART_PIN(Q) (Q == BOARD_USART2_TX_PIN || Q == BOARD_USART2_RX_PIN) + #define IS_OSC_PIN(Q) (Q == PH0 || Q == PH1 || Q == PC14 || Q == PC15) + + #define M43_NEVER_TOUCH(Q) (IS_HOST_USART_PIN(Q) || IS_OSC_PIN(Q)) +#endif + +static pin_t DIGITAL_PIN_TO_ANALOG_PIN(pin_t pin) { + if (!VALID_PIN(pin)) return -1; + const int8_t adc_channel = int8_t(PIN_MAP[pin].adc_info.channel); + return pin_t(adc_channel); +} + +static bool IS_ANALOG(pin_t pin) { + if (!VALID_PIN(pin)) return false; + + if (PIN_MAP[pin].adc_info.channel != ADC_PIN_INVALID) + return _GET_MODE(pin) == INPUT_ANALOG && !M43_NEVER_TOUCH(pin); + + return false; +} + +static bool GET_PINMODE(const pin_t pin) { + return VALID_PIN(pin) && !IS_INPUT(pin); +} + +static bool GET_ARRAY_IS_DIGITAL(const int16_t array_pin) { + const pin_t pin = GET_ARRAY_PIN(array_pin); + return (!IS_ANALOG(pin)); +} + +/** + * @brief print pin PWM status + * @return true if pin is currently a PWM pin, false otherwise + */ +bool pwm_status(const pin_t pin) { + // Get timer assignment for pin + timera_config_t *unit; + en_timera_channel_t channel; + en_port_func_t port_function; + if (!timera_get_assignment(pin, unit, channel, port_function) || unit == nullptr) { + // No pwm pin or no unit assigned + return false; + } + + // A pin that is PWM output is: + // - Assigned to a timerA unit (tested above) + // - Unit is initialized + // - Channel is active + // - PinMode is OUTPUT_PWM + return timera_is_unit_initialized(unit) && timera_is_channel_active(unit, channel) && getPinMode(pin) == OUTPUT_PWM; +} + +void pwm_details(const pin_t pin) { + // Get timer assignment for pin + timera_config_t *unit; + en_timera_channel_t channel; + en_port_func_t port_function; + if (!timera_get_assignment(pin, unit, channel, port_function) || unit == nullptr) + return; // No pwm pin or no unit assigned + + // Print timer assignment of pin, eg. "TimerA1Ch2 Func4" + SERIAL_ECHOPGM("TimerA", TIMERA_REG_TO_X(unit->peripheral.register_base), + "Ch", TIMERA_CHANNEL_TO_X(channel), + " Func", int(port_function)); + SERIAL_ECHO_SP(3); // 3 spaces + + // Print timer unit state, eg. "1/16 PERAR=1234" OR "N/A" + if (timera_is_unit_initialized(unit)) { + // Unit initialized, print + // - Timer clock divider + // - Timer period value (PERAR) + const uint8_t clock_divider = timera_clk_div_to_n(unit->state.base_init->enClkDiv); + const uint16_t period = TIMERA_GetPeriodValue(unit->peripheral.register_base); + SERIAL_ECHOPGM("1/", clock_divider, " PERAR=", period); + } + else { + // Unit not initialized + SERIAL_ECHOPGM("N/A"); + return; + } + + SERIAL_ECHO_SP(3); // 3 spaces + + // Print timer channel state, e.g. "CMPAR=1234" OR "N/A" + if (timera_is_channel_active(unit, channel)) { + // Channel active, print + // - Channel compare value + const uint16_t compare = TIMERA_GetCompareValue(unit->peripheral.register_base, channel); + SERIAL_ECHOPGM("CMPAR=", compare); + } + else { + // Channel inactive + SERIAL_ECHOPGM("N/A"); + } +} + +void print_port(pin_t pin) { + const char port = 'A' + char(pin >> 4); // Pin div 16 + const int16_t gbit = PIN_MAP[pin].bit_pos; + char buffer[8]; + sprintf_P(buffer, PSTR("P%c%hd "), port, gbit); + if (gbit < 10) { + SERIAL_CHAR(' '); + } + + SERIAL_ECHO(buffer); +} diff --git a/Marlin/src/HAL/HC32/printf_retarget.cpp b/Marlin/src/HAL/HC32/printf_retarget.cpp new file mode 100644 index 000000000000..2c98415dff96 --- /dev/null +++ b/Marlin/src/HAL/HC32/printf_retarget.cpp @@ -0,0 +1,55 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 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 . + * + */ + +#ifdef ARDUINO_ARCH_HC32 +#ifdef REDIRECT_PRINTF_TO_SERIAL + +#if !defined(__GNUC__) + #error "only GCC is supported" +#endif + +#include "../../inc/MarlinConfig.h" + +/** + * @brief implementation of _write that redirects everything to the host serial(s) + * @param file file descriptor. don't care + * @param ptr pointer to the data to write + * @param len length of the data to write + * @return number of bytes written + */ +extern "C" int _write(int file, char *ptr, int len) { + //SERIAL_ECHO_START(); // echo: + for (int i = 0; i < len; i++) SERIAL_CHAR(ptr[i]); + return len; +} + +/** + * @brief implementation of _isatty that always returns 1 + * @param file file descriptor. don't care + * @return everything is a tty. there are no files to be had + */ +extern "C" int _isatty(int file) { + return 1; +} + +#endif // REDIRECT_PRINTF_TO_SERIAL +#endif // ARDUINO_ARCH_HC32 diff --git a/Marlin/src/HAL/HC32/sdio.cpp b/Marlin/src/HAL/HC32/sdio.cpp new file mode 100644 index 000000000000..4360d715ff19 --- /dev/null +++ b/Marlin/src/HAL/HC32/sdio.cpp @@ -0,0 +1,137 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 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 . + * + */ + +#ifdef ARDUINO_ARCH_HC32 + +#include "sdio.h" +#include +#include + +// +// SDIO configuration +// + +#define SDIO_PERIPHERAL M4_SDIOC1 + +// Use DMA2 channel 0 +#define SDIO_DMA_PERIPHERAL M4_DMA2 +#define SDIO_DMA_CHANNEL DmaCh0 + +// SDIO read/write operation retries and timeouts +#define SDIO_READ_RETRIES 3 +#define SDIO_READ_TIMEOUT 100 // ms + +#define SDIO_WRITE_RETRIES 1 +#define SDIO_WRITE_TIMEOUT 100 // ms + +// +// HAL functions +// + +#define WITH_RETRY(retries, fn) \ + for (int retry = 0; retry < (retries); retry++) { \ + MarlinHAL::watchdog_refresh(); \ + yield(); \ + fn \ + } + +stc_sd_handle_t *handle; + +bool SDIO_Init() { + // Configure SDIO pins + GPIO_SetFunc(BOARD_SDIO_D0, Func_Sdio); + GPIO_SetFunc(BOARD_SDIO_D1, Func_Sdio); + GPIO_SetFunc(BOARD_SDIO_D2, Func_Sdio); + GPIO_SetFunc(BOARD_SDIO_D3, Func_Sdio); + GPIO_SetFunc(BOARD_SDIO_CLK, Func_Sdio); + GPIO_SetFunc(BOARD_SDIO_CMD, Func_Sdio); + GPIO_SetFunc(BOARD_SDIO_DET, Func_Sdio); + + // Create DMA configuration + stc_sdcard_dma_init_t *dmaConf = new stc_sdcard_dma_init_t; + dmaConf->DMAx = SDIO_DMA_PERIPHERAL; + dmaConf->enDmaCh = SDIO_DMA_CHANNEL; + + // Create handle in DMA mode + handle = new stc_sd_handle_t; + handle->SDIOCx = SDIO_PERIPHERAL; + handle->enDevMode = SdCardDmaMode; + handle->pstcDmaInitCfg = dmaConf; + + // Create card configuration + // This should be a fairly safe configuration for most cards + stc_sdcard_init_t cardConf = { + .enBusWidth = SdiocBusWidth4Bit, + .enClkFreq = SdiocClk400K, + .enSpeedMode = SdiocNormalSpeedMode, + //.pstcInitCfg = NULL, + }; + + // Initialize sd card + en_result_t rc = SDCARD_Init(handle, &cardConf); + if (rc != Ok) printf("SDIO_Init() error (rc=%u)\n", rc); + + return rc == Ok; +} + +bool SDIO_ReadBlock(uint32_t block, uint8_t *dst) { + CORE_ASSERT(handle != NULL, "SDIO not initialized"); + CORE_ASSERT(dst != NULL, "SDIO_ReadBlock dst is NULL"); + + WITH_RETRY(SDIO_READ_RETRIES, { + en_result_t rc = SDCARD_ReadBlocks(handle, block, 1, dst, SDIO_READ_TIMEOUT); + if (rc == Ok) return true; + printf("SDIO_ReadBlock error (rc=%u; ErrorCode=%lu)\n", rc, handle->u32ErrorCode); + }) + + return false; +} + +bool SDIO_WriteBlock(uint32_t block, const uint8_t *src) { + CORE_ASSERT(handle != NULL, "SDIO not initialized"); + CORE_ASSERT(src != NULL, "SDIO_WriteBlock src is NULL"); + + WITH_RETRY(SDIO_WRITE_RETRIES, { + en_result_t rc = SDCARD_WriteBlocks(handle, block, 1, (uint8_t *)src, SDIO_WRITE_TIMEOUT); + if (rc == Ok) return true; + printf("SDIO_WriteBlock error (rc=%u; ErrorCode=%lu)\n", rc, handle->u32ErrorCode); + }) + + return false; +} + +bool SDIO_IsReady() { + CORE_ASSERT(handle != NULL, "SDIO not initialized"); + return bool(handle->stcCardStatus.READY_FOR_DATA); +} + +uint32_t SDIO_GetCardSize() { + CORE_ASSERT(handle != NULL, "SDIO not initialized"); + + // Multiply number of blocks with block size to get size in bytes + const uint64_t cardSizeBytes = uint64_t(handle->stcSdCardInfo.u32LogBlockNbr) * uint64_t(handle->stcSdCardInfo.u32LogBlockSize); + + // If the card is bigger than ~4Gb (maximum a 32bit integer can hold), clamp to the maximum value of a 32 bit integer + return _MAX(cardSizeBytes, UINT32_MAX); +} + +#endif // ARDUINO_ARCH_HC32 diff --git a/Marlin/src/HAL/HC32/sdio.h b/Marlin/src/HAL/HC32/sdio.h new file mode 100644 index 000000000000..89d4b061b19b --- /dev/null +++ b/Marlin/src/HAL/HC32/sdio.h @@ -0,0 +1,28 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com + * Copyright (c) 2017 Victor Perez + * + * 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 . + * + */ +#pragma once +#include "../../inc/MarlinConfig.h" + +bool SDIO_Init(); +bool SDIO_ReadBlock(uint32_t block, uint8_t *dst); +bool SDIO_WriteBlock(uint32_t block, const uint8_t *src); +bool SDIO_IsReady(); +uint32_t SDIO_GetCardSize(); diff --git a/Marlin/src/HAL/HC32/spi_pins.h b/Marlin/src/HAL/HC32/spi_pins.h new file mode 100644 index 000000000000..8a8e054b9bd9 --- /dev/null +++ b/Marlin/src/HAL/HC32/spi_pins.h @@ -0,0 +1,19 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * 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 . + * + */ +#pragma once diff --git a/Marlin/src/HAL/HC32/sysclock.cpp b/Marlin/src/HAL/HC32/sysclock.cpp new file mode 100644 index 000000000000..d205d725cc72 --- /dev/null +++ b/Marlin/src/HAL/HC32/sysclock.cpp @@ -0,0 +1,124 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 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 . + * + */ + +/** + * HC32f460 system clock configuration + */ + +#ifdef ARDUINO_ARCH_HC32 + +// Get BOARD_XTAL_FREQUENCY from configuration / pins +#include "../../inc/MarlinConfig.h" + +#include +#include + +void core_hook_sysclock_init() { + // Set wait cycles, as we are about to switch to 200 MHz HCLK + sysclock_configure_flash_wait_cycles(); + sysclock_configure_sram_wait_cycles(); + + // Configure MPLLp to 200 MHz output, with different settings depending on XTAL availability + #if BOARD_XTAL_FREQUENCY == 8000000 // 8 MHz XTAL + // - M = 1 => 8 MHz / 1 = 8 MHz + // - N = 50 => 8 MHz * 50 = 400 MHz + // - P = 2 => 400 MHz / 2 = 200 MHz (sysclk) + // - Q,R = 4 => 400 MHz / 4 = 100 MHz (dont care) + stc_clk_mpll_cfg_t pllConf = { + .PllpDiv = 2u, // P + .PllqDiv = 4u, // Q + .PllrDiv = 4u, // R + .plln = 50u, // N + .pllmDiv = 1u, // M + }; + sysclock_configure_xtal(); + sysclock_configure_mpll(ClkPllSrcXTAL, &pllConf); + + #elif BOARD_XTAL_FREQUENCY == 16000000 // 16 MHz XTAL + // - M = 1 => 16 MHz / 1 = 16 MHz + // - N = 50 => 16 MHz * 25 = 400 MHz + // - P = 2 => 400 MHz / 2 = 200 MHz (sysclk) + // - Q,R = 4 => 400 MHz / 4 = 100 MHz (dont care) + stc_clk_mpll_cfg_t pllConf = { + .PllpDiv = 2u, // P + .PllqDiv = 4u, // Q + .PllrDiv = 4u, // R + .plln = 50u, // N + .pllmDiv = 1u, // M + }; + sysclock_configure_xtal(); + sysclock_configure_mpll(ClkPllSrcXTAL, &pllConf); + + #warning "HC32F460 with 16 MHz XTAL has not been tested." + + #else // HRC (16 MHz) + // - M = 1 => 16 MHz / 1 = 16 MHz + // - N = 25 => 16 MHz * 25 = 400 MHz + // - P = 2 => 400 MHz / 2 = 200 MHz (sysclk) + // - Q,R = 4 => 400 MHz / 4 = 100 MHz (dont care) + stc_clk_mpll_cfg_t pllConf = { + .PllpDiv = 2u, // P + .PllqDiv = 4u, // Q + .PllrDiv = 4u, // R + .plln = 25u, // N + .pllmDiv = 1u, // M + }; + sysclock_configure_hrc(); + sysclock_configure_mpll(ClkPllSrcHRC, &pllConf); + + // HRC could have been configured by ICG to 20 MHz + // TODO: handle gracefully if HRC is not 16 MHz + if (1UL != (HRC_FREQ_MON() & 1UL)) { + panic("HRC is not 16 MHz"); + } + + #ifdef BOARD_XTAL_FREQUENCY + #warning "No valid XTAL frequency defined, falling back to HRC." + #endif + #endif + + // Setup clock divisors for sysclk = 200 MHz: + // Note: PCLK1 is used for step+temp timers, and need to be kept at 50 MHz (until there is a better solution) + stc_clk_sysclk_cfg_t sysClkConf = { + .enHclkDiv = ClkSysclkDiv1, // HCLK = 200 MHz (CPU) + .enExclkDiv = ClkSysclkDiv2, // EXCLK = 100 MHz (SDIO) + .enPclk0Div = ClkSysclkDiv1, // PCLK0 = 200 MHz (Timer6 (not used)) + .enPclk1Div = ClkSysclkDiv4, // PCLK1 = 50 MHz (USART, SPI, I2S, Timer0 (step+temp), TimerA (Servo)) + .enPclk2Div = ClkSysclkDiv4, // PCLK2 = 50 MHz (ADC) + .enPclk3Div = ClkSysclkDiv4, // PCLK3 = 50 MHz (I2C, WDT) + .enPclk4Div = ClkSysclkDiv2, // PCLK4 = 100 MHz (ADC ctl) + }; + sysclock_set_clock_dividers(&sysClkConf); + + // Set power mode + #define POWER_MODE_SYSTEM_CLOCK 200000000 // 200 MHz + power_mode_update_pre(POWER_MODE_SYSTEM_CLOCK); + + // Switch to MPLL as sysclk source + CLK_SetSysClkSource(CLKSysSrcMPLL); + + // Set power mode + power_mode_update_post(POWER_MODE_SYSTEM_CLOCK); + #undef POWER_MODE_SYSTEM_CLOCK +} + +#endif // ARDUINO_ARCH_HC32 diff --git a/Marlin/src/HAL/HC32/timers.cpp b/Marlin/src/HAL/HC32/timers.cpp new file mode 100644 index 000000000000..5f7d499622d5 --- /dev/null +++ b/Marlin/src/HAL/HC32/timers.cpp @@ -0,0 +1,54 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 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 . + * + */ + +#ifdef ARDUINO_ARCH_HC32 + +#include "timers.h" +#include + +/** + * Timer0 Unit 2 Channel A is used for Temperature interrupts + */ +Timer0 temp_timer(&TIMER02A_config, &Temp_Handler); + +/** + * Timer0 Unit 2 Channel B is used for Step interrupts + */ +Timer0 step_timer(&TIMER02B_config, &Step_Handler); + +void HAL_timer_start(const timer_channel_t timer_num, const uint32_t frequency) { + if (timer_num == TEMP_TIMER_NUM) { + CORE_DEBUG_PRINTF("HAL_timer_start: temp timer, f=%ld\n", long(frequency)); + timer_num->start(frequency, TEMP_TIMER_PRESCALE); + timer_num->setCallbackPriority(TEMP_TIMER_PRIORITY); + } + else if (timer_num == STEP_TIMER_NUM) { + CORE_DEBUG_PRINTF("HAL_timer_start: step timer, f=%ld\n", long(frequency)); + timer_num->start(frequency, STEPPER_TIMER_PRESCALE); + timer_num->setCallbackPriority(STEP_TIMER_PRIORITY); + } + else { + CORE_ASSERT_FAIL("HAL_timer_start: invalid timer_num") + } +} + +#endif // ARDUINO_ARCH_HC32 diff --git a/Marlin/src/HAL/HC32/timers.h b/Marlin/src/HAL/HC32/timers.h new file mode 100644 index 000000000000..17d8967982c2 --- /dev/null +++ b/Marlin/src/HAL/HC32/timers.h @@ -0,0 +1,135 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * Copyright (c) 2016 Bob Cousins bobcousins42@googlemail.com + * Copyright (c) 2017 Victor Perez + * + * 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 . + */ +#pragma once +#include +#include + +// +// Timer Types +// +typedef Timer0 *timer_channel_t; +typedef uint16_t hal_timer_t; +#define HAL_TIMER_TYPE_MAX 0xFFFF + +// +// Timer instances +// +extern Timer0 temp_timer; +extern Timer0 step_timer; + +// +// Timer Configurations +// + +// TODO: some calculations (step irq min_step_rate) require the timer rate to be known at compile time +// this is not possible with the HC32F460, as the timer rate depends on PCLK1 +// as a workaround, PCLK1 = 50MHz is assumed (check with clock dump in MarlinHAL::init()) +#define HAL_TIMER_RATE 50000000 // 50MHz +// #define HAL_TIMER_RATE TIMER0_BASE_FREQUENCY + +// TODO: CYCLES_PER_MICROSECOND seems to be used by Marlin to calculate the number of cycles per microsecond in the timer ISRs +// by default, it uses F_CPU, but since that is not known at compile time for HC32, we overwrite it here +#undef CYCLES_PER_MICROSECOND +#define CYCLES_PER_MICROSECOND (HAL_TIMER_RATE / 1000000UL) + +// Temperature timer +#define TEMP_TIMER_NUM (&temp_timer) +#define TEMP_TIMER_PRIORITY DDL_IRQ_PRIORITY_02 +#define TEMP_TIMER_PRESCALE 16ul +#define TEMP_TIMER_RATE 1000 // 1kHz +#define TEMP_TIMER_FREQUENCY TEMP_TIMER_RATE // Alias for Marlin + +// Stepper timer +#define STEP_TIMER_NUM (&step_timer) +#define STEP_TIMER_PRIORITY DDL_IRQ_PRIORITY_01 +#define STEPPER_TIMER_PRESCALE 16ul + +// TODO: STEPPER_TIMER_RATE seems to work fine like this, but requires further testing... +#define STEPPER_TIMER_RATE (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE) // 50MHz / 16 = 3.125MHz +#define STEPPER_TIMER_TICKS_PER_US (STEPPER_TIMER_RATE / 1000000) + +// Pulse timer (== stepper timer) +#define PULSE_TIMER_NUM STEP_TIMER_NUM +#define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE +#define PULSE_TIMER_TICKS_PER_US STEPPER_TIMER_TICKS_PER_US + +// +// Channel aliases +// +#define MF_TIMER_TEMP TEMP_TIMER_NUM +#define MF_TIMER_STEP STEP_TIMER_NUM +#define MF_TIMER_PULSE PULSE_TIMER_NUM + +// +// HAL functions +// +void HAL_timer_start(const timer_channel_t timer_num, const uint32_t frequency); + +// Inlined since they are somewhat critical +#define MARLIN_HAL_TIMER_INLINE_ATTR __attribute__((always_inline)) inline + +MARLIN_HAL_TIMER_INLINE_ATTR void HAL_timer_enable_interrupt(const timer_channel_t timer_num) { + timer_num->resume(); +} + +MARLIN_HAL_TIMER_INLINE_ATTR void HAL_timer_disable_interrupt(const timer_channel_t timer_num) { + timer_num->pause(); +} + +MARLIN_HAL_TIMER_INLINE_ATTR bool HAL_timer_interrupt_enabled(const timer_channel_t timer_num) { + return timer_num->isPaused(); +} + +MARLIN_HAL_TIMER_INLINE_ATTR void HAL_timer_set_compare(const timer_channel_t timer_num, const hal_timer_t compare) { + timer_num->setCompareValue(compare); +} + +MARLIN_HAL_TIMER_INLINE_ATTR hal_timer_t HAL_timer_get_count(const timer_channel_t timer_num) { + return timer_num->getCount(); +} + +MARLIN_HAL_TIMER_INLINE_ATTR void HAL_timer_isr_prologue(const timer_channel_t timer_num) { + timer_num->clearInterruptFlag(); +} + +MARLIN_HAL_TIMER_INLINE_ATTR void HAL_timer_isr_epilogue(const timer_channel_t timer_num) {} + +// +// HAL function aliases +// +#define ENABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(STEP_TIMER_NUM) +#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(STEP_TIMER_NUM) +#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(STEP_TIMER_NUM) + +#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(TEMP_TIMER_NUM) +#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(TEMP_TIMER_NUM); + +// +// HAL ISR callbacks +// +void Step_Handler(); +void Temp_Handler(); + +#ifndef HAL_STEP_TIMER_ISR +#define HAL_STEP_TIMER_ISR() void Step_Handler() +#endif +#ifndef HAL_TEMP_TIMER_ISR +#define HAL_TEMP_TIMER_ISR() void Temp_Handler() +#endif diff --git a/Marlin/src/HAL/platforms.h b/Marlin/src/HAL/platforms.h index 84ba7087b0ea..9eaf7cea9894 100644 --- a/Marlin/src/HAL/platforms.h +++ b/Marlin/src/HAL/platforms.h @@ -35,6 +35,8 @@ #define HAL_PATH(PATH, NAME) XSTR(PATH/HAL/TEENSY40_41/NAME) #elif defined(TARGET_LPC1768) #define HAL_PATH(PATH, NAME) XSTR(PATH/HAL/LPC1768/NAME) +#elif defined(ARDUINO_ARCH_HC32) + #define HAL_PATH(PATH, NAME) XSTR(PATH/HAL/HC32/NAME) #elif defined(__STM32F1__) || defined(TARGET_STM32F1) #define HAL_PATH(PATH, NAME) XSTR(PATH/HAL/STM32F1/NAME) #elif defined(ARDUINO_ARCH_STM32) diff --git a/Marlin/src/HAL/shared/servo.h b/Marlin/src/HAL/shared/servo.h index 15153ca53fa9..786c1e6a7231 100644 --- a/Marlin/src/HAL/shared/servo.h +++ b/Marlin/src/HAL/shared/servo.h @@ -74,6 +74,8 @@ #include "../TEENSY40_41/Servo.h" #elif defined(TARGET_LPC1768) #include "../LPC1768/Servo.h" +#elif defined(ARDUINO_ARCH_HC32) + #include "../HC32/Servo.h" #elif defined(__STM32F1__) || defined(TARGET_STM32F1) #include "../STM32F1/Servo.h" #elif defined(ARDUINO_ARCH_STM32) diff --git a/Marlin/src/core/boards.h b/Marlin/src/core/boards.h index 174ec404a796..cf590724b588 100644 --- a/Marlin/src/core/boards.h +++ b/Marlin/src/core/boards.h @@ -510,6 +510,11 @@ #define BOARD_MINITRONICS20 7103 // Minitronics v2.0 +// +// HC32 ARM Cortex-M4 +// +#define BOARD_AQUILA_V101 7200 // Aquila V1.0.1 as found in the Voxelab Aquila X2 + // // Custom board // diff --git a/Marlin/src/inc/Conditionals_adv.h b/Marlin/src/inc/Conditionals_adv.h index 7fc6050f0db9..634652c9bf99 100644 --- a/Marlin/src/inc/Conditionals_adv.h +++ b/Marlin/src/inc/Conditionals_adv.h @@ -1256,7 +1256,7 @@ * currently HAL.h must be included ahead of pins.h. */ #if LCD_IS_SERIAL_HOST && !defined(LCD_SERIAL_PORT) - #if MB(BTT_SKR_MINI_E3_V1_0, BTT_SKR_MINI_E3_V1_2, BTT_SKR_MINI_E3_V2_0, BTT_SKR_MINI_E3_V3_0, BTT_SKR_E3_TURBO, BTT_OCTOPUS_V1_1) + #if MB(BTT_SKR_MINI_E3_V1_0, BTT_SKR_MINI_E3_V1_2, BTT_SKR_MINI_E3_V2_0, BTT_SKR_MINI_E3_V3_0, BTT_SKR_E3_TURBO, BTT_OCTOPUS_V1_1, AQUILA_V101) #define LCD_SERIAL_PORT 1 #elif MB(CREALITY_V24S1_301, CREALITY_V24S1_301F4, CREALITY_F401RE, CREALITY_V423, MKS_ROBIN, PANOWIN_CUTLASS, KODAMA_BARDO) #define LCD_SERIAL_PORT 2 diff --git a/Marlin/src/libs/BL24CXX.cpp b/Marlin/src/libs/BL24CXX.cpp index adfdc1387cf2..767561143cb8 100644 --- a/Marlin/src/libs/BL24CXX.cpp +++ b/Marlin/src/libs/BL24CXX.cpp @@ -48,7 +48,7 @@ #ifdef __STM32F1__ #define SDA_IN() do{ PIN_MAP[IIC_EEPROM_SDA].gpio_device->regs->CRH &= 0XFFFF0FFF; PIN_MAP[IIC_EEPROM_SDA].gpio_device->regs->CRH |= 8 << 12; }while(0) #define SDA_OUT() do{ PIN_MAP[IIC_EEPROM_SDA].gpio_device->regs->CRH &= 0XFFFF0FFF; PIN_MAP[IIC_EEPROM_SDA].gpio_device->regs->CRH |= 3 << 12; }while(0) -#elif defined(STM32F1) || defined(STM32F4) +#elif defined(STM32F1) || defined(STM32F4) || defined(ARDUINO_ARCH_HC32) #define SDA_IN() SET_INPUT(IIC_EEPROM_SDA) #define SDA_OUT() SET_OUTPUT(IIC_EEPROM_SDA) #endif diff --git a/Marlin/src/pins/hc32f4/env_validate.h b/Marlin/src/pins/hc32f4/env_validate.h new file mode 100644 index 000000000000..7883bc03c743 --- /dev/null +++ b/Marlin/src/pins/hc32f4/env_validate.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 . + * + */ +#pragma once + +#ifndef ARDUINO_ARCH_HC32 + #error "Oops! Select an HC32F460 board in 'Tools > Board.'" +#endif diff --git a/Marlin/src/pins/hc32f4/pins_AQUILA_101.h b/Marlin/src/pins/hc32f4/pins_AQUILA_101.h new file mode 100644 index 000000000000..a9dfb9b0f9b8 --- /dev/null +++ b/Marlin/src/pins/hc32f4/pins_AQUILA_101.h @@ -0,0 +1,212 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 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 . + * + */ +#pragma once + +// +// Voxelab Aquila V1.0.1 and V1.0.2 (HC32F460) as found in the Voxelab Aquila X2 +// +#include "env_validate.h" + +#if HAS_MULTI_HOTEND || E_STEPPERS > 1 + #error "Aquila V1.0.1 only supports one hotend and E-stepper" +#endif + +#ifndef BOARD_INFO_NAME + #define BOARD_INFO_NAME "Aquila V1.0.1" +#endif +#ifndef DEFAULT_MACHINE_NAME + #define DEFAULT_MACHINE_NAME "Aquila" +#endif + +// +// Onboard crystal oscillator +// +#ifndef BOARD_XTAL_FREQUENCY + #define BOARD_XTAL_FREQUENCY 8000000 // 8 MHz XTAL +#endif + +// +// Release PB4 (Y_ENABLE_PIN) from JTAG NRST role +// +//#define DISABLE_DEBUG +//#define DISABLE_JTAG + +// +// EEPROM +// +#if NO_EEPROM_SELECTED + #define IIC_BL24CXX_EEPROM + //#define SDCARD_EEPROM_EMULATION + #undef NO_EEPROM_SELECTED +#endif + +#if ENABLED(IIC_BL24CXX_EEPROM) + #define IIC_EEPROM_SDA PA11 + #define IIC_EEPROM_SCL PA12 + #define MARLIN_EEPROM_SIZE 0x800 // 2K (24C16) +#elif ENABLED(SDCARD_EEPROM_EMULATION) + #define MARLIN_EEPROM_SIZE 0x800 // 2K +#endif + +// +// Servos +// +#ifndef SERVO0_PIN + #define SERVO0_PIN PB0 // BLTouch OUT +#endif + +// +// Limit Switches +// +#define X_STOP_PIN PA5 +#define Y_STOP_PIN PA6 +#define Z_STOP_PIN PA7 + +#ifndef Z_MIN_PROBE_PIN + #define Z_MIN_PROBE_PIN PB1 // BLTouch IN +#endif + +// +// Filament Runout Sensor +// +#ifndef FIL_RUNOUT_PIN + #define FIL_RUNOUT_PIN PA4 +#endif + +// +// Steppers +// +#define X_STEP_PIN PC2 +#define X_DIR_PIN PB9 +#define X_ENABLE_PIN PC3 // All steppers share enable pins + +#define Y_STEP_PIN PB8 +#define Y_DIR_PIN PB7 +#define Y_ENABLE_PIN X_ENABLE_PIN + +#define Z_STEP_PIN PB6 +#define Z_DIR_PIN PB5 +#define Z_ENABLE_PIN X_ENABLE_PIN + +#define E0_STEP_PIN PB4 +#define E0_DIR_PIN PB3 +#define E0_ENABLE_PIN X_ENABLE_PIN + +// +// Temperature Sensors +// +#define TEMP_0_PIN PC5 // HEATER1 ADC1_IN15 +#define TEMP_BED_PIN PC4 // HOT BED ADC1_IN14 + +// +// Heaters / Fans +// +#define HEATER_0_PIN PA1 // HEATER1 +#define HEATER_BED_PIN PA2 // HOT BED + +#define FAN0_PIN PA0 // FAN0 + +// +// SD Card +// +#define SD_DETECT_PIN PA10 +#define SDCARD_CONNECTION ONBOARD +#define ONBOARD_SDIO +#define NO_SD_HOST_DRIVE // This board's SD card is only seen by the printer + +/** + * ------ + * PC6 | 1 2 | PB2 + * PC0 | 3 4 | PC1 + * PB14 5 6 | PB13 + * PB12 | 7 8 | PB15 + * GND | 9 10 | +5V + * ------ + * EXP1 + */ +#define EXP1_01_PIN PC6 +#define EXP1_02_PIN PB2 +#define EXP1_03_PIN PC0 +#define EXP1_04_PIN PC1 +#define EXP1_05_PIN PB14 // ENC +#define EXP1_06_PIN PB13 // BEEPER +#define EXP1_07_PIN PB12 // EN2 +#define EXP1_08_PIN PB15 // EN1 + +#if ANY(HAS_DWIN_E3V2, IS_DWIN_MARLINUI) + /** + * Display pinout (display side, so RX/TX are swapped) + * + * ------ + * NC | 1 2 | NC + * RX | 3 4 | TX + * EN 5 6 | BEEP + * B | 7 8 | A + * GND | 9 10 | +5V + * ------ + */ + + #ifndef BEEPER_PIN + #define BEEPER_PIN EXP1_06_PIN // BEEP + #endif + + #define BTN_ENC EXP1_05_PIN // EN + #define BTN_EN1 EXP1_08_PIN // A + #define BTN_EN2 EXP1_07_PIN // B + + #ifndef LCD_SERIAL_PORT + #define LCD_SERIAL_PORT 1 + #endif + +#endif + +// +// SDIO Pins +// +#define BOARD_SDIO_D0 PC8 +#define BOARD_SDIO_D1 PC9 +#define BOARD_SDIO_D2 PC10 +#define BOARD_SDIO_D3 PC11 +#define BOARD_SDIO_CLK PC12 +#define BOARD_SDIO_CMD PD2 +#define BOARD_SDIO_DET PA10 + +// +// USART Pins +// + +// Display +#define BOARD_USART1_TX_PIN PC0 +#define BOARD_USART1_RX_PIN PC1 + +// Host +#define BOARD_USART2_TX_PIN PA9 +#define BOARD_USART2_RX_PIN PA15 + +// Unused / Debug +#define BOARD_USART3_TX_PIN PE5 +#define BOARD_USART3_RX_PIN PE4 + +// Onboard LED (HIGH = off, LOW = on) +#ifndef LED_BUILTIN + #define LED_BUILTIN PA3 +#endif diff --git a/Marlin/src/pins/mega/pins_GT2560_V41b.h b/Marlin/src/pins/mega/pins_GT2560_V41b.h index e74b2994840f..12d45be9853d 100644 --- a/Marlin/src/pins/mega/pins_GT2560_V41b.h +++ b/Marlin/src/pins/mega/pins_GT2560_V41b.h @@ -84,7 +84,7 @@ #endif #ifndef Z2_STOP_PIN #define Z2_STOP_PIN 80 // PE7 - Extended mega2560 pin -#endif +#endif /** Filament Runout Sensors * diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index 6b44d68445c5..a7076d90e4ce 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -885,6 +885,12 @@ #elif MB(MINITRONICS20) #include "samd/pins_MINITRONICS20.h" // SAMD21 env:SAMD21_minitronics20 +// +// HC32 ARM Cortex-M4 +// +#elif MB(AQUILA_V101) + #include "hc32f4/pins_AQUILA_101.h" // HC32F460 env:HC32F460C_aquila_101 + // // Custom board (with custom PIO env) // diff --git a/Marlin/src/pins/stm32f1/pins_MD_D301.h b/Marlin/src/pins/stm32f1/pins_MD_D301.h index b40ffb936d7d..5724879badec 100644 --- a/Marlin/src/pins/stm32f1/pins_MD_D301.h +++ b/Marlin/src/pins/stm32f1/pins_MD_D301.h @@ -210,7 +210,7 @@ #define TFT_CS_PIN FSMC_CS_PIN #define TFT_RS_PIN FSMC_RS_PIN - + // Buffer for Color UI #define TFT_BUFFER_WORDS 3200 #endif diff --git a/buildroot/tests/HC32F460C_aquila_101 b/buildroot/tests/HC32F460C_aquila_101 new file mode 100755 index 000000000000..0544720891a7 --- /dev/null +++ b/buildroot/tests/HC32F460C_aquila_101 @@ -0,0 +1,15 @@ +#!/usr/bin/env bash +# +# Build tests for HC32F460C_aquila_101 +# + +# exit on first failure +set -e + +restore_configs +opt_set MOTHERBOARD BOARD_AQUILA_V101 SERIAL_PORT 1 +opt_enable EEPROM_SETTINGS SDSUPPORT EMERGENCY_PARSER +exec_test $1 $2 "Default Configuration with Fallback SD EEPROM" "$3" + +# cleanup +restore_configs diff --git a/ini/hc32.ini b/ini/hc32.ini new file mode 100644 index 000000000000..676f9e19b6e5 --- /dev/null +++ b/ini/hc32.ini @@ -0,0 +1,88 @@ +# +# Marlin Firmware +# PlatformIO Configuration File +# + +################################# +# +# HC32F460 Architecture with unified HC32 HAL +# +# Naming Example: HC32F460JEUA +# +# |- Xiaohua Semiconductor +# | |- CPU bit width (32: 32-bit) +# | | |- Product Type (F: Universal MCU) +# | | | |- Core Type (4: Cortex-M4) +# | | | | |- Performance (6: High Performance) +# | | | | | |- Configuration (0: Configuration 1) +# | | | | | | |- Pin Count (J: 48, K: 60/64, P: 100) +# | | | | | | | |- Flash Capacity (C: 256KB, E: 512KB) +# | | | | | | | | |- Package (T: LQFP, U: QFN, H:VFBGA) +# | | | | | | | | | |- Temperature range (A: -40-85°C, B: -40-105°C) +# HC 32 F 4 6 0 J E U A +# +################################# + +# +# Base Environment for all HC32F460 variants +# +[HC32F460_base] +platform = https://github.com/shadow578/platform-hc32f46x/archive/main.zip +board = generic_hc32f460 +build_src_filter = ${common.default_src_filter} + + +build_type = release +build_flags = + -D ARDUINO_ARCH_HC32 + -D REDIRECT_PRINTF_TO_SERIAL # Redirect core-provided printf to host serial + -D F_CPU=SYSTEM_CLOCK_FREQUENCIES.pclk1 # Override F_CPU to PCLK1, as marlin freaks out otherwise... + -D PLATFORM_M997_SUPPORT # Enable M997 command + + # DDL / Arduino Configuration + -D DISABLE_SERIAL_GLOBALS # Disable global Serial objects, we use our own + -D CORE_DISABLE_FAULT_HANDLER # Disable arduino core fault handler (we use our own) + + # DDL / Arduino Debug Options + #-D __DEBUG # DDL debug mode + #-D __CORE_DEBUG # Arduino core debug mode + -D PANIC_ENABLE # enable custom panic handlers (in MinSerial) + # options to reduce debug mode footprint (-16K; messages are less verbose) + -D __DEBUG_SHORT_FILENAMES # Use short filenames in DDL debug output + -D __PANIC_SHORT_FILENAMES # Use short filenames in core panic output + -D __OMIT_PANIC_MESSAGE # Omit panic messages in core panic output + + +# Drivers and Middleware required by the HC32 HAL +board_build.ddl.ots = true +board_build.ddl.sdioc = true +board_build.ddl.wdt = true +board_build.ddl.timer0 = true +board_build.ddl.timera = true +board_build.mw.sd_card = true + +# Additional flags to reduce binary size +board_build.flags.cpp = + -fno-threadsafe-statics # Disable thread-safe statics (only one core anyway) + -fno-exceptions # Disable exceptions (not used by marlin) + -fno-rtti # Disable RTTI (not used by marlin) + +# +# Base HC32F460xCxx (256K Flash) +# +[HC32F460C_base] +extends = HC32F460_base +board_build.ld_args.flash_size = 256K + +# +# Base HC32F460xExx (512K Flash) +# +[HC32F460E_base] +extends = HC32F460_base +board_build.ld_args.flash_size = 512K + +# +# Aquila V1.0.1 Mainboard, as found in the Voxelab Aquila X2 +# +[env:HC32F460C_aquila_101] +extends = HC32F460C_base +board_build.ld_args.flash_start = 0xC000 # Bootloader start address, as logged by the bootloader on boot +board_build.ld_args.boot_mode = secondary # Save ~1.4k of flash by compiling as secondary firmware diff --git a/platformio.ini b/platformio.ini index e3bdb6f58676..81f97e73b8c4 100644 --- a/platformio.ini +++ b/platformio.ini @@ -21,6 +21,7 @@ extra_configs = ini/due.ini ini/esp32.ini ini/features.ini + ini/hc32.ini ini/lpc176x.ini ini/native.ini ini/samd21.ini From e958b6da9eaff0a4a2c1a0ff9ebf7480a5ecfce7 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Mon, 27 Nov 2023 00:23:10 +0000 Subject: [PATCH 27/77] [cron] Bump distribution date (2023-11-27) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index f9da779f1cff..d3b4d058ff64 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2023-11-26" +//#define STRING_DISTRIBUTION_DATE "2023-11-27" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index fd5cac89d3af..f28395a6c957 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2023-11-26" + #define STRING_DISTRIBUTION_DATE "2023-11-27" #endif /** From b78f0012e99739de337254f7b8681ea7a6aa5f3d Mon Sep 17 00:00:00 2001 From: Andrew <18502096+classicrocker883@users.noreply.github.com> Date: Tue, 28 Nov 2023 01:10:18 -0500 Subject: [PATCH 28/77] =?UTF-8?q?=F0=9F=93=9D=20Fix=20comment=20dates=20(#?= =?UTF-8?q?26472)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/stm32f1/pins_BEAST.h | 2 +- Marlin/src/pins/stm32f1/pins_STM32F1R.h | 2 +- Marlin/src/pins/stm32f1/pins_STM3R_MINI.h | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/Marlin/src/pins/stm32f1/pins_BEAST.h b/Marlin/src/pins/stm32f1/pins_BEAST.h index b136ca52cd70..cf64ff1c6a29 100644 --- a/Marlin/src/pins/stm32f1/pins_BEAST.h +++ b/Marlin/src/pins/stm32f1/pins_BEAST.h @@ -24,7 +24,7 @@ #include "env_validate.h" /** - * 21017 Victor Perez Marlin for stm32f1 test + * 2017 Victor Perez Marlin for stm32f1 test */ #define BOARD_INFO_NAME "Beast STM32" diff --git a/Marlin/src/pins/stm32f1/pins_STM32F1R.h b/Marlin/src/pins/stm32f1/pins_STM32F1R.h index a2efa632f8c8..9cbc69149cd5 100644 --- a/Marlin/src/pins/stm32f1/pins_STM32F1R.h +++ b/Marlin/src/pins/stm32f1/pins_STM32F1R.h @@ -24,7 +24,7 @@ #include "env_validate.h" /** - * 21017 Victor Perez Marlin for stm32f1 test + * 2017 Victor Perez Marlin for stm32f1 test */ #define BOARD_INFO_NAME "Misc. STM32F1R" diff --git a/Marlin/src/pins/stm32f1/pins_STM3R_MINI.h b/Marlin/src/pins/stm32f1/pins_STM3R_MINI.h index b4cf21ee7f04..e5b16460f010 100644 --- a/Marlin/src/pins/stm32f1/pins_STM3R_MINI.h +++ b/Marlin/src/pins/stm32f1/pins_STM3R_MINI.h @@ -24,7 +24,7 @@ #include "env_validate.h" /** - * 10 Dec 2017 Victor Perez Marlin for stm32f1 test + * 2017 Victor Perez Marlin for stm32f1 test */ #define BOARD_INFO_NAME "STM3R Mini" From 7a96a082b70deeed8648f7c1bebe21a3a0aaab56 Mon Sep 17 00:00:00 2001 From: I3DBeeTech <129617321+I3DBeeTech@users.noreply.github.com> Date: Tue, 28 Nov 2023 12:13:17 +0530 Subject: [PATCH 29/77] =?UTF-8?q?=E2=9C=A8=20BlackBeezMini=203D=20by=20I3D?= =?UTF-8?q?BEE=20(#26406)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine Co-authored-by: thisiskeithb <13375512+thisiskeithb@users.noreply.github.com> --- Marlin/src/core/boards.h | 1 + Marlin/src/pins/pins.h | 2 + Marlin/src/pins/stm32f4/pins_BLACKBEEZMINI.h | 176 ++++++++++++++++++ .../src/pins/stm32f4/pins_BTT_BTT002_V1_0.h | 18 +- .../PlatformIO/scripts/offset_and_rename.py | 2 +- ini/stm32f4.ini | 14 ++ 6 files changed, 202 insertions(+), 11 deletions(-) create mode 100644 Marlin/src/pins/stm32f4/pins_BLACKBEEZMINI.h diff --git a/Marlin/src/core/boards.h b/Marlin/src/core/boards.h index cf590724b588..0c685460bf08 100644 --- a/Marlin/src/core/boards.h +++ b/Marlin/src/core/boards.h @@ -462,6 +462,7 @@ #define BOARD_I3DBEEZ9_V1 5247 // I3DBEEZ9 V1 (STM32F407ZG) #define BOARD_MELLOW_FLY_E3_V2 5248 // Mellow Fly E3 V2 (STM32F407VG) #define BOARD_FYSETC_CHEETAH_V30 5249 // FYSETC Cheetah V3.0 (STM32F446RC) +#define BOARD_BLACKBEEZMINI_V1 5250 // BlackBeezMini V1 (STM32F401CCU6) // // ARM Cortex-M7 diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index a7076d90e4ce..1618078f45f6 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -810,6 +810,8 @@ #include "stm32f4/pins_I3DBEEZ9.h" // STM32F4 env:I3DBEEZ9_V1 #elif MB(MELLOW_FLY_E3_V2) #include "stm32f4/pins_MELLOW_FLY_E3_V2.h" // STM32F4 env:FLY_E3_V2 +#elif MB(BLACKBEEZMINI_V1) + #include "stm32f4/pins_BLACKBEEZMINI.h" // STM32F4 env:BLACKBEEZMINI_V1 // // ARM Cortex-M7 diff --git a/Marlin/src/pins/stm32f4/pins_BLACKBEEZMINI.h b/Marlin/src/pins/stm32f4/pins_BLACKBEEZMINI.h new file mode 100644 index 000000000000..33b2219655ea --- /dev/null +++ b/Marlin/src/pins/stm32f4/pins_BLACKBEEZMINI.h @@ -0,0 +1,176 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 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 . + * + */ +#pragma once + +#if NOT_TARGET(STM32F4) + #error "Oops! Select an STM32F4 board in 'Tools > Board.'" +#elif HOTENDS > 1 || E_STEPPERS > 1 + #error "STM32F401CCU6 boards support one hotend / E-steppers only." +#endif + +#include "env_validate.h" + +#ifndef DEFAULT_MACHINE_NAME + #define DEFAULT_MACHINE_NAME "I3DBEE BP_01" +#endif + +#define TEMP_TIMER 5 + +//#define DISABLE_DEBUG // DISABLE_(DEBUG|JTAG) is not supported for STM32F4. +//#define DISABLE_JTAG +//#define ALLOW_STM32F4 +//#define BOARD_NO_NATIVE_USB + +// +// EEPROM +// +#if NO_EEPROM_SELECTED + #define FLASH_EEPROM_EMULATION + #define FLASH_EEPROM_LEVELING + #define FLASH_SECTOR (FLASH_SECTOR_TOTAL - 1) + #define FLASH_UNIT_SIZE 0x4000 // 16kB + #define MARLIN_EEPROM_SIZE FLASH_UNIT_SIZE + #undef NO_EEPROM_SELECTED +#endif + +/* +#if NO_EEPROM_SELECTED + #define IIC_BL24CXX_EEPROM // EEPROM on I2C-0 + #define SDCARD_EEPROM_EMULATION +#endif +*/ + +// +// Limit Switches +// +#define X_STOP_PIN PB9 +#define Y_STOP_PIN PB3 +#define Z_STOP_PIN PA9 + +// +// Steppers +// +#define X_STEP_PIN PB7 +#define X_DIR_PIN PB6 +#define X_ENABLE_PIN PB8 + +#define Y_STEP_PIN PB5 +#define Y_DIR_PIN PB4 +#define Y_ENABLE_PIN X_ENABLE_PIN + +#define Z_STEP_PIN PA15 +#define Z_DIR_PIN PA10 +#define Z_ENABLE_PIN X_ENABLE_PIN + +#define E0_STEP_PIN PA8 +#define E0_DIR_PIN PB15 +#define E0_ENABLE_PIN X_ENABLE_PIN + +// +// Temperature Sensors +// +#define TEMP_0_PIN PB1 // Analog Input (HOTEND thermistor) +#define TEMP_BED_PIN PB0 // Analog Input (BED thermistor) + +// +// Heaters / Fans +// +#define HEATER_0_PIN PA2 // HOTEND MOSFET +#define HEATER_BED_PIN PA0 // BED MOSFET + +#define FAN1_PIN PA1 // FAN1 header on board - PRINT FAN + +// +// SD Card +// +#define SDSS PA4 +#define SD_DETECT_PIN -1 +#define SD_SCK_PIN PA5 +#define SD_MISO_PIN PA6 +#define SD_MOSI_PIN PA7 + +/** + * ------ ------ + * (BEEPER) PB10 | 1 2 | PC13 (BTN_ENC) (MISO) PA6 | 1 2 | PA5 (SCK) + * (LCD_EN) PB13 | 3 4 | PB12 (LCD_RS) (BTN_EN1) PC15 | 3 4 | PA4 (SD_SS) + * (LCD_D4) PB14 5 6 | PA3 (LCD_D5) (BTN_EN2) PC14 5 6 | PA7 (MOSI) + * (LCD_D6) - | 7 8 | - (LCD_D7) (SD_DET) - | 7 8 | RESET + * GND | 9 10 | 5V GND | 9 10 | - + * ------ ------ + * EXP1 EXP2 + */ +#define EXP1_01_PIN PB10 // BEEPER +#define EXP1_02_PIN PC13 // ENC +#define EXP1_03_PIN PB13 // EN +#define EXP1_04_PIN PB12 // RS +#define EXP1_05_PIN PB14 // D4 +#define EXP1_06_PIN PA3 // D5 +#define EXP1_07_PIN -1 +#define EXP1_08_PIN -1 + +#define EXP2_01_PIN PA6 // MISO +#define EXP2_02_PIN PA5 // SCK +#define EXP2_03_PIN PC15 // EN1 +#define EXP2_04_PIN PA4 // SS +#define EXP2_05_PIN PC14 // EN2 +#define EXP2_06_PIN PA7 // MOSI +#define EXP2_07_PIN -1 +#define EXP2_08_PIN -1 // RESET +#define EXP2_10_PIN -1 + +// +// LCD / Controller +// +#if HAS_WIRED_LCD + #define BEEPER_PIN EXP1_01_PIN + + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN + #define BTN_ENC EXP1_02_PIN + + #define LCD_PINS_RS EXP1_04_PIN + #define LCD_PINS_EN EXP1_03_PIN + #define LCD_PINS_D4 EXP1_05_PIN + #define LCD_PINS_D5 EXP1_06_PIN + + #if ENABLED(FYSETC_MINI_12864) + #define DOGLCD_CS EXP1_03_PIN + #define DOGLCD_A0 EXP1_04_PIN + //#define LCD_BACKLIGHT_PIN -1 + #define LCD_RESET_PIN EXP1_05_PIN // Must be high or open for LCD to operate normally. + #if ENABLED(FYSETC_MINI_12864_2_1) + #define NEOPIXEL_PIN EXP1_06_PIN + #endif + #endif + + // + // GLCD features + // + //#define LCD_CONTRAST 190 + + // + // Dcreen orientation + // + //#define LCD_SCREEN_ROT_90 + //#define LCD_SCREEN_ROT_180 + //#define LCD_SCREEN_ROT_270 +#endif diff --git a/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h b/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h index bc80720916fb..d7196b75fc34 100644 --- a/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h +++ b/Marlin/src/pins/stm32f4/pins_BTT_BTT002_V1_0.h @@ -201,16 +201,14 @@ #endif /** - * ---------------------------------BTT002 V1.0--------------------------------- - * ------ ------ | - * (BEEPER) PE7 | 1 2 | PB1 (BTN_ENC) (MISO) PA6 | 1 2 | PA5 (SCK) | - * (LCD_EN) PE9 | 3 4 | PE8 (LCD_RS) (BTN_EN1) PC5 | 3 4 | PA4 (SD_SS) | - * (LCD_D4) PE10 5 6 | PE11 (LCD_D5) (BTN_EN2) PB0 5 6 | PA7 (MOSI) | - * (LCD_D6) PE12 | 7 8 | PE13 (LCD_D7) (SD_DET) PC4 | 7 8 | RESET | - * GND | 9 10 | 5V GND | 9 10 | PA3 | - * ------ ------ | - * EXP1 EXP2 | - * ------------------------------------------------------------------------------ + * ------ ------ + * (BEEPER) PE7 | 1 2 | PB1 (BTN_ENC) (MISO) PA6 | 1 2 | PA5 (SCK) + * (LCD_EN) PE9 | 3 4 | PE8 (LCD_RS) (BTN_EN1) PC5 | 3 4 | PA4 (SD_SS) + * (LCD_D4) PE10 5 6 | PE11 (LCD_D5) (BTN_EN2) PB0 5 6 | PA7 (MOSI) + * (LCD_D6) PE12 | 7 8 | PE13 (LCD_D7) (SD_DET) PC4 | 7 8 | RESET + * GND | 9 10 | 5V GND | 9 10 | PA3 + * ------ ------ + * EXP1 EXP2 */ #define EXP1_01_PIN PE7 #define EXP1_02_PIN PB1 diff --git a/buildroot/share/PlatformIO/scripts/offset_and_rename.py b/buildroot/share/PlatformIO/scripts/offset_and_rename.py index 20f2b78024b8..353518600853 100644 --- a/buildroot/share/PlatformIO/scripts/offset_and_rename.py +++ b/buildroot/share/PlatformIO/scripts/offset_and_rename.py @@ -1,7 +1,7 @@ # # offset_and_rename.py # -# - If 'build.offset' is provided, either by JSON or by the environment... +# - If 'board_build.offset' is provided, either by JSON or by the environment... # - Set linker flag LD_FLASH_OFFSET and relocate the VTAB based on 'build.offset'. # - Set linker flag LD_MAX_DATA_SIZE based on 'build.maximum_ram_size'. # - Define STM32_FLASH_SIZE from 'upload.maximum_size' for use by Flash-based EEPROM emulation. diff --git a/ini/stm32f4.ini b/ini/stm32f4.ini index f094b96c9bd2..0ba6b66c3fed 100644 --- a/ini/stm32f4.ini +++ b/ini/stm32f4.ini @@ -820,6 +820,20 @@ build_flags = ${stm32_variant.build_flags} -DSTM32F407_5ZX debug_tool = stlink upload_protocol = stlink +# +# BlackBeezMini (blackpill_f401cc) +# +[env:BLACKBEEZMINI_V1] +platform = ststm32 +extends = common_stm32 +board = blackpill_f401cc +board_build.offset = 0x0000 +build_flags = ${common_stm32.build_flags} + -Os -DHAL_PCD_MODULE_ENABLED + -DHAL_UART_MODULE_ENABLED +monitor_speed = 250000 +upload_protocol = dfu + # # Mellow Fly E3 V2 (STM32F407VGT6 ARM Cortex-M4) # From b95aa36b01801a7d8ad6cba4172058f708f635a6 Mon Sep 17 00:00:00 2001 From: Keith Bennett <13375512+thisiskeithb@users.noreply.github.com> Date: Mon, 27 Nov 2023 22:46:21 -0800 Subject: [PATCH 30/77] =?UTF-8?q?=F0=9F=93=9D=20Community=20Reporting=20re?= =?UTF-8?q?dux=20(#26368)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .github/code_of_conduct.md | 2 +- .github/contributing.md | 8 +++++--- 2 files changed, 6 insertions(+), 4 deletions(-) diff --git a/.github/code_of_conduct.md b/.github/code_of_conduct.md index 888c2ccf76fd..5fd9e0c8eeb5 100644 --- a/.github/code_of_conduct.md +++ b/.github/code_of_conduct.md @@ -30,7 +30,7 @@ Project maintainers have the right and responsibility to remove, edit, or reject ## Enforcement -Instances of abusive, harassing, or otherwise unacceptable behavior may be reported by messaging @MarlinFirmware/moderators on the relevant issue, [or privately](//github.com/orgs/MarlinFirmware/teams/moderators). All complaints will be reviewed and investigated and will result in a response that is deemed necessary and appropriate to the circumstances. +Instances of abusive, harassing, or otherwise unacceptable behavior may be reported by following GitHub's [reporting abuse or spam article](https://docs.github.com/en/communities/maintaining-your-safety-on-github/reporting-abuse-or-spam). All complaints will be reviewed and investigated and will result in a response that is deemed necessary and appropriate to the circumstances. ## Attribution diff --git a/.github/contributing.md b/.github/contributing.md index f3825d208112..c9b31998e99d 100644 --- a/.github/contributing.md +++ b/.github/contributing.md @@ -26,11 +26,12 @@ The following is a set of guidelines for contributing to Marlin, hosted by the [ ## Code of Conduct -This project and everyone participating in it is governed by the [Marlin Code of Conduct](code_of_conduct.md). By participating, you are expected to uphold this code. Please report unacceptable behavior by messaging @MarlinFirmware/moderators on the relevant issue, [or privately](//github.com/orgs/MarlinFirmware/teams/moderators). +This project and everyone participating in it is governed by the [Marlin Code of Conduct](code_of_conduct.md). By participating, you are expected to uphold this code. Please report unacceptable behavior by following GitHub's [reporting abuse or spam article](https://docs.github.com/en/communities/maintaining-your-safety-on-github/reporting-abuse-or-spam). ## I don't want to read this whole thing I just have a question!!! -> **Note:** Please don't file an issue to ask a question. You'll get faster results by using the resources below. +> [!NOTE] +> Please don't file an issue to ask a question. You'll get faster results by using the resources below. We have a Message Board and a Facebook group where our knowledgable user community can provide helpful advice if you have questions. @@ -55,7 +56,8 @@ This section guides you through submitting a Bug Report for Marlin. Following th Before creating a Bug Report, please test the "nightly" development branch, as you might find out that you don't need to create one. When you are creating a Bug Report, please [include as many details as possible](#how-do-i-submit-a-good-bug-report). Fill out [the required template](ISSUE_TEMPLATE/bug_report.yml), the information it asks for helps us resolve issues faster. -> **Note:** Regressions can happen. If you find a **Closed** issue that seems like your issue, go ahead and open a new issue and include a link to the original issue in the body of your new one. All you need to create a link is the issue number, preceded by #. For example, #8888. +> [!NOTE] +> Regressions can happen. If you find a **Closed** issue that seems like your issue, go ahead and open a new issue and include a link to the original issue in the body of your new one. All you need to create a link is the issue number, preceded by #. For example, #8888. #### How Do I Submit A (Good) Bug Report? From 8fa4f5a40faed43e20389432fd7be89303216b28 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Tue, 28 Nov 2023 12:08:12 +0000 Subject: [PATCH 31/77] [cron] Bump distribution date (2023-11-28) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index d3b4d058ff64..7c5e72750eab 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2023-11-27" +//#define STRING_DISTRIBUTION_DATE "2023-11-28" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index f28395a6c957..5fa5e2576076 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2023-11-27" + #define STRING_DISTRIBUTION_DATE "2023-11-28" #endif /** From dabcd6590350a3096309647cc51bd289fbc4554a Mon Sep 17 00:00:00 2001 From: ellensp <530024+ellensp@users.noreply.github.com> Date: Wed, 29 Nov 2023 11:23:18 +1300 Subject: [PATCH 32/77] =?UTF-8?q?=F0=9F=9A=B8=20Fix=20ProUI=20hostui.notif?= =?UTF-8?q?y('finished')=20(#26478)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/e3v2/proui/dwin.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/lcd/e3v2/proui/dwin.cpp b/Marlin/src/lcd/e3v2/proui/dwin.cpp index 366ecffbd9b2..8d4aa9106bfa 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin.cpp @@ -1722,7 +1722,7 @@ void dwinPrintAborted() { ); } #endif - hostui.notify("Print Aborted"); + TERN_(HOST_PROMPT_SUPPORT, hostui.notify(GET_TEXT_F(MSG_PRINT_ABORTED))); dwinPrintFinished(); } From f4228cc4c1e1ed499a07f9357afa6a978c1fd7a5 Mon Sep 17 00:00:00 2001 From: mikemerryguy <57319047+mikemerryguy@users.noreply.github.com> Date: Tue, 28 Nov 2023 18:55:21 -0500 Subject: [PATCH 33/77] =?UTF-8?q?=E2=9C=A8=20XY=5FAFTER=5FHOMING,=20EVENT?= =?UTF-8?q?=5FGCODE=5FAFTER=5FHOMING=20(#26469)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/Configuration.h | 13 ++++++++----- Marlin/src/gcode/calibrate/G28.cpp | 9 +++++++++ buildroot/tests/mega2560 | 1 + 3 files changed, 18 insertions(+), 5 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 0639f432c518..4d0351bb493c 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -1758,10 +1758,13 @@ */ //#define Z_IDLE_HEIGHT Z_HOME_POS -//#define Z_CLEARANCE_FOR_HOMING 4 // (mm) Minimal Z height before homing (G28) for Z clearance above the bed, clamps, ... - // Be sure to have this much clearance over your Z_MAX_POS to prevent grinding. +//#define Z_CLEARANCE_FOR_HOMING 4 // (mm) Minimal Z height before homing (G28) for Z clearance above the bed, clamps, ... + // You'll need this much clearance above Z_MAX_POS to avoid grinding. -//#define Z_AFTER_HOMING 10 // (mm) Height to move to after homing (if Z was homed) +//#define Z_AFTER_HOMING 10 // (mm) Height to move to after homing (if Z was homed) +//#define XY_AFTER_HOMING { 10, 10 } // (mm) Move to an XY position after homing (and raising Z) + +//#define EVENT_GCODE_AFTER_HOMING "M300 P440 S200" // Commands to run after G28 (and move to XY_AFTER_HOMING) // Direction of endstops when homing; 1=MAX, -1=MIN // :[-1,1] @@ -2246,8 +2249,8 @@ //#define Z_SAFE_HOMING #if ENABLED(Z_SAFE_HOMING) - #define Z_SAFE_HOMING_X_POINT X_CENTER // X point for Z homing - #define Z_SAFE_HOMING_Y_POINT Y_CENTER // Y point for Z homing + #define Z_SAFE_HOMING_X_POINT X_CENTER // (mm) X point for Z homing + #define Z_SAFE_HOMING_Y_POINT Y_CENTER // (mm) Y point for Z homing //#define Z_SAFE_HOMING_POINT_ABSOLUTE // Ignore home offsets (M206) for Z homing position #endif diff --git a/Marlin/src/gcode/calibrate/G28.cpp b/Marlin/src/gcode/calibrate/G28.cpp index 531dc5b558b0..ba16c7bbd7e2 100644 --- a/Marlin/src/gcode/calibrate/G28.cpp +++ b/Marlin/src/gcode/calibrate/G28.cpp @@ -638,6 +638,11 @@ void GcodeSuite::G28() { tool_change(old_tool_index, TERN(PARKING_EXTRUDER, !pe_final_change_must_unpark, DISABLED(DUAL_X_CARRIAGE))); // Do move if one of these #endif + #ifdef XY_AFTER_HOMING + constexpr xy_pos_t xy_after XY_AFTER_HOMING; + do_blocking_move_to(xy_after); + #endif + restore_feedrate_and_scaling(); if (ENABLED(NANODLP_Z_SYNC) && (ENABLED(NANODLP_ALL_AXIS) || TERN0(HAS_Z_AXIS, doZ))) @@ -654,4 +659,8 @@ void GcodeSuite::G28() { TERN_(FULL_REPORT_TO_HOST_FEATURE, set_and_report_grblstate(old_grblstate)); + #ifdef EVENT_GCODE_AFTER_HOMING + gcode.process_subcommands_now(F(EVENT_GCODE_AFTER_HOMING)); + #endif + } diff --git a/buildroot/tests/mega2560 b/buildroot/tests/mega2560 index 46de664e43b6..d647a6ddb16c 100755 --- a/buildroot/tests/mega2560 +++ b/buildroot/tests/mega2560 @@ -94,6 +94,7 @@ opt_set MOTHERBOARD BOARD_AZTEEG_X3_PRO MIXING_STEPPERS 5 LCD_LANGUAGE ru \ FIL_RUNOUT2_PIN 16 FIL_RUNOUT3_PIN 17 FIL_RUNOUT4_PIN 4 FIL_RUNOUT5_PIN 5 opt_enable MIXING_EXTRUDER GRADIENT_MIX GRADIENT_VTOOL CR10_STOCKDISPLAY \ USE_CONTROLLER_FAN CONTROLLER_FAN_EDITABLE CONTROLLER_FAN_IGNORE_Z \ + XY_AFTER_HOMING EVENT_GCODE_AFTER_HOMING \ FILAMENT_RUNOUT_SENSOR ADVANCED_PAUSE_FEATURE NOZZLE_PARK_FEATURE INPUT_SHAPING_X INPUT_SHAPING_Y opt_disable DISABLE_OTHER_EXTRUDERS exec_test $1 $2 "Azteeg X3 | Mixing Extruder (x5) | Gradient Mix | Input Shaping | Greek" "$3" From 3457952854eb612c88a790dfcccb68fcde26e8f0 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Wed, 29 Nov 2023 00:27:28 +0000 Subject: [PATCH 34/77] [cron] Bump distribution date (2023-11-29) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 7c5e72750eab..efa0e262e3cd 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2023-11-28" +//#define STRING_DISTRIBUTION_DATE "2023-11-29" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 5fa5e2576076..a1976dd12398 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2023-11-28" + #define STRING_DISTRIBUTION_DATE "2023-11-29" #endif /** From 921198e81ce246d38d2675db14b7884ef37093f3 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 28 Nov 2023 21:11:23 -0600 Subject: [PATCH 35/77] =?UTF-8?q?=F0=9F=A7=91=E2=80=8D=F0=9F=92=BB=20More?= =?UTF-8?q?=20SAMD51=20ADCs?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/SAMD51/HAL.cpp | 66 ++++++++++++++++++++++++++++++++++- 1 file changed, 65 insertions(+), 1 deletion(-) diff --git a/Marlin/src/HAL/SAMD51/HAL.cpp b/Marlin/src/HAL/SAMD51/HAL.cpp index 8ec5d5a86c4b..beace8126cbf 100644 --- a/Marlin/src/HAL/SAMD51/HAL.cpp +++ b/Marlin/src/HAL/SAMD51/HAL.cpp @@ -60,11 +60,14 @@ #define GET_PROBE_ADC() TERN(HAS_TEMP_ADC_PROBE, PIN_TO_ADC(TEMP_PROBE_PIN), -1) #define GET_COOLER_ADC() TERN(HAS_TEMP_ADC_COOLER, PIN_TO_ADC(TEMP_COOLER_PIN), -1) #define GET_BOARD_ADC() TERN(HAS_TEMP_ADC_BOARD, PIN_TO_ADC(TEMP_BOARD_PIN), -1) +#define GET_SOC_ADC() TERN(HAS_TEMP_ADC_SOC, PIN_TO_ADC(TEMP_SOC_PIN), -1) #define GET_FILAMENT_WIDTH_ADC() TERN(FILAMENT_WIDTH_SENSOR, PIN_TO_ADC(FILWIDTH_PIN), -1) #define GET_BUTTONS_ADC() TERN(HAS_ADC_BUTTONS, PIN_TO_ADC(ADC_KEYPAD_PIN), -1) #define GET_JOY_ADC_X() TERN(HAS_JOY_ADC_X, PIN_TO_ADC(JOY_X_PIN), -1) #define GET_JOY_ADC_Y() TERN(HAS_JOY_ADC_Y, PIN_TO_ADC(JOY_Y_PIN), -1) #define GET_JOY_ADC_Z() TERN(HAS_JOY_ADC_Z, PIN_TO_ADC(JOY_Z_PIN), -1) +#define GET_POWERMON_ADC_CURRENT() TERN(POWER_MONITOR_CURRENT, PIN_TO_ADC(POWER_MONITOR_CURRENT_PIN), -1) +#define GET_POWERMON_ADC_VOLTS() TERN(POWER_MONITOR_VOLTAGE, PIN_TO_ADC(POWER_MONITOR_VOLTAGE_PIN), -1) #define IS_ADC_REQUIRED(n) ( \ GET_TEMP_0_ADC() == n || GET_TEMP_1_ADC() == n || GET_TEMP_2_ADC() == n || GET_TEMP_3_ADC() == n \ @@ -73,10 +76,11 @@ || GET_CHAMBER_ADC() == n \ || GET_PROBE_ADC() == n \ || GET_COOLER_ADC() == n \ - || GET_BOARD_ADC() == n \ + || GET_BOARD_ADC() == n || GET_SOC_ADC() == n \ || GET_FILAMENT_WIDTH_ADC() == n \ || GET_BUTTONS_ADC() == n \ || GET_JOY_ADC_X() == n || GET_JOY_ADC_Y() == n || GET_JOY_ADC_Z() == n \ + || GET_POWERMON_ADC_CURRENT() == n || GET_POWERMON_ADC_VOLTS() == n \ ) #if IS_ADC_REQUIRED(0) @@ -136,6 +140,9 @@ enum ADCIndex { #if GET_BOARD_ADC() == 0 TEMP_BOARD, #endif + #if GET_SOC_ADC() == 0 + TEMP_SOC, + #endif #if GET_FILAMENT_WIDTH_ADC() == 0 FILWIDTH, #endif @@ -151,6 +158,15 @@ enum ADCIndex { #if GET_JOY_ADC_Z() == 0 JOY_Z, #endif + #if GET_POWERMON_ADC_CURRENT() == 0 + POWERMON_CURRENT, + #endif + #if GET_POWERMON_ADC_VOLTS() == 0 + POWERMON_VOLTS, + #endif + + // Use later indexes for ADC index 1 + #if GET_TEMP_0_ADC() == 1 TEMP_0, #endif @@ -190,6 +206,9 @@ enum ADCIndex { #if GET_BOARD_ADC() == 1 TEMP_BOARD, #endif + #if GET_SOC_ADC() == 1 + TEMP_SOC, + #endif #if GET_FILAMENT_WIDTH_ADC() == 1 FILWIDTH, #endif @@ -205,6 +224,13 @@ enum ADCIndex { #if GET_JOY_ADC_Z() == 1 JOY_Z, #endif + #if GET_POWERMON_ADC_CURRENT() == 1 + POWERMON_CURRENT, + #endif + #if GET_POWERMON_ADC_VOLTS() == 1 + POWERMON_VOLTS, + #endif + ADC_COUNT }; @@ -303,6 +329,9 @@ enum ADCIndex { #if GET_BOARD_ADC() == 0 TEMP_BOARD_PIN, #endif + #if GET_SOC_ADC() == 0 + TEMP_SOC_PIN, + #endif #if GET_FILAMENT_WIDTH_ADC() == 0 FILWIDTH_PIN, #endif @@ -318,7 +347,15 @@ enum ADCIndex { #if GET_JOY_ADC_Z() == 0 JOY_Z_PIN, #endif + #if GET_POWERMON_ADC_CURRENT() == 0 + POWER_MONITOR_CURRENT_PIN, + #endif + #if GET_POWERMON_ADC_VOLTS() == 0 + POWER_MONITOR_VOLTS_PIN, + #endif + // ADC1 pins + #if GET_TEMP_0_ADC() == 1 TEMP_0_PIN, #endif @@ -358,6 +395,9 @@ enum ADCIndex { #if GET_BOARD_ADC() == 1 TEMP_BOARD_PIN, #endif + #if GET_SOC_ADC() == 1 + TEMP_SOC_PIN, + #endif #if GET_FILAMENT_WIDTH_ADC() == 1 FILWIDTH_PIN, #endif @@ -373,6 +413,12 @@ enum ADCIndex { #if GET_JOY_ADC_Z() == 1 JOY_Z_PIN, #endif + #if GET_POWERMON_ADC_CURRENT() == 1 + POWER_MONITOR_CURRENT_PIN, + #endif + #if GET_POWERMON_ADC_VOLTS() == 1 + POWER_MONITOR_VOLTS_PIN, + #endif }; static uint16_t adc_results[ADC_COUNT]; @@ -420,6 +466,9 @@ enum ADCIndex { #if GET_BOARD_ADC() == 0 { PIN_TO_INPUTCTRL(TEMP_BOARD_PIN) }, #endif + #if GET_SOC_ADC() == 0 + { PIN_TO_INPUTCTRL(TEMP_SOC_PIN) }, + #endif #if GET_FILAMENT_WIDTH_ADC() == 0 { PIN_TO_INPUTCTRL(FILWIDTH_PIN) }, #endif @@ -435,6 +484,12 @@ enum ADCIndex { #if GET_JOY_ADC_Z() == 0 { PIN_TO_INPUTCTRL(JOY_Z_PIN) }, #endif + #if GET_POWERMON_ADC_CURRENT() == 0 + { PIN_TO_INPUTCTRL(POWER_MONITOR_CURRENT_PIN) }, + #endif + #if GET_POWERMON_ADC_VOLTS() == 0 + { PIN_TO_INPUTCTRL(POWER_MONITOR_VOLTS_PIN) }, + #endif }; #define ADC0_AINCOUNT COUNT(adc0_dma_regs_list) @@ -483,6 +538,9 @@ enum ADCIndex { #if GET_BOARD_ADC() == 1 { PIN_TO_INPUTCTRL(TEMP_BOARD_PIN) }, #endif + #if GET_SOC_ADC() == 1 + { PIN_TO_INPUTCTRL(TEMP_SOC_PIN) }, + #endif #if GET_FILAMENT_WIDTH_ADC() == 1 { PIN_TO_INPUTCTRL(FILWIDTH_PIN) }, #endif @@ -498,6 +556,12 @@ enum ADCIndex { #if GET_JOY_ADC_Z() == 1 { PIN_TO_INPUTCTRL(JOY_Z_PIN) }, #endif + #if GET_POWERMON_ADC_CURRENT() == 1 + { PIN_TO_INPUTCTRL(POWER_MONITOR_CURRENT_PIN) }, + #endif + #if GET_POWERMON_ADC_VOLTS() == 1 + { PIN_TO_INPUTCTRL(POWER_MONITOR_VOLTS_PIN) }, + #endif }; #define ADC1_AINCOUNT COUNT(adc1_dma_regs_list) From b9620140874d01da533f0bb604fc61c654e52859 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 29 Nov 2023 14:19:27 -0600 Subject: [PATCH 36/77] =?UTF-8?q?=E2=9C=85=20Label=20bug=20reports?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .github/ISSUE_TEMPLATE/bug_report.yml | 1 + .github/workflows/clean-closed.yml | 1 + 2 files changed, 2 insertions(+) diff --git a/.github/ISSUE_TEMPLATE/bug_report.yml b/.github/ISSUE_TEMPLATE/bug_report.yml index 52bac0cd04bd..56060f0a4801 100644 --- a/.github/ISSUE_TEMPLATE/bug_report.yml +++ b/.github/ISSUE_TEMPLATE/bug_report.yml @@ -1,6 +1,7 @@ name: 🪲 Report a bug description: Create a bug report to help improve Marlin Firmware title: "[BUG] (bug summary)" +labels: 'Bug: Potential ?' body: - type: markdown attributes: diff --git a/.github/workflows/clean-closed.yml b/.github/workflows/clean-closed.yml index 2eab285aeeab..318d083dfae3 100644 --- a/.github/workflows/clean-closed.yml +++ b/.github/workflows/clean-closed.yml @@ -23,6 +23,7 @@ jobs: - "S: Please Merge" - "S: Please Test" - "help wanted" + - "Bug: Potential ?" - "Needs: Discussion" - "Needs: Documentation" - "Needs: More Data" From d62ee95d283105b4260a1e6542fb35123bd9eea4 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 29 Nov 2023 14:24:20 -0600 Subject: [PATCH 37/77] =?UTF-8?q?=F0=9F=94=A8=20Update=20config/schema=20s?= =?UTF-8?q?cripts=20(#26483)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/config.ini | 40 ++++++++++ .../share/PlatformIO/scripts/configuration.py | 49 +++++++++++- buildroot/share/PlatformIO/scripts/schema.py | 79 ++++++++++++------- .../share/PlatformIO/scripts/signature.py | 47 ++++++----- 4 files changed, 160 insertions(+), 55 deletions(-) mode change 100644 => 100755 buildroot/share/PlatformIO/scripts/configuration.py mode change 100644 => 100755 buildroot/share/PlatformIO/scripts/signature.py diff --git a/Marlin/config.ini b/Marlin/config.ini index 17ff3bec7efb..fed2a5c68c0a 100644 --- a/Marlin/config.ini +++ b/Marlin/config.ini @@ -3,10 +3,50 @@ # config.ini - Options to apply before the build # [config:base] +# +# ini_use_config - A comma-separated list of actions to apply to the Configuration files. +# The actions will be applied in the listed order. +# - none +# Ignore this file and don't apply any configuration options +# +# - base +# Just apply the options in config:base to the configuration +# +# - minimal +# Just apply the options in config:minimal to the configuration +# +# - all +# Apply all 'config:*' sections in this file to the configuration +# +# - another.ini +# Load another INI file with a path relative to this config.ini file (i.e., within Marlin/) +# +# - https://me.myserver.com/path/to/configs +# Fetch configurations from any URL. +# +# - example/Creality/Ender-5 Plus @ bugfix-2.1.x +# Fetch example configuration files from the MarlinFirmware/Configurations repository +# https://raw.githubusercontent.com/MarlinFirmware/Configurations/bugfix-2.1.x/config/examples/Creality/Ender-5%20Plus/ +# +# - example/default @ release-2.0.9.7 +# Fetch default configuration files from the MarlinFirmware/Configurations repository +# https://raw.githubusercontent.com/MarlinFirmware/Configurations/release-2.0.9.7/config/default/ +# +# - [disable] +# Comment out all #defines in both Configuration.h and Configuration_adv.h. This is useful +# to start with a clean slate before applying any config: options, so only the options explicitly +# set in config.ini will be enabled in the configuration. +# +# - [flatten] (Not yet implemented) +# Produce a flattened set of Configuration.h and Configuration_adv.h files with only the enabled +# #defines and no comments. A clean look, but context-free. +# ini_use_config = none # Load all config: sections in this file ;ini_use_config = all +# Disable everything and apply subsequent config:base options +;ini_use_config = [disable], base # Load config file relative to Marlin/ ;ini_use_config = another.ini # Download configurations from GitHub diff --git a/buildroot/share/PlatformIO/scripts/configuration.py b/buildroot/share/PlatformIO/scripts/configuration.py old mode 100644 new mode 100755 index 496af8a76930..e0387a219da4 --- a/buildroot/share/PlatformIO/scripts/configuration.py +++ b/buildroot/share/PlatformIO/scripts/configuration.py @@ -1,8 +1,9 @@ +#!/usr/bin/env python3 # # configuration.py # Apply options from config.ini to the existing Configuration headers # -import re, shutil, configparser +import re, shutil, configparser, datetime from pathlib import Path verbose = 0 @@ -43,6 +44,7 @@ def apply_opt(name, val, conf=None): if val in ("on", "", None): newline = re.sub(r'^(\s*)//+\s*(#define)(\s{1,3})?(\s*)', r'\1\2 \4', line) elif val == "off": + # TODO: Comment more lines in a multi-line define with \ continuation newline = re.sub(r'^(\s*)(#define)(\s{1,3})?(\s*)', r'\1//\2 \4', line) else: # For options with values, enable and set the value @@ -88,9 +90,38 @@ def apply_opt(name, val, conf=None): elif not isdef: break linenum += 1 - lines.insert(linenum, f"{prefix}#define {added:30} // Added by config.ini\n") + currtime = datetime.datetime.now().strftime("%Y-%m-%d %H:%M:%S") + lines.insert(linenum, f"{prefix}#define {added:30} // Added by config.ini {currtime}\n") fullpath.write_text(''.join(lines), encoding='utf-8') +# Disable all (most) defined options in the configuration files. +# Everything in the named sections. Section hint for exceptions may be added. +def disable_all_options(): + # Create a regex to match the option and capture parts of the line + regex = re.compile(r'^(\s*)(#define\s+)([A-Z0-9_]+\b)(\s?)(\s*)(.*?)(\s*)(//.*)?$', re.IGNORECASE) + + # Disable all enabled options in both Config files + for file in ("Configuration.h", "Configuration_adv.h"): + fullpath = config_path(file) + lines = fullpath.read_text(encoding='utf-8').split('\n') + found = False + for i in range(len(lines)): + line = lines[i] + match = regex.match(line) + if match: + name = match[3].upper() + if name in ('CONFIGURATION_H_VERSION', 'CONFIGURATION_ADV_H_VERSION'): continue + if name.startswith('_'): continue + found = True + # Comment out the define + # TODO: Comment more lines in a multi-line define with \ continuation + lines[i] = re.sub(r'^(\s*)(#define)(\s{1,3})?(\s*)', r'\1//\2 \4', line) + blab(f"Disable {name}") + + # If the option was found, write the modified lines + if found: + fullpath.write_text('\n'.join(lines), encoding='utf-8') + # Fetch configuration files from GitHub given the path. # Return True if any files were fetched. def fetch_example(url): @@ -130,7 +161,7 @@ def fetch_example(url): def section_items(cp, sectkey): return cp.items(sectkey) if sectkey in cp.sections() else [] -# Apply all items from a config section +# Apply all items from a config section. Ignore ini_ items outside of config:base and config:root. def apply_ini_by_name(cp, sect): iniok = True if sect in ('config:base', 'config:root'): @@ -206,7 +237,17 @@ def apply_config_ini(cp): fetch_example(ckey) ckey = 'base' - if ckey == 'all': + # + # [flatten] Write out Configuration.h and Configuration_adv.h files with + # just the enabled options and all other content removed. + # + #if ckey == '[flatten]': + # write_flat_configs() + + if ckey == '[disable]': + disable_all_options() + + elif ckey == 'all': apply_sections(cp) else: diff --git a/buildroot/share/PlatformIO/scripts/schema.py b/buildroot/share/PlatformIO/scripts/schema.py index 535a8f671e94..80ba70a29812 100755 --- a/buildroot/share/PlatformIO/scripts/schema.py +++ b/buildroot/share/PlatformIO/scripts/schema.py @@ -2,8 +2,14 @@ # # schema.py # -# Used by signature.py via common-dependencies.py to generate a schema file during the PlatformIO build. -# This script can also be run standalone from within the Marlin repo to generate all schema files. +# Used by signature.py via common-dependencies.py to generate a schema file during the PlatformIO build +# when CONFIG_EXPORT is defined in the configuration. +# +# This script can also be run standalone from within the Marlin repo to generate JSON and YAML schema files. +# +# This script is a companion to abm/js/schema.js in the MarlinFirmware/AutoBuildMarlin project, which has +# been extended to evaluate conditions and can determine what options are actually enabled, not just which +# options are uncommented. That will be migrated to this script for standalone migration. # import re,json from pathlib import Path @@ -95,6 +101,8 @@ class Parse: sch_out = { 'basic':{}, 'advanced':{} } # Regex for #define NAME [VALUE] [COMMENT] with sanitized line defgrep = re.compile(r'^(//)?\s*(#define)\s+([A-Za-z0-9_]+)\s*(.*?)\s*(//.+)?$') + # Pattern to match a float value + flt = r'[-+]?\s*(\d+\.|\d*\.\d+)([eE][-+]?\d+)?[fF]?' # Defines to ignore ignore = ('CONFIGURATION_H_VERSION', 'CONFIGURATION_ADV_H_VERSION', 'CONFIG_EXAMPLES_DIR', 'CONFIG_EXPORT') # Start with unknown state @@ -314,26 +322,27 @@ def atomize(s): } # Type is based on the value - if val == '': - value_type = 'switch' - elif re.match(r'^(true|false)$', val): - value_type = 'bool' - val = val == 'true' - elif re.match(r'^[-+]?\s*\d+$', val): - value_type = 'int' - val = int(val) - elif re.match(r'[-+]?\s*(\d+\.|\d*\.\d+)([eE][-+]?\d+)?[fF]?', val): - value_type = 'float' - val = float(val.replace('f','')) - else: - value_type = 'string' if val[0] == '"' \ - else 'char' if val[0] == "'" \ - else 'state' if re.match(r'^(LOW|HIGH)$', val) \ - else 'enum' if re.match(r'^[A-Za-z0-9_]{3,}$', val) \ - else 'int[]' if re.match(r'^{(\s*[-+]?\s*\d+\s*(,\s*)?)+}$', val) \ - else 'float[]' if re.match(r'^{(\s*[-+]?\s*(\d+\.|\d*\.\d+)([eE][-+]?\d+)?[fF]?\s*(,\s*)?)+}$', val) \ - else 'array' if val[0] == '{' \ - else '' + value_type = \ + 'switch' if val == '' \ + else 'bool' if re.match(r'^(true|false)$', val) \ + else 'int' if re.match(r'^[-+]?\s*\d+$', val) \ + else 'ints' if re.match(r'^([-+]?\s*\d+)(\s*,\s*[-+]?\s*\d+)+$', val) \ + else 'floats' if re.match(rf'({flt}(\s*,\s*{flt})+)', val) \ + else 'float' if re.match(f'^({flt})$', val) \ + else 'string' if val[0] == '"' \ + else 'char' if val[0] == "'" \ + else 'state' if re.match(r'^(LOW|HIGH)$', val) \ + else 'enum' if re.match(r'^[A-Za-z0-9_]{3,}$', val) \ + else 'int[]' if re.match(r'^{\s*[-+]?\s*\d+(\s*,\s*[-+]?\s*\d+)*\s*}$', val) \ + else 'float[]' if re.match(r'^{{\s*{flt}(\s*,\s*{flt})*\s*}}$', val) \ + else 'array' if val[0] == '{' \ + else '' + + val = (val == 'true') if value_type == 'bool' \ + else int(val) if value_type == 'int' \ + else val.replace('f','') if value_type == 'floats' \ + else float(val.replace('f','')) if value_type == 'float' \ + else val if val != '': define_info['value'] = val if value_type != '': define_info['type'] = value_type @@ -402,25 +411,35 @@ def main(): if schema: - # Get the first command line argument + # Get the command line arguments after the script name import sys - if len(sys.argv) > 1: - arg = sys.argv[1] - else: - arg = 'some' + args = sys.argv[1:] + if len(args) == 0: args = ['some'] + + # Does the given array intersect at all with args? + def inargs(c): return len(set(args) & set(c)) > 0 + + # Help / Unknown option + unk = not inargs(['some','json','jsons','group','yml','yaml']) + if (unk): print(f"Unknown option: '{args[0]}'") + if inargs(['-h', '--help']) or unk: + print("Usage: schema.py [some|json|jsons|group|yml|yaml]...") + print(" some = json + yml") + print(" jsons = json + group") + return # JSON schema - if arg in ['some', 'json', 'jsons']: + if inargs(['some', 'json', 'jsons']): print("Generating JSON ...") dump_json(schema, Path('schema.json')) # JSON schema (wildcard names) - if arg in ['group', 'jsons']: + if inargs(['group', 'jsons']): group_options(schema) dump_json(schema, Path('schema_grouped.json')) # YAML - if arg in ['some', 'yml', 'yaml']: + if inargs(['some', 'yml', 'yaml']): try: import yaml except ImportError: diff --git a/buildroot/share/PlatformIO/scripts/signature.py b/buildroot/share/PlatformIO/scripts/signature.py old mode 100644 new mode 100755 index 84312da01bd9..ab1a46bae523 --- a/buildroot/share/PlatformIO/scripts/signature.py +++ b/buildroot/share/PlatformIO/scripts/signature.py @@ -1,3 +1,4 @@ +#!/usr/bin/env python3 # # signature.py # @@ -44,35 +45,35 @@ def compress_file(filepath, storedname, outpath): zipf.write(filepath, arcname=storedname, compress_type=zipfile.ZIP_BZIP2, compresslevel=9) # -# Compute the build signature. The idea is to extract all defines in the configuration headers -# to build a unique reversible signature from this build so it can be included in the binary -# We can reverse the signature to get a 1:1 equivalent configuration file +# Compute the build signature by extracting all configuration settings and +# building a unique reversible signature that can be included in the binary. +# The signature can be reversed to get a 1:1 equivalent configuration file. # def compute_build_signature(env): if 'BUILD_SIGNATURE' in env: return + build_path = Path(env['PROJECT_BUILD_DIR'], env['PIOENV']) + marlin_json = build_path / 'marlin_config.json' + marlin_zip = build_path / 'mc.zip' + # Definitions from these files will be kept files_to_keep = [ 'Marlin/Configuration.h', 'Marlin/Configuration_adv.h' ] - build_path = Path(env['PROJECT_BUILD_DIR'], env['PIOENV']) - # Check if we can skip processing hashes = '' for header in files_to_keep: hashes += get_file_sha256sum(header)[0:10] - marlin_json = build_path / 'marlin_config.json' - marlin_zip = build_path / 'mc.zip' - - # Read existing config file + # Read a previously exported JSON file + # Same configuration, skip recomputing the build signature + same_hash = False try: with marlin_json.open() as infile: conf = json.load(infile) - if conf['__INITIAL_HASH'] == hashes: - # Same configuration, skip recomputing the building signature + same_hash = conf['__INITIAL_HASH'] == hashes + if same_hash: compress_file(marlin_json, 'marlin_config.json', marlin_zip) - return except: pass @@ -125,9 +126,6 @@ def compute_build_signature(env): # Remove all boards now if key.startswith("BOARD_") and key != "BOARD_INFO_NAME": continue - # Remove all keys ending by "_NAME" as it does not make a difference to the configuration - if key.endswith("_NAME") and key != "CUSTOM_MACHINE_NAME": - continue # Remove all keys ending by "_T_DECLARED" as it's a copy of extraneous system stuff if key.endswith("_T_DECLARED"): continue @@ -196,7 +194,7 @@ def tryint(key): outfile.write(ini_fmt.format(key.lower(), ' = ' + val)) # - # Produce a schema.json file if CONFIG_EXPORT == 3 + # CONFIG_EXPORT 3 = schema.json, 4 = schema.yml # if config_dump >= 3: try: @@ -207,7 +205,7 @@ def tryint(key): if conf_schema: # - # Produce a schema.json file if CONFIG_EXPORT == 3 + # 3 = schema.json # if config_dump in (3, 13): print("Generating schema.json ...") @@ -217,7 +215,7 @@ def tryint(key): schema.dump_json(conf_schema, build_path / 'schema_grouped.json') # - # Produce a schema.yml file if CONFIG_EXPORT == 4 + # 4 = schema.yml # elif config_dump == 4: print("Generating schema.yml ...") @@ -243,8 +241,9 @@ def tryint(key): # # Produce a JSON file for CONFIGURATION_EMBEDDING or CONFIG_EXPORT == 1 + # Skip if an identical JSON file was already present. # - if config_dump == 1 or 'CONFIGURATION_EMBEDDING' in defines: + if not same_hash and (config_dump == 1 or 'CONFIGURATION_EMBEDDING' in defines): with marlin_json.open('w') as outfile: json.dump(data, outfile, separators=(',', ':')) @@ -255,9 +254,10 @@ def tryint(key): return # Compress the JSON file as much as we can - compress_file(marlin_json, 'marlin_config.json', marlin_zip) + if not same_hash: + compress_file(marlin_json, 'marlin_config.json', marlin_zip) - # Generate a C source file for storing this array + # Generate a C source file containing the entire ZIP file as an array with open('Marlin/src/mczip.h','wb') as result_file: result_file.write( b'#ifndef NO_CONFIGURATION_EMBEDDING_WARNING\n' @@ -274,3 +274,8 @@ def tryint(key): if count % 16: result_file.write(b'\n') result_file.write(b'};\n') + +if __name__ == "__main__": + # Build required. From command line just explain usage. + print("Use schema.py to export JSON and YAML from the command-line.") + print("Build Marlin with CONFIG_EXPORT 2 to export 'config.ini'.") From 95821b07b11fc94c00269cbab075bec8b1b6c05a Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 29 Nov 2023 16:45:37 -0600 Subject: [PATCH 38/77] =?UTF-8?q?=E2=9C=85=20Auto-label=20older=20open=20[?= =?UTF-8?q?BUG]=20issues?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .github/workflows/auto-label.yml | 42 +++++++++++++++++++++++++++++++ .github/workflows/close-stale.yml | 2 +- 2 files changed, 43 insertions(+), 1 deletion(-) create mode 100644 .github/workflows/auto-label.yml diff --git a/.github/workflows/auto-label.yml b/.github/workflows/auto-label.yml new file mode 100644 index 000000000000..f3a752da3d45 --- /dev/null +++ b/.github/workflows/auto-label.yml @@ -0,0 +1,42 @@ +# +# auto-label.yml +# - Find all open issues without a label and a title containing "[BUG]". +# - Apply the label "Bug: Potential ?" to these issues. +# + +on: + schedule: + - cron: "30 8 * * *" + +jobs: + autolabel: + name: Auto Label + if: github.repository == 'MarlinFirmware/Marlin' + runs-on: ubuntu-latest + steps: + - name: Auto Label for [BUG] + uses: actions/github-script@v5 + with: + script: | + # Get all open issues in this repository + const issueList = await github.rest.issues.listForRepo({ + owner: context.repo.owner, + repo: context.repo.repo, + state: 'open' + }); + # Filter the list of issues to only those that don't have any labels + # and have a title that contains '[BUG]'. Only the first 50 issues. + const matchingIssues = issueList.data.filter( + issue => issue.title.includes('[BUG]') && issue.labels.length === 0 + ); + # Process the first 50 + for (const issue of matchingIssues.slice(0, 50)) { + // Run the desired action on the issue + // For example, to add a label: + await github.rest.issues.addLabels({ + owner: context.repo.owner, + repo: context.repo.repo, + issue_number: issue.number, + labels: ['Bug: Potential ?'] + }); + } diff --git a/.github/workflows/close-stale.yml b/.github/workflows/close-stale.yml index ef1b33b4eb17..397f9b5ea6c2 100644 --- a/.github/workflows/close-stale.yml +++ b/.github/workflows/close-stale.yml @@ -17,7 +17,7 @@ jobs: runs-on: ubuntu-latest steps: - - uses: actions/stale@v3 + - uses: actions/stale@v8 with: repo-token: ${{ secrets.GITHUB_TOKEN }} stale-issue-message: | From 61349dc6d30f0df8175ac176852ae81065ef2da4 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Thu, 30 Nov 2023 00:21:18 +0000 Subject: [PATCH 39/77] [cron] Bump distribution date (2023-11-30) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index efa0e262e3cd..07815b01d6fe 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2023-11-29" +//#define STRING_DISTRIBUTION_DATE "2023-11-30" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index a1976dd12398..3d192cb4740a 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2023-11-29" + #define STRING_DISTRIBUTION_DATE "2023-11-30" #endif /** From 3d8e3c3c9a2e955b7075783b8a95c3526b2936a5 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 30 Nov 2023 16:25:11 -0600 Subject: [PATCH 40/77] =?UTF-8?q?=F0=9F=90=9B=20Touch=20fixes=20(#26455)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/LPC1768/tft/xpt2046.cpp | 2 +- Marlin/src/HAL/STM32/tft/xpt2046.cpp | 2 +- Marlin/src/HAL/STM32F1/tft/xpt2046.cpp | 2 +- Marlin/src/lcd/e3v2/jyersui/dwin.cpp | 10 ++-- Marlin/src/lcd/e3v2/proui/bedlevel_tools.cpp | 10 ++-- .../extui/mks_ui/tft_lvgl_configuration.cpp | 23 +++----- Marlin/src/lcd/tft/touch.cpp | 58 ++++++++++--------- Marlin/src/lcd/tft/touch.h | 10 ++-- Marlin/src/lcd/tft_io/touch_calibration.cpp | 30 +++++----- Marlin/src/lcd/tft_io/touch_calibration.h | 51 ++++++++-------- Marlin/src/lcd/touch/touch_buttons.cpp | 10 +++- 11 files changed, 103 insertions(+), 105 deletions(-) diff --git a/Marlin/src/HAL/LPC1768/tft/xpt2046.cpp b/Marlin/src/HAL/LPC1768/tft/xpt2046.cpp index 6c00a4cae0b2..a737266c6811 100644 --- a/Marlin/src/HAL/LPC1768/tft/xpt2046.cpp +++ b/Marlin/src/HAL/LPC1768/tft/xpt2046.cpp @@ -78,7 +78,7 @@ bool XPT2046::getRawPoint(int16_t * const x, int16_t * const y) { if (isBusy() || !isTouched()) return false; *x = getRawData(XPT2046_X); *y = getRawData(XPT2046_Y); - return true; + return isTouched(); } uint16_t XPT2046::getRawData(const XPTCoordinate coordinate) { diff --git a/Marlin/src/HAL/STM32/tft/xpt2046.cpp b/Marlin/src/HAL/STM32/tft/xpt2046.cpp index 57c50653c9ce..c5645ad79c4a 100644 --- a/Marlin/src/HAL/STM32/tft/xpt2046.cpp +++ b/Marlin/src/HAL/STM32/tft/xpt2046.cpp @@ -123,7 +123,7 @@ bool XPT2046::getRawPoint(int16_t * const x, int16_t * const y) { if (isBusy() || !isTouched()) return false; *x = getRawData(XPT2046_X); *y = getRawData(XPT2046_Y); - return true; + return isTouched(); } uint16_t XPT2046::getRawData(const XPTCoordinate coordinate) { diff --git a/Marlin/src/HAL/STM32F1/tft/xpt2046.cpp b/Marlin/src/HAL/STM32F1/tft/xpt2046.cpp index 3428110c127e..475290de45b2 100644 --- a/Marlin/src/HAL/STM32F1/tft/xpt2046.cpp +++ b/Marlin/src/HAL/STM32F1/tft/xpt2046.cpp @@ -90,7 +90,7 @@ bool XPT2046::getRawPoint(int16_t * const x, int16_t * const y) { if (isBusy() || !isTouched()) return false; *x = getRawData(XPT2046_X); *y = getRawData(XPT2046_Y); - return true; + return isTouched(); } uint16_t XPT2046::getRawData(const XPTCoordinate coordinate) { diff --git a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp index 6e7898a389f9..be8605e3bba0 100644 --- a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp @@ -389,9 +389,9 @@ class TextScroller { // Draw value text on if (viewer_print_value) { - xy_uint_t offset { 0, cell_height_px / 2 - 6 }; + const int8_t offset_y = cell_height_px / 2 - 6; if (isnan(bedlevel.z_values[x][y])) { // undefined - dwinDrawString(false, font6x12, COLOR_WHITE, COLOR_BG_BLUE, start_x_px + cell_width_px / 2 - 5, start_y_px + offset.y, F("X")); + dwinDrawString(false, font6x12, COLOR_WHITE, COLOR_BG_BLUE, start_x_px + cell_width_px / 2 - 5, start_y_px + offset_y, F("X")); } else { // has value MString<12> msg; @@ -399,10 +399,10 @@ class TextScroller { msg.set(p_float_t(abs(bedlevel.z_values[x][y]), 2)); else msg.setf(F("%02i"), uint16_t(abs(bedlevel.z_values[x][y] - int16_t(bedlevel.z_values[x][y])) * 100)); - offset.x = cell_width_px / 2 - 3 * msg.length() - 2; + const int8_t offset_x = cell_width_px / 2 - 3 * msg.length() - 2; if (GRID_MAX_POINTS_X >= 10) - dwinDrawString(false, font6x12, COLOR_WHITE, COLOR_BG_BLUE, start_x_px - 2 + offset.x, start_y_px + offset.y /*+ square / 2 - 6*/, F(".")); - dwinDrawString(false, font6x12, COLOR_WHITE, COLOR_BG_BLUE, start_x_px + 1 + offset.x, start_y_px + offset.y /*+ square / 2 - 6*/, msg); + dwinDrawString(false, font6x12, COLOR_WHITE, COLOR_BG_BLUE, start_x_px - 2 + offset_x, start_y_px + offset_y /*+ square / 2 - 6*/, F(".")); + dwinDrawString(false, font6x12, COLOR_WHITE, COLOR_BG_BLUE, start_x_px + 1 + offset_x, start_y_px + offset_y /*+ square / 2 - 6*/, msg); } safe_delay(10); LCD_SERIAL.flushTX(); diff --git a/Marlin/src/lcd/e3v2/proui/bedlevel_tools.cpp b/Marlin/src/lcd/e3v2/proui/bedlevel_tools.cpp index f2fe008667c6..64d145c95dfd 100644 --- a/Marlin/src/lcd/e3v2/proui/bedlevel_tools.cpp +++ b/Marlin/src/lcd/e3v2/proui/bedlevel_tools.cpp @@ -247,9 +247,9 @@ bool BedLevelTools::meshValidate() { // Draw value text on const uint8_t fs = DWINUI::fontWidth(meshfont); if (viewer_print_value) { - xy_uint_t offset { 0, cell_height_px / 2 - fs }; + const int8_t offset_y = cell_height_px / 2 - fs; if (isnan(bedlevel.z_values[x][y])) { // undefined - dwinDrawString(false, meshfont, COLOR_WHITE, COLOR_BG_BLUE, start_x_px + cell_width_px / 2 - 5, start_y_px + offset.y, F("X")); + dwinDrawString(false, meshfont, COLOR_WHITE, COLOR_BG_BLUE, start_x_px + cell_width_px / 2 - 5, start_y_px + offset_y, F("X")); } else { // has value MString<12> msg; @@ -257,10 +257,10 @@ bool BedLevelTools::meshValidate() { msg.set(p_float_t(abs(bedlevel.z_values[x][y]), 2)); else msg.setf(F("%02i"), uint16_t(abs(bedlevel.z_values[x][y] - int16_t(bedlevel.z_values[x][y])) * 100)); - offset.x = cell_width_px / 2 - (fs / 2) * msg.length() - 2; + const int8_t offset_x = cell_width_px / 2 - (fs / 2) * msg.length() - 2; if ((GRID_MAX_POINTS_X) >= TERN(TJC_DISPLAY, 8, 10)) - dwinDrawString(false, meshfont, COLOR_WHITE, COLOR_BG_BLUE, start_x_px - 2 + offset.x, start_y_px + offset.y, F(".")); - dwinDrawString(false, meshfont, COLOR_WHITE, COLOR_BG_BLUE, start_x_px + 1 + offset.x, start_y_px + offset.y, msg); + dwinDrawString(false, meshfont, COLOR_WHITE, COLOR_BG_BLUE, start_x_px - 2 + offset_x, start_y_px + offset_y, F(".")); + dwinDrawString(false, meshfont, COLOR_WHITE, COLOR_BG_BLUE, start_x_px + 1 + offset_x, start_y_px + offset_y, msg); } safe_delay(10); LCD_SERIAL.flushTX(); diff --git a/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp b/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp index 7adce94c2fa6..ba898162d1f7 100644 --- a/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp +++ b/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp @@ -305,35 +305,28 @@ uint16_t getTickDiff(const uint16_t curTick, const uint16_t lastTick) { return (TICK_CYCLE) * (lastTick <= curTick ? (curTick - lastTick) : (0xFFFFFFFF - lastTick + curTick)); } -static bool get_point(xy_int_t &point) { - if (!touch.getRawPoint(&point.x, &point.y)) return false; +static bool get_point(int16_t * const x, int16_t * const y) { + if (!touch.getRawPoint(x, y)) return false; #if ENABLED(TOUCH_SCREEN_CALIBRATION) const calibrationState state = touch_calibration.get_calibration_state(); if (WITHIN(state, CALIBRATION_TOP_LEFT, CALIBRATION_BOTTOM_LEFT)) { - if (touch_calibration.handleTouch(point)) lv_update_touch_calibration_screen(); + if (touch_calibration.handleTouch(*x, *y)) lv_update_touch_calibration_screen(); return false; } #endif - point.x = int16_t((int32_t(point.x) * _TOUCH_CALIBRATION_X) >> 16) + _TOUCH_OFFSET_X; - point.y = int16_t((int32_t(point.y) * _TOUCH_CALIBRATION_Y) >> 16) + _TOUCH_OFFSET_Y; + *x = int16_t((int32_t(*x) * _TOUCH_CALIBRATION_X) >> 16) + _TOUCH_OFFSET_X; + *y = int16_t((int32_t(*y) * _TOUCH_CALIBRATION_Y) >> 16) + _TOUCH_OFFSET_Y; return true; } bool my_touchpad_read(lv_indev_drv_t * indev_driver, lv_indev_data_t * data) { static xy_int_t last { 0, 0 }; - if (get_point(last)) { - data->point.x = (TFT_ROTATION == TFT_ROTATE_180) ? TFT_WIDTH - last.x : last.x; - data->point.y = (TFT_ROTATION == TFT_ROTATE_180) ? TFT_HEIGHT - last.y : last.y; - data->state = LV_INDEV_STATE_PR; - } - else { - data->point.x = (TFT_ROTATION == TFT_ROTATE_180) ? TFT_WIDTH - last.x : last.x; - data->point.y = (TFT_ROTATION == TFT_ROTATE_180) ? TFT_HEIGHT - last.y : last.y; - data->state = LV_INDEV_STATE_REL; - } + data->state = get_point(&last.x, &last.y) ? LV_INDEV_STATE_PR : LV_INDEV_STATE_REL; + data->point.x = (TFT_ROTATION == TFT_ROTATE_180) ? TFT_WIDTH - last.x : last.x; + data->point.y = (TFT_ROTATION == TFT_ROTATE_180) ? TFT_HEIGHT - last.y : last.y; return false; // Return `false` since no data is buffering or left to read } diff --git a/Marlin/src/lcd/tft/touch.cpp b/Marlin/src/lcd/tft/touch.cpp index 8e79e397adea..3c0b21ba8fd3 100644 --- a/Marlin/src/lcd/tft/touch.cpp +++ b/Marlin/src/lcd/tft/touch.cpp @@ -39,7 +39,7 @@ #include "tft.h" bool Touch::enabled = true; -xy_int_t Touch::point; +int16_t Touch::x, Touch::y; touch_control_t Touch::controls[]; touch_control_t *Touch::current_control; uint16_t Touch::controls_count; @@ -67,13 +67,17 @@ void Touch::add_control(TouchControlType type, uint16_t x, uint16_t y, uint16_t if (controls_count == MAX_CONTROLS) return; controls[controls_count].type = type; - controls[controls_count].pos.set(x, y); - controls[controls_count].size.set(width, height); + controls[controls_count].x = x; + controls[controls_count].y = y; + controls[controls_count].width = width; + controls[controls_count].height = height; controls[controls_count].data = data; controls_count++; } void Touch::idle() { + int16_t _x, _y; + if (!enabled) return; // Return if Touch::idle is called within the same millisecond @@ -81,8 +85,7 @@ void Touch::idle() { if (now <= next_touch_ms) return; next_touch_ms = now; - xy_int_t got_point; - if (get_point(got_point)) { + if (get_point(&_x, &_y)) { #if HAS_RESUME_CONTINUE // UI is waiting for a click anywhere? if (wait_for_user) { @@ -106,13 +109,11 @@ void Touch::idle() { if (time_to_hold == 0) time_to_hold = now + MINIMUM_HOLD_TIME; if (PENDING(now, time_to_hold)) return; - if (bool(point)) { + if (x != 0 && y != 0) { if (current_control) { - if ( WITHIN(point.x, current_control->pos.x - FREE_MOVE_RANGE, current_control->pos.x + current_control->size.x + FREE_MOVE_RANGE) - && WITHIN(point.y, current_control->pos.y - FREE_MOVE_RANGE, current_control->pos.y + current_control->size.y + FREE_MOVE_RANGE) - ) { - LIMIT(point.x, current_control->pos.x, current_control->pos.x + current_control->size.x); - LIMIT(point.y, current_control->pos.y, current_control->pos.y + current_control->size.y); + if (WITHIN(x, current_control->x - FREE_MOVE_RANGE, current_control->x + current_control->width + FREE_MOVE_RANGE) && WITHIN(y, current_control->y - FREE_MOVE_RANGE, current_control->y + current_control->height + FREE_MOVE_RANGE)) { + LIMIT(x, current_control->x, current_control->x + current_control->width); + LIMIT(y, current_control->y, current_control->y + current_control->height); touch(current_control); } else @@ -120,10 +121,7 @@ void Touch::idle() { } else { for (uint16_t i = 0; i < controls_count; i++) { - if (TERN0(TOUCH_SCREEN_CALIBRATION, controls[i].type == CALIBRATE) - || ( WITHIN(point.x, controls[i].pos.x, controls[i].pos.x + controls[i].size.x) - && WITHIN(point.y, controls[i].pos.y, controls[i].pos.y + controls[i].size.y)) - ) { + if ((WITHIN(x, controls[i].x, controls[i].x + controls[i].width) && WITHIN(y, controls[i].y, controls[i].y + controls[i].height)) || (TERN(TOUCH_SCREEN_CALIBRATION, controls[i].type == CALIBRATE, false))) { touch_control_type = controls[i].type; touch(&controls[i]); break; @@ -134,10 +132,11 @@ void Touch::idle() { if (!current_control) touch_time = now; } - point = got_point; + x = _x; + y = _y; } else { - point.reset(); + x = y = 0; current_control = nullptr; touch_time = 0; touch_control_type = NONE; @@ -150,7 +149,7 @@ void Touch::touch(touch_control_t *control) { switch (control->type) { #if ENABLED(TOUCH_SCREEN_CALIBRATION) case CALIBRATE: - if (touch_calibration.handleTouch(point)) ui.refresh(); + if (touch_calibration.handleTouch(x, y)) ui.refresh(); break; #endif @@ -177,7 +176,7 @@ void Touch::touch(touch_control_t *control) { ui.encoderPosition = ui.encoderPosition + LCD_HEIGHT < (uint32_t)screen_items ? ui.encoderPosition + LCD_HEIGHT : screen_items; ui.refresh(); break; - case SLIDER: hold(control); ui.encoderPosition = (point.x - control->pos.x) * control->data / control->size.x; break; + case SLIDER: hold(control); ui.encoderPosition = (x - control->x) * control->data / control->width; break; case INCREASE: hold(control, repeat_delay - 5); TERN(AUTO_BED_LEVELING_UBL, ui.external_control ? bedlevel.encoder_diff++ : ui.encoderPosition++, ui.encoderPosition++); break; case DECREASE: hold(control, repeat_delay - 5); TERN(AUTO_BED_LEVELING_UBL, ui.external_control ? bedlevel.encoder_diff-- : ui.encoderPosition--, ui.encoderPosition--); break; case HEATER: @@ -263,16 +262,19 @@ void Touch::hold(touch_control_t *control, millis_t delay) { ui.refresh(); } -bool Touch::get_point(xy_int_t &point) { - bool is_touched = false; +bool Touch::get_point(int16_t * const x, int16_t * const y) { #if ANY(TFT_TOUCH_DEVICE_XPT2046, TFT_TOUCH_DEVICE_GT911) - is_touched = (TOUCH_ORIENTATION_NONE != _TOUCH_ORIENTATION) - && (TOUCH_PORTRAIT == _TOUCH_ORIENTATION - ? io.getRawPoint(&point.y, &point.x) - : io.getRawPoint(&point.x, &point.y)); - #if ENABLED(TFT_TOUCH_DEVICE_XPT2046) - point.x = uint16_t((uint32_t(point.x) * _TOUCH_CALIBRATION_X) >> 16) + _TOUCH_OFFSET_X; - point.y = uint16_t((uint32_t(point.y) * _TOUCH_CALIBRATION_Y) >> 16) + _TOUCH_OFFSET_Y; + const bool is_touched = TOUCH_PORTRAIT == _TOUCH_ORIENTATION ? io.getRawPoint(y, x) : io.getRawPoint(x, y); + #endif + #if ENABLED(TFT_TOUCH_DEVICE_XPT2046) + #if ENABLED(TOUCH_SCREEN_CALIBRATION) + if (is_touched && TOUCH_ORIENTATION_NONE != _TOUCH_ORIENTATION) { + *x = int16_t((int32_t(*x) * _TOUCH_CALIBRATION_X) >> 16) + _TOUCH_OFFSET_X; + *y = int16_t((int32_t(*y) * _TOUCH_CALIBRATION_Y) >> 16) + _TOUCH_OFFSET_Y; + } + #else + *x = uint16_t((uint32_t(*x) * _TOUCH_CALIBRATION_X) >> 16) + _TOUCH_OFFSET_X; + *y = uint16_t((uint32_t(*y) * _TOUCH_CALIBRATION_Y) >> 16) + _TOUCH_OFFSET_Y; #endif #endif diff --git a/Marlin/src/lcd/tft/touch.h b/Marlin/src/lcd/tft/touch.h index 6c0ff88f4674..93f9327a15b3 100644 --- a/Marlin/src/lcd/tft/touch.h +++ b/Marlin/src/lcd/tft/touch.h @@ -57,8 +57,10 @@ enum TouchControlType : uint16_t { typedef struct __attribute__((__packed__)) { TouchControlType type; - xy_uint_t pos; - xy_uint_t size; + uint16_t x; + uint16_t y; + uint16_t width; + uint16_t height; intptr_t data; } touch_control_t; @@ -75,7 +77,7 @@ typedef struct __attribute__((__packed__)) { class Touch { private: static TOUCH_DRIVER_CLASS io; - static xy_int_t point; + static int16_t x, y; static bool enabled; static touch_control_t controls[MAX_CONTROLS]; @@ -85,7 +87,7 @@ class Touch { static millis_t next_touch_ms, time_to_hold, repeat_delay, touch_time; static TouchControlType touch_control_type; - static bool get_point(xy_int_t &point); + static bool get_point(int16_t * const x, int16_t * const y); static void touch(touch_control_t *control); static void hold(touch_control_t *control, millis_t delay=0); diff --git a/Marlin/src/lcd/tft_io/touch_calibration.cpp b/Marlin/src/lcd/tft_io/touch_calibration.cpp index b1cdfe6cda94..f76c29eb49f2 100644 --- a/Marlin/src/lcd/tft_io/touch_calibration.cpp +++ b/Marlin/src/lcd/tft_io/touch_calibration.cpp @@ -58,18 +58,18 @@ void TouchCalibration::validate_calibration() { #define CP(N) calibration_points[CALIBRATION_##N] if (landscape) { calibration_state = CALIBRATION_SUCCESS; - calibration.x = ((CP(TOP_RIGHT).x - CP(TOP_LEFT).x) << 17) / (CP(BOTTOM_RIGHT).raw.x + CP(TOP_RIGHT).raw.x - CP(BOTTOM_LEFT).raw.x - CP(TOP_LEFT).raw.x); - calibration.y = ((CP(BOTTOM_LEFT).y - CP(TOP_LEFT).y) << 17) / (CP(BOTTOM_RIGHT).raw.y - CP(TOP_RIGHT).raw.y + CP(BOTTOM_LEFT).raw.y - CP(TOP_LEFT).raw.y); - calibration.offset.x = CP(TOP_LEFT).x - int16_t(((CP(TOP_LEFT).raw.x + CP(BOTTOM_LEFT).raw.x) * calibration.x) >> 17); - calibration.offset.y = CP(TOP_LEFT).y - int16_t(((CP(TOP_LEFT).raw.y + CP(TOP_RIGHT).raw.y) * calibration.y) >> 17); + calibration.x = ((CP(TOP_RIGHT).x - CP(TOP_LEFT).x) << 17) / (CP(BOTTOM_RIGHT).raw_x + CP(TOP_RIGHT).raw_x - CP(BOTTOM_LEFT).raw_x - CP(TOP_LEFT).raw_x); + calibration.y = ((CP(BOTTOM_LEFT).y - CP(TOP_LEFT).y) << 17) / (CP(BOTTOM_RIGHT).raw_y - CP(TOP_RIGHT).raw_y + CP(BOTTOM_LEFT).raw_y - CP(TOP_LEFT).raw_y); + calibration.offset_x = CP(TOP_LEFT).x - int16_t(((CP(TOP_LEFT).raw_x + CP(BOTTOM_LEFT).raw_x) * calibration.x) >> 17); + calibration.offset_y = CP(TOP_LEFT).y - int16_t(((CP(TOP_LEFT).raw_y + CP(TOP_RIGHT).raw_y) * calibration.y) >> 17); calibration.orientation = TOUCH_LANDSCAPE; } else if (portrait) { calibration_state = CALIBRATION_SUCCESS; - calibration.x = ((CP(TOP_RIGHT).x - CP(TOP_LEFT).x) << 17) / (CP(BOTTOM_RIGHT).raw.y + CP(TOP_RIGHT).raw.y - CP(BOTTOM_LEFT).raw.y - CP(TOP_LEFT).raw.y); - calibration.y = ((CP(BOTTOM_LEFT).y - CP(TOP_LEFT).y) << 17) / (CP(BOTTOM_RIGHT).raw.x - CP(TOP_RIGHT).raw.x + CP(BOTTOM_LEFT).raw.x - CP(TOP_LEFT).raw.x); - calibration.offset.x = CP(TOP_LEFT).x - int16_t(((CP(TOP_LEFT).raw.y + CP(BOTTOM_LEFT).raw.y) * calibration.x) >> 17); - calibration.offset.y = CP(TOP_LEFT).y - int16_t(((CP(TOP_LEFT).raw.x + CP(TOP_RIGHT).raw.x) * calibration.y) >> 17); + calibration.x = ((CP(TOP_RIGHT).x - CP(TOP_LEFT).x) << 17) / (CP(BOTTOM_RIGHT).raw_y + CP(TOP_RIGHT).raw_y - CP(BOTTOM_LEFT).raw_y - CP(TOP_LEFT).raw_y); + calibration.y = ((CP(BOTTOM_LEFT).y - CP(TOP_LEFT).y) << 17) / (CP(BOTTOM_RIGHT).raw_x - CP(TOP_RIGHT).raw_x + CP(BOTTOM_LEFT).raw_x - CP(TOP_LEFT).raw_x); + calibration.offset_x = CP(TOP_LEFT).x - int16_t(((CP(TOP_LEFT).raw_y + CP(BOTTOM_LEFT).raw_y) * calibration.x) >> 17); + calibration.offset_y = CP(TOP_LEFT).y - int16_t(((CP(TOP_LEFT).raw_x + CP(TOP_RIGHT).raw_x) * calibration.y) >> 17); calibration.orientation = TOUCH_PORTRAIT; } else { @@ -83,23 +83,23 @@ void TouchCalibration::validate_calibration() { SERIAL_ECHOLNPGM("Touch screen calibration completed"); SERIAL_ECHOLN(F("#define TOUCH_"), F("CALIBRATION_X "), calibration.x); SERIAL_ECHOLN(F("#define TOUCH_"), F("CALIBRATION_Y "), calibration.y); - SERIAL_ECHOLN(F("#define TOUCH_"), F("OFFSET_X "), calibration.offset.x); - SERIAL_ECHOLN(F("#define TOUCH_"), F("OFFSET_Y "), calibration.offset.y); + SERIAL_ECHOLN(F("#define TOUCH_"), F("OFFSET_X "), calibration.offset_x); + SERIAL_ECHOLN(F("#define TOUCH_"), F("OFFSET_Y "), calibration.offset_y); SERIAL_ECHO(F("#define TOUCH_")); SERIAL_ECHO_TERNARY(calibration.orientation == TOUCH_LANDSCAPE, "ORIENTATION ", "TOUCH_LANDSCAPE", "TOUCH_PORTRAIT", "\n"); TERN_(TOUCH_CALIBRATION_AUTO_SAVE, settings.save()); } } -bool TouchCalibration::handleTouch(const xy_int_t &point) { +bool TouchCalibration::handleTouch(const uint16_t x, const uint16_t y) { const millis_t now = millis(); + if (next_touch_update_ms && PENDING(now, next_touch_update_ms)) return false; next_touch_update_ms = now + BUTTON_DELAY_MENU; if (calibration_state < CALIBRATION_SUCCESS) { - calibration_points[calibration_state].raw = point; - DEBUG_ECHOLNPGM("TouchCalibration - State: ", calibration_state, - ", x: ", calibration_points[calibration_state].x, ", raw.x: ", point.x, - ", y: ", calibration_points[calibration_state].y, ", raw.y: ", point.y); + calibration_points[calibration_state].raw_x = x; + calibration_points[calibration_state].raw_y = y; + DEBUG_ECHOLNPGM("TouchCalibration - State: ", calibration_state, ", x: ", calibration_points[calibration_state].x, ", raw_x: ", x, ", y: ", calibration_points[calibration_state].y, ", raw_y: ", y); } switch (calibration_state) { diff --git a/Marlin/src/lcd/tft_io/touch_calibration.h b/Marlin/src/lcd/tft_io/touch_calibration.h index be226db224cc..5e15f85cb570 100644 --- a/Marlin/src/lcd/tft_io/touch_calibration.h +++ b/Marlin/src/lcd/tft_io/touch_calibration.h @@ -27,8 +27,8 @@ #define _TOUCH_CALIBRATION_X touch_calibration.calibration.x #define _TOUCH_CALIBRATION_Y touch_calibration.calibration.y -#define _TOUCH_OFFSET_X touch_calibration.calibration.offset.x -#define _TOUCH_OFFSET_Y touch_calibration.calibration.offset.y +#define _TOUCH_OFFSET_X touch_calibration.calibration.offset_x +#define _TOUCH_OFFSET_Y touch_calibration.calibration.offset_y #define _TOUCH_ORIENTATION touch_calibration.calibration.orientation #ifndef TOUCH_SCREEN_CALIBRATION_PRECISION @@ -38,22 +38,15 @@ #define TOUCH_SCREEN_HOLD_TO_CALIBRATE_MS 2500 #endif -typedef struct __attribute__((__packed__)) TouchCal : xy_long_t { - xy_int_t offset; +typedef struct __attribute__((__packed__)) { + int32_t x, y; + int16_t offset_x, offset_y; uint8_t orientation; - TouchCal() { set(xy_long_t({ 0, 0 }), xy_int_t({ 0, 0 }), TOUCH_ORIENTATION_NONE); } - void set(const xy_long_t &xy, const xy_int_t &hv, const uint8_t o) { - xy_long_t::set(xy); offset = hv; orientation = o; - } - void reset() { - set(xy_long_t({ TOUCH_CALIBRATION_X, TOUCH_CALIBRATION_Y }), - xy_int_t({ TOUCH_OFFSET_X, TOUCH_OFFSET_Y }), - TOUCH_ORIENTATION); - } } touch_calibration_t; -typedef struct __attribute__((__packed__)) : xy_uint_t { - xy_int_t raw; +typedef struct __attribute__((__packed__)) { + uint16_t x, y; + int16_t raw_x, raw_y; } touch_calibration_point_t; enum calibrationState : uint8_t { @@ -72,24 +65,28 @@ class TouchCalibration { static touch_calibration_point_t calibration_points[4]; static millis_t next_touch_update_ms; - static bool validate_precision(int32_t a, int32_t b) { return (a > b ? (100 * b) / a : (100 * a) / b) > (TOUCH_SCREEN_CALIBRATION_PRECISION); } - static bool validate_precision_x(uint8_t a, uint8_t b) { return validate_precision(calibration_points[a].raw.x, calibration_points[b].raw.x); } - static bool validate_precision_y(uint8_t a, uint8_t b) { return validate_precision(calibration_points[a].raw.y, calibration_points[b].raw.y); } + static bool validate_precision(int32_t a, int32_t b) { return (a > b ? (100 * b) / a : (100 * a) / b) > TOUCH_SCREEN_CALIBRATION_PRECISION; } + static bool validate_precision_x(uint8_t a, uint8_t b) { return validate_precision(calibration_points[a].raw_x, calibration_points[b].raw_x); } + static bool validate_precision_y(uint8_t a, uint8_t b) { return validate_precision(calibration_points[a].raw_y, calibration_points[b].raw_y); } static void validate_calibration(); static touch_calibration_t calibration; static uint8_t failed_count; - static void calibration_reset() { calibration.set(xy_long_t({ TOUCH_CALIBRATION_X, TOUCH_CALIBRATION_Y }), xy_int_t({ TOUCH_OFFSET_X, TOUCH_OFFSET_Y }), TOUCH_ORIENTATION); } - static bool need_calibration() { return !(calibration.offset.x || calibration.offset.y || calibration.x || calibration.y); } + static void calibration_reset() { calibration = { TOUCH_CALIBRATION_X, TOUCH_CALIBRATION_Y, TOUCH_OFFSET_X, TOUCH_OFFSET_Y, TOUCH_ORIENTATION }; } + static bool need_calibration() { return !calibration.offset_x && !calibration.offset_y && !calibration.x && !calibration.y; } static calibrationState calibration_start() { next_touch_update_ms = millis() + 750UL; - calibration.reset(); + calibration = { 0, 0, 0, 0, TOUCH_ORIENTATION_NONE }; calibration_state = CALIBRATION_TOP_LEFT; - calibration_points[CALIBRATION_TOP_LEFT].set(30, 30); - calibration_points[CALIBRATION_TOP_RIGHT].set(TFT_WIDTH - 31, 30); - calibration_points[CALIBRATION_BOTTOM_RIGHT].set(TFT_WIDTH - 31, TFT_HEIGHT - 31); - calibration_points[CALIBRATION_BOTTOM_LEFT].set(30, TFT_HEIGHT - 31); + calibration_points[CALIBRATION_TOP_LEFT].x = 30; + calibration_points[CALIBRATION_TOP_LEFT].y = 30; + calibration_points[CALIBRATION_TOP_RIGHT].x = TFT_WIDTH - 31; + calibration_points[CALIBRATION_TOP_RIGHT].y = 30; + calibration_points[CALIBRATION_BOTTOM_RIGHT].x = TFT_WIDTH - 31; + calibration_points[CALIBRATION_BOTTOM_RIGHT].y = TFT_HEIGHT - 31; + calibration_points[CALIBRATION_BOTTOM_LEFT].x = 30; + calibration_points[CALIBRATION_BOTTOM_LEFT].y = TFT_HEIGHT - 31; failed_count = 0; return calibration_state; } @@ -100,12 +97,12 @@ class TouchCalibration { return !need_calibration(); } - static bool handleTouch(const xy_int_t &point); + static bool handleTouch(const uint16_t x, const uint16_t y); }; extern TouchCalibration touch_calibration; -#else // TOUCH_SCREEN_CALIBRATION +#else // !TOUCH_SCREEN_CALIBRATION #define _TOUCH_CALIBRATION_X (TOUCH_CALIBRATION_X) #define _TOUCH_CALIBRATION_Y (TOUCH_CALIBRATION_Y) diff --git a/Marlin/src/lcd/touch/touch_buttons.cpp b/Marlin/src/lcd/touch/touch_buttons.cpp index 636a31dafa41..7d31b21c04a6 100644 --- a/Marlin/src/lcd/touch/touch_buttons.cpp +++ b/Marlin/src/lcd/touch/touch_buttons.cpp @@ -66,6 +66,7 @@ uint8_t TouchButtons::read_buttons() { int16_t x, y; #if ENABLED(TFT_TOUCH_DEVICE_XPT2046) + const bool is_touched = TOUCH_PORTRAIT == _TOUCH_ORIENTATION ? touchIO.getRawPoint(&y, &x) : touchIO.getRawPoint(&x, &y); @@ -88,13 +89,16 @@ uint8_t TouchButtons::read_buttons() { #if ENABLED(TOUCH_SCREEN_CALIBRATION) const calibrationState state = touch_calibration.get_calibration_state(); if (WITHIN(state, CALIBRATION_TOP_LEFT, CALIBRATION_BOTTOM_LEFT)) { - if (!no_touch && touch_calibration.handleTouch(xy_int_t({x, y}))) ui.refresh(); + if (!no_touch && touch_calibration.handleTouch(x, y)) ui.refresh(); no_touch = true; return 0; } + x = int16_t((int32_t(x) * _TOUCH_CALIBRATION_X) >> 16) + _TOUCH_OFFSET_X; + y = int16_t((int32_t(y) * _TOUCH_CALIBRATION_Y) >> 16) + _TOUCH_OFFSET_Y; + #else + x = uint16_t((uint32_t(x) * _TOUCH_CALIBRATION_X) >> 16) + _TOUCH_OFFSET_X; + y = uint16_t((uint32_t(y) * _TOUCH_CALIBRATION_Y) >> 16) + _TOUCH_OFFSET_Y; #endif - x = uint16_t((uint32_t(x) * _TOUCH_CALIBRATION_X) >> 16) + _TOUCH_OFFSET_X; - y = uint16_t((uint32_t(y) * _TOUCH_CALIBRATION_Y) >> 16) + _TOUCH_OFFSET_Y; #elif ENABLED(TFT_TOUCH_DEVICE_GT911) From fe8266b59105c24a6dced92bfd604374e5e9ef8d Mon Sep 17 00:00:00 2001 From: Erkan Ozgur Yilmaz Date: Thu, 30 Nov 2023 22:52:11 +0000 Subject: [PATCH 41/77] =?UTF-8?q?=F0=9F=9A=B8=20Fix=20BLTouch=20HSMode=20d?= =?UTF-8?q?eploy=20(#26311)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/module/probe.cpp | 10 +++++++--- 1 file changed, 7 insertions(+), 3 deletions(-) diff --git a/Marlin/src/module/probe.cpp b/Marlin/src/module/probe.cpp index deeb53942ba3..0bd83bc3ac10 100644 --- a/Marlin/src/module/probe.cpp +++ b/Marlin/src/module/probe.cpp @@ -596,11 +596,15 @@ bool Probe::probe_down_to_z(const_float_t z, const_feedRate_t fr_mm_s) { thermalManager.wait_for_hotend_heating(active_extruder); #endif - // Ensure the BLTouch is deployed. Does nothing if already deployed. - if (TERN0(BLTOUCH, bltouch.deploy())) return true; + #if ENABLED(BLTOUCH) + // Ensure the BLTouch is deployed. (Does nothing if already deployed.) + // Don't deploy with high_speed_mode enabled. The probe already re-deploys itself. + if (TERN(MEASURE_BACKLASH_WHEN_PROBING, true, !bltouch.high_speed_mode) && bltouch.deploy()) + return true; + #endif #if HAS_Z_SERVO_PROBE && (ENABLED(Z_SERVO_INTERMEDIATE_STOW) || defined(Z_SERVO_MEASURE_ANGLE)) - probe_specific_action(true); // Always re-deploy in this case + probe_specific_action(true); // Always re-deploy in this case #endif // Disable stealthChop if used. Enable diag1 pin on driver. From b55678a7d08f75a44993381e056fa5c537c9a4dd Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Fri, 1 Dec 2023 00:23:41 +0000 Subject: [PATCH 42/77] [cron] Bump distribution date (2023-12-01) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 07815b01d6fe..96bcec0bbc7c 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2023-11-30" +//#define STRING_DISTRIBUTION_DATE "2023-12-01" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 3d192cb4740a..a91f9c1e9448 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2023-11-30" + #define STRING_DISTRIBUTION_DATE "2023-12-01" #endif /** From e393c7fa0e00264308b66c6a332b60f6fca6cb80 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 30 Nov 2023 20:51:55 -0600 Subject: [PATCH 43/77] =?UTF-8?q?=E2=9C=85=20=20Temporarily=20allow=20PR?= =?UTF-8?q?=20against=202.1.x?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .github/workflows/check-pr.yml | 1 - 1 file changed, 1 deletion(-) diff --git a/.github/workflows/check-pr.yml b/.github/workflows/check-pr.yml index abb0d44706d3..2b15067f5156 100644 --- a/.github/workflows/check-pr.yml +++ b/.github/workflows/check-pr.yml @@ -12,7 +12,6 @@ on: - 1.0.x - 1.1.x - 2.0.x - - 2.1.x jobs: bad_target: From c53844ff91b65576f60f8060a296d68d1d25c92a Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 1 Dec 2023 04:45:55 -0600 Subject: [PATCH 44/77] =?UTF-8?q?=E2=9C=85=20Temporary=20CI=20Tests=20for?= =?UTF-8?q?=202.1.x?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .github/workflows/test-builds.yml | 2 ++ 1 file changed, 2 insertions(+) diff --git a/.github/workflows/test-builds.yml b/.github/workflows/test-builds.yml index 057fa8b75f19..7c62b5af6c54 100644 --- a/.github/workflows/test-builds.yml +++ b/.github/workflows/test-builds.yml @@ -9,6 +9,7 @@ on: pull_request: branches: - bugfix-2.1.x + - 2.1.x paths-ignore: - config/** - data/** @@ -17,6 +18,7 @@ on: push: branches: - bugfix-2.1.x + - 2.1.x paths-ignore: - config/** - data/** From b17d3d3e9c68032d4b7e4ad03a7f65fb9f0fd5d0 Mon Sep 17 00:00:00 2001 From: ellensp <530024+ellensp@users.noreply.github.com> Date: Sat, 2 Dec 2023 04:25:57 +1300 Subject: [PATCH 45/77] =?UTF-8?q?=F0=9F=A7=91=E2=80=8D=F0=9F=92=BB=20More?= =?UTF-8?q?=20num-to-string=20digits=20/=20precisions=20(#26343)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/src/lcd/menu/menu_advanced.cpp | 8 +- Marlin/src/lcd/menu/menu_item.h | 9 ++ Marlin/src/libs/numtostr.cpp | 210 ++++++++++++++------------ Marlin/src/libs/numtostr.h | 52 +++++-- 4 files changed, 167 insertions(+), 112 deletions(-) diff --git a/Marlin/src/lcd/menu/menu_advanced.cpp b/Marlin/src/lcd/menu/menu_advanced.cpp index 90a37ed5199c..1d95961f3b7b 100644 --- a/Marlin/src/lcd/menu/menu_advanced.cpp +++ b/Marlin/src/lcd/menu/menu_advanced.cpp @@ -371,8 +371,8 @@ void menu_backlash(); #define _MPC_EDIT_ITEMS(N) \ MPC_t &mpc = thermalManager.temp_hotend[MenuItemBase::itemIndex].mpc; \ - EDIT_ITEM_FAST_N(float31sign, N, MSG_MPC_POWER_E, &mpc.heater_power, 1, 200); \ - EDIT_ITEM_FAST_N(float31sign, N, MSG_MPC_BLOCK_HEAT_CAPACITY_E, &mpc.block_heat_capacity, 0, 40); \ + EDIT_ITEM_FAST_N(float41, N, MSG_MPC_POWER_E, &mpc.heater_power, 1, 200); \ + EDIT_ITEM_FAST_N(float31, N, MSG_MPC_BLOCK_HEAT_CAPACITY_E, &mpc.block_heat_capacity, 0, 40); \ EDIT_ITEM_FAST_N(float43, N, MSG_SENSOR_RESPONSIVENESS_E, &mpc.sensor_responsiveness, 0, 1); \ EDIT_ITEM_FAST_N(float43, N, MSG_MPC_AMBIENT_XFER_COEFF_E, &mpc.ambient_xfer_coeff_fan0, 0, 1) @@ -563,7 +563,7 @@ void menu_backlash(); editable.decimal = stepper.get_shaping_frequency(X_AXIS); if (editable.decimal) { ACTION_ITEM_N(X_AXIS, MSG_SHAPING_DISABLE, []{ stepper.set_shaping_frequency(X_AXIS, 0.0f); }); - EDIT_ITEM_FAST_N(float61, X_AXIS, MSG_SHAPING_FREQ, &editable.decimal, min_frequency, 200.0f, []{ stepper.set_shaping_frequency(X_AXIS, editable.decimal); }); + EDIT_ITEM_FAST_N(float41, X_AXIS, MSG_SHAPING_FREQ, &editable.decimal, min_frequency, 200.0f, []{ stepper.set_shaping_frequency(X_AXIS, editable.decimal); }); editable.decimal = stepper.get_shaping_damping_ratio(X_AXIS); EDIT_ITEM_FAST_N(float42_52, X_AXIS, MSG_SHAPING_ZETA, &editable.decimal, 0.0f, 1.0f, []{ stepper.set_shaping_damping_ratio(X_AXIS, editable.decimal); }); } @@ -574,7 +574,7 @@ void menu_backlash(); editable.decimal = stepper.get_shaping_frequency(Y_AXIS); if (editable.decimal) { ACTION_ITEM_N(Y_AXIS, MSG_SHAPING_DISABLE, []{ stepper.set_shaping_frequency(Y_AXIS, 0.0f); }); - EDIT_ITEM_FAST_N(float61, Y_AXIS, MSG_SHAPING_FREQ, &editable.decimal, min_frequency, 200.0f, []{ stepper.set_shaping_frequency(Y_AXIS, editable.decimal); }); + EDIT_ITEM_FAST_N(float41, Y_AXIS, MSG_SHAPING_FREQ, &editable.decimal, min_frequency, 200.0f, []{ stepper.set_shaping_frequency(Y_AXIS, editable.decimal); }); editable.decimal = stepper.get_shaping_damping_ratio(Y_AXIS); EDIT_ITEM_FAST_N(float42_52, Y_AXIS, MSG_SHAPING_ZETA, &editable.decimal, 0.0f, 1.0f, []{ stepper.set_shaping_damping_ratio(Y_AXIS, editable.decimal); }); } diff --git a/Marlin/src/lcd/menu/menu_item.h b/Marlin/src/lcd/menu/menu_item.h index 4d3e33db4c5a..11f78d25d5da 100644 --- a/Marlin/src/lcd/menu/menu_item.h +++ b/Marlin/src/lcd/menu/menu_item.h @@ -150,10 +150,19 @@ DEFINE_MENU_EDIT_ITEM_TYPE(uint16_5 ,uint16_t ,ui16tostr5rj , 0.01f DEFINE_MENU_EDIT_ITEM_TYPE(float3 ,float ,ftostr3rj , 1 ); // 123 right-justified DEFINE_MENU_EDIT_ITEM_TYPE(float42_52 ,float ,ftostr42_52 , 100 , + 0.001f ); // _2.34, 12.34, -2.34 or 123.45, -23.45 DEFINE_MENU_EDIT_ITEM_TYPE(float43 ,float ,ftostr43sign ,1000 , + 0.0001f); // -1.234, _1.234, +1.234 +DEFINE_MENU_EDIT_ITEM_TYPE(float53 ,float ,ftostr53sign ,1000 , + 0.0001f); // -12.345, _2.345, +2.345 +DEFINE_MENU_EDIT_ITEM_TYPE(float54 ,float ,ftostr54sign ,10000 , + 0.00001f); // -1.2345, _1.2345, +1.2345 DEFINE_MENU_EDIT_ITEM_TYPE(float4 ,float ,ftostr4sign , 1 ); // 1234 right-justified DEFINE_MENU_EDIT_ITEM_TYPE(float5 ,float ,ftostr5rj , 1 ); // 12345 right-justified DEFINE_MENU_EDIT_ITEM_TYPE(float5_25 ,float ,ftostr5rj , 0.04f ); // 12345 right-justified (25 increment) +DEFINE_MENU_EDIT_ITEM_TYPE(float31 ,float ,ftostr31rj , 10 , + 0.01f ); // 45.6 right-justified +DEFINE_MENU_EDIT_ITEM_TYPE(float41 ,float ,ftostr41rj , 10 , + 0.01f ); // 345.6 right-justified +DEFINE_MENU_EDIT_ITEM_TYPE(float51 ,float ,ftostr51rj , 10 , + 0.01f ); // 1234.5 right-justified DEFINE_MENU_EDIT_ITEM_TYPE(float61 ,float ,ftostr61rj , 10 , + 0.01f ); // 12345.6 right-justified +DEFINE_MENU_EDIT_ITEM_TYPE(float32 ,float ,ftostr32rj , 100 , + 0.001f ); // 1.23 +DEFINE_MENU_EDIT_ITEM_TYPE(float42 ,float ,ftostr42rj , 100 , + 0.001f ); // 12.34 right-justified +DEFINE_MENU_EDIT_ITEM_TYPE(float52 ,float ,ftostr52rj , 100 , + 0.001f ); // 123.45 right-justified +DEFINE_MENU_EDIT_ITEM_TYPE(float62 ,float ,ftostr62rj , 100 , + 0.001f ); // 1234.56 right-justified DEFINE_MENU_EDIT_ITEM_TYPE(float72 ,float ,ftostr72rj , 100 , + 0.001f ); // 12345.67 right-justified DEFINE_MENU_EDIT_ITEM_TYPE(float31sign ,float ,ftostr31sign , 10 , + 0.01f ); // +12.3 DEFINE_MENU_EDIT_ITEM_TYPE(float41sign ,float ,ftostr41sign , 10 , + 0.01f ); // +123.4 diff --git a/Marlin/src/libs/numtostr.cpp b/Marlin/src/libs/numtostr.cpp index e27373263556..3efbf68217e6 100644 --- a/Marlin/src/libs/numtostr.cpp +++ b/Marlin/src/libs/numtostr.cpp @@ -45,7 +45,7 @@ constexpr long UINTFLOAT(const float V, const int N) { char conv[9] = { 0 }; -// Format uint8_t (0-100) as rj string with 123% / _12% / __1% format +// Format uint8_t (0-100) as rj string with __3% / _23% / 123% format const char* pcttostrpctrj(const uint8_t i) { conv[4] = RJDIGIT(i, 100); conv[5] = RJDIGIT(i, 10); @@ -59,7 +59,7 @@ const char* ui8tostr4pctrj(const uint8_t i) { return pcttostrpctrj(ui8_to_percent(i)); } -// Convert unsigned 8bit int to string 123 format +// Convert unsigned 8bit int to string with __3 / _23 / 123 format const char* ui8tostr3rj(const uint8_t i) { conv[5] = RJDIGIT(i, 100); conv[6] = RJDIGIT(i, 10); @@ -74,7 +74,7 @@ const char* ui8tostr2(const uint8_t i) { return &conv[6]; } -// Convert signed 8bit int to rj string with 123 or -12 format +// Convert signed 8bit int to rj string with __3 / _23 / 123 / -_3 / -23 format const char* i8tostr3rj(const int8_t x) { int xx = x; conv[5] = MINUSOR(xx, RJDIGIT(xx, 100)); @@ -105,32 +105,26 @@ const char* i8tostr3rj(const int8_t x) { } #endif -// Convert unsigned 16bit int to string 12345 format -const char* ui16tostr5rj(const uint16_t xx) { - conv[3] = RJDIGIT(xx, 10000); - conv[4] = RJDIGIT(xx, 1000); - conv[5] = RJDIGIT(xx, 100); - conv[6] = RJDIGIT(xx, 10); +// Convert unsigned 16bit int to right-justified string +inline const char* ui16tostrXrj(const uint16_t xx, const int index) { + switch (index) { + case 0 ... 3: conv[3] = RJDIGIT(xx, 10000); + case 4: conv[4] = RJDIGIT(xx, 1000); + case 5: conv[5] = RJDIGIT(xx, 100); + case 6: conv[6] = RJDIGIT(xx, 10); + } conv[7] = DIGIMOD(xx, 1); - return &conv[3]; + return &conv[index]; } -// Convert unsigned 16bit int to string 1234 format -const char* ui16tostr4rj(const uint16_t xx) { - conv[4] = RJDIGIT(xx, 1000); - conv[5] = RJDIGIT(xx, 100); - conv[6] = RJDIGIT(xx, 10); - conv[7] = DIGIMOD(xx, 1); - return &conv[4]; -} +// Convert unsigned 16bit int to string with 12345 format +const char* ui16tostr5rj(const uint16_t xx) { return ui16tostrXrj(xx, 8 - 5); } -// Convert unsigned 16bit int to string 123 format -const char* ui16tostr3rj(const uint16_t xx) { - conv[5] = RJDIGIT(xx, 100); - conv[6] = RJDIGIT(xx, 10); - conv[7] = DIGIMOD(xx, 1); - return &conv[5]; -} +// Convert unsigned 16bit int to string with 1234 format +const char* ui16tostr4rj(const uint16_t xx) { return ui16tostrXrj(xx, 8 - 4); } + +// Convert unsigned 16bit int to string with 123 format +const char* ui16tostr3rj(const uint16_t xx) { return ui16tostrXrj(xx, 8 - 3); } // Convert signed 16bit int to rj string with 123 or -12 format const char* i16tostr3rj(const int16_t x) { @@ -222,7 +216,7 @@ const char* ftostr41ns(const_float_t f) { return &conv[3]; } -// Convert signed float to fixed-length string with 12.34 / _2.34 / -2.34 or -23.45 / 123.45 format +// Convert float to fixed-length string with 12.34 / _2.34 / -2.34 or -23.45 / 123.45 format const char* ftostr42_52(const_float_t f) { if (f <= -10 || f >= 100) return ftostr52(f); // -23.45 / 123.45 long i = INTFLOAT(f, 2); @@ -234,7 +228,7 @@ const char* ftostr42_52(const_float_t f) { return &conv[3]; } -// Convert signed float to fixed-length string with 023.45 / -23.45 format +// Convert float to fixed-length string with 023.45 / -23.45 format const char* ftostr52(const_float_t f) { long i = INTFLOAT(f, 2); conv[2] = MINUSOR(i, DIGIMOD(i, 10000)); @@ -246,7 +240,7 @@ const char* ftostr52(const_float_t f) { return &conv[2]; } -// Convert signed float to fixed-length string with 12.345 / _2.345 / -2.345 or -23.45 / 123.45 format +// Convert float to fixed-length string with 12.345 / _2.345 / -2.345 or -23.45 / 123.45 format const char* ftostr53_63(const_float_t f) { if (f <= -10 || f >= 100) return ftostr63(f); // -23.456 / 123.456 long i = INTFLOAT(f, 3); @@ -259,7 +253,7 @@ const char* ftostr53_63(const_float_t f) { return &conv[2]; } -// Convert signed float to fixed-length string with 023.456 / -23.456 format +// Convert float to fixed-length string with 023.456 / -23.456 format const char* ftostr63(const_float_t f) { long i = INTFLOAT(f, 3); conv[1] = MINUSOR(i, DIGIMOD(i, 100000)); @@ -289,42 +283,58 @@ const char* ftostr63(const_float_t f) { #endif -// Convert float to fixed-length string with +12.3 / -12.3 format -const char* ftostr31sign(const_float_t f) { - int i = INTFLOAT(f, 1); - conv[3] = MINUSOR(i, '+'); - conv[4] = DIGIMOD(i, 100); +// +// Convert float to fixed-length string with +/- and a single decimal place +// +inline const char* ftostrX1sign(const_float_t f, const int index) { + long i = INTFLOAT(f, 1); + conv[index] = MINUSOR(i, '+'); + switch (index + 1) { + case 1: conv[1] = DIGIMOD(i, 100000); + case 2: conv[2] = DIGIMOD(i, 10000); + case 3: conv[3] = DIGIMOD(i, 1000); + case 4: conv[4] = DIGIMOD(i, 100); + } conv[5] = DIGIMOD(i, 10); conv[6] = '.'; conv[7] = DIGIMOD(i, 1); - return &conv[3]; + return &conv[index]; } +// Convert float to fixed-length string with +12.3 / -12.3 format +const char* ftostr31sign(const_float_t f) { return ftostrX1sign(f, 3); } + // Convert float to fixed-length string with +123.4 / -123.4 format -const char* ftostr41sign(const_float_t f) { - int i = INTFLOAT(f, 1); - conv[2] = MINUSOR(i, '+'); - conv[3] = DIGIMOD(i, 1000); - conv[4] = DIGIMOD(i, 100); - conv[5] = DIGIMOD(i, 10); - conv[6] = '.'; - conv[7] = DIGIMOD(i, 1); - return &conv[2]; -} +const char* ftostr41sign(const_float_t f) { return ftostrX1sign(f, 2); } -// Convert signed float to string (6 digit) with -1.234 / _0.000 / +1.234 format -const char* ftostr43sign(const_float_t f, char plus/*=' '*/) { - long i = INTFLOAT(f, 3); - conv[2] = i ? MINUSOR(i, plus) : ' '; +// Convert float to fixed-length string with +1234.5 / +1234.5 format +const char* ftostr51sign(const_float_t f) { return ftostrX1sign(f, 1); } + +// +// Convert float to string with +/ /- and 3 decimal places +// +inline const char* ftostrX3sign(const_float_t f, const int index, char plus/*=' '*/) { + long i = INTFLOAT(f, 1); + conv[index] = i ? MINUSOR(i, plus) : ' '; + switch (index + 1) { + case 1: conv[1] = DIGIMOD(i, 100000); + case 2: conv[2] = DIGIMOD(i, 10000); + } conv[3] = DIGIMOD(i, 1000); conv[4] = '.'; conv[5] = DIGIMOD(i, 100); conv[6] = DIGIMOD(i, 10); conv[7] = DIGIMOD(i, 1); - return &conv[2]; + return &conv[index]; } -// Convert signed float to string (5 digit) with -1.2345 / _0.0000 / +1.2345 format +// Convert float to string (6 chars) with -1.234 / _0.000 / +1.234 format +const char* ftostr43sign(const_float_t f, char plus/*=' '*/) { return ftostrX3sign(f, 2, plus); } + +// Convert float to string (7 chars) with -12.345 / _00.000 / +12.345 format +const char* ftostr53sign(const_float_t f, char plus/*=' '*/) { return ftostrX3sign(f, 1, plus); } + +// Convert float to string (7 chars) with -1.2345 / _0.0000 / +1.2345 format const char* ftostr54sign(const_float_t f, char plus/*=' '*/) { long i = INTFLOAT(f, 4); conv[1] = i ? MINUSOR(i, plus) : ' '; @@ -343,19 +353,6 @@ const char* ftostr5rj(const_float_t f) { return ui16tostr5rj(i); } -// Convert signed float to string with +1234.5 format -const char* ftostr51sign(const_float_t f) { - long i = INTFLOAT(f, 1); - conv[1] = MINUSOR(i, '+'); - conv[2] = DIGIMOD(i, 10000); - conv[3] = DIGIMOD(i, 1000); - conv[4] = DIGIMOD(i, 100); - conv[5] = DIGIMOD(i, 10); - conv[6] = '.'; - conv[7] = DIGIMOD(i, 1); - return &conv[1]; -} - // Convert signed float to string with +123.45 format const char* ftostr52sign(const_float_t f) { long i = INTFLOAT(f, 2); @@ -369,47 +366,66 @@ const char* ftostr52sign(const_float_t f) { return &conv[1]; } -// Convert signed float to string with +12.345 format -const char* ftostr53sign(const_float_t f) { - long i = INTFLOAT(f, 3); - conv[1] = MINUSOR(i, '+'); - conv[2] = DIGIMOD(i, 10000); - conv[3] = DIGIMOD(i, 1000); - conv[4] = '.'; - conv[5] = DIGIMOD(i, 100); - conv[6] = DIGIMOD(i, 10); - conv[7] = DIGIMOD(i, 1); - return &conv[1]; -} - -// Convert unsigned float to string with ____5.6, ___45.6, __345.6, _2345.6, 12345.6 format -const char* ftostr61rj(const_float_t f) { +// Convert unsigned float to string with a single digit precision +inline const char* ftostrX1rj(const_float_t f, const int index=1) { const long i = UINTFLOAT(f, 1); - conv[1] = RJDIGIT(i, 100000); - conv[2] = RJDIGIT(i, 10000); - conv[3] = RJDIGIT(i, 1000); - conv[4] = RJDIGIT(i, 100); + switch (index) { + case 0: conv[0] = RJDIGIT(i, 1000000); + case 1: conv[1] = RJDIGIT(i, 100000); + case 2: conv[2] = RJDIGIT(i, 10000); + case 3: conv[3] = RJDIGIT(i, 1000); + case 4: conv[4] = RJDIGIT(i, 100); + } conv[5] = DIGIMOD(i, 10); conv[6] = '.'; conv[7] = DIGIMOD(i, 1); - return &conv[1]; + return &conv[index]; } -// Convert unsigned float to string with ____5.67, ___45.67, __345.67, _2345.67, 12345.67 format -const char* ftostr72rj(const_float_t f) { +// Convert unsigned float to string with _2.3 / 12.3 format +const char* ftostr31rj(const_float_t f) { return ftostrX1rj(f, 7 - 3); } + +// Convert unsigned float to string with __3.4 / _23.4 / 123.4 format +const char* ftostr41rj(const_float_t f) { return ftostrX1rj(f, 7 - 4); } + +// Convert unsigned float to string with ___4.5 / __34.5 / _234.5 / 1234.5 format +const char* ftostr51rj(const_float_t f) { return ftostrX1rj(f, 7 - 5); } + +// Convert unsigned float to string with ____5.6 / ___45.6 / __345.6 / _2345.6 / 12345.6 format +const char* ftostr61rj(const_float_t f) { return ftostrX1rj(f, 7 - 6); } + +// Convert unsigned float to string with two digit precision +inline const char* ftostrX2rj(const_float_t f, const int index=1) { const long i = UINTFLOAT(f, 2); - conv[0] = RJDIGIT(i, 1000000); - conv[1] = RJDIGIT(i, 100000); - conv[2] = RJDIGIT(i, 10000); - conv[3] = RJDIGIT(i, 1000); - conv[4] = DIGIMOD(i, 100); + switch (index) { + case 0: conv[0] = RJDIGIT(i, 1000000); + case 1: conv[1] = RJDIGIT(i, 100000); + case 2: conv[2] = RJDIGIT(i, 10000); + case 3: conv[3] = RJDIGIT(i, 1000); + case 4: conv[4] = RJDIGIT(i, 100); + } conv[5] = '.'; conv[6] = DIGIMOD(i, 10); conv[7] = DIGIMOD(i, 1); - return conv; + return &conv[index]; } -// Convert signed float to space-padded string with -_23.4_ format +// Convert unsigned float to string with 1.23 format +const char* ftostr32rj(const_float_t f) { return ftostrX2rj(f, 4); } + +// Convert unsigned float to string with _2.34, 12.34 format +const char* ftostr42rj(const_float_t f) { return ftostrX2rj(f, 3); } + +// Convert unsigned float to string with __3.45, _23.45, 123.45 format +const char* ftostr52rj(const_float_t f) { return ftostrX2rj(f, 2); } + +// Convert unsigned float to string with ___4.56, __34.56, _234.56, 1234.56 format +const char* ftostr62rj(const_float_t f) { return ftostrX2rj(f, 1); } + +// Convert unsigned float to string with ____5.67, ___45.67, __345.67, _2345.67, 12345.67 format +const char* ftostr72rj(const_float_t f) { return ftostrX2rj(f, 0); } + +// Convert float to space-padded string with -_23.4_ format const char* ftostr52sp(const_float_t f) { long i = INTFLOAT(f, 2); uint8_t dig; @@ -418,17 +434,17 @@ const char* ftostr52sp(const_float_t f) { conv[3] = RJDIGIT(i, 1000); conv[4] = DIGIMOD(i, 100); - if ((dig = i % 10)) { // second digit after decimal point? + if ((dig = i % 10)) { // Second digit after decimal point? conv[5] = '.'; conv[6] = DIGIMOD(i, 10); conv[7] = DIGIT(dig); } else { - if ((dig = (i / 10) % 10)) { // first digit after decimal point? + if ((dig = (i / 10) % 10)) { // First digit after decimal point? conv[5] = '.'; conv[6] = DIGIT(dig); } - else // nothing after decimal point + else // Nothing after decimal point conv[5] = conv[6] = ' '; conv[7] = ' '; } @@ -440,7 +456,7 @@ const char* utostr3(const uint16_t x) { return i16tostr3left(_MIN(x, 999U)); } -// Convert signed float to space-padded string with 1.23, 12.34, 123.45 format +// Convert float to space-padded string with 1.23, 12.34, 123.45 format const char* ftostr52sprj(const_float_t f) { long i = INTFLOAT(f, 2); LIMIT(i, -99999, 99999); // cap to -999.99 - 999.99 range diff --git a/Marlin/src/libs/numtostr.h b/Marlin/src/libs/numtostr.h index f8af09ebeeca..fde07e836846 100644 --- a/Marlin/src/libs/numtostr.h +++ b/Marlin/src/libs/numtostr.h @@ -40,7 +40,7 @@ const char* ui8tostr3rj(const uint8_t i); const char* i8tostr3rj(const int8_t x); #if HAS_PRINT_PROGRESS_PERMYRIAD - // Convert 16-bit unsigned permyriad value to percent: 100 / 23 / 23.4 / 3.45 + // Convert 16-bit unsigned permyriad value to percent: _100 / __23 / 23.4 / 3.45 const char* permyriadtostr4(const uint16_t xx); #endif @@ -86,22 +86,34 @@ const char* ftostr53_63(const_float_t x); // Convert signed float to fixed-length string with 023.456 / -23.456 format const char* ftostr63(const_float_t x); -// Convert float to fixed-length string with +12.3 / -12.3 format +// Convert signed float to fixed-length string with +12.3 / -12.3 format const char* ftostr31sign(const_float_t x); -// Convert float to fixed-length string with +123.4 / -123.4 format +// Convert signed float to fixed-length string with +123.4 / -123.4 format const char* ftostr41sign(const_float_t x); +// Convert signed float to fixed-length string with +1234.5 / +1234.5 format +const char* ftostr51sign(const_float_t x); + // Convert signed float to string (6 digit) with -1.234 / _0.000 / +1.234 format const char* ftostr43sign(const_float_t x, char plus=' '); +// Convert signed float to string (7 chars) with -12.345 / _00.000 / +12.345 format +const char* ftostr53sign(const_float_t x, char plus=' '); + // Convert signed float to string (5 digit) with -1.2345 / _0.0000 / +1.2345 format const char* ftostr54sign(const_float_t x, char plus=' '); // Convert unsigned float to rj string with 12345 format const char* ftostr5rj(const_float_t x); -// Convert signed float to string with +1234.5 format +// Convert signed float to fixed-length string with +12.3 / -12.3 format +const char* ftostr31sign(const_float_t x); + +// Convert signed float to fixed-length string with +123.4 / -123.4 format +const char* ftostr41sign(const_float_t x); + +// Convert signed float to fixed-length string with +1234.5 format const char* ftostr51sign(const_float_t x); // Convert signed float to space-padded string with -_23.4_ format @@ -110,23 +122,41 @@ const char* ftostr52sp(const_float_t x); // Convert signed float to string with +123.45 format const char* ftostr52sign(const_float_t x); -// Convert signed float to string with +12.345 format -const char* ftostr53sign(const_float_t f); +// Convert unsigned float to string with _2.3 / 12.3 format +const char* ftostr31rj(const_float_t x); -// Convert unsigned float to string with 12345.6 format omitting trailing zeros +// Convert unsigned float to string with __3.4 / _23.4 / 123.4 format +const char* ftostr41rj(const_float_t x); + +// Convert unsigned float to string with ___4.5 / __34.5 / _234.5 / 1234.5 format +const char* ftostr51rj(const_float_t x); + +// Convert unsigned float to string with ____5.6 / ___45.6 / __345.6 / _2345.6 / 12345.6 format const char* ftostr61rj(const_float_t x); -// Convert unsigned float to string with 12345.67 format omitting trailing zeros +// Convert unsigned float to string with 1.23 format +const char* ftostr32rj(const_float_t f); + +// Convert unsigned float to string with _2.34, 12.34 format +const char* ftostr42rj(const_float_t f); + +// Convert unsigned float to string with __3.45, _23.45, 123.45 format +const char* ftostr52rj(const_float_t f); + +// Convert unsigned float to string with ___4.56, __34.56, _234.56, 1234.56 format +const char* ftostr62rj(const_float_t f); + +// Convert unsigned float to string with ____5.67, ___45.67, __345.67, _2345.67, 12345.67 format const char* ftostr72rj(const_float_t x); -// Convert float to rj string with 123 or -12 format +// Convert signed float to rj string with 123 or -12 format FORCE_INLINE const char* ftostr3rj(const_float_t x) { return i16tostr3rj(int16_t(x + (x < 0 ? -0.5f : 0.5f))); } #if ENABLED(LCD_DECIMAL_SMALL_XY) - // Convert float to rj string with 1234, _123, 12.3, _1.2, -123, _-12, or -1.2 format + // Convert signed float to rj string with 1234, _123, 12.3, _1.2, -123, _-12, or -1.2 format const char* ftostr4sign(const_float_t fx); #else - // Convert float to rj string with 1234, _123, -123, __12, _-12, ___1, or __-1 format + // Convert signed float to rj string with 1234, _123, -123, __12, _-12, ___1, or __-1 format FORCE_INLINE const char* ftostr4sign(const_float_t x) { return i16tostr4signrj(int16_t(x + (x < 0 ? -0.5f : 0.5f))); } #endif From f265fb59436e91369461efd8b5a6bf92aa0b3a96 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sat, 2 Dec 2023 00:20:23 +0000 Subject: [PATCH 46/77] [cron] Bump distribution date (2023-12-02) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 96bcec0bbc7c..9a6ae222137d 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2023-12-01" +//#define STRING_DISTRIBUTION_DATE "2023-12-02" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index a91f9c1e9448..2d0e81227797 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2023-12-01" + #define STRING_DISTRIBUTION_DATE "2023-12-02" #endif /** From c484228c56f031b2bf44ea2194b0a84b47e2ae98 Mon Sep 17 00:00:00 2001 From: Andrew <18502096+classicrocker883@users.noreply.github.com> Date: Fri, 1 Dec 2023 22:18:24 -0500 Subject: [PATCH 47/77] =?UTF-8?q?=E2=9C=85=20Fix=20some=20action=20labels?= =?UTF-8?q?=20(#26490)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: thisiskeithb <13375512+thisiskeithb@users.noreply.github.com> Co-authored-by: Scott Lahteine --- .github/ISSUE_TEMPLATE/bug_report.yml | 2 +- .github/ISSUE_TEMPLATE/feature_request.yml | 2 +- .github/workflows/auto-label.yml | 2 ++ 3 files changed, 4 insertions(+), 2 deletions(-) diff --git a/.github/ISSUE_TEMPLATE/bug_report.yml b/.github/ISSUE_TEMPLATE/bug_report.yml index 56060f0a4801..e0ee13af0778 100644 --- a/.github/ISSUE_TEMPLATE/bug_report.yml +++ b/.github/ISSUE_TEMPLATE/bug_report.yml @@ -1,7 +1,7 @@ name: 🪲 Report a bug description: Create a bug report to help improve Marlin Firmware title: "[BUG] (bug summary)" -labels: 'Bug: Potential ?' +labels: ["Bug: Potential ?"] body: - type: markdown attributes: diff --git a/.github/ISSUE_TEMPLATE/feature_request.yml b/.github/ISSUE_TEMPLATE/feature_request.yml index b64383cd48b2..2e8607142ca8 100644 --- a/.github/ISSUE_TEMPLATE/feature_request.yml +++ b/.github/ISSUE_TEMPLATE/feature_request.yml @@ -1,7 +1,7 @@ name: ✨ Request a feature description: Request a new Marlin Firmware feature title: "[FR] (feature summary)" -labels: 'T: Feature Request' +labels: ["T: Feature Request"] body: - type: markdown attributes: diff --git a/.github/workflows/auto-label.yml b/.github/workflows/auto-label.yml index f3a752da3d45..2ed486bb8c9c 100644 --- a/.github/workflows/auto-label.yml +++ b/.github/workflows/auto-label.yml @@ -4,6 +4,8 @@ # - Apply the label "Bug: Potential ?" to these issues. # +name: Label Old Bugs + on: schedule: - cron: "30 8 * * *" From bd6eb832500478c9e3be55f1126d0139aa013bb0 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 1 Dec 2023 09:19:13 -0600 Subject: [PATCH 48/77] =?UTF-8?q?=F0=9F=A9=B9=20Fix=20some=20minor=20issue?= =?UTF-8?q?s?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/ESP32/HAL.cpp | 2 +- Marlin/src/HAL/SAMD51/HAL.cpp | 59 +++++++++---------- Marlin/src/HAL/STM32F1/HAL.cpp | 4 +- Marlin/src/HAL/STM32F1/HAL.h | 2 - Marlin/src/HAL/STM32F1/onboard_sd.cpp | 3 - Marlin/src/inc/Conditionals_adv.h | 2 +- Marlin/src/inc/Warnings.cpp | 2 +- Marlin/src/lcd/e3v2/common/encoder.h | 2 +- Marlin/src/lcd/e3v2/proui/dwin_lcd.cpp | 2 +- .../dgus_reloaded/dgus_reloaded_extui.cpp | 2 +- Marlin/src/lcd/menu/menu_bed_leveling.cpp | 2 +- Marlin/src/pins/stm32f1/pins_CREALITY_V521.h | 2 +- Marlin/src/pins/stm32f4/pins_TRONXY_V10.h | 2 +- .../sublime/MarlinFirmware.sublime-project | 3 +- ini/stm32f1-maple.ini | 2 - 15 files changed, 42 insertions(+), 49 deletions(-) diff --git a/Marlin/src/HAL/ESP32/HAL.cpp b/Marlin/src/HAL/ESP32/HAL.cpp index 27f6516f9ae8..4890972b0193 100644 --- a/Marlin/src/HAL/ESP32/HAL.cpp +++ b/Marlin/src/HAL/ESP32/HAL.cpp @@ -175,7 +175,7 @@ uint8_t MarlinHAL::get_reset_source() { return rtc_get_reset_reason(1); } void MarlinHAL::reboot() { ESP.restart(); } -void _delay_ms(int delay_ms) { delay(delay_ms); } +void _delay_ms(const int ms) { delay(ms); } // return free memory between end of heap (or end bss) and whatever is current int MarlinHAL::freeMemory() { return ESP.getFreeHeap(); } diff --git a/Marlin/src/HAL/SAMD51/HAL.cpp b/Marlin/src/HAL/SAMD51/HAL.cpp index beace8126cbf..a3c871ce516a 100644 --- a/Marlin/src/HAL/SAMD51/HAL.cpp +++ b/Marlin/src/HAL/SAMD51/HAL.cpp @@ -47,27 +47,27 @@ #endif #endif -#define GET_TEMP_0_ADC() TERN(HAS_TEMP_ADC_0, PIN_TO_ADC(TEMP_0_PIN), -1) -#define GET_TEMP_1_ADC() TERN(HAS_TEMP_ADC_1, PIN_TO_ADC(TEMP_1_PIN), -1) -#define GET_TEMP_2_ADC() TERN(HAS_TEMP_ADC_2, PIN_TO_ADC(TEMP_2_PIN), -1) -#define GET_TEMP_3_ADC() TERN(HAS_TEMP_ADC_3, PIN_TO_ADC(TEMP_3_PIN), -1) -#define GET_TEMP_4_ADC() TERN(HAS_TEMP_ADC_4, PIN_TO_ADC(TEMP_4_PIN), -1) -#define GET_TEMP_5_ADC() TERN(HAS_TEMP_ADC_5, PIN_TO_ADC(TEMP_5_PIN), -1) -#define GET_TEMP_6_ADC() TERN(HAS_TEMP_ADC_6, PIN_TO_ADC(TEMP_6_PIN), -1) -#define GET_TEMP_7_ADC() TERN(HAS_TEMP_ADC_7, PIN_TO_ADC(TEMP_7_PIN), -1) -#define GET_BED_ADC() TERN(HAS_TEMP_ADC_BED, PIN_TO_ADC(TEMP_BED_PIN), -1) -#define GET_CHAMBER_ADC() TERN(HAS_TEMP_ADC_CHAMBER, PIN_TO_ADC(TEMP_CHAMBER_PIN), -1) -#define GET_PROBE_ADC() TERN(HAS_TEMP_ADC_PROBE, PIN_TO_ADC(TEMP_PROBE_PIN), -1) -#define GET_COOLER_ADC() TERN(HAS_TEMP_ADC_COOLER, PIN_TO_ADC(TEMP_COOLER_PIN), -1) -#define GET_BOARD_ADC() TERN(HAS_TEMP_ADC_BOARD, PIN_TO_ADC(TEMP_BOARD_PIN), -1) -#define GET_SOC_ADC() TERN(HAS_TEMP_ADC_SOC, PIN_TO_ADC(TEMP_SOC_PIN), -1) -#define GET_FILAMENT_WIDTH_ADC() TERN(FILAMENT_WIDTH_SENSOR, PIN_TO_ADC(FILWIDTH_PIN), -1) -#define GET_BUTTONS_ADC() TERN(HAS_ADC_BUTTONS, PIN_TO_ADC(ADC_KEYPAD_PIN), -1) -#define GET_JOY_ADC_X() TERN(HAS_JOY_ADC_X, PIN_TO_ADC(JOY_X_PIN), -1) -#define GET_JOY_ADC_Y() TERN(HAS_JOY_ADC_Y, PIN_TO_ADC(JOY_Y_PIN), -1) -#define GET_JOY_ADC_Z() TERN(HAS_JOY_ADC_Z, PIN_TO_ADC(JOY_Z_PIN), -1) -#define GET_POWERMON_ADC_CURRENT() TERN(POWER_MONITOR_CURRENT, PIN_TO_ADC(POWER_MONITOR_CURRENT_PIN), -1) -#define GET_POWERMON_ADC_VOLTS() TERN(POWER_MONITOR_VOLTAGE, PIN_TO_ADC(POWER_MONITOR_VOLTAGE_PIN), -1) +#define GET_TEMP_0_ADC() TERN(HAS_TEMP_ADC_0, PIN_TO_ADC(TEMP_0_PIN), -1) +#define GET_TEMP_1_ADC() TERN(HAS_TEMP_ADC_1, PIN_TO_ADC(TEMP_1_PIN), -1) +#define GET_TEMP_2_ADC() TERN(HAS_TEMP_ADC_2, PIN_TO_ADC(TEMP_2_PIN), -1) +#define GET_TEMP_3_ADC() TERN(HAS_TEMP_ADC_3, PIN_TO_ADC(TEMP_3_PIN), -1) +#define GET_TEMP_4_ADC() TERN(HAS_TEMP_ADC_4, PIN_TO_ADC(TEMP_4_PIN), -1) +#define GET_TEMP_5_ADC() TERN(HAS_TEMP_ADC_5, PIN_TO_ADC(TEMP_5_PIN), -1) +#define GET_TEMP_6_ADC() TERN(HAS_TEMP_ADC_6, PIN_TO_ADC(TEMP_6_PIN), -1) +#define GET_TEMP_7_ADC() TERN(HAS_TEMP_ADC_7, PIN_TO_ADC(TEMP_7_PIN), -1) +#define GET_BED_ADC() TERN(HAS_TEMP_ADC_BED, PIN_TO_ADC(TEMP_BED_PIN), -1) +#define GET_CHAMBER_ADC() TERN(HAS_TEMP_ADC_CHAMBER, PIN_TO_ADC(TEMP_CHAMBER_PIN), -1) +#define GET_PROBE_ADC() TERN(HAS_TEMP_ADC_PROBE, PIN_TO_ADC(TEMP_PROBE_PIN), -1) +#define GET_COOLER_ADC() TERN(HAS_TEMP_ADC_COOLER, PIN_TO_ADC(TEMP_COOLER_PIN), -1) +#define GET_BOARD_ADC() TERN(HAS_TEMP_ADC_BOARD, PIN_TO_ADC(TEMP_BOARD_PIN), -1) +#define GET_SOC_ADC() TERN(HAS_TEMP_ADC_BOARD, PIN_TO_ADC(TEMP_BOARD_PIN), -1) +#define GET_FILAMENT_WIDTH_ADC() TERN(FILAMENT_WIDTH_SENSOR, PIN_TO_ADC(FILWIDTH_PIN), -1) +#define GET_BUTTONS_ADC() TERN(HAS_ADC_BUTTONS, PIN_TO_ADC(ADC_KEYPAD_PIN), -1) +#define GET_JOY_ADC_X() TERN(HAS_JOY_ADC_X, PIN_TO_ADC(JOY_X_PIN), -1) +#define GET_JOY_ADC_Y() TERN(HAS_JOY_ADC_Y, PIN_TO_ADC(JOY_Y_PIN), -1) +#define GET_JOY_ADC_Z() TERN(HAS_JOY_ADC_Z, PIN_TO_ADC(JOY_Z_PIN), -1) +#define GET_POWERMON_ADC_CURRENT() TERN(POWER_MONITOR_CURRENT, PIN_TO_ADC(POWER_MONITOR_CURRENT_PIN), -1) +#define GET_POWERMON_ADC_VOLTS() TERN(POWER_MONITOR_VOLTAGE, PIN_TO_ADC(POWER_MONITOR_VOLTAGE_PIN), -1) #define IS_ADC_REQUIRED(n) ( \ GET_TEMP_0_ADC() == n || GET_TEMP_1_ADC() == n || GET_TEMP_2_ADC() == n || GET_TEMP_3_ADC() == n \ @@ -162,10 +162,10 @@ enum ADCIndex { POWERMON_CURRENT, #endif #if GET_POWERMON_ADC_VOLTS() == 0 - POWERMON_VOLTS, + POWERMON_VOLTAGE, #endif - // Use later indexes for ADC index 1 + // Indexes for ADC1 after those for ADC0 #if GET_TEMP_0_ADC() == 1 TEMP_0, @@ -228,9 +228,8 @@ enum ADCIndex { POWERMON_CURRENT, #endif #if GET_POWERMON_ADC_VOLTS() == 1 - POWERMON_VOLTS, + POWERMON_VOLTAGE, #endif - ADC_COUNT }; @@ -351,10 +350,10 @@ enum ADCIndex { POWER_MONITOR_CURRENT_PIN, #endif #if GET_POWERMON_ADC_VOLTS() == 0 - POWER_MONITOR_VOLTS_PIN, + POWER_MONITOR_VOLTAGE_PIN, #endif - // ADC1 pins + // Pins for ADC1 after ADC0 #if GET_TEMP_0_ADC() == 1 TEMP_0_PIN, @@ -417,7 +416,7 @@ enum ADCIndex { POWER_MONITOR_CURRENT_PIN, #endif #if GET_POWERMON_ADC_VOLTS() == 1 - POWER_MONITOR_VOLTS_PIN, + POWER_MONITOR_VOLTAGE_PIN, #endif }; @@ -488,7 +487,7 @@ enum ADCIndex { { PIN_TO_INPUTCTRL(POWER_MONITOR_CURRENT_PIN) }, #endif #if GET_POWERMON_ADC_VOLTS() == 0 - { PIN_TO_INPUTCTRL(POWER_MONITOR_VOLTS_PIN) }, + { PIN_TO_INPUTCTRL(POWER_MONITOR_VOLTAGE_PIN) }, #endif }; @@ -560,7 +559,7 @@ enum ADCIndex { { PIN_TO_INPUTCTRL(POWER_MONITOR_CURRENT_PIN) }, #endif #if GET_POWERMON_ADC_VOLTS() == 1 - { PIN_TO_INPUTCTRL(POWER_MONITOR_VOLTS_PIN) }, + { PIN_TO_INPUTCTRL(POWER_MONITOR_VOLTAGE_PIN) }, #endif }; diff --git a/Marlin/src/HAL/STM32F1/HAL.cpp b/Marlin/src/HAL/STM32F1/HAL.cpp index a83c3a23bf7d..376778a2b3b2 100644 --- a/Marlin/src/HAL/STM32F1/HAL.cpp +++ b/Marlin/src/HAL/STM32F1/HAL.cpp @@ -313,7 +313,7 @@ enum ADCIndex : uint8_t { OPTITEM(HAS_JOY_ADC_Y, JOY_Y) OPTITEM(HAS_JOY_ADC_Z, JOY_Z) OPTITEM(POWER_MONITOR_CURRENT, POWERMON_CURRENT) - OPTITEM(POWER_MONITOR_VOLTAGE, POWERMON_VOLTS) + OPTITEM(POWER_MONITOR_VOLTAGE, POWERMON_VOLTAGE) ADC_COUNT }; @@ -381,7 +381,7 @@ void MarlinHAL::adc_start(const pin_t pin) { _TCASE(FILAMENT_WIDTH_SENSOR, FILWIDTH_PIN, FILWIDTH) _TCASE(HAS_ADC_BUTTONS, ADC_KEYPAD_PIN, ADC_KEY) _TCASE(POWER_MONITOR_CURRENT, POWER_MONITOR_CURRENT_PIN, POWERMON_CURRENT) - _TCASE(POWER_MONITOR_VOLTAGE, POWER_MONITOR_VOLTAGE_PIN, POWERMON_VOLTS) + _TCASE(POWER_MONITOR_VOLTAGE, POWER_MONITOR_VOLTAGE_PIN, POWERMON_VOLTAGE) } adc_result = (adc_results[(int)pin_index] & 0xFFF) >> (12 - HAL_ADC_RESOLUTION); // shift out unused bits } diff --git a/Marlin/src/HAL/STM32F1/HAL.h b/Marlin/src/HAL/STM32F1/HAL.h index c4b90db68a19..52d3b805e611 100644 --- a/Marlin/src/HAL/STM32F1/HAL.h +++ b/Marlin/src/HAL/STM32F1/HAL.h @@ -221,8 +221,6 @@ void flashFirmware(const int16_t); // Memory related #define __bss_end __bss_end__ -void _delay_ms(const int ms); - extern "C" char* _sbrk(int incr); #pragma GCC diagnostic push diff --git a/Marlin/src/HAL/STM32F1/onboard_sd.cpp b/Marlin/src/HAL/STM32F1/onboard_sd.cpp index df5549217d98..a3d8dcb2d57e 100644 --- a/Marlin/src/HAL/STM32F1/onboard_sd.cpp +++ b/Marlin/src/HAL/STM32F1/onboard_sd.cpp @@ -5,9 +5,6 @@ * Copyright (c) 2019 BigTreeTech [https://github.com/bigtreetech] * Copyright (C) 2015, ChaN, all right reserved. * - * Based on Sprinter and grbl. - * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * * This software is a free software and there is NO WARRANTY. * No restriction on use. You can use, modify and redistribute it for * personal, non-profit or commercial products UNDER YOUR RESPONSIBILITY. diff --git a/Marlin/src/inc/Conditionals_adv.h b/Marlin/src/inc/Conditionals_adv.h index 634652c9bf99..44a87dbb1a0d 100644 --- a/Marlin/src/inc/Conditionals_adv.h +++ b/Marlin/src/inc/Conditionals_adv.h @@ -1256,7 +1256,7 @@ * currently HAL.h must be included ahead of pins.h. */ #if LCD_IS_SERIAL_HOST && !defined(LCD_SERIAL_PORT) - #if MB(BTT_SKR_MINI_E3_V1_0, BTT_SKR_MINI_E3_V1_2, BTT_SKR_MINI_E3_V2_0, BTT_SKR_MINI_E3_V3_0, BTT_SKR_E3_TURBO, BTT_OCTOPUS_V1_1, AQUILA_V101) + #if MB(BTT_SKR_MINI_E3_V1_0, BTT_SKR_MINI_E3_V1_2, BTT_SKR_MINI_E3_V2_0, BTT_SKR_MINI_E3_V3_0, BTT_SKR_MINI_E3_V3_0_1, BTT_SKR_E3_TURBO, BTT_OCTOPUS_V1_1, AQUILA_V101) #define LCD_SERIAL_PORT 1 #elif MB(CREALITY_V24S1_301, CREALITY_V24S1_301F4, CREALITY_F401RE, CREALITY_V423, MKS_ROBIN, PANOWIN_CUTLASS, KODAMA_BARDO) #define LCD_SERIAL_PORT 2 diff --git a/Marlin/src/inc/Warnings.cpp b/Marlin/src/inc/Warnings.cpp index 26ecfbf533a5..606d308c08cf 100644 --- a/Marlin/src/inc/Warnings.cpp +++ b/Marlin/src/inc/Warnings.cpp @@ -707,7 +707,7 @@ /** * Maple environment */ -#ifdef __STM32F1__ +#if defined(__STM32F1__) && DISABLED(NO_MAPLE_WARNING) #warning "Maple build environments are deprecated. Please use a non-Maple build environment. Report issues to the Marlin Firmware project." #endif diff --git a/Marlin/src/lcd/e3v2/common/encoder.h b/Marlin/src/lcd/e3v2/common/encoder.h index 72d37108dcf2..ce431c9811b1 100644 --- a/Marlin/src/lcd/e3v2/common/encoder.h +++ b/Marlin/src/lcd/e3v2/common/encoder.h @@ -45,7 +45,7 @@ typedef enum { ENCODER_DIFF_ENTER = 3 // click } EncoderState; -#define ENCODER_WAIT_MS 20 +#define ENCODER_WAIT_MS TERN(DWIN_LCD_PROUI, 10, 20) // Encoder initialization void encoderConfiguration(); diff --git a/Marlin/src/lcd/e3v2/proui/dwin_lcd.cpp b/Marlin/src/lcd/e3v2/proui/dwin_lcd.cpp index 853da8532e12..7c71b8fc5974 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin_lcd.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin_lcd.cpp @@ -127,7 +127,7 @@ void dwinWriteToMem(uint8_t mem, uint16_t addr, uint16_t length, uint8_t *data) dwinWord(i, addr + indx); // start address of the data block ++i; for (uint8_t j = 0; j < i; ++j) { LCD_SERIAL.write(dwinSendBuf[j]); delayMicroseconds(1); } // Buf header - for (uint16_t j = indx; j <= indx + to_send - 1; j++) LCD_SERIAL.write(*(data + j)); delayMicroseconds(1); // write block of data + for (uint16_t j = indx; j <= indx + to_send - 1; j++) { LCD_SERIAL.write(*(data + j)); delayMicroseconds(1); } // write block of data for (uint8_t j = 0; j < 4; ++j) { LCD_SERIAL.write(dwinBufTail[j]); delayMicroseconds(1); } block++; pending -= to_send; diff --git a/Marlin/src/lcd/extui/dgus_reloaded/dgus_reloaded_extui.cpp b/Marlin/src/lcd/extui/dgus_reloaded/dgus_reloaded_extui.cpp index 3434bdf8c366..68e405776e9d 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/dgus_reloaded_extui.cpp +++ b/Marlin/src/lcd/extui/dgus_reloaded/dgus_reloaded_extui.cpp @@ -21,7 +21,7 @@ */ /** - * lcd/extui/dgus_e3s1pro/dgus_e3s1pro_extui.cpp + * lcd/extui/dgus_reloaded/dgus_reloaded_extui.cpp */ #include "../../../inc/MarlinConfigPre.h" diff --git a/Marlin/src/lcd/menu/menu_bed_leveling.cpp b/Marlin/src/lcd/menu/menu_bed_leveling.cpp index f4d5a269af69..9fb9813ee504 100644 --- a/Marlin/src/lcd/menu/menu_bed_leveling.cpp +++ b/Marlin/src/lcd/menu/menu_bed_leveling.cpp @@ -138,7 +138,7 @@ // void _lcd_level_bed_moving() { if (ui.should_draw()) { - MString<9> msg; + MString<10> msg; msg.setf(F(" %i / %u"), int(manual_probe_index + 1), total_probe_points); MenuItem_static::draw(LCD_HEIGHT / 2, GET_TEXT_F(MSG_LEVEL_BED_NEXT_POINT), SS_CENTER, msg); } diff --git a/Marlin/src/pins/stm32f1/pins_CREALITY_V521.h b/Marlin/src/pins/stm32f1/pins_CREALITY_V521.h index d555c0aaa12d..2660b6e50518 100644 --- a/Marlin/src/pins/stm32f1/pins_CREALITY_V521.h +++ b/Marlin/src/pins/stm32f1/pins_CREALITY_V521.h @@ -135,7 +135,7 @@ #define FAN0_PIN PB14 // FAN #define FAN1_PIN PB12 // FAN -#define FAN_SOFT_PWM +#define FAN_SOFT_PWM_REQUIRED // // SD Card diff --git a/Marlin/src/pins/stm32f4/pins_TRONXY_V10.h b/Marlin/src/pins/stm32f4/pins_TRONXY_V10.h index e9e069583afe..97580bf618f9 100644 --- a/Marlin/src/pins/stm32f4/pins_TRONXY_V10.h +++ b/Marlin/src/pins/stm32f4/pins_TRONXY_V10.h @@ -157,7 +157,7 @@ #define FAN2_PIN PG9 // FAN2 #define FAN3_PIN PF10 // FAN3 #define CONTROLLER_FAN_PIN PD7 // BOARD FAN -#define FAN_SOFT_PWM +#define FAN_SOFT_PWM_REQUIRED // // Laser / Spindle diff --git a/buildroot/share/sublime/MarlinFirmware.sublime-project b/buildroot/share/sublime/MarlinFirmware.sublime-project index 11808dd45df0..62607ac0c6d1 100644 --- a/buildroot/share/sublime/MarlinFirmware.sublime-project +++ b/buildroot/share/sublime/MarlinFirmware.sublime-project @@ -30,6 +30,7 @@ "ensure_newline_at_eof_on_save": true, "tab_size": 2, "translate_tabs_to_spaces": true, - "trim_trailing_white_space_on_save": true + "trim_trailing_white_space_on_save": true, + "uncrustify_config" : "${project_dir}/../extras/uncrustify.cfg" } } diff --git a/ini/stm32f1-maple.ini b/ini/stm32f1-maple.ini index 34025a8a38b2..4c4d938fe6df 100644 --- a/ini/stm32f1-maple.ini +++ b/ini/stm32f1-maple.ini @@ -399,8 +399,6 @@ build_flags = ${STM32F1_maple.build_flags} -DTEMP_TIMER_CHAN=4 board_build.address = 0x08007000 board_build.ldscript = sovol.ld board_build.rename = firmware-{date}-{time}.bin -extra_scripts = ${STM32F1_maple.extra_scripts} - buildroot/share/PlatformIO/scripts/custom_board.py debug_tool = jlink upload_protocol = jlink From e695c473afb0a1546951d5759e50d03a595b99a1 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sun, 3 Dec 2023 00:23:05 +0000 Subject: [PATCH 49/77] [cron] Bump distribution date (2023-12-03) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 9a6ae222137d..d39b2ec0acbf 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2023-12-02" +//#define STRING_DISTRIBUTION_DATE "2023-12-03" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 2d0e81227797..8f29b3772622 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2023-12-02" + #define STRING_DISTRIBUTION_DATE "2023-12-03" #endif /** From 1a42c38e0eefdf62976bf7a5a35224d3c675f9ff Mon Sep 17 00:00:00 2001 From: Keith Bennett <13375512+thisiskeithb@users.noreply.github.com> Date: Sat, 2 Dec 2023 22:03:46 -0800 Subject: [PATCH 50/77] =?UTF-8?q?=F0=9F=A9=B9=20Replace=20more=20DEBUG=5FE?= =?UTF-8?q?CHOF=20(#26495)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Followup to #25928 --- Marlin/src/gcode/calibrate/G28.cpp | 2 +- Marlin/src/module/endstops.cpp | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/gcode/calibrate/G28.cpp b/Marlin/src/gcode/calibrate/G28.cpp index ba16c7bbd7e2..dbdbdc5affee 100644 --- a/Marlin/src/gcode/calibrate/G28.cpp +++ b/Marlin/src/gcode/calibrate/G28.cpp @@ -263,7 +263,7 @@ void GcodeSuite::G28() { #if ENABLED(DEBUG_LEVELING_FEATURE) auto debug_current = [](FSTR_P const s, const int16_t a, const int16_t b) { - if (DEBUGGING(LEVELING)) { DEBUG_ECHOF(s); DEBUG_ECHOLNPGM(" current: ", a, " -> ", b); } + if (DEBUGGING(LEVELING)) { DEBUG_ECHOLN(s, F(" current: "), a, F(" -> "), b); } }; #else #define debug_current(...) diff --git a/Marlin/src/module/endstops.cpp b/Marlin/src/module/endstops.cpp index 0f060f572048..9c6a3c011cca 100644 --- a/Marlin/src/module/endstops.cpp +++ b/Marlin/src/module/endstops.cpp @@ -1360,7 +1360,7 @@ void Endstops::update() { #if ENABLED(DEBUG_LEVELING_FEATURE) auto debug_current = [](FSTR_P const s, const int16_t a, const int16_t b) { - if (DEBUGGING(LEVELING)) { DEBUG_ECHOF(s); DEBUG_ECHOLNPGM(" current: ", a, " -> ", b); } + if (DEBUGGING(LEVELING)) { DEBUG_ECHOLN(s, F(" current: "), a, F(" -> "), b); } }; #else #define debug_current(...) From dde878db049357199bd14be1b36564b80244ca8b Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 3 Dec 2023 00:32:28 -0600 Subject: [PATCH 51/77] =?UTF-8?q?=E2=9C=85=20Use=20actions/github-script@v?= =?UTF-8?q?7?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .github/workflows/auto-label.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/auto-label.yml b/.github/workflows/auto-label.yml index 2ed486bb8c9c..c3cbb3b21028 100644 --- a/.github/workflows/auto-label.yml +++ b/.github/workflows/auto-label.yml @@ -17,7 +17,7 @@ jobs: runs-on: ubuntu-latest steps: - name: Auto Label for [BUG] - uses: actions/github-script@v5 + uses: actions/github-script@v7 with: script: | # Get all open issues in this repository From 1c1c4739105790c31424810aedfca8c526bcce12 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 3 Dec 2023 01:22:14 -0600 Subject: [PATCH 52/77] =?UTF-8?q?=E2=9C=85=20Fix=20auto-label=20action=20c?= =?UTF-8?q?omments?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .github/workflows/auto-label.yml | 9 +++------ 1 file changed, 3 insertions(+), 6 deletions(-) diff --git a/.github/workflows/auto-label.yml b/.github/workflows/auto-label.yml index c3cbb3b21028..c69e6c4fade9 100644 --- a/.github/workflows/auto-label.yml +++ b/.github/workflows/auto-label.yml @@ -20,21 +20,18 @@ jobs: uses: actions/github-script@v7 with: script: | - # Get all open issues in this repository + // Get all open issues in this repository const issueList = await github.rest.issues.listForRepo({ owner: context.repo.owner, repo: context.repo.repo, state: 'open' }); - # Filter the list of issues to only those that don't have any labels - # and have a title that contains '[BUG]'. Only the first 50 issues. + // Filter issues without labels that have a title containing '[BUG]'. const matchingIssues = issueList.data.filter( issue => issue.title.includes('[BUG]') && issue.labels.length === 0 ); - # Process the first 50 + // Process the first 50 for (const issue of matchingIssues.slice(0, 50)) { - // Run the desired action on the issue - // For example, to add a label: await github.rest.issues.addLabels({ owner: context.repo.owner, repo: context.repo.repo, From 0d4f41fb6dfd1a4f5efde4bb2d5a66b3543462de Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Mon, 4 Dec 2023 00:22:06 +0000 Subject: [PATCH 53/77] [cron] Bump distribution date (2023-12-04) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index d39b2ec0acbf..67d8329c38a3 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2023-12-03" +//#define STRING_DISTRIBUTION_DATE "2023-12-04" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 8f29b3772622..00848ef9e115 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2023-12-03" + #define STRING_DISTRIBUTION_DATE "2023-12-04" #endif /** From d5d45e85e4b88e531e4c519f8c40281ea2826364 Mon Sep 17 00:00:00 2001 From: David Buezas Date: Tue, 5 Dec 2023 04:31:34 +0100 Subject: [PATCH 54/77] =?UTF-8?q?=E2=9C=A8=20DOUBLE=5FLCD=5FFRAMERATE=20(#?= =?UTF-8?q?26500)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration_adv.h | 4 ++++ Marlin/src/core/macros.h | 6 +++++- Marlin/src/lcd/marlinui.h | 2 +- 3 files changed, 10 insertions(+), 2 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index b72f7d8da11b..5871c99a215f 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1579,6 +1579,10 @@ //#define SOUND_MENU_ITEM // Add a mute option to the LCD menu #define SOUND_ON_DEFAULT // Buzzer/speaker default enabled state + #if HAS_WIRED_LCD + //#define DOUBLE_LCD_FRAMERATE // Not recommended for slow boards. + #endif + // The timeout to return to the status screen from sub-menus //#define LCD_TIMEOUT_TO_STATUS 15000 // (ms) diff --git a/Marlin/src/core/macros.h b/Marlin/src/core/macros.h index bc0df357ca22..beb6bfe3e9a5 100644 --- a/Marlin/src/core/macros.h +++ b/Marlin/src/core/macros.h @@ -218,12 +218,16 @@ #define _OPTCODE(A) A; #define OPTCODE(O,A) TERN_(O,DEFER4(_OPTCODE)(A)) -// Macros to avoid 'f + 0.0' which is not always optimized away. Minus included for symmetry. +// Macros to avoid operations that aren't always optimized away (e.g., 'f + 0.0' and 'f * 1.0'). // Compiler flags -fno-signed-zeros -ffinite-math-only also cover 'f * 1.0', 'f - f', etc. #define PLUS_TERN0(O,A) _TERN(_ENA_1(O),,+ (A)) // OPTION ? '+ (A)' : '' #define MINUS_TERN0(O,A) _TERN(_ENA_1(O),,- (A)) // OPTION ? '- (A)' : '' +#define MUL_TERN1(O,A) _TERN(_ENA_1(O),,* (A)) // OPTION ? '* (A)' : '' +#define DIV_TERN1(O,A) _TERN(_ENA_1(O),,/ (A)) // OPTION ? '/ (A)' : '' #define SUM_TERN(O,B,A) ((B) PLUS_TERN0(O,A)) // ((B) (OPTION ? '+ (A)' : '')) #define DIFF_TERN(O,B,A) ((B) MINUS_TERN0(O,A)) // ((B) (OPTION ? '- (A)' : '')) +#define MUL_TERN(O,B,A) ((B) MUL_TERN1(O,A)) // ((B) (OPTION ? '* (A)' : '')) +#define DIV_TERN(O,B,A) ((B) DIV_TERN1(O,A)) // ((B) (OPTION ? '/ (A)' : '')) // Macros to support pins/buttons exist testing #define PIN_EXISTS(PN) (defined(PN##_PIN) && PN##_PIN >= 0) diff --git a/Marlin/src/lcd/marlinui.h b/Marlin/src/lcd/marlinui.h index 7dd5b6b2d83d..595b89b6e00f 100644 --- a/Marlin/src/lcd/marlinui.h +++ b/Marlin/src/lcd/marlinui.h @@ -88,7 +88,7 @@ typedef bool (*statusResetFunc_t)(); #if ANY(HAS_WIRED_LCD, DWIN_CREALITY_LCD_JYERSUI) #define LCD_WITH_BLINK 1 - #define LCD_UPDATE_INTERVAL TERN(HAS_TOUCH_BUTTONS, 50, 100) + #define LCD_UPDATE_INTERVAL DIV_TERN(DOUBLE_LCD_FRAMERATE, TERN(HAS_TOUCH_BUTTONS, 50, 100), 2) #endif #if HAS_MARLINUI_U8GLIB From 8cf936ccb144fa8a23712d181ad7c743709eb683 Mon Sep 17 00:00:00 2001 From: ellensp <530024+ellensp@users.noreply.github.com> Date: Tue, 5 Dec 2023 16:35:12 +1300 Subject: [PATCH 55/77] =?UTF-8?q?=F0=9F=A9=B9=20Fix=20ftostrX3sign=20(#264?= =?UTF-8?q?97)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/libs/numtostr.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/libs/numtostr.cpp b/Marlin/src/libs/numtostr.cpp index 3efbf68217e6..6f4e4a480bfb 100644 --- a/Marlin/src/libs/numtostr.cpp +++ b/Marlin/src/libs/numtostr.cpp @@ -314,7 +314,7 @@ const char* ftostr51sign(const_float_t f) { return ftostrX1sign(f, 1); } // Convert float to string with +/ /- and 3 decimal places // inline const char* ftostrX3sign(const_float_t f, const int index, char plus/*=' '*/) { - long i = INTFLOAT(f, 1); + long i = INTFLOAT(f, 3); conv[index] = i ? MINUSOR(i, plus) : ' '; switch (index + 1) { case 1: conv[1] = DIGIMOD(i, 100000); From d58168a03f32ba5f12d2dc280849e759d64b6c40 Mon Sep 17 00:00:00 2001 From: ellensp <530024+ellensp@users.noreply.github.com> Date: Tue, 5 Dec 2023 17:19:02 +1300 Subject: [PATCH 56/77] =?UTF-8?q?=F0=9F=A9=B9=20Fix=20a=20NeoPixel=20overr?= =?UTF-8?q?ide=20(#26492)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/stm32f4/pins_MKS_MONSTER8_V2.h | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8_V2.h b/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8_V2.h index d70e935f0a29..772a93605ae6 100644 --- a/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8_V2.h +++ b/Marlin/src/pins/stm32f4/pins_MKS_MONSTER8_V2.h @@ -58,6 +58,9 @@ #define WIFI_RESET_PIN PD14 // MKS ESP WIFI RESET PIN #endif -#define NEOPIXEL_PIN PC5 +// The FYSETC_MINI_12864_2_1 uses one of the EXP pins +#if DISABLED(FYSETC_MINI_12864_2_1) && !defined(NEOPIXEL_PIN) + #define NEOPIXEL_PIN PC5 +#endif #include "pins_MKS_MONSTER8_common.h" From 065440891be1be8caeb03a065ccc4a3cd68ba23f Mon Sep 17 00:00:00 2001 From: Alexander Gavrilenko Date: Tue, 5 Dec 2023 07:46:39 +0300 Subject: [PATCH 57/77] =?UTF-8?q?=F0=9F=9A=B8=20UI=20refresh=20for=20some?= =?UTF-8?q?=20events=20(#26487)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/menu/menu_advanced.cpp | 8 ++++---- Marlin/src/lcd/menu/menu_main.cpp | 4 ++-- 2 files changed, 6 insertions(+), 6 deletions(-) diff --git a/Marlin/src/lcd/menu/menu_advanced.cpp b/Marlin/src/lcd/menu/menu_advanced.cpp index 1d95961f3b7b..51fb55c9a471 100644 --- a/Marlin/src/lcd/menu/menu_advanced.cpp +++ b/Marlin/src/lcd/menu/menu_advanced.cpp @@ -562,24 +562,24 @@ void menu_backlash(); #if ENABLED(INPUT_SHAPING_X) editable.decimal = stepper.get_shaping_frequency(X_AXIS); if (editable.decimal) { - ACTION_ITEM_N(X_AXIS, MSG_SHAPING_DISABLE, []{ stepper.set_shaping_frequency(X_AXIS, 0.0f); }); + ACTION_ITEM_N(X_AXIS, MSG_SHAPING_DISABLE, []{ stepper.set_shaping_frequency(X_AXIS, 0.0f); ui.refresh(LCDVIEW_CLEAR_CALL_REDRAW); }); EDIT_ITEM_FAST_N(float41, X_AXIS, MSG_SHAPING_FREQ, &editable.decimal, min_frequency, 200.0f, []{ stepper.set_shaping_frequency(X_AXIS, editable.decimal); }); editable.decimal = stepper.get_shaping_damping_ratio(X_AXIS); EDIT_ITEM_FAST_N(float42_52, X_AXIS, MSG_SHAPING_ZETA, &editable.decimal, 0.0f, 1.0f, []{ stepper.set_shaping_damping_ratio(X_AXIS, editable.decimal); }); } else - ACTION_ITEM_N(X_AXIS, MSG_SHAPING_ENABLE, []{ stepper.set_shaping_frequency(X_AXIS, (SHAPING_FREQ_X) ?: (SHAPING_MIN_FREQ)); }); + ACTION_ITEM_N(X_AXIS, MSG_SHAPING_ENABLE, []{ stepper.set_shaping_frequency(X_AXIS, (SHAPING_FREQ_X) ?: (SHAPING_MIN_FREQ)); ui.refresh(LCDVIEW_CLEAR_CALL_REDRAW); }); #endif #if ENABLED(INPUT_SHAPING_Y) editable.decimal = stepper.get_shaping_frequency(Y_AXIS); if (editable.decimal) { - ACTION_ITEM_N(Y_AXIS, MSG_SHAPING_DISABLE, []{ stepper.set_shaping_frequency(Y_AXIS, 0.0f); }); + ACTION_ITEM_N(Y_AXIS, MSG_SHAPING_DISABLE, []{ stepper.set_shaping_frequency(Y_AXIS, 0.0f); ui.refresh(LCDVIEW_CLEAR_CALL_REDRAW); }); EDIT_ITEM_FAST_N(float41, Y_AXIS, MSG_SHAPING_FREQ, &editable.decimal, min_frequency, 200.0f, []{ stepper.set_shaping_frequency(Y_AXIS, editable.decimal); }); editable.decimal = stepper.get_shaping_damping_ratio(Y_AXIS); EDIT_ITEM_FAST_N(float42_52, Y_AXIS, MSG_SHAPING_ZETA, &editable.decimal, 0.0f, 1.0f, []{ stepper.set_shaping_damping_ratio(Y_AXIS, editable.decimal); }); } else - ACTION_ITEM_N(Y_AXIS, MSG_SHAPING_ENABLE, []{ stepper.set_shaping_frequency(Y_AXIS, (SHAPING_FREQ_Y) ?: (SHAPING_MIN_FREQ)); }); + ACTION_ITEM_N(Y_AXIS, MSG_SHAPING_ENABLE, []{ stepper.set_shaping_frequency(Y_AXIS, (SHAPING_FREQ_Y) ?: (SHAPING_MIN_FREQ)); ui.refresh(LCDVIEW_CLEAR_CALL_REDRAW); }); #endif END_MENU(); diff --git a/Marlin/src/lcd/menu/menu_main.cpp b/Marlin/src/lcd/menu/menu_main.cpp index 1bf380e3608c..3daeb285a17a 100644 --- a/Marlin/src/lcd/menu/menu_main.cpp +++ b/Marlin/src/lcd/menu/menu_main.cpp @@ -296,7 +296,7 @@ void menu_main() { #if ENABLED(TFT_COLOR_UI) // Menu display issue on item removal with multi language selection menu if (encoderTopLine > 0) encoderTopLine--; - ui.refresh(LCDVIEW_CALL_REDRAW_NEXT); + ui.refresh(LCDVIEW_CLEAR_CALL_REDRAW); #endif }); #endif @@ -413,7 +413,7 @@ void menu_main() { #if ENABLED(TFT_COLOR_UI) // Menu display issue on item removal with multi language selection menu if (encoderTopLine > 0) encoderTopLine--; - ui.refresh(LCDVIEW_CALL_REDRAW_NEXT); + ui.refresh(LCDVIEW_CLEAR_CALL_REDRAW); #endif }); #endif From 2b1375c8eaf72c5145fdf5e85de934c494cb5e9d Mon Sep 17 00:00:00 2001 From: ellensp <530024+ellensp@users.noreply.github.com> Date: Tue, 5 Dec 2023 18:27:58 +1300 Subject: [PATCH 58/77] =?UTF-8?q?=F0=9F=90=9B=20Fix=20thermistor=2014=20&?= =?UTF-8?q?=2060=20constexprness=20(#26499)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/module/thermistor/thermistor_14.h | 2 +- Marlin/src/module/thermistor/thermistor_68.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/module/thermistor/thermistor_14.h b/Marlin/src/module/thermistor/thermistor_14.h index f0bc6f606ee8..0d432f3d65ce 100644 --- a/Marlin/src/module/thermistor/thermistor_14.h +++ b/Marlin/src/module/thermistor/thermistor_14.h @@ -22,7 +22,7 @@ #pragma once // R25 = 100 kOhm, beta25 = 4092 K, 4.7 kOhm pull-up, bed thermistor -const temp_entry_t temptable_14[] PROGMEM = { +constexpr temp_entry_t temptable_14[] PROGMEM = { { OV( 23), 275 }, { OV( 25), 270 }, { OV( 27), 265 }, diff --git a/Marlin/src/module/thermistor/thermistor_68.h b/Marlin/src/module/thermistor/thermistor_68.h index 270456dcb59c..f8b0f625e72b 100644 --- a/Marlin/src/module/thermistor/thermistor_68.h +++ b/Marlin/src/module/thermistor/thermistor_68.h @@ -24,7 +24,7 @@ #define REVERSE_TEMP_SENSOR_RANGE_68 1 // PT100 amplifier board from Dyze Design -const temp_entry_t temptable_68[] PROGMEM = { +constexpr temp_entry_t temptable_68[] PROGMEM = { { OV(273), 0 }, { OV(294), 20 }, { OV(315), 40 }, From 4a4c1db606ece3a235244c90fc397946d0c863a6 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Tue, 5 Dec 2023 06:06:24 +0000 Subject: [PATCH 59/77] [cron] Bump distribution date (2023-12-05) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 67d8329c38a3..0c5d41c1b2e8 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2023-12-04" +//#define STRING_DISTRIBUTION_DATE "2023-12-05" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 00848ef9e115..f24452835866 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2023-12-04" + #define STRING_DISTRIBUTION_DATE "2023-12-05" #endif /** From 425af4240b222448ab2ebe5c5d152adeed2079a4 Mon Sep 17 00:00:00 2001 From: studiodyne <42887851+studiodyne@users.noreply.github.com> Date: Wed, 6 Dec 2023 06:05:48 +0100 Subject: [PATCH 60/77] =?UTF-8?q?=F0=9F=90=9B=20Fix=20tool-change=20E=20pr?= =?UTF-8?q?ime=20(#26494)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Followup to #17248 --- Marlin/src/module/tool_change.cpp | 18 +++++++++++++++++- 1 file changed, 17 insertions(+), 1 deletion(-) diff --git a/Marlin/src/module/tool_change.cpp b/Marlin/src/module/tool_change.cpp index 22982fa91a44..373dcf314221 100644 --- a/Marlin/src/module/tool_change.cpp +++ b/Marlin/src/module/tool_change.cpp @@ -1028,7 +1028,7 @@ void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_axis, 0. if (!too_cold(active_extruder)) { destination = current_position; // Remember the old position - const bool ok = TERN1(TOOLCHANGE_PARK, all_axes_homed() && toolchange_settings.enable_park); + const bool ok = TERN0(TOOLCHANGE_PARK, all_axes_homed() && toolchange_settings.enable_park); #if HAS_FAN && TOOLCHANGE_FS_FAN >= 0 // Store and stop fan. Restored on any exit. @@ -1080,7 +1080,20 @@ void fast_line_to_current(const AxisEnum fr_axis) { _line_to_current(fr_axis, 0. } #endif + // Clone previous position extruder_cutting_recover(destination.e); // Cutting recover + + // Retract if previously retracted + #if ENABLED(FWRETRACT) + if (fwretract.retracted[active_extruder]) + unscaled_e_move(-fwretract.settings.retract_length, fwretract.settings.retract_feedrate_mm_s); + #endif + + // If resume_position is negative + if (current_position.e < 0) unscaled_e_move(current_position.e, MMM_TO_MMS(toolchange_settings.retract_speed)); + + planner.synchronize(); + planner.set_e_position_mm(current_position.e); // Extruder primed and ready } } @@ -1597,6 +1610,9 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { unscaled_e_move(-fwretract.settings.retract_length, fwretract.settings.retract_feedrate_mm_s); #endif + // If resume_position is negative + if (resume_current_e < 0) unscaled_e_move(resume_current_e, MMM_TO_MMS(toolchange_settings.retract_speed)); + // If no available extruder if (EXTRUDERS < 2 || active_extruder >= EXTRUDERS - 2 || active_extruder == migration.last) migration.automode = false; From a41e16ffee0ae828ecb73eeea3caab2f4aed82a8 Mon Sep 17 00:00:00 2001 From: Andrew <18502096+classicrocker883@users.noreply.github.com> Date: Wed, 6 Dec 2023 00:11:41 -0500 Subject: [PATCH 61/77] =?UTF-8?q?=E2=9C=A8=20Voxelab=20Aquila=20N32=20(via?= =?UTF-8?q?=20Maple)=20(#26470)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/src/HAL/STM32/HAL.h | 6 +- Marlin/src/HAL/STM32F1/HAL.cpp | 279 ++---- Marlin/src/HAL/STM32F1/HAL.h | 48 + Marlin/src/HAL/STM32F1/HAL_N32.cpp | 641 +++++++++++++ Marlin/src/HAL/STM32F1/HAL_N32.h | 892 +++++++++++++++++++ Marlin/src/HAL/STM32F1/MarlinSerial.cpp | 2 +- Marlin/src/HAL/STM32F1/adc.h | 57 ++ Marlin/src/HAL/STM32F1/timers.h | 2 +- Marlin/src/core/boards.h | 3 +- Marlin/src/inc/Warnings.cpp | 14 + Marlin/src/lcd/e3v2/creality/dwin.cpp | 1 - Marlin/src/lcd/e3v2/proui/dwinui.cpp | 2 +- Marlin/src/lcd/e3v2/proui/dwinui.h | 2 +- Marlin/src/lcd/e3v2/proui/menus.cpp | 2 +- Marlin/src/pins/gd32f1/pins_VOXELAB_AQUILA.h | 39 + Marlin/src/pins/hc32f4/pins_AQUILA_101.h | 20 +- Marlin/src/pins/pins.h | 2 + ini/hc32.ini | 3 +- ini/stm32f1-maple.ini | 23 + 19 files changed, 1828 insertions(+), 210 deletions(-) create mode 100644 Marlin/src/HAL/STM32F1/HAL_N32.cpp create mode 100644 Marlin/src/HAL/STM32F1/HAL_N32.h create mode 100644 Marlin/src/HAL/STM32F1/adc.h create mode 100644 Marlin/src/pins/gd32f1/pins_VOXELAB_AQUILA.h diff --git a/Marlin/src/HAL/STM32/HAL.h b/Marlin/src/HAL/STM32/HAL.h index b3430f333987..276f031685fe 100644 --- a/Marlin/src/HAL/STM32/HAL.h +++ b/Marlin/src/HAL/STM32/HAL.h @@ -138,11 +138,7 @@ typedef double isr_float_t; // FPU ops are used for single-precision, so use double for ISRs. -#if defined(STM32G0B1xx) || defined(STM32H7xx) - typedef int32_t pin_t; -#else - typedef int16_t pin_t; -#endif +typedef int32_t pin_t; // Parity with platform/ststm32 class libServo; typedef libServo hal_servo_t; diff --git a/Marlin/src/HAL/STM32F1/HAL.cpp b/Marlin/src/HAL/STM32F1/HAL.cpp index 376778a2b3b2..e6cbb9fc0605 100644 --- a/Marlin/src/HAL/STM32F1/HAL.cpp +++ b/Marlin/src/HAL/STM32F1/HAL.cpp @@ -29,53 +29,8 @@ #include "../../inc/MarlinConfig.h" #include "HAL.h" -#include - -// ------------------------ -// Types -// ------------------------ - -#define __I -#define __IO volatile - typedef struct { - __I uint32_t CPUID; /*!< Offset: 0x000 (R/ ) CPUID Base Register */ - __IO uint32_t ICSR; /*!< Offset: 0x004 (R/W) Interrupt Control and State Register */ - __IO uint32_t VTOR; /*!< Offset: 0x008 (R/W) Vector Table Offset Register */ - __IO uint32_t AIRCR; /*!< Offset: 0x00C (R/W) Application Interrupt and Reset Control Register */ - __IO uint32_t SCR; /*!< Offset: 0x010 (R/W) System Control Register */ - __IO uint32_t CCR; /*!< Offset: 0x014 (R/W) Configuration Control Register */ - __IO uint8_t SHP[12]; /*!< Offset: 0x018 (R/W) System Handlers Priority Registers (4-7, 8-11, 12-15) */ - __IO uint32_t SHCSR; /*!< Offset: 0x024 (R/W) System Handler Control and State Register */ - __IO uint32_t CFSR; /*!< Offset: 0x028 (R/W) Configurable Fault Status Register */ - __IO uint32_t HFSR; /*!< Offset: 0x02C (R/W) HardFault Status Register */ - __IO uint32_t DFSR; /*!< Offset: 0x030 (R/W) Debug Fault Status Register */ - __IO uint32_t MMFAR; /*!< Offset: 0x034 (R/W) MemManage Fault Address Register */ - __IO uint32_t BFAR; /*!< Offset: 0x038 (R/W) BusFault Address Register */ - __IO uint32_t AFSR; /*!< Offset: 0x03C (R/W) Auxiliary Fault Status Register */ - __I uint32_t PFR[2]; /*!< Offset: 0x040 (R/ ) Processor Feature Register */ - __I uint32_t DFR; /*!< Offset: 0x048 (R/ ) Debug Feature Register */ - __I uint32_t ADR; /*!< Offset: 0x04C (R/ ) Auxiliary Feature Register */ - __I uint32_t MMFR[4]; /*!< Offset: 0x050 (R/ ) Memory Model Feature Register */ - __I uint32_t ISAR[5]; /*!< Offset: 0x060 (R/ ) Instruction Set Attributes Register */ - uint32_t RESERVED0[5]; - __IO uint32_t CPACR; /*!< Offset: 0x088 (R/W) Coprocessor Access Control Register */ - } SCB_Type; - -// ------------------------ -// Local defines -// ------------------------ - -#define SCS_BASE (0xE000E000UL) /*!< System Control Space Base Address */ -#define SCB_BASE (SCS_BASE + 0x0D00UL) /*!< System Control Block Base Address */ - -#define SCB ((SCB_Type *) SCB_BASE ) /*!< SCB configuration struct */ - -/* SCB Application Interrupt and Reset Control Register Definitions */ -#define SCB_AIRCR_VECTKEY_Pos 16 /*!< SCB AIRCR: VECTKEY Position */ -#define SCB_AIRCR_VECTKEY_Msk (0xFFFFUL << SCB_AIRCR_VECTKEY_Pos) /*!< SCB AIRCR: VECTKEY Mask */ - -#define SCB_AIRCR_PRIGROUP_Pos 8 /*!< SCB AIRCR: PRIGROUP Position */ -#define SCB_AIRCR_PRIGROUP_Msk (7UL << SCB_AIRCR_PRIGROUP_Pos) /*!< SCB AIRCR: PRIGROUP Mask */ +#include "adc.h" +uint16_t adc_results[ADC_COUNT]; // ------------------------ // Serial ports @@ -171,153 +126,9 @@ void analogWrite(const pin_t pin, int pwm_val8) { uint16_t MarlinHAL::adc_result; -// ------------------------ -// Private functions -// ------------------------ - -static void NVIC_SetPriorityGrouping(uint32_t PriorityGroup) { - uint32_t reg_value; - uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07); // only values 0..7 are used - - reg_value = SCB->AIRCR; // read old register configuration - reg_value &= ~(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk); // clear bits to change - reg_value = (reg_value | - ((uint32_t)0x5FA << SCB_AIRCR_VECTKEY_Pos) | - (PriorityGroupTmp << 8)); // Insert write key & priority group - SCB->AIRCR = reg_value; -} - -// ------------------------ -// Public functions -// ------------------------ - -void flashFirmware(const int16_t) { hal.reboot(); } - -// -// Leave PA11/PA12 intact if USBSerial is not used -// -#if SERIAL_USB - namespace wirish { namespace priv { - #if SERIAL_PORT > 0 - #if SERIAL_PORT2 - #if SERIAL_PORT2 > 0 - void board_setup_usb() {} - #endif - #else - void board_setup_usb() {} - #endif - #endif - } } -#endif - -TERN_(POSTMORTEM_DEBUGGING, extern void install_min_serial()); - -// ------------------------ -// MarlinHAL class -// ------------------------ - -void MarlinHAL::init() { - NVIC_SetPriorityGrouping(0x3); - #if PIN_EXISTS(LED) - OUT_WRITE(LED_PIN, LOW); - #endif - #if HAS_SD_HOST_DRIVE - MSC_SD_init(); - #elif ALL(SERIAL_USB, EMERGENCY_PARSER) - usb_cdcacm_set_hooks(USB_CDCACM_HOOK_RX, my_rx_callback); - #endif - #if PIN_EXISTS(USB_CONNECT) - OUT_WRITE(USB_CONNECT_PIN, !USB_CONNECT_INVERTING); // USB clear connection - delay(1000); // Give OS time to notice - WRITE(USB_CONNECT_PIN, USB_CONNECT_INVERTING); - #endif - TERN_(POSTMORTEM_DEBUGGING, install_min_serial()); // Install the minimal serial handler -} - -// HAL idle task -void MarlinHAL::idletask() { - #if HAS_SHARED_MEDIA - // If Marlin is using the SD card we need to lock it to prevent access from - // a PC via USB. - // Other HALs use IS_SD_PRINTING() and IS_SD_FILE_OPEN() to check for access but - // this will not reliably detect delete operations. To be safe we will lock - // the disk if Marlin has it mounted. Unfortunately there is currently no way - // to unmount the disk from the LCD menu. - // if (IS_SD_PRINTING() || IS_SD_FILE_OPEN()) - /* copy from lpc1768 framework, should be fixed later for process HAS_SD_HOST_DRIVE*/ - // process USB mass storage device class loop - MarlinMSC.loop(); - #endif -} - -void MarlinHAL::reboot() { nvic_sys_reset(); } +#ifndef VOXELAB_N32 -// ------------------------ -// Free Memory Accessor -// ------------------------ - -extern "C" { - extern unsigned int _ebss; // end of bss section -} - -/** - * TODO: Change this to correct it for libmaple - */ - -// return free memory between end of heap (or end bss) and whatever is current - -/* -#include -//extern caddr_t _sbrk(int incr); -#ifndef CONFIG_HEAP_END -extern char _lm_heap_end; -#define CONFIG_HEAP_END ((caddr_t)&_lm_heap_end) -#endif - -extern "C" { - static int freeMemory() { - char top = 't'; - return &top - reinterpret_cast(sbrk(0)); - } - int freeMemory() { - int free_memory; - int heap_end = (int)_sbrk(0); - free_memory = ((int)&free_memory) - ((int)heap_end); - return free_memory; - } -} -*/ - -// ------------------------ -// ADC -// ------------------------ - -enum ADCIndex : uint8_t { - OPTITEM(HAS_TEMP_ADC_0, TEMP_0) - OPTITEM(HAS_TEMP_ADC_1, TEMP_1) - OPTITEM(HAS_TEMP_ADC_2, TEMP_2) - OPTITEM(HAS_TEMP_ADC_3, TEMP_3) - OPTITEM(HAS_TEMP_ADC_4, TEMP_4) - OPTITEM(HAS_TEMP_ADC_5, TEMP_5) - OPTITEM(HAS_TEMP_ADC_6, TEMP_6) - OPTITEM(HAS_TEMP_ADC_7, TEMP_7) - OPTITEM(HAS_HEATED_BED, TEMP_BED) - OPTITEM(HAS_TEMP_CHAMBER, TEMP_CHAMBER) - OPTITEM(HAS_TEMP_ADC_PROBE, TEMP_PROBE) - OPTITEM(HAS_TEMP_COOLER, TEMP_COOLER) - OPTITEM(HAS_TEMP_BOARD, TEMP_BOARD) - OPTITEM(HAS_TEMP_SOC, TEMP_SOC) - OPTITEM(FILAMENT_WIDTH_SENSOR, FILWIDTH) - OPTITEM(HAS_ADC_BUTTONS, ADC_KEY) - OPTITEM(HAS_JOY_ADC_X, JOY_X) - OPTITEM(HAS_JOY_ADC_Y, JOY_Y) - OPTITEM(HAS_JOY_ADC_Z, JOY_Z) - OPTITEM(POWER_MONITOR_CURRENT, POWERMON_CURRENT) - OPTITEM(POWER_MONITOR_VOLTAGE, POWERMON_VOLTAGE) - ADC_COUNT -}; - -static uint16_t adc_results[ADC_COUNT]; +#include // Init the AD in continuous capture mode void MarlinHAL::adc_init() { @@ -345,7 +156,7 @@ void MarlinHAL::adc_init() { OPTITEM(POWER_MONITOR_VOLTAGE, POWER_MONITOR_VOLTAGE_PIN) }; static STM32ADC adc(ADC1); - // configure the ADC + // Configure the ADC adc.calibrate(); adc.setSampleRate((F_CPU > 72000000) ? ADC_SMPR_71_5 : ADC_SMPR_41_5); // 71.5 or 41.5 ADC cycles adc.setPins((uint8_t *)adc_pins, ADC_COUNT); @@ -355,6 +166,8 @@ void MarlinHAL::adc_init() { adc.startConversion(); } +#endif // !VOXELAB_N32 + void MarlinHAL::adc_start(const pin_t pin) { #define __TCASE(N,I) case N: pin_index = I; break; #define _TCASE(C,N,I) TERN_(C, __TCASE(N, I)) @@ -386,4 +199,82 @@ void MarlinHAL::adc_start(const pin_t pin) { adc_result = (adc_results[(int)pin_index] & 0xFFF) >> (12 - HAL_ADC_RESOLUTION); // shift out unused bits } +// ------------------------ +// Public functions +// ------------------------ + +void NVIC_SetPriorityGrouping(uint32_t PriorityGroup) { + uint32_t reg_value; + uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07); // only values 0..7 are used + + reg_value = SCB->AIRCR; // read old register configuration + reg_value &= ~(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk); // clear bits to change + reg_value = (reg_value | + ((uint32_t)0x5FA << SCB_AIRCR_VECTKEY_Pos) | + (PriorityGroupTmp << 8)); // Insert write key & priority group + SCB->AIRCR = reg_value; +} + +void flashFirmware(const int16_t) { hal.reboot(); } + +// +// Leave PA11/PA12 intact if USBSerial is not used +// +#if SERIAL_USB + namespace wirish { namespace priv { + #if SERIAL_PORT > 0 + #if SERIAL_PORT2 + #if SERIAL_PORT2 > 0 + void board_setup_usb() {} + #endif + #else + void board_setup_usb() {} + #endif + #endif + } } +#endif + +TERN_(POSTMORTEM_DEBUGGING, extern void install_min_serial()); + +// ------------------------ +// MarlinHAL class +// ------------------------ + +void MarlinHAL::init() { + NVIC_SetPriorityGrouping(0x3); + #if PIN_EXISTS(LED) + OUT_WRITE(LED_PIN, LOW); + #endif + #if HAS_SD_HOST_DRIVE + MSC_SD_init(); + #elif ALL(SERIAL_USB, EMERGENCY_PARSER) + usb_cdcacm_set_hooks(USB_CDCACM_HOOK_RX, my_rx_callback); + #endif + #if PIN_EXISTS(USB_CONNECT) + OUT_WRITE(USB_CONNECT_PIN, !USB_CONNECT_INVERTING); // USB clear connection + delay(1000); // Give OS time to notice + WRITE(USB_CONNECT_PIN, USB_CONNECT_INVERTING); + #endif + TERN_(POSTMORTEM_DEBUGGING, install_min_serial()); // Install the minimal serial handler +} + +// HAL idle task +void MarlinHAL::idletask() { + #if HAS_SHARED_MEDIA + /** + * When Marlin is using the SD card it should be locked to prevent it being + * accessed from a PC over USB. + * Other HALs use (IS_SD_PRINTING() || IS_SD_FILE_OPEN()) to check for access + * but this won't reliably detect other file operations. To be safe we just lock + * the drive whenever Marlin has it mounted. LCDs should include an Unmount + * command so drives can be released as needed. + */ + /* Copied from LPC1768 framework. Should be fixed later to process HAS_SD_HOST_DRIVE */ + //if (!drive_locked()) // TODO + MarlinMSC.loop(); // Process USB mass storage device class loop + #endif +} + +void MarlinHAL::reboot() { nvic_sys_reset(); } + #endif // __STM32F1__ diff --git a/Marlin/src/HAL/STM32F1/HAL.h b/Marlin/src/HAL/STM32F1/HAL.h index 52d3b805e611..41c91e200f89 100644 --- a/Marlin/src/HAL/STM32F1/HAL.h +++ b/Marlin/src/HAL/STM32F1/HAL.h @@ -223,6 +223,8 @@ void flashFirmware(const int16_t); extern "C" char* _sbrk(int incr); +void NVIC_SetPriorityGrouping(uint32_t PriorityGroup); + #pragma GCC diagnostic push #if GCC_VERSION <= 50000 #pragma GCC diagnostic ignored "-Wunused-function" @@ -306,3 +308,49 @@ class MarlinHAL { static void set_pwm_frequency(const pin_t pin, const uint16_t f_desired); }; + +// ------------------------ +// Types +// ------------------------ + +#define __I +#define __IO volatile + typedef struct { + __I uint32_t CPUID; /*!< Offset: 0x000 (R/ ) CPUID Base Register */ + __IO uint32_t ICSR; /*!< Offset: 0x004 (R/W) Interrupt Control and State Register */ + __IO uint32_t VTOR; /*!< Offset: 0x008 (R/W) Vector Table Offset Register */ + __IO uint32_t AIRCR; /*!< Offset: 0x00C (R/W) Application Interrupt and Reset Control Register */ + __IO uint32_t SCR; /*!< Offset: 0x010 (R/W) System Control Register */ + __IO uint32_t CCR; /*!< Offset: 0x014 (R/W) Configuration Control Register */ + __IO uint8_t SHP[12]; /*!< Offset: 0x018 (R/W) System Handlers Priority Registers (4-7, 8-11, 12-15) */ + __IO uint32_t SHCSR; /*!< Offset: 0x024 (R/W) System Handler Control and State Register */ + __IO uint32_t CFSR; /*!< Offset: 0x028 (R/W) Configurable Fault Status Register */ + __IO uint32_t HFSR; /*!< Offset: 0x02C (R/W) HardFault Status Register */ + __IO uint32_t DFSR; /*!< Offset: 0x030 (R/W) Debug Fault Status Register */ + __IO uint32_t MMFAR; /*!< Offset: 0x034 (R/W) MemManage Fault Address Register */ + __IO uint32_t BFAR; /*!< Offset: 0x038 (R/W) BusFault Address Register */ + __IO uint32_t AFSR; /*!< Offset: 0x03C (R/W) Auxiliary Fault Status Register */ + __I uint32_t PFR[2]; /*!< Offset: 0x040 (R/ ) Processor Feature Register */ + __I uint32_t DFR; /*!< Offset: 0x048 (R/ ) Debug Feature Register */ + __I uint32_t ADR; /*!< Offset: 0x04C (R/ ) Auxiliary Feature Register */ + __I uint32_t MMFR[4]; /*!< Offset: 0x050 (R/ ) Memory Model Feature Register */ + __I uint32_t ISAR[5]; /*!< Offset: 0x060 (R/ ) Instruction Set Attributes Register */ + uint32_t RESERVED0[5]; + __IO uint32_t CPACR; /*!< Offset: 0x088 (R/W) Coprocessor Access Control Register */ + } SCB_Type; + +// ------------------------ +// System Control Space +// ------------------------ + +#define SCS_BASE (0xE000E000UL) /*!< System Control Space Base Address */ +#define SCB_BASE (SCS_BASE + 0x0D00UL) /*!< System Control Block Base Address */ + +#define SCB ((SCB_Type *) SCB_BASE ) /*!< SCB configuration struct */ + +/* SCB Application Interrupt and Reset Control Register Definitions */ +#define SCB_AIRCR_VECTKEY_Pos 16 /*!< SCB AIRCR: VECTKEY Position */ +#define SCB_AIRCR_VECTKEY_Msk (0xFFFFUL << SCB_AIRCR_VECTKEY_Pos) /*!< SCB AIRCR: VECTKEY Mask */ + +#define SCB_AIRCR_PRIGROUP_Pos 8 /*!< SCB AIRCR: PRIGROUP Position */ +#define SCB_AIRCR_PRIGROUP_Msk (7UL << SCB_AIRCR_PRIGROUP_Pos) /*!< SCB AIRCR: PRIGROUP Mask */ diff --git a/Marlin/src/HAL/STM32F1/HAL_N32.cpp b/Marlin/src/HAL/STM32F1/HAL_N32.cpp new file mode 100644 index 000000000000..971a344f210d --- /dev/null +++ b/Marlin/src/HAL/STM32F1/HAL_N32.cpp @@ -0,0 +1,641 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 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 . + * + */ + +/** + * HAL for stm32duino.com based on Libmaple and compatible (STM32F1) + * Specifically for VOXELAB_N32. TODO: Rework for generic N32 MCU. + */ + +#if defined(__STM32F1__) && defined(VOXELAB_N32) + +#include "../../inc/MarlinConfig.h" +#include "HAL_N32.h" +#include "HAL.h" + +#include "adc.h" + +void ADC_Init(ADC_Module* NS_ADCx, ADC_InitType* ADC_InitStruct) { + uint32_t tmpreg1 = 0; + uint8_t tmpreg2 = 0; + + /*---------------------------- ADCx CTRL1 Configuration -----------------*/ + /* Get the ADCx CTRL1 value */ + tmpreg1 = NS_ADCx->CTRL1; + /* Clear DUALMOD and SCAN bits */ + tmpreg1 &= CTRL1_CLR_MASK; + /* Configure ADCx: Dual mode and scan conversion mode */ + /* Set DUALMOD bits according to WorkMode value */ + /* Set SCAN bit according to MultiChEn value */ + tmpreg1 |= (uint32_t)(ADC_InitStruct->WorkMode | ((uint32_t)ADC_InitStruct->MultiChEn << 8)); + /* Write to ADCx CTRL1 */ + NS_ADCx->CTRL1 = tmpreg1; + + /*---------------------------- ADCx CTRL2 Configuration -----------------*/ + /* Get the ADCx CTRL2 value */ + tmpreg1 = NS_ADCx->CTRL2; + /* Clear CONT, ALIGN and EXTSEL bits */ + tmpreg1 &= CTRL2_CLR_MASK; + /* Configure ADCx: external trigger event and continuous conversion mode */ + /* Set ALIGN bit according to DatAlign value */ + /* Set EXTSEL bits according to ExtTrigSelect value */ + /* Set CONT bit according to ContinueConvEn value */ + tmpreg1 |= (uint32_t)(ADC_InitStruct->DatAlign | ADC_InitStruct->ExtTrigSelect + | ((uint32_t)ADC_InitStruct->ContinueConvEn << 1)); + /* Write to ADCx CTRL2 */ + NS_ADCx->CTRL2 = tmpreg1; + + /*---------------------------- ADCx RSEQ1 Configuration -----------------*/ + /* Get the ADCx RSEQ1 value */ + tmpreg1 = NS_ADCx->RSEQ1; + /* Clear L bits */ + tmpreg1 &= RSEQ1_CLR_MASK; + /* Configure ADCx: regular channel sequence length */ + /* Set L bits according to ChsNumber value */ + tmpreg2 |= (uint8_t)(ADC_InitStruct->ChsNumber - (uint8_t)1); + tmpreg1 |= (uint32_t)tmpreg2 << 20; + /* Write to ADCx RSEQ1 */ + NS_ADCx->RSEQ1 = tmpreg1; +} + +/**================================================================ + * ADC reset + ================================================================*/ +void ADC_DeInit(ADC_Module* NS_ADCx) { + uint32_t reg_temp; + + if (NS_ADCx == NS_ADC1) { + /* Enable ADC1 reset state */ + reg_temp = ADC_RCC_AHBPRST; + reg_temp |= RCC_AHB_PERIPH_ADC1; + ADC_RCC_AHBPRST = reg_temp; // ADC module reunion position + ADC_RCC_AHBPRST = 0x00000000; // ADC module reset and clear + } + else if (NS_ADCx == NS_ADC2) { + /* Enable ADC2 reset state */ + reg_temp = ADC_RCC_AHBPRST; + reg_temp |= RCC_AHB_PERIPH_ADC2; + ADC_RCC_AHBPRST = reg_temp; // ADC module reunion position + ADC_RCC_AHBPRST = 0x00000000; // ADC module reset and clear + } + else if (NS_ADCx == NS_ADC3) { + /* Enable ADC2 reset state */ + reg_temp = ADC_RCC_AHBPRST; + reg_temp |= RCC_AHB_PERIPH_ADC3; + ADC_RCC_AHBPRST = reg_temp; // ADC module reunion position + ADC_RCC_AHBPRST = 0x00000000; // ADC module reset and clear + } + else if (NS_ADCx == NS_ADC4) { + /* Enable ADC3 reset state */ + reg_temp = ADC_RCC_AHBPRST; + reg_temp |= RCC_AHB_PERIPH_ADC4; + ADC_RCC_AHBPRST = reg_temp; // ADC module reunion position + ADC_RCC_AHBPRST = 0x00000000; // ADC module reset and clear + } +} + +/**================================================================ + * ADC module enable + ================================================================*/ +void ADC_Enable(ADC_Module* NS_ADCx, uint32_t Cmd) { + if (Cmd) + /* Set the AD_ON bit to wake up the ADC from power down mode */ + NS_ADCx->CTRL2 |= CTRL2_AD_ON_SET; + else + /* Disable the selected ADC peripheral */ + NS_ADCx->CTRL2 &= CTRL2_AD_ON_RESET; +} + +/**================================================================ + * Get the ADC status logo bit + ================================================================*/ +uint32_t ADC_GetFlagStatusNew(ADC_Module* NS_ADCx, uint8_t ADC_FLAG_NEW) { + uint32_t bitstatus = 0; + + /* Check the status of the specified ADC flag */ + if ((NS_ADCx->CTRL3 & ADC_FLAG_NEW) != (uint8_t)0) + /* ADC_FLAG_NEW is set */ + bitstatus = 1; + else + /* ADC_FLAG_NEW is reset */ + bitstatus = 0; + /* Return the ADC_FLAG_NEW status */ + return bitstatus; +} + +/**================================================================ + * Open ADC calibration + ================================================================*/ +void ADC_StartCalibration(ADC_Module* NS_ADCx) { + /* Enable the selected ADC calibration process */ + if (NS_ADCx->CALFACT == 0) + NS_ADCx->CTRL2 |= CTRL2_CAL_SET; +} + +/**================================================================ + * Enable ADC DMA + ================================================================*/ +void ADC_EnableDMA(ADC_Module* NS_ADCx, uint32_t Cmd) { + if (Cmd != 0) + /* Enable the selected ADC DMA request */ + NS_ADCx->CTRL2 |= CTRL2_DMA_SET; + else + /* Disable the selected ADC DMA request */ + NS_ADCx->CTRL2 &= CTRL2_DMA_RESET; +} + +/**================================================================ + * Configure ADC interrupt enable enable + ================================================================*/ +void ADC_ConfigInt(ADC_Module* NS_ADCx, uint16_t ADC_IT, uint32_t Cmd) { + uint8_t itmask = 0; + + /* Get the ADC IT index */ + itmask = (uint8_t)ADC_IT; + if (Cmd != 0) + /* Enable the selected ADC interrupts */ + NS_ADCx->CTRL1 |= itmask; + else + /* Disable the selected ADC interrupts */ + NS_ADCx->CTRL1 &= (~(uint32_t)itmask); +} + +/**================================================================ + * Get ADC calibration status + ================================================================*/ +uint32_t ADC_GetCalibrationStatus(ADC_Module* NS_ADCx) { + uint32_t bitstatus = 0; + + /* Check the status of CAL bit */ + if ((NS_ADCx->CTRL2 & CTRL2_CAL_SET) != (uint32_t)0) + /* CAL bit is set: calibration on going */ + bitstatus = 1; + else + /* CAL bit is reset: end of calibration */ + bitstatus = 0; + + if (NS_ADCx->CALFACT != 0) + bitstatus = 0; + /* Return the CAL bit status */ + return bitstatus; +} + +/**================================================================ + * Configure the ADC channel + ================================================================*/ +void ADC_ConfigRegularChannel(ADC_Module* NS_ADCx, uint8_t ADC_Channel, uint8_t Rank, uint8_t ADC_SampleTime) { + uint32_t tmpreg1 = 0, tmpreg2 = 0; + + if (ADC_Channel == ADC_CH_18) { + tmpreg1 = NS_ADCx->SAMPT3; + tmpreg1 &= (~0x00000007); + tmpreg1 |= ADC_SampleTime; + NS_ADCx->SAMPT3 = tmpreg1; + } + else if (ADC_Channel > ADC_CH_9) { /* if ADC_CH_10 ... ADC_CH_17 is selected */ + /* Get the old register value */ + tmpreg1 = NS_ADCx->SAMPT1; + /* Calculate the mask to clear */ + tmpreg2 = SAMPT1_SMP_SET << (3 * (ADC_Channel - 10)); + /* Clear the old channel sample time */ + tmpreg1 &= ~tmpreg2; + /* Calculate the mask to set */ + tmpreg2 = (uint32_t)ADC_SampleTime << (3 * (ADC_Channel - 10)); + /* Set the new channel sample time */ + tmpreg1 |= tmpreg2; + /* Store the new register value */ + NS_ADCx->SAMPT1 = tmpreg1; + } + else { /* ADC_Channel include in ADC_Channel_[0..9] */ + /* Get the old register value */ + tmpreg1 = NS_ADCx->SAMPT2; + /* Calculate the mask to clear */ + tmpreg2 = SAMPT2_SMP_SET << (3 * ADC_Channel); + /* Clear the old channel sample time */ + tmpreg1 &= ~tmpreg2; + /* Calculate the mask to set */ + tmpreg2 = (uint32_t)ADC_SampleTime << (3 * ADC_Channel); + /* Set the new channel sample time */ + tmpreg1 |= tmpreg2; + /* Store the new register value */ + NS_ADCx->SAMPT2 = tmpreg1; + } + /* For Rank 1 to 6 */ + if (Rank < 7) { + /* Get the old register value */ + tmpreg1 = NS_ADCx->RSEQ3; + /* Calculate the mask to clear */ + tmpreg2 = SQR3_SEQ_SET << (5 * (Rank - 1)); + /* Clear the old SQx bits for the selected rank */ + tmpreg1 &= ~tmpreg2; + /* Calculate the mask to set */ + tmpreg2 = (uint32_t)ADC_Channel << (5 * (Rank - 1)); + /* Set the SQx bits for the selected rank */ + tmpreg1 |= tmpreg2; + /* Store the new register value */ + NS_ADCx->RSEQ3 = tmpreg1; + } + /* For Rank 7 to 12 */ + else if (Rank < 13) { + /* Get the old register value */ + tmpreg1 = NS_ADCx->RSEQ2; + /* Calculate the mask to clear */ + tmpreg2 = SQR2_SEQ_SET << (5 * (Rank - 7)); + /* Clear the old SQx bits for the selected rank */ + tmpreg1 &= ~tmpreg2; + /* Calculate the mask to set */ + tmpreg2 = (uint32_t)ADC_Channel << (5 * (Rank - 7)); + /* Set the SQx bits for the selected rank */ + tmpreg1 |= tmpreg2; + /* Store the new register value */ + NS_ADCx->RSEQ2 = tmpreg1; + } + /* For Rank 13 to 16 */ + else { + /* Get the old register value */ + tmpreg1 = NS_ADCx->RSEQ1; + /* Calculate the mask to clear */ + tmpreg2 = SQR1_SEQ_SET << (5 * (Rank - 13)); + /* Clear the old SQx bits for the selected rank */ + tmpreg1 &= ~tmpreg2; + /* Calculate the mask to set */ + tmpreg2 = (uint32_t)ADC_Channel << (5 * (Rank - 13)); + /* Set the SQx bits for the selected rank */ + tmpreg1 |= tmpreg2; + /* Store the new register value */ + NS_ADCx->RSEQ1 = tmpreg1; + } +} + +/**================================================================ + * Start ADC conversion + ================================================================*/ +void ADC_EnableSoftwareStartConv(ADC_Module* NS_ADCx, uint32_t Cmd) { + if (Cmd != 0) + /* Enable the selected ADC conversion on external event and start the selected + ADC conversion */ + NS_ADCx->CTRL2 |= CTRL2_EXT_TRIG_SWSTART_SET; + else + /* Disable the selected ADC conversion on external event and stop the selected + ADC conversion */ + NS_ADCx->CTRL2 &= CTRL2_EXT_TRIG_SWSTART_RESET; +} + +/**================================================================ + * Get the ADC status logo bit + ================================================================*/ +uint32_t ADC_GetFlagStatus(ADC_Module* NS_ADCx, uint8_t ADC_FLAG) { + uint32_t bitstatus = 0; + + /* Check the status of the specified ADC flag */ + if ((NS_ADCx->STS & ADC_FLAG) != (uint8_t)0) + /* ADC_FLAG is set */ + bitstatus = 1; + else + /* ADC_FLAG is reset */ + bitstatus = 0; + /* Return the ADC_FLAG status */ + return bitstatus; +} + +/**================================================================ + * Clear status logo bit + ================================================================*/ +void ADC_ClearFlag(ADC_Module* NS_ADCx, uint8_t ADC_FLAG) { + /* Clear the selected ADC flags */ + NS_ADCx->STS &= ~(uint32_t)ADC_FLAG; +} + +/**================================================================ + * Get ADC sampling value + ================================================================*/ +uint16_t ADC_GetDat(ADC_Module* NS_ADCx) { + /* Return the selected ADC conversion value */ + return (uint16_t)NS_ADCx->DAT; +} + +/**================================================================ + * Initialize ADC clock + ================================================================*/ + +void enable_adc_clk(uint8_t cmd) { + uint32_t reg_temp; + if (cmd) { + /** Make PWR clock */ + reg_temp = ADC_RCC_APB1PCLKEN; + reg_temp |= RCC_APB1Periph_PWR; + ADC_RCC_APB1PCLKEN = reg_temp; + + /** Enable expansion mode */ + reg_temp = NS_PWR_CR3; + reg_temp |= 0x00000001; + NS_PWR_CR3 = reg_temp; + + /** Make ADC clock */ + reg_temp = ADC_RCC_AHBPCLKEN; + reg_temp |= ( RCC_AHB_PERIPH_ADC1 | + RCC_AHB_PERIPH_ADC2 | + RCC_AHB_PERIPH_ADC3 | + RCC_AHB_PERIPH_ADC4 ); + ADC_RCC_AHBPCLKEN = reg_temp; + + /** Reset */ + reg_temp = ADC_RCC_AHBPRST; + reg_temp |= ( RCC_AHB_PERIPH_ADC1 | + RCC_AHB_PERIPH_ADC2 | + RCC_AHB_PERIPH_ADC3 | + RCC_AHB_PERIPH_ADC4 ); + ADC_RCC_AHBPRST = reg_temp; // ADC module reunion position + ADC_RCC_AHBPRST &= ~reg_temp; // ADC module reset and clear + + /** Set ADC 1M clock */ + reg_temp = ADC_RCC_CFG2; + reg_temp &= CFG2_ADC1MSEL_RESET_MASK; // HSI as an ADC 1M clock + reg_temp &= CFG2_ADC1MPRES_RESET_MASK; + reg_temp |= 7 << 11; // Adc1m 8m / 8 = 1m + + /** Set the ADC PLL frequency split coefficient */ + reg_temp &= CFG2_ADCPLLPRES_RESET_MASK; + reg_temp |= RCC_ADCPLLCLK_DIV4; // ADC PLL frequency split coefficient + + /** Set the ADC HCLK frequency frequency coefficient */ + reg_temp &= CFG2_ADCHPRES_RESET_MASK; + reg_temp |= RCC_ADCHCLK_DIV4; // ADC HCLK frequency split coefficient + ADC_RCC_CFG2 = reg_temp; // Write to register + } + else { + /** Turn off the ADC clock */ + reg_temp = ADC_RCC_AHBPCLKEN; + reg_temp &= ~( RCC_AHB_PERIPH_ADC1 | + RCC_AHB_PERIPH_ADC2 | + RCC_AHB_PERIPH_ADC3 | + RCC_AHB_PERIPH_ADC4 ); + ADC_RCC_AHBPCLKEN = reg_temp; + } + +} + +/**================================================================ + * Initialize ADC peripheral parameters + ================================================================*/ +void ADC_Initial(ADC_Module* NS_ADCx) { + ADC_InitType ADC_InitStructure; + + /* ADC configuration ------------------------------------------------------*/ + ADC_InitStructure.WorkMode = ADC_WORKMODE_INDEPENDENT; // Independent mode + ADC_InitStructure.MultiChEn = 1; // Multi-channel enable + ADC_InitStructure.ContinueConvEn = 1; // Continuous enable + ADC_InitStructure.ExtTrigSelect = ADC_EXT_TRIGCONV_NONE; // Non-trigger + ADC_InitStructure.DatAlign = ADC_DAT_ALIGN_R; // Right alignment + ADC_InitStructure.ChsNumber = 2; // Scan channel number + ADC_Init(NS_ADCx, &ADC_InitStructure); + + /* ADC regular channel14 configuration */ + ADC_ConfigRegularChannel(NS_ADCx, ADC2_Channel_05_PC4, 2, ADC_SAMP_TIME_55CYCLES5); + ADC_ConfigRegularChannel(NS_ADCx, ADC2_Channel_12_PC5, 1, ADC_SAMP_TIME_55CYCLES5); + + /** 使能ADC DMA */ + ADC_EnableDMA(NS_ADCx, 1); + + /* Enable ADC */ + ADC_Enable(NS_ADCx, 1); + while(ADC_GetFlagStatusNew(NS_ADCx, ADC_FLAG_RDY) == 0); + + /* Start ADC calibration */ + ADC_StartCalibration(NS_ADCx); + while (ADC_GetCalibrationStatus(NS_ADCx)); + + /* Start ADC Software Conversion */ + ADC_EnableSoftwareStartConv(NS_ADCx, 1); +} + +/**================================================================ + * Single independent sampling + ================================================================*/ +uint16_t ADC_GetData(ADC_Module* NS_ADCx, uint8_t ADC_Channel) { + uint16_t dat; + + /** Set channel parameters */ + ADC_ConfigRegularChannel(NS_ADCx, ADC_Channel, 1, ADC_SAMP_TIME_239CYCLES5); + + /* Start ADC Software Conversion */ + ADC_EnableSoftwareStartConv(NS_ADCx, 1); + while(ADC_GetFlagStatus(NS_ADCx, ADC_FLAG_ENDC) == 0); + + ADC_ClearFlag(NS_ADCx, ADC_FLAG_ENDC); + ADC_ClearFlag(NS_ADCx, ADC_FLAG_STR); + dat = ADC_GetDat(NS_ADCx); + return dat; +} + +void DMA_DeInit(DMA_ChannelType* DMAyChx) { + + /* Disable the selected DMAy Channelx */ + DMAyChx->CHCFG &= (uint16_t)(~DMA_CHCFG1_CHEN); + + /* Reset DMAy Channelx control register */ + DMAyChx->CHCFG = 0; + + /* Reset DMAy Channelx remaining bytes register */ + DMAyChx->TXNUM = 0; + + /* Reset DMAy Channelx peripheral address register */ + DMAyChx->PADDR = 0; + + /* Reset DMAy Channelx memory address register */ + DMAyChx->MADDR = 0; + + if (DMAyChx == DMA1_CH1) { + /* Reset interrupt pending bits for DMA1 Channel1 */ + DMA1->INTCLR |= DMA1_CH1_INT_MASK; + } + else if (DMAyChx == DMA1_CH2) { + /* Reset interrupt pending bits for DMA1 Channel2 */ + DMA1->INTCLR |= DMA1_CH2_INT_MASK; + } + else if (DMAyChx == DMA1_CH3) { + /* Reset interrupt pending bits for DMA1 Channel3 */ + DMA1->INTCLR |= DMA1_CH3_INT_MASK; + } + else if (DMAyChx == DMA1_CH4) { + /* Reset interrupt pending bits for DMA1 Channel4 */ + DMA1->INTCLR |= DMA1_CH4_INT_MASK; + } + else if (DMAyChx == DMA1_CH5) { + /* Reset interrupt pending bits for DMA1 Channel5 */ + DMA1->INTCLR |= DMA1_CH5_INT_MASK; + } + else if (DMAyChx == DMA1_CH6) { + /* Reset interrupt pending bits for DMA1 Channel6 */ + DMA1->INTCLR |= DMA1_CH6_INT_MASK; + } + else if (DMAyChx == DMA1_CH7) { + /* Reset interrupt pending bits for DMA1 Channel7 */ + DMA1->INTCLR |= DMA1_CH7_INT_MASK; + } + else if (DMAyChx == DMA1_CH8) { + /* Reset interrupt pending bits for DMA1 Channel8 */ + DMA1->INTCLR |= DMA1_CH8_INT_MASK; + } + else if (DMAyChx == DMA2_CH1) { + /* Reset interrupt pending bits for DMA2 Channel1 */ + DMA2->INTCLR |= DMA2_CH1_INT_MASK; + } + else if (DMAyChx == DMA2_CH2) { + /* Reset interrupt pending bits for DMA2 Channel2 */ + DMA2->INTCLR |= DMA2_CH2_INT_MASK; + } + else if (DMAyChx == DMA2_CH3) { + /* Reset interrupt pending bits for DMA2 Channel3 */ + DMA2->INTCLR |= DMA2_CH3_INT_MASK; + } + else if (DMAyChx == DMA2_CH4) { + /* Reset interrupt pending bits for DMA2 Channel4 */ + DMA2->INTCLR |= DMA2_CH4_INT_MASK; + } + else if (DMAyChx == DMA2_CH5) { + /* Reset interrupt pending bits for DMA2 Channel5 */ + DMA2->INTCLR |= DMA2_CH5_INT_MASK; + } + else if (DMAyChx == DMA2_CH6) { + /* Reset interrupt pending bits for DMA2 Channel6 */ + DMA2->INTCLR |= DMA2_CH6_INT_MASK; + } + else if (DMAyChx == DMA2_CH7) { + /* Reset interrupt pending bits for DMA2 Channel7 */ + DMA2->INTCLR |= DMA2_CH7_INT_MASK; + } + else if (DMAyChx == DMA2_CH8) + /* Reset interrupt pending bits for DMA2 Channel8 */ + DMA2->INTCLR |= DMA2_CH8_INT_MASK; +} + +void DMA_Init(DMA_ChannelType* DMAyChx, DMA_InitType* DMA_InitParam) { + uint32_t tmpregister = 0; + + /*--------------------------- DMAy Channelx CHCFG Configuration --------------*/ + /* Get the DMAyChx CHCFG value */ + tmpregister = DMAyChx->CHCFG; + /* Clear MEM2MEM, PL, MSIZE, PSIZE, MINC, PINC, CIRC and DIR bits */ + tmpregister &= CCR_CLEAR_Mask; + /* Configure DMAy Channelx: data transfer, data size, priority level and mode */ + /* Set DIR bit according to Direction value */ + /* Set CIRC bit according to CircularMode value */ + /* Set PINC bit according to PeriphInc value */ + /* Set MINC bit according to DMA_MemoryInc value */ + /* Set PSIZE bits according to PeriphDataSize value */ + /* Set MSIZE bits according to MemDataSize value */ + /* Set PL bits according to Priority value */ + /* Set the MEM2MEM bit according to Mem2Mem value */ + tmpregister |= DMA_InitParam->Direction | DMA_InitParam->CircularMode | DMA_InitParam->PeriphInc + | DMA_InitParam->DMA_MemoryInc | DMA_InitParam->PeriphDataSize | DMA_InitParam->MemDataSize + | DMA_InitParam->Priority | DMA_InitParam->Mem2Mem; + + /* Write to DMAy Channelx CHCFG */ + DMAyChx->CHCFG = tmpregister; + + /*--------------------------- DMAy Channelx TXNUM Configuration --------------*/ + /* Write to DMAy Channelx TXNUM */ + DMAyChx->TXNUM = DMA_InitParam->BufSize; + + /*--------------------------- DMAy Channelx PADDR Configuration --------------*/ + /* Write to DMAy Channelx PADDR */ + DMAyChx->PADDR = DMA_InitParam->PeriphAddr; + + /*--------------------------- DMAy Channelx MADDR Configuration --------------*/ + /* Write to DMAy Channelx MADDR */ + DMAyChx->MADDR = DMA_InitParam->MemAddr; +} + +void DMA_EnableChannel(DMA_ChannelType* DMAyChx, uint32_t Cmd) { + if (Cmd != 0) { + /* Enable the selected DMAy Channelx */ + DMAyChx->CHCFG |= DMA_CHCFG1_CHEN; + } + else { + /* Disable the selected DMAy Channelx */ + DMAyChx->CHCFG &= (uint16_t)(~DMA_CHCFG1_CHEN); + } +} + +/**================================================================ + * Initialize the DMA of ADC + ================================================================*/ +void ADC_DMA_init() { + DMA_InitType DMA_InitStructure; + uint32_t reg_temp; + + /** Make DMA clock */ + reg_temp = ADC_RCC_AHBPCLKEN; + reg_temp |= ( RCC_AHB_PERIPH_DMA1 | + RCC_AHB_PERIPH_DMA2 ); + ADC_RCC_AHBPCLKEN = reg_temp; + + /* DMA channel configuration*/ + DMA_DeInit(USE_DMA_CH); + DMA_InitStructure.PeriphAddr = (uint32_t)&USE_ADC->DAT; + DMA_InitStructure.MemAddr = (uint32_t)adc_results; + DMA_InitStructure.Direction = DMA_DIR_PERIPH_SRC; // Peripheral-> memory + DMA_InitStructure.BufSize = 2; + DMA_InitStructure.PeriphInc = DMA_PERIPH_INC_DISABLE; + DMA_InitStructure.DMA_MemoryInc = DMA_MEM_INC_ENABLE; // Memory ++ + DMA_InitStructure.PeriphDataSize = DMA_PERIPH_DATA_SIZE_HALFWORD; + DMA_InitStructure.MemDataSize = DMA_MemoryDataSize_HalfWord; + DMA_InitStructure.CircularMode = DMA_MODE_CIRCULAR; + DMA_InitStructure.Priority = DMA_PRIORITY_HIGH; + DMA_InitStructure.Mem2Mem = DMA_M2M_DISABLE; + DMA_Init(USE_DMA_CH, &DMA_InitStructure); + + /* Enable DMA channel1 */ + DMA_EnableChannel(USE_DMA_CH, 1); +} + +/**============================================================================= + * n32g452 - end + ==============================================================================*/ + +#define NS_PINRT(V...) do{ SERIAL_ECHO_START(); SERIAL_ECHOLNPAIR(V); }while(0) + +// Init the AD in continuous capture mode +void MarlinHAL::adc_init() { + uint32_t reg_temp; + + //SERIAL_ECHO_MSG("\r\n n32g45x HAL_adc_init\r\n"); + + // GPIO settings + reg_temp = ADC_RCC_APB2PCLKEN; + reg_temp |= 0x0f; // Make PORT mouth clock + ADC_RCC_APB2PCLKEN = reg_temp; + + //reg_temp = NS_GPIOC_PL_CFG; + //reg_temp &= 0XFF00FFFF; + //NS_GPIOC_PL_CFG = reg_temp; // PC4/5 analog input + + enable_adc_clk(1); // Make ADC clock + ADC_DMA_init(); // DMA initialization + ADC_Initial(NS_ADC2); // ADC initialization + + delay(2); + //NS_PINRT("get adc1 = ", adc_results[0], "\r\n"); + //NS_PINRT("get adc2 = ", adc_results[1], "\r\n"); +} + +#endif // __STM32F1__ && VOXELAB_N32 diff --git a/Marlin/src/HAL/STM32F1/HAL_N32.h b/Marlin/src/HAL/STM32F1/HAL_N32.h new file mode 100644 index 000000000000..46ec7ba6db9c --- /dev/null +++ b/Marlin/src/HAL/STM32F1/HAL_N32.h @@ -0,0 +1,892 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 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 . + * + */ + +/** + * HAL for stm32duino.com based on Libmaple and compatible (STM32F1) + * Specifically for VOXELAB_N32 (N32G452). TODO: Rework for generic N32 MCU. + */ + +#include + +typedef struct { + uint32_t WorkMode; + uint32_t MultiChEn; + uint32_t ContinueConvEn; + uint32_t ExtTrigSelect; + uint32_t DatAlign; + uint8_t ChsNumber; +} ADC_InitType; + +typedef struct { + __IO uint32_t STS; + __IO uint32_t CTRL1; + __IO uint32_t CTRL2; + __IO uint32_t SAMPT1; + __IO uint32_t SAMPT2; + __IO uint32_t JOFFSET1; + __IO uint32_t JOFFSET2; + __IO uint32_t JOFFSET3; + __IO uint32_t JOFFSET4; + __IO uint32_t WDGHIGH; + __IO uint32_t WDGLOW; + __IO uint32_t RSEQ1; + __IO uint32_t RSEQ2; + __IO uint32_t RSEQ3; + __IO uint32_t JSEQ; + __IO uint32_t JDAT1; + __IO uint32_t JDAT2; + __IO uint32_t JDAT3; + __IO uint32_t JDAT4; + __IO uint32_t DAT; + __IO uint32_t DIFSEL; + __IO uint32_t CALFACT; + __IO uint32_t CTRL3; + __IO uint32_t SAMPT3; +} ADC_Module; + +#define NS_ADC1_BASE ((uint32_t)0x40020800) +#define NS_ADC2_BASE ((uint32_t)0x40020c00) +#define NS_ADC3_BASE ((uint32_t)0x40021800) +#define NS_ADC4_BASE ((uint32_t)0x40021c00) + +#define NS_ADC1 ((ADC_Module*)NS_ADC1_BASE) +#define NS_ADC2 ((ADC_Module*)NS_ADC2_BASE) +#define NS_ADC3 ((ADC_Module*)NS_ADC3_BASE) +#define NS_ADC4 ((ADC_Module*)NS_ADC4_BASE) + +#define ADC1_Channel_01_PA0 ((uint8_t)0x01) +#define ADC1_Channel_02_PA1 ((uint8_t)0x02) +#define ADC1_Channel_03_PA6 ((uint8_t)0x03) +#define ADC1_Channel_04_PA3 ((uint8_t)0x04) +#define ADC1_Channel_05_PF4 ((uint8_t)0x05) +#define ADC1_Channel_06_PC0 ((uint8_t)0x06) +#define ADC1_Channel_07_PC1 ((uint8_t)0x07) +#define ADC1_Channel_08_PC2 ((uint8_t)0x08) +#define ADC1_Channel_09_PC3 ((uint8_t)0x09) +#define ADC1_Channel_10_PF2 ((uint8_t)0x0A) +#define ADC1_Channel_11_PA2 ((uint8_t)0x0B) + +#define ADC2_Channel_01_PA4 ((uint8_t)0x01) +#define ADC2_Channel_02_PA5 ((uint8_t)0x02) +#define ADC2_Channel_03_PB1 ((uint8_t)0x03) +#define ADC2_Channel_04_PA7 ((uint8_t)0x04) +#define ADC2_Channel_05_PC4 ((uint8_t)0x05) +#define ADC2_Channel_06_PC0 ((uint8_t)0x06) +#define ADC2_Channel_07_PC1 ((uint8_t)0x07) +#define ADC2_Channel_08_PC2 ((uint8_t)0x08) +#define ADC2_Channel_09_PC3 ((uint8_t)0x09) +#define ADC2_Channel_10_PF2 ((uint8_t)0x0A) +#define ADC2_Channel_11_PA2 ((uint8_t)0x0B) +#define ADC2_Channel_12_PC5 ((uint8_t)0x0C) +#define ADC2_Channel_13_PB2 ((uint8_t)0x0D) + +#define ADC3_Channel_01_PB11 ((uint8_t)0x01) +#define ADC3_Channel_02_PE9 ((uint8_t)0x02) +#define ADC3_Channel_03_PE13 ((uint8_t)0x03) +#define ADC3_Channel_04_PE12 ((uint8_t)0x04) +#define ADC3_Channel_05_PB13 ((uint8_t)0x05) +#define ADC3_Channel_06_PE8 ((uint8_t)0x06) +#define ADC3_Channel_07_PD10 ((uint8_t)0x07) +#define ADC3_Channel_08_PD11 ((uint8_t)0x08) +#define ADC3_Channel_09_PD12 ((uint8_t)0x09) +#define ADC3_Channel_10_PD13 ((uint8_t)0x0A) +#define ADC3_Channel_11_PD14 ((uint8_t)0x0B) +#define ADC3_Channel_12_PB0 ((uint8_t)0x0C) +#define ADC3_Channel_13_PE7 ((uint8_t)0x0D) +#define ADC3_Channel_14_PE10 ((uint8_t)0x0E) +#define ADC3_Channel_15_PE11 ((uint8_t)0x0F) + +#define ADC4_Channel_01_PE14 ((uint8_t)0x01) +#define ADC4_Channel_02_PE15 ((uint8_t)0x02) +#define ADC4_Channel_03_PB12 ((uint8_t)0x03) +#define ADC4_Channel_04_PB14 ((uint8_t)0x04) +#define ADC4_Channel_05_PB15 ((uint8_t)0x05) +#define ADC4_Channel_06_PE8 ((uint8_t)0x06) +#define ADC4_Channel_07_PD10 ((uint8_t)0x07) +#define ADC4_Channel_08_PD11 ((uint8_t)0x08) +#define ADC4_Channel_09_PD12 ((uint8_t)0x09) +#define ADC4_Channel_10_PD13 ((uint8_t)0x0A) +#define ADC4_Channel_11_PD14 ((uint8_t)0x0B) +#define ADC4_Channel_12_PD8 ((uint8_t)0x0C) +#define ADC4_Channel_13_PD9 ((uint8_t)0x0D) + +#define ADC_RCC_BASE ((uint32_t)0x40021000) +#define ADC_RCC_CTRL *((uint32_t*)(ADC_RCC_BASE + 0x00)) +#define ADC_RCC_CFG *((uint32_t*)(ADC_RCC_BASE + 0x04)) +#define ADC_RCC_CLKINT *((uint32_t*)(ADC_RCC_BASE + 0x08)) +#define ADC_RCC_APB2PRST *((uint32_t*)(ADC_RCC_BASE + 0x0c)) +#define ADC_RCC_APB1PRST *((uint32_t*)(ADC_RCC_BASE + 0x10)) +#define ADC_RCC_AHBPCLKEN *((uint32_t*)(ADC_RCC_BASE + 0x14)) +#define ADC_RCC_APB2PCLKEN *((uint32_t*)(ADC_RCC_BASE + 0x18)) +#define ADC_RCC_APB1PCLKEN *((uint32_t*)(ADC_RCC_BASE + 0x1c)) +#define ADC_RCC_BDCTRL *((uint32_t*)(ADC_RCC_BASE + 0x20)) +#define ADC_RCC_CTRLSTS *((uint32_t*)(ADC_RCC_BASE + 0x24)) +#define ADC_RCC_AHBPRST *((uint32_t*)(ADC_RCC_BASE + 0x28)) +#define ADC_RCC_CFG2 *((uint32_t*)(ADC_RCC_BASE + 0x2c)) +#define ADC_RCC_CFG3 *((uint32_t*)(ADC_RCC_BASE + 0x30)) + +#define NS_PWR_CR3 *((uint32_t*)(0x40007000 + 0x0C)) +#define RCC_APB1Periph_PWR ((uint32_t)0x10000000) + +/////////////////////////////// +#define NS_GPIOA_BASE ((uint32_t)0x40010800) +#define NS_GPIOA_PL_CFG *((uint32_t*)(NS_GPIOA_BASE + 0x00)) +#define NS_GPIOA_PH_CFG *((uint32_t*)(NS_GPIOA_BASE + 0x04)) + +#define NS_GPIOC_BASE ((uint32_t)0x40011000) +#define NS_GPIOC_PL_CFG *((uint32_t*)(NS_GPIOC_BASE + 0x00)) +#define NS_GPIOC_PH_CFG *((uint32_t*)(NS_GPIOC_BASE + 0x04)) + +/* CFG2 register bit mask */ +#define CFG2_TIM18CLKSEL_SET_MASK ((uint32_t)0x20000000) +#define CFG2_TIM18CLKSEL_RESET_MASK ((uint32_t)0xDFFFFFFF) +#define CFG2_RNGCPRES_SET_MASK ((uint32_t)0x1F000000) +#define CFG2_RNGCPRES_RESET_MASK ((uint32_t)0xE0FFFFFF) +#define CFG2_ADC1MSEL_SET_MASK ((uint32_t)0x00000400) +#define CFG2_ADC1MSEL_RESET_MASK ((uint32_t)0xFFFFFBFF) +#define CFG2_ADC1MPRES_SET_MASK ((uint32_t)0x0000F800) +#define CFG2_ADC1MPRES_RESET_MASK ((uint32_t)0xFFFF07FF) +#define CFG2_ADCPLLPRES_SET_MASK ((uint32_t)0x000001F0) +#define CFG2_ADCPLLPRES_RESET_MASK ((uint32_t)0xFFFFFE0F) +#define CFG2_ADCHPRES_SET_MASK ((uint32_t)0x0000000F) +#define CFG2_ADCHPRES_RESET_MASK ((uint32_t)0xFFFFFFF0) + +#define RCC_ADCPLLCLK_DISABLE ((uint32_t)0xFFFFFEFF) +#define RCC_ADCPLLCLK_DIV1 ((uint32_t)0x00000100) +#define RCC_ADCPLLCLK_DIV2 ((uint32_t)0x00000110) +#define RCC_ADCPLLCLK_DIV4 ((uint32_t)0x00000120) +#define RCC_ADCPLLCLK_DIV6 ((uint32_t)0x00000130) +#define RCC_ADCPLLCLK_DIV8 ((uint32_t)0x00000140) +#define RCC_ADCPLLCLK_DIV10 ((uint32_t)0x00000150) +#define RCC_ADCPLLCLK_DIV12 ((uint32_t)0x00000160) +#define RCC_ADCPLLCLK_DIV16 ((uint32_t)0x00000170) +#define RCC_ADCPLLCLK_DIV32 ((uint32_t)0x00000180) +#define RCC_ADCPLLCLK_DIV64 ((uint32_t)0x00000190) +#define RCC_ADCPLLCLK_DIV128 ((uint32_t)0x000001A0) +#define RCC_ADCPLLCLK_DIV256 ((uint32_t)0x000001B0) +#define RCC_ADCPLLCLK_DIV_OTHERS ((uint32_t)0x000001C0) + +#define RCC_ADCHCLK_DIV1 ((uint32_t)0x00000000) +#define RCC_ADCHCLK_DIV2 ((uint32_t)0x00000001) +#define RCC_ADCHCLK_DIV4 ((uint32_t)0x00000002) +#define RCC_ADCHCLK_DIV6 ((uint32_t)0x00000003) +#define RCC_ADCHCLK_DIV8 ((uint32_t)0x00000004) +#define RCC_ADCHCLK_DIV10 ((uint32_t)0x00000005) +#define RCC_ADCHCLK_DIV12 ((uint32_t)0x00000006) +#define RCC_ADCHCLK_DIV16 ((uint32_t)0x00000007) +#define RCC_ADCHCLK_DIV32 ((uint32_t)0x00000008) +#define RCC_ADCHCLK_DIV_OTHERS ((uint32_t)0x00000008) + +#define SAMPT1_SMP_SET ((uint32_t)0x00000007) +#define SAMPT2_SMP_SET ((uint32_t)0x00000007) + +#define SQR4_SEQ_SET ((uint32_t)0x0000001F) +#define SQR3_SEQ_SET ((uint32_t)0x0000001F) +#define SQR2_SEQ_SET ((uint32_t)0x0000001F) +#define SQR1_SEQ_SET ((uint32_t)0x0000001F) + +#define CTRL1_CLR_MASK ((uint32_t)0xFFF0FEFF) +#define RSEQ1_CLR_MASK ((uint32_t)0xFF0FFFFF) +#define CTRL2_CLR_MASK ((uint32_t)0xFFF1F7FD) + +#define ADC_CH_0 ((uint8_t)0x00) +#define ADC_CH_1 ((uint8_t)0x01) +#define ADC_CH_2 ((uint8_t)0x02) +#define ADC_CH_3 ((uint8_t)0x03) +#define ADC_CH_4 ((uint8_t)0x04) +#define ADC_CH_5 ((uint8_t)0x05) +#define ADC_CH_6 ((uint8_t)0x06) +#define ADC_CH_7 ((uint8_t)0x07) +#define ADC_CH_8 ((uint8_t)0x08) +#define ADC_CH_9 ((uint8_t)0x09) +#define ADC_CH_10 ((uint8_t)0x0A) +#define ADC_CH_11 ((uint8_t)0x0B) +#define ADC_CH_12 ((uint8_t)0x0C) +#define ADC_CH_13 ((uint8_t)0x0D) +#define ADC_CH_14 ((uint8_t)0x0E) +#define ADC_CH_15 ((uint8_t)0x0F) +#define ADC_CH_16 ((uint8_t)0x10) +#define ADC_CH_17 ((uint8_t)0x11) +#define ADC_CH_18 ((uint8_t)0x12) + +#define ADC_WORKMODE_INDEPENDENT ((uint32_t)0x00000000) +#define ADC_WORKMODE_REG_INJECT_SIMULT ((uint32_t)0x00010000) +#define ADC_WORKMODE_REG_SIMULT_ALTER_TRIG ((uint32_t)0x00020000) +#define ADC_WORKMODE_INJ_SIMULT_FAST_INTERL ((uint32_t)0x00030000) +#define ADC_WORKMODE_INJ_SIMULT_SLOW_INTERL ((uint32_t)0x00040000) +#define ADC_WORKMODE_INJ_SIMULT ((uint32_t)0x00050000) +#define ADC_WORKMODE_REG_SIMULT ((uint32_t)0x00060000) +#define ADC_WORKMODE_FAST_INTERL ((uint32_t)0x00070000) +#define ADC_WORKMODE_SLOW_INTERL ((uint32_t)0x00080000) +#define ADC_WORKMODE_ALTER_TRIG ((uint32_t)0x00090000) + +#define ADC_EXT_TRIGCONV_T1_CC3 ((uint32_t)0x00040000) //!< For ADC1, ADC2 , ADC3 and ADC4 +#define ADC_EXT_TRIGCONV_NONE ((uint32_t)0x000E0000) //!< For ADC1, ADC2 , ADC3 and ADC4 + +#define ADC_DAT_ALIGN_R ((uint32_t)0x00000000) +#define ADC_DAT_ALIGN_L ((uint32_t)0x00000800) + +#define ADC_FLAG_RDY ((uint8_t)0x20) +#define ADC_FLAG_PD_RDY ((uint8_t)0x40) + +#define CTRL2_AD_ON_SET ((uint32_t)0x00000001) +#define CTRL2_AD_ON_RESET ((uint32_t)0xFFFFFFFE) + +#define CTRL2_CAL_SET ((uint32_t)0x00000004) + +/* ADC Software start mask */ +#define CTRL2_EXT_TRIG_SWSTART_SET ((uint32_t)0x00500000) +#define CTRL2_EXT_TRIG_SWSTART_RESET ((uint32_t)0xFFAFFFFF) + +#define ADC_SAMP_TIME_1CYCLES5 ((uint8_t)0x00) +#define ADC_SAMP_TIME_7CYCLES5 ((uint8_t)0x01) +#define ADC_SAMP_TIME_13CYCLES5 ((uint8_t)0x02) +#define ADC_SAMP_TIME_28CYCLES5 ((uint8_t)0x03) +#define ADC_SAMP_TIME_41CYCLES5 ((uint8_t)0x04) +#define ADC_SAMP_TIME_55CYCLES5 ((uint8_t)0x05) +#define ADC_SAMP_TIME_71CYCLES5 ((uint8_t)0x06) +#define ADC_SAMP_TIME_239CYCLES5 ((uint8_t)0x07) + +#define ADC_FLAG_AWDG ((uint8_t)0x01) +#define ADC_FLAG_ENDC ((uint8_t)0x02) +#define ADC_FLAG_JENDC ((uint8_t)0x04) +#define ADC_FLAG_JSTR ((uint8_t)0x08) +#define ADC_FLAG_STR ((uint8_t)0x10) +#define ADC_FLAG_EOC_ANY ((uint8_t)0x20) +#define ADC_FLAG_JEOC_ANY ((uint8_t)0x40) + +/* ADC DMA mask */ +#define CTRL2_DMA_SET ((uint32_t)0x00000100) +#define CTRL2_DMA_RESET ((uint32_t)0xFFFFFEFF) + +typedef struct { + uint32_t PeriphAddr; + uint32_t MemAddr; + uint32_t Direction; + uint32_t BufSize; + uint32_t PeriphInc; + uint32_t DMA_MemoryInc; + uint32_t PeriphDataSize; + uint32_t MemDataSize; + uint32_t CircularMode; + uint32_t Priority; + uint32_t Mem2Mem; +} DMA_InitType; + +typedef struct { + __IO uint32_t CHCFG; + __IO uint32_t TXNUM; + __IO uint32_t PADDR; + __IO uint32_t MADDR; + __IO uint32_t CHSEL; +} DMA_ChannelType; + +#define DMA_DIR_PERIPH_DST ((uint32_t)0x00000010) +#define DMA_DIR_PERIPH_SRC ((uint32_t)0x00000000) + +#define DMA_PERIPH_INC_ENABLE ((uint32_t)0x00000040) +#define DMA_PERIPH_INC_DISABLE ((uint32_t)0x00000000) + +#define DMA_MEM_INC_ENABLE ((uint32_t)0x00000080) +#define DMA_MEM_INC_DISABLE ((uint32_t)0x00000000) + +#define DMA_PERIPH_DATA_SIZE_BYTE ((uint32_t)0x00000000) +#define DMA_PERIPH_DATA_SIZE_HALFWORD ((uint32_t)0x00000100) +#define DMA_PERIPH_DATA_SIZE_WORD ((uint32_t)0x00000200) + +#define DMA_MemoryDataSize_Byte ((uint32_t)0x00000000) +#define DMA_MemoryDataSize_HalfWord ((uint32_t)0x00000400) +#define DMA_MemoryDataSize_Word ((uint32_t)0x00000800) + +#define DMA_MODE_CIRCULAR ((uint32_t)0x00000020) +#define DMA_MODE_NORMAL ((uint32_t)0x00000000) + +#define DMA_M2M_ENABLE ((uint32_t)0x00004000) +#define DMA_M2M_DISABLE ((uint32_t)0x00000000) + +#define RCC_AHB_PERIPH_DMA1 ((uint32_t)0x00000001) +#define RCC_AHB_PERIPH_DMA2 ((uint32_t)0x00000002) + +/******************* Bit definition for DMA_CHCFG1 register *******************/ +#define DMA_CHCFG1_CHEN ((uint16_t)0x0001) //!< Channel enable +#define DMA_CHCFG1_TXCIE ((uint16_t)0x0002) //!< Transfer complete interrupt enable +#define DMA_CHCFG1_HTXIE ((uint16_t)0x0004) //!< Half Transfer interrupt enable +#define DMA_CHCFG1_ERRIE ((uint16_t)0x0008) //!< Transfer error interrupt enable +#define DMA_CHCFG1_DIR ((uint16_t)0x0010) //!< Data transfer direction +#define DMA_CHCFG1_CIRC ((uint16_t)0x0020) //!< Circular mode +#define DMA_CHCFG1_PINC ((uint16_t)0x0040) //!< Peripheral increment mode +#define DMA_CHCFG1_MINC ((uint16_t)0x0080) //!< Memory increment mode + +#define NS_DMA1_BASE (0x40020000) +#define DMA1_CH1_BASE (NS_DMA1_BASE + 0x0008) +#define DMA1_CH2_BASE (NS_DMA1_BASE + 0x001C) +#define DMA1_CH3_BASE (NS_DMA1_BASE + 0x0030) +#define DMA1_CH4_BASE (NS_DMA1_BASE + 0x0044) +#define DMA1_CH5_BASE (NS_DMA1_BASE + 0x0058) +#define DMA1_CH6_BASE (NS_DMA1_BASE + 0x006C) +#define DMA1_CH7_BASE (NS_DMA1_BASE + 0x0080) +#define DMA1_CH8_BASE (NS_DMA1_BASE + 0x0094) + +#define NS_DMA2_BASE (0x40020400) +#define DMA2_CH1_BASE (NS_DMA2_BASE + 0x008) +#define DMA2_CH2_BASE (NS_DMA2_BASE + 0x01C) +#define DMA2_CH3_BASE (NS_DMA2_BASE + 0x0030) +#define DMA2_CH4_BASE (NS_DMA2_BASE + 0x0044) +#define DMA2_CH5_BASE (NS_DMA2_BASE + 0x0058) +#define DMA2_CH6_BASE (NS_DMA2_BASE + 0x006C) +#define DMA2_CH7_BASE (NS_DMA2_BASE + 0x0080) +#define DMA2_CH8_BASE (NS_DMA2_BASE + 0x0094) + +#define DMA1 ((DMA_Module*)NS_DMA1_BASE) +#define DMA2 ((DMA_Module*)NS_DMA2_BASE) +#define DMA1_CH1 ((DMA_ChannelType*)DMA1_CH1_BASE) +#define DMA1_CH2 ((DMA_ChannelType*)DMA1_CH2_BASE) +#define DMA1_CH3 ((DMA_ChannelType*)DMA1_CH3_BASE) +#define DMA1_CH4 ((DMA_ChannelType*)DMA1_CH4_BASE) +#define DMA1_CH5 ((DMA_ChannelType*)DMA1_CH5_BASE) +#define DMA1_CH6 ((DMA_ChannelType*)DMA1_CH6_BASE) +#define DMA1_CH7 ((DMA_ChannelType*)DMA1_CH7_BASE) +#define DMA1_CH8 ((DMA_ChannelType*)DMA1_CH8_BASE) +#define DMA2_CH1 ((DMA_ChannelType*)DMA2_CH1_BASE) +#define DMA2_CH2 ((DMA_ChannelType*)DMA2_CH2_BASE) +#define DMA2_CH3 ((DMA_ChannelType*)DMA2_CH3_BASE) +#define DMA2_CH4 ((DMA_ChannelType*)DMA2_CH4_BASE) +#define DMA2_CH5 ((DMA_ChannelType*)DMA2_CH5_BASE) +#define DMA2_CH6 ((DMA_ChannelType*)DMA2_CH6_BASE) +#define DMA2_CH7 ((DMA_ChannelType*)DMA2_CH7_BASE) +#define DMA2_CH8 ((DMA_ChannelType*)DMA2_CH8_BASE) + +/******************************************************************************/ +/* */ +/* DMA Controller */ +/* */ +/******************************************************************************/ + +/******************* Bit definition for DMA_INTSTS register ********************/ +#define DMA_INTSTS_GLBF1 ((uint32_t)0x00000001) //!< Channel 1 Global interrupt flag +#define DMA_INTSTS_TXCF1 ((uint32_t)0x00000002) //!< Channel 1 Transfer Complete flag +#define DMA_INTSTS_HTXF1 ((uint32_t)0x00000004) //!< Channel 1 Half Transfer flag +#define DMA_INTSTS_ERRF1 ((uint32_t)0x00000008) //!< Channel 1 Transfer Error flag +#define DMA_INTSTS_GLBF2 ((uint32_t)0x00000010) //!< Channel 2 Global interrupt flag +#define DMA_INTSTS_TXCF2 ((uint32_t)0x00000020) //!< Channel 2 Transfer Complete flag +#define DMA_INTSTS_HTXF2 ((uint32_t)0x00000040) //!< Channel 2 Half Transfer flag +#define DMA_INTSTS_ERRF2 ((uint32_t)0x00000080) //!< Channel 2 Transfer Error flag +#define DMA_INTSTS_GLBF3 ((uint32_t)0x00000100) //!< Channel 3 Global interrupt flag +#define DMA_INTSTS_TXCF3 ((uint32_t)0x00000200) //!< Channel 3 Transfer Complete flag +#define DMA_INTSTS_HTXF3 ((uint32_t)0x00000400) //!< Channel 3 Half Transfer flag +#define DMA_INTSTS_ERRF3 ((uint32_t)0x00000800) //!< Channel 3 Transfer Error flag +#define DMA_INTSTS_GLBF4 ((uint32_t)0x00001000) //!< Channel 4 Global interrupt flag +#define DMA_INTSTS_TXCF4 ((uint32_t)0x00002000) //!< Channel 4 Transfer Complete flag +#define DMA_INTSTS_HTXF4 ((uint32_t)0x00004000) //!< Channel 4 Half Transfer flag +#define DMA_INTSTS_ERRF4 ((uint32_t)0x00008000) //!< Channel 4 Transfer Error flag +#define DMA_INTSTS_GLBF5 ((uint32_t)0x00010000) //!< Channel 5 Global interrupt flag +#define DMA_INTSTS_TXCF5 ((uint32_t)0x00020000) //!< Channel 5 Transfer Complete flag +#define DMA_INTSTS_HTXF5 ((uint32_t)0x00040000) //!< Channel 5 Half Transfer flag +#define DMA_INTSTS_ERRF5 ((uint32_t)0x00080000) //!< Channel 5 Transfer Error flag +#define DMA_INTSTS_GLBF6 ((uint32_t)0x00100000) //!< Channel 6 Global interrupt flag +#define DMA_INTSTS_TXCF6 ((uint32_t)0x00200000) //!< Channel 6 Transfer Complete flag +#define DMA_INTSTS_HTXF6 ((uint32_t)0x00400000) //!< Channel 6 Half Transfer flag +#define DMA_INTSTS_ERRF6 ((uint32_t)0x00800000) //!< Channel 6 Transfer Error flag +#define DMA_INTSTS_GLBF7 ((uint32_t)0x01000000) //!< Channel 7 Global interrupt flag +#define DMA_INTSTS_TXCF7 ((uint32_t)0x02000000) //!< Channel 7 Transfer Complete flag +#define DMA_INTSTS_HTXF7 ((uint32_t)0x04000000) //!< Channel 7 Half Transfer flag +#define DMA_INTSTS_ERRF7 ((uint32_t)0x08000000) //!< Channel 7 Transfer Error flag +#define DMA_INTSTS_GLBF8 ((uint32_t)0x10000000) //!< Channel 7 Global interrupt flag +#define DMA_INTSTS_TXCF8 ((uint32_t)0x20000000) //!< Channel 7 Transfer Complete flag +#define DMA_INTSTS_HTXF8 ((uint32_t)0x40000000) //!< Channel 7 Half Transfer flag +#define DMA_INTSTS_ERRF8 ((uint32_t)0x80000000) //!< Channel 7 Transfer Error flag + +/******************* Bit definition for DMA_INTCLR register *******************/ +#define DMA_INTCLR_CGLBF1 ((uint32_t)0x00000001) //!< Channel 1 Global interrupt clear +#define DMA_INTCLR_CTXCF1 ((uint32_t)0x00000002) //!< Channel 1 Transfer Complete clear +#define DMA_INTCLR_CHTXF1 ((uint32_t)0x00000004) //!< Channel 1 Half Transfer clear +#define DMA_INTCLR_CERRF1 ((uint32_t)0x00000008) //!< Channel 1 Transfer Error clear +#define DMA_INTCLR_CGLBF2 ((uint32_t)0x00000010) //!< Channel 2 Global interrupt clear +#define DMA_INTCLR_CTXCF2 ((uint32_t)0x00000020) //!< Channel 2 Transfer Complete clear +#define DMA_INTCLR_CHTXF2 ((uint32_t)0x00000040) //!< Channel 2 Half Transfer clear +#define DMA_INTCLR_CERRF2 ((uint32_t)0x00000080) //!< Channel 2 Transfer Error clear +#define DMA_INTCLR_CGLBF3 ((uint32_t)0x00000100) //!< Channel 3 Global interrupt clear +#define DMA_INTCLR_CTXCF3 ((uint32_t)0x00000200) //!< Channel 3 Transfer Complete clear +#define DMA_INTCLR_CHTXF3 ((uint32_t)0x00000400) //!< Channel 3 Half Transfer clear +#define DMA_INTCLR_CERRF3 ((uint32_t)0x00000800) //!< Channel 3 Transfer Error clear +#define DMA_INTCLR_CGLBF4 ((uint32_t)0x00001000) //!< Channel 4 Global interrupt clear +#define DMA_INTCLR_CTXCF4 ((uint32_t)0x00002000) //!< Channel 4 Transfer Complete clear +#define DMA_INTCLR_CHTXF4 ((uint32_t)0x00004000) //!< Channel 4 Half Transfer clear +#define DMA_INTCLR_CERRF4 ((uint32_t)0x00008000) //!< Channel 4 Transfer Error clear +#define DMA_INTCLR_CGLBF5 ((uint32_t)0x00010000) //!< Channel 5 Global interrupt clear +#define DMA_INTCLR_CTXCF5 ((uint32_t)0x00020000) //!< Channel 5 Transfer Complete clear +#define DMA_INTCLR_CHTXF5 ((uint32_t)0x00040000) //!< Channel 5 Half Transfer clear +#define DMA_INTCLR_CERRF5 ((uint32_t)0x00080000) //!< Channel 5 Transfer Error clear +#define DMA_INTCLR_CGLBF6 ((uint32_t)0x00100000) //!< Channel 6 Global interrupt clear +#define DMA_INTCLR_CTXCF6 ((uint32_t)0x00200000) //!< Channel 6 Transfer Complete clear +#define DMA_INTCLR_CHTXF6 ((uint32_t)0x00400000) //!< Channel 6 Half Transfer clear +#define DMA_INTCLR_CERRF6 ((uint32_t)0x00800000) //!< Channel 6 Transfer Error clear +#define DMA_INTCLR_CGLBF7 ((uint32_t)0x01000000) //!< Channel 7 Global interrupt clear +#define DMA_INTCLR_CTXCF7 ((uint32_t)0x02000000) //!< Channel 7 Transfer Complete clear +#define DMA_INTCLR_CHTXF7 ((uint32_t)0x04000000) //!< Channel 7 Half Transfer clear +#define DMA_INTCLR_CERRF7 ((uint32_t)0x08000000) //!< Channel 7 Transfer Error clear +#define DMA_INTCLR_CGLBF8 ((uint32_t)0x10000000) //!< Channel 7 Global interrupt clear +#define DMA_INTCLR_CTXCF8 ((uint32_t)0x20000000) //!< Channel 7 Transfer Complete clear +#define DMA_INTCLR_CHTXF8 ((uint32_t)0x40000000) //!< Channel 7 Half Transfer clear +#define DMA_INTCLR_CERRF8 ((uint32_t)0x80000000) //!< Channel 7 Transfer Error clear + +/******************* Bit definition for DMA_CHCFG1 register *******************/ +#define DMA_CHCFG1_CHEN ((uint16_t)0x0001) //!< Channel enable +#define DMA_CHCFG1_TXCIE ((uint16_t)0x0002) //!< Transfer complete interrupt enable +#define DMA_CHCFG1_HTXIE ((uint16_t)0x0004) //!< Half Transfer interrupt enable +#define DMA_CHCFG1_ERRIE ((uint16_t)0x0008) //!< Transfer error interrupt enable +#define DMA_CHCFG1_DIR ((uint16_t)0x0010) //!< Data transfer direction +#define DMA_CHCFG1_CIRC ((uint16_t)0x0020) //!< Circular mode +#define DMA_CHCFG1_PINC ((uint16_t)0x0040) //!< Peripheral increment mode +#define DMA_CHCFG1_MINC ((uint16_t)0x0080) //!< Memory increment mode + +#define DMA_CHCFG1_PSIZE ((uint16_t)0x0300) //!< PSIZE[1:0] bits (Peripheral size) +#define DMA_CHCFG1_PSIZE_0 ((uint16_t)0x0100) //!< Bit 0 +#define DMA_CHCFG1_PSIZE_1 ((uint16_t)0x0200) //!< Bit 1 + +#define DMA_CHCFG1_MSIZE ((uint16_t)0x0C00) //!< MSIZE[1:0] bits (Memory size) +#define DMA_CHCFG1_MSIZE_0 ((uint16_t)0x0400) //!< Bit 0 +#define DMA_CHCFG1_MSIZE_1 ((uint16_t)0x0800) //!< Bit 1 + +#define DMA_CHCFG1_PRIOLVL ((uint16_t)0x3000) //!< PL[1:0] bits(Channel Priority level) +#define DMA_CHCFG1_PRIOLVL_0 ((uint16_t)0x1000) //!< Bit 0 +#define DMA_CHCFG1_PRIOLVL_1 ((uint16_t)0x2000) //!< Bit 1 + +#define DMA_CHCFG1_MEM2MEM ((uint16_t)0x4000) //!< Memory to memory mode + +/******************* Bit definition for DMA_CHCFG2 register *******************/ +#define DMA_CHCFG2_CHEN ((uint16_t)0x0001) //!< Channel enable +#define DMA_CHCFG2_TXCIE ((uint16_t)0x0002) //!< Transfer complete interrupt enable +#define DMA_CHCFG2_HTXIE ((uint16_t)0x0004) //!< Half Transfer interrupt enable +#define DMA_CHCFG2_ERRIE ((uint16_t)0x0008) //!< Transfer error interrupt enable +#define DMA_CHCFG2_DIR ((uint16_t)0x0010) //!< Data transfer direction +#define DMA_CHCFG2_CIRC ((uint16_t)0x0020) //!< Circular mode +#define DMA_CHCFG2_PINC ((uint16_t)0x0040) //!< Peripheral increment mode +#define DMA_CHCFG2_MINC ((uint16_t)0x0080) //!< Memory increment mode + +#define DMA_CHCFG2_PSIZE ((uint16_t)0x0300) //!< PSIZE[1:0] bits (Peripheral size) +#define DMA_CHCFG2_PSIZE_0 ((uint16_t)0x0100) //!< Bit 0 +#define DMA_CHCFG2_PSIZE_1 ((uint16_t)0x0200) //!< Bit 1 + +#define DMA_CHCFG2_MSIZE ((uint16_t)0x0C00) //!< MSIZE[1:0] bits (Memory size) +#define DMA_CHCFG2_MSIZE_0 ((uint16_t)0x0400) //!< Bit 0 +#define DMA_CHCFG2_MSIZE_1 ((uint16_t)0x0800) //!< Bit 1 + +#define DMA_CHCFG2_PRIOLVL ((uint16_t)0x3000) //!< PL[1:0] bits (Channel Priority level) +#define DMA_CHCFG2_PRIOLVL_0 ((uint16_t)0x1000) //!< Bit 0 +#define DMA_CHCFG2_PRIOLVL_1 ((uint16_t)0x2000) //!< Bit 1 + +#define DMA_CHCFG2_MEM2MEM ((uint16_t)0x4000) //!< Memory to memory mode + +/******************* Bit definition for DMA_CHCFG3 register *******************/ +#define DMA_CHCFG3_CHEN ((uint16_t)0x0001) //!< Channel enable +#define DMA_CHCFG3_TXCIE ((uint16_t)0x0002) //!< Transfer complete interrupt enable +#define DMA_CHCFG3_HTXIE ((uint16_t)0x0004) //!< Half Transfer interrupt enable +#define DMA_CHCFG3_ERRIE ((uint16_t)0x0008) //!< Transfer error interrupt enable +#define DMA_CHCFG3_DIR ((uint16_t)0x0010) //!< Data transfer direction +#define DMA_CHCFG3_CIRC ((uint16_t)0x0020) //!< Circular mode +#define DMA_CHCFG3_PINC ((uint16_t)0x0040) //!< Peripheral increment mode +#define DMA_CHCFG3_MINC ((uint16_t)0x0080) //!< Memory increment mode + +#define DMA_CHCFG3_PSIZE ((uint16_t)0x0300) //!< PSIZE[1:0] bits (Peripheral size) +#define DMA_CHCFG3_PSIZE_0 ((uint16_t)0x0100) //!< Bit 0 +#define DMA_CHCFG3_PSIZE_1 ((uint16_t)0x0200) //!< Bit 1 + +#define DMA_CHCFG3_MSIZE ((uint16_t)0x0C00) //!< MSIZE[1:0] bits (Memory size) +#define DMA_CHCFG3_MSIZE_0 ((uint16_t)0x0400) //!< Bit 0 +#define DMA_CHCFG3_MSIZE_1 ((uint16_t)0x0800) //!< Bit 1 + +#define DMA_CHCFG3_PRIOLVL ((uint16_t)0x3000) //!< PL[1:0] bits (Channel Priority level) +#define DMA_CHCFG3_PRIOLVL_0 ((uint16_t)0x1000) //!< Bit 0 +#define DMA_CHCFG3_PRIOLVL_1 ((uint16_t)0x2000) //!< Bit 1 + +#define DMA_CHCFG3_MEM2MEM ((uint16_t)0x4000) //!< Memory to memory mode + +/*!<****************** Bit definition for DMA_CHCFG4 register *******************/ +#define DMA_CHCFG4_CHEN ((uint16_t)0x0001) //!< Channel enable +#define DMA_CHCFG4_TXCIE ((uint16_t)0x0002) //!< Transfer complete interrupt enable +#define DMA_CHCFG4_HTXIE ((uint16_t)0x0004) //!< Half Transfer interrupt enable +#define DMA_CHCFG4_ERRIE ((uint16_t)0x0008) //!< Transfer error interrupt enable +#define DMA_CHCFG4_DIR ((uint16_t)0x0010) //!< Data transfer direction +#define DMA_CHCFG4_CIRC ((uint16_t)0x0020) //!< Circular mode +#define DMA_CHCFG4_PINC ((uint16_t)0x0040) //!< Peripheral increment mode +#define DMA_CHCFG4_MINC ((uint16_t)0x0080) //!< Memory increment mode + +#define DMA_CHCFG4_PSIZE ((uint16_t)0x0300) //!< PSIZE[1:0] bits (Peripheral size) +#define DMA_CHCFG4_PSIZE_0 ((uint16_t)0x0100) //!< Bit 0 +#define DMA_CHCFG4_PSIZE_1 ((uint16_t)0x0200) //!< Bit 1 + +#define DMA_CHCFG4_MSIZE ((uint16_t)0x0C00) //!< MSIZE[1:0] bits (Memory size) +#define DMA_CHCFG4_MSIZE_0 ((uint16_t)0x0400) //!< Bit 0 +#define DMA_CHCFG4_MSIZE_1 ((uint16_t)0x0800) //!< Bit 1 + +#define DMA_CHCFG4_PRIOLVL ((uint16_t)0x3000) //!< PL[1:0] bits (Channel Priority level) +#define DMA_CHCFG4_PRIOLVL_0 ((uint16_t)0x1000) //!< Bit 0 +#define DMA_CHCFG4_PRIOLVL_1 ((uint16_t)0x2000) //!< Bit 1 + +#define DMA_CHCFG4_MEM2MEM ((uint16_t)0x4000) //!< Memory to memory mode + +/****************** Bit definition for DMA_CHCFG5 register *******************/ +#define DMA_CHCFG5_CHEN ((uint16_t)0x0001) //!< Channel enable +#define DMA_CHCFG5_TXCIE ((uint16_t)0x0002) //!< Transfer complete interrupt enable +#define DMA_CHCFG5_HTXIE ((uint16_t)0x0004) //!< Half Transfer interrupt enable +#define DMA_CHCFG5_ERRIE ((uint16_t)0x0008) //!< Transfer error interrupt enable +#define DMA_CHCFG5_DIR ((uint16_t)0x0010) //!< Data transfer direction +#define DMA_CHCFG5_CIRC ((uint16_t)0x0020) //!< Circular mode +#define DMA_CHCFG5_PINC ((uint16_t)0x0040) //!< Peripheral increment mode +#define DMA_CHCFG5_MINC ((uint16_t)0x0080) //!< Memory increment mode + +#define DMA_CHCFG5_PSIZE ((uint16_t)0x0300) //!< PSIZE[1:0] bits (Peripheral size) +#define DMA_CHCFG5_PSIZE_0 ((uint16_t)0x0100) //!< Bit 0 +#define DMA_CHCFG5_PSIZE_1 ((uint16_t)0x0200) //!< Bit 1 + +#define DMA_CHCFG5_MSIZE ((uint16_t)0x0C00) //!< MSIZE[1:0] bits (Memory size) +#define DMA_CHCFG5_MSIZE_0 ((uint16_t)0x0400) //!< Bit 0 +#define DMA_CHCFG5_MSIZE_1 ((uint16_t)0x0800) //!< Bit 1 + +#define DMA_CHCFG5_PRIOLVL ((uint16_t)0x3000) //!< PL[1:0] bits (Channel Priority level) +#define DMA_CHCFG5_PRIOLVL_0 ((uint16_t)0x1000) //!< Bit 0 +#define DMA_CHCFG5_PRIOLVL_1 ((uint16_t)0x2000) //!< Bit 1 + +#define DMA_CHCFG5_MEM2MEM ((uint16_t)0x4000) //!< Memory to memory mode enable + +/******************* Bit definition for DMA_CHCFG6 register *******************/ +#define DMA_CHCFG6_CHEN ((uint16_t)0x0001) //!< Channel enable +#define DMA_CHCFG6_TXCIE ((uint16_t)0x0002) //!< Transfer complete interrupt enable +#define DMA_CHCFG6_HTXIE ((uint16_t)0x0004) //!< Half Transfer interrupt enable +#define DMA_CHCFG6_ERRIE ((uint16_t)0x0008) //!< Transfer error interrupt enable +#define DMA_CHCFG6_DIR ((uint16_t)0x0010) //!< Data transfer direction +#define DMA_CHCFG6_CIRC ((uint16_t)0x0020) //!< Circular mode +#define DMA_CHCFG6_PINC ((uint16_t)0x0040) //!< Peripheral increment mode +#define DMA_CHCFG6_MINC ((uint16_t)0x0080) //!< Memory increment mode + +#define DMA_CHCFG6_PSIZE ((uint16_t)0x0300) //!< PSIZE[1:0] bits (Peripheral size) +#define DMA_CHCFG6_PSIZE_0 ((uint16_t)0x0100) //!< Bit 0 +#define DMA_CHCFG6_PSIZE_1 ((uint16_t)0x0200) //!< Bit 1 + +#define DMA_CHCFG6_MSIZE ((uint16_t)0x0C00) //!< MSIZE[1:0] bits (Memory size) +#define DMA_CHCFG6_MSIZE_0 ((uint16_t)0x0400) //!< Bit 0 +#define DMA_CHCFG6_MSIZE_1 ((uint16_t)0x0800) //!< Bit 1 + +#define DMA_CHCFG6_PRIOLVL ((uint16_t)0x3000) //!< PL[1:0] bits (Channel Priority level) +#define DMA_CHCFG6_PRIOLVL_0 ((uint16_t)0x1000) //!< Bit 0 +#define DMA_CHCFG6_PRIOLVL_1 ((uint16_t)0x2000) //!< Bit 1 + +#define DMA_CHCFG6_MEM2MEM ((uint16_t)0x4000) //!< Memory to memory mode + +/******************* Bit definition for DMA_CHCFG7 register *******************/ +#define DMA_CHCFG7_CHEN ((uint16_t)0x0001) //!< Channel enable +#define DMA_CHCFG7_TXCIE ((uint16_t)0x0002) //!< Transfer complete interrupt enable +#define DMA_CHCFG7_HTXIE ((uint16_t)0x0004) //!< Half Transfer interrupt enable +#define DMA_CHCFG7_ERRIE ((uint16_t)0x0008) //!< Transfer error interrupt enable +#define DMA_CHCFG7_DIR ((uint16_t)0x0010) //!< Data transfer direction +#define DMA_CHCFG7_CIRC ((uint16_t)0x0020) //!< Circular mode +#define DMA_CHCFG7_PINC ((uint16_t)0x0040) //!< Peripheral increment mode +#define DMA_CHCFG7_MINC ((uint16_t)0x0080) //!< Memory increment mode + +#define DMA_CHCFG7_PSIZE , ((uint16_t)0x0300) //!< PSIZE[1:0] bits (Peripheral size) +#define DMA_CHCFG7_PSIZE_0 ((uint16_t)0x0100) //!< Bit 0 +#define DMA_CHCFG7_PSIZE_1 ((uint16_t)0x0200) //!< Bit 1 + +#define DMA_CHCFG7_MSIZE ((uint16_t)0x0C00) //!< MSIZE[1:0] bits (Memory size) +#define DMA_CHCFG7_MSIZE_0 ((uint16_t)0x0400) //!< Bit 0 +#define DMA_CHCFG7_MSIZE_1 ((uint16_t)0x0800) //!< Bit 1 + +#define DMA_CHCFG7_PRIOLVL ((uint16_t)0x3000) //!< PL[1:0] bits (Channel Priority level) +#define DMA_CHCFG7_PRIOLVL_0 ((uint16_t)0x1000) //!< Bit 0 +#define DMA_CHCFG7_PRIOLVL_1 ((uint16_t)0x2000) //!< Bit 1 + +#define DMA_CHCFG7_MEM2MEM ((uint16_t)0x4000) //!< Memory to memory mode enable + +/******************* Bit definition for DMA_CHCFG8 register *******************/ +#define DMA_CHCFG8_CHEN ((uint16_t)0x0001) //!< Channel enable +#define DMA_CHCFG8_TXCIE ((uint16_t)0x0002) //!< Transfer complete interrupt enable +#define DMA_CHCFG8_HTXIE ((uint16_t)0x0004) //!< Half Transfer interrupt enable +#define DMA_CHCFG8_ERRIE ((uint16_t)0x0008) //!< Transfer error interrupt enable +#define DMA_CHCFG8_DIR ((uint16_t)0x0010) //!< Data transfer direction +#define DMA_CHCFG8_CIRC ((uint16_t)0x0020) //!< Circular mode +#define DMA_CHCFG8_PINC ((uint16_t)0x0040) //!< Peripheral increment mode +#define DMA_CHCFG8_MINC ((uint16_t)0x0080) //!< Memory increment mode + +#define DMA_CHCFG8_PSIZE , ((uint16_t)0x0300) //!< PSIZE[1:0] bits (Peripheral size) +#define DMA_CHCFG8_PSIZE_0 ((uint16_t)0x0100) //!< Bit 0 +#define DMA_CHCFG8_PSIZE_1 ((uint16_t)0x0200) //!< Bit 1 + +#define DMA_CHCFG8_MSIZE ((uint16_t)0x0C00) //!< MSIZE[1:0] bits (Memory size) +#define DMA_CHCFG8_MSIZE_0 ((uint16_t)0x0400) //!< Bit 0 +#define DMA_CHCFG8_MSIZE_1 ((uint16_t)0x0800) //!< Bit 1 + +#define DMA_CHCFG8_PRIOLVL ((uint16_t)0x3000) //!< PL[1:0] bits (Channel Priority level) +#define DMA_CHCFG8_PRIOLVL_0 ((uint16_t)0x1000) //!< Bit 0 +#define DMA_CHCFG8_PRIOLVL_1 ((uint16_t)0x2000) //!< Bit 1 + +#define DMA_CHCFG8_MEM2MEM ((uint16_t)0x4000) //!< Memory to memory mode enable + +/****************** Bit definition for DMA_TXNUM1 register ******************/ +#define DMA_TXNUM1_NDTX ((uint16_t)0xFFFF) //!< Number of data to Transfer + +/****************** Bit definition for DMA_TXNUM2 register ******************/ +#define DMA_TXNUM2_NDTX ((uint16_t)0xFFFF) //!< Number of data to Transfer + +/****************** Bit definition for DMA_TXNUM3 register ******************/ +#define DMA_TXNUM3_NDTX ((uint16_t)0xFFFF) //!< Number of data to Transfer + +/****************** Bit definition for DMA_TXNUM4 register ******************/ +#define DMA_TXNUM4_NDTX ((uint16_t)0xFFFF) //!< Number of data to Transfer + +/****************** Bit definition for DMA_TXNUM5 register ******************/ +#define DMA_TXNUM5_NDTX ((uint16_t)0xFFFF) //!< Number of data to Transfer + +/****************** Bit definition for DMA_TXNUM6 register ******************/ +#define DMA_TXNUM6_NDTX ((uint16_t)0xFFFF) //!< Number of data to Transfer + +/****************** Bit definition for DMA_TXNUM7 register ******************/ +#define DMA_TXNUM7_NDTX ((uint16_t)0xFFFF) //!< Number of data to Transfer + +/****************** Bit definition for DMA_TXNUM8 register ******************/ +#define DMA_TXNUM8_NDTX ((uint16_t)0xFFFF) //!< Number of data to Transfer + +/****************** Bit definition for DMA_PADDR1 register *******************/ +#define DMA_PADDR1_ADDR ((uint32_t)0xFFFFFFFF) //!< Peripheral Address + +/****************** Bit definition for DMA_PADDR2 register *******************/ +#define DMA_PADDR2_ADDR ((uint32_t)0xFFFFFFFF) //!< Peripheral Address + +/****************** Bit definition for DMA_PADDR3 register *******************/ +#define DMA_PADDR3_ADDR ((uint32_t)0xFFFFFFFF) //!< Peripheral Address + +/****************** Bit definition for DMA_PADDR4 register *******************/ +#define DMA_PADDR4_ADDR ((uint32_t)0xFFFFFFFF) //!< Peripheral Address + +/****************** Bit definition for DMA_PADDR5 register *******************/ +#define DMA_PADDR5_ADDR ((uint32_t)0xFFFFFFFF) //!< Peripheral Address + +/****************** Bit definition for DMA_PADDR6 register *******************/ +#define DMA_PADDR6_ADDR ((uint32_t)0xFFFFFFFF) //!< Peripheral Address + +/****************** Bit definition for DMA_PADDR7 register *******************/ +#define DMA_PADDR7_ADDR ((uint32_t)0xFFFFFFFF) //!< Peripheral Address + +/****************** Bit definition for DMA_PADDR8 register *******************/ +#define DMA_PADDR8_ADDR ((uint32_t)0xFFFFFFFF) //!< Peripheral Address + +/****************** Bit definition for DMA_MADDR1 register *******************/ +#define DMA_MADDR1_ADDR ((uint32_t)0xFFFFFFFF) //!< Memory Address + +/****************** Bit definition for DMA_MADDR2 register *******************/ +#define DMA_MADDR2_ADDR ((uint32_t)0xFFFFFFFF) //!< Memory Address + +/****************** Bit definition for DMA_MADDR3 register *******************/ +#define DMA_MADDR3_ADDR ((uint32_t)0xFFFFFFFF) //!< Memory Address + +/****************** Bit definition for DMA_MADDR4 register *******************/ +#define DMA_MADDR4_ADDR ((uint32_t)0xFFFFFFFF) //!< Memory Address + +/****************** Bit definition for DMA_MADDR5 register *******************/ +#define DMA_MADDR5_ADDR ((uint32_t)0xFFFFFFFF) //!< Memory Address + +/****************** Bit definition for DMA_MADDR6 register *******************/ +#define DMA_MADDR6_ADDR ((uint32_t)0xFFFFFFFF) //!< Memory Address + +/****************** Bit definition for DMA_MADDR7 register *******************/ +#define DMA_MADDR7_ADDR ((uint32_t)0xFFFFFFFF) //!< Memory Address + +/****************** Bit definition for DMA_MADDR8 register *******************/ +#define DMA_MADDR8_ADDR ((uint32_t)0xFFFFFFFF) //!< Memory Address + +/****************** Bit definition for DMA_CHSEL1 register *******************/ +#define DMA_CHSEL1_CH_SEL ((uint32_t)0x0000003F) //!< Channel Select + +/****************** Bit definition for DMA_CHSEL2 register *******************/ +#define DMA_CHSEL2_CH_SEL ((uint32_t)0x0000003F) //!< Channel Select + +/****************** Bit definition for DMA_CHSEL3 register *******************/ +#define DMA_CHSEL3_CH_SEL ((uint32_t)0x0000003F) //!< Channel Select + +/****************** Bit definition for DMA_CHSEL4 register *******************/ +#define DMA_CHSEL4_CH_SEL ((uint32_t)0x0000003F) //!< Channel Select + +/****************** Bit definition for DMA_CHSEL5 register *******************/ +#define DMA_CHSEL5_CH_SEL ((uint32_t)0x0000003F) //!< Channel Select + +/****************** Bit definition for DMA_CHSEL6 register *******************/ +#define DMA_CHSEL6_CH_SEL ((uint32_t)0x0000003F) //!< Channel Select + +/****************** Bit definition for DMA_CHSEL7 register *******************/ +#define DMA_CHSEL7_CH_SEL ((uint32_t)0x0000003F) //!< Channel Select + +/****************** Bit definition for DMA_CHSEL8 register *******************/ +#define DMA_CHSEL8_CH_SEL ((uint32_t)0x0000003F) //!< Channel Select + +/****************** Bit definition for DMA_CHMAPEN register *******************/ +#define DMA_CHMAPEN_MAP_EN ((uint32_t)0x00000001) //!< Channel Map Enable + +/* DMA1 Channelx interrupt pending bit masks */ +#define DMA1_CH1_INT_MASK ((uint32_t)(DMA_INTSTS_GLBF1 | DMA_INTSTS_TXCF1 | DMA_INTSTS_HTXF1 | DMA_INTSTS_ERRF1)) +#define DMA1_CH2_INT_MASK ((uint32_t)(DMA_INTSTS_GLBF2 | DMA_INTSTS_TXCF2 | DMA_INTSTS_HTXF2 | DMA_INTSTS_ERRF2)) +#define DMA1_CH3_INT_MASK ((uint32_t)(DMA_INTSTS_GLBF3 | DMA_INTSTS_TXCF3 | DMA_INTSTS_HTXF3 | DMA_INTSTS_ERRF3)) +#define DMA1_CH4_INT_MASK ((uint32_t)(DMA_INTSTS_GLBF4 | DMA_INTSTS_TXCF4 | DMA_INTSTS_HTXF4 | DMA_INTSTS_ERRF4)) +#define DMA1_CH5_INT_MASK ((uint32_t)(DMA_INTSTS_GLBF5 | DMA_INTSTS_TXCF5 | DMA_INTSTS_HTXF5 | DMA_INTSTS_ERRF5)) +#define DMA1_CH6_INT_MASK ((uint32_t)(DMA_INTSTS_GLBF6 | DMA_INTSTS_TXCF6 | DMA_INTSTS_HTXF6 | DMA_INTSTS_ERRF6)) +#define DMA1_CH7_INT_MASK ((uint32_t)(DMA_INTSTS_GLBF7 | DMA_INTSTS_TXCF7 | DMA_INTSTS_HTXF7 | DMA_INTSTS_ERRF7)) +#define DMA1_CH8_INT_MASK ((uint32_t)(DMA_INTSTS_GLBF8 | DMA_INTSTS_TXCF8 | DMA_INTSTS_HTXF8 | DMA_INTSTS_ERRF8)) + +/* DMA2 Channelx interrupt pending bit masks */ +#define DMA2_CH1_INT_MASK ((uint32_t)(DMA_INTSTS_GLBF1 | DMA_INTSTS_TXCF1 | DMA_INTSTS_HTXF1 | DMA_INTSTS_ERRF1)) +#define DMA2_CH2_INT_MASK ((uint32_t)(DMA_INTSTS_GLBF2 | DMA_INTSTS_TXCF2 | DMA_INTSTS_HTXF2 | DMA_INTSTS_ERRF2)) +#define DMA2_CH3_INT_MASK ((uint32_t)(DMA_INTSTS_GLBF3 | DMA_INTSTS_TXCF3 | DMA_INTSTS_HTXF3 | DMA_INTSTS_ERRF3)) +#define DMA2_CH4_INT_MASK ((uint32_t)(DMA_INTSTS_GLBF4 | DMA_INTSTS_TXCF4 | DMA_INTSTS_HTXF4 | DMA_INTSTS_ERRF4)) +#define DMA2_CH5_INT_MASK ((uint32_t)(DMA_INTSTS_GLBF5 | DMA_INTSTS_TXCF5 | DMA_INTSTS_HTXF5 | DMA_INTSTS_ERRF5)) +#define DMA2_CH6_INT_MASK ((uint32_t)(DMA_INTSTS_GLBF6 | DMA_INTSTS_TXCF6 | DMA_INTSTS_HTXF6 | DMA_INTSTS_ERRF6)) +#define DMA2_CH7_INT_MASK ((uint32_t)(DMA_INTSTS_GLBF7 | DMA_INTSTS_TXCF7 | DMA_INTSTS_HTXF7 | DMA_INTSTS_ERRF7)) +#define DMA2_CH8_INT_MASK ((uint32_t)(DMA_INTSTS_GLBF8 | DMA_INTSTS_TXCF8 | DMA_INTSTS_HTXF8 | DMA_INTSTS_ERRF8)) + +typedef struct { + __IO uint32_t INTSTS; + __IO uint32_t INTCLR; + __IO DMA_ChannelType DMA_Channel[8]; + __IO uint32_t CHMAPEN; +} DMA_Module; + +#define RCC_AHB_PERIPH_ADC1 ((uint32_t)0x00001000) +#define RCC_AHB_PERIPH_ADC2 ((uint32_t)0x00002000) +#define RCC_AHB_PERIPH_ADC3 ((uint32_t)0x00004000) +#define RCC_AHB_PERIPH_ADC4 ((uint32_t)0x00008000) + +void ADC_Init(ADC_Module* NS_ADCx, ADC_InitType* ADC_InitStruct); + +/**================================================================ + * ADC reset + ================================================================*/ +void ADC_DeInit(ADC_Module* NS_ADCx); + +/**================================================================ + * ADC module enable + ================================================================*/ +void ADC_Enable(ADC_Module* NS_ADCx, uint32_t Cmd); + +/**================================================================ + * Get the ADC status logo bit + ================================================================*/ +uint32_t ADC_GetFlagStatusNew(ADC_Module* NS_ADCx, uint8_t ADC_FLAG_NEW); + +/**================================================================ + * Open ADC calibration + ================================================================*/ +void ADC_StartCalibration(ADC_Module* NS_ADCx); + +/**================================================================ + * Enable ADC DMA + ================================================================*/ +void ADC_EnableDMA(ADC_Module* NS_ADCx, uint32_t Cmd); + +/**================================================================ + * Configure ADC interrupt enable enable + ================================================================*/ +void ADC_ConfigInt(ADC_Module* NS_ADCx, uint16_t ADC_IT, uint32_t Cmd); + +/**================================================================ + * Get ADC calibration status + ================================================================*/ +uint32_t ADC_GetCalibrationStatus(ADC_Module* NS_ADCx); + +/**================================================================ + * Configure the ADC channel + ================================================================*/ +void ADC_ConfigRegularChannel(ADC_Module* NS_ADCx, uint8_t ADC_Channel, uint8_t Rank, uint8_t ADC_SampleTime); + +/**================================================================ + * Start ADC conversion + ================================================================*/ +void ADC_EnableSoftwareStartConv(ADC_Module* NS_ADCx, uint32_t Cmd); + +/**================================================================ + * Get the ADC status logo bit + ================================================================*/ +uint32_t ADC_GetFlagStatus(ADC_Module* NS_ADCx, uint8_t ADC_FLAG); + +/**================================================================ + * Clear status logo bit + ================================================================*/ +void ADC_ClearFlag(ADC_Module* NS_ADCx, uint8_t ADC_FLAG); + +/**================================================================ + * Get ADC sampling value + ================================================================*/ +uint16_t ADC_GetDat(ADC_Module* NS_ADCx); + +//////////////////////////////////////////////////////////////////////////////// + +typedef struct { + __IO uint32_t CR; /* Completely compatible */ + __IO uint32_t CFGR; /* Not compatible: ADC frequency is not set here */ + __IO uint32_t CIR; /* Completely compatible */ + + __IO uint32_t APB2RSTR; /* Completely compatible */ + __IO uint32_t APB1RSTR; /* Completely compatible */ + + __IO uint32_t AHBENR; /* Not compatible: ADC clock enables settings here */ + __IO uint32_t APB2ENR; /* Not compatible: ADC clock enables to be here */ + __IO uint32_t APB1ENR; /* compatible */ + __IO uint32_t BDCR; /* compatible */ + __IO uint32_t CSR; /* compatible */ + + + __IO uint32_t AHBRSTR; /* Not compatible, ADC reset here settings */ + __IO uint32_t CFGR2; /* Not compatible, ADC clock settings here */ + __IO uint32_t CFGR3; /* Not compatible, add a new register */ + +} RCC_TypeDef; + +#define RCC ((RCC_TypeDef *) ADC_RCC_BASE) + +/**================================================================ + * Initialize ADC clock + ================================================================*/ + +void enable_adc_clk(uint8_t cmd); + +/**================================================================ + * Initialize ADC peripheral parameters + ================================================================*/ +void ADC_Initial(ADC_Module* NS_ADCx); + +/**================================================================ + * Single independent sampling + ================================================================*/ +uint16_t ADC_GetData(ADC_Module* NS_ADCx, uint8_t ADC_Channel); + +void DMA_DeInit(DMA_ChannelType* DMAyChx); + +#define CCR_CLEAR_Mask ((uint32_t)0xFFFF800F) + +void DMA_Init(DMA_ChannelType* DMAyChx, DMA_InitType* DMA_InitParam); + +void DMA_EnableChannel(DMA_ChannelType* DMAyChx, uint32_t Cmd); + +#define USE_ADC NS_ADC2 +#define USE_DMA_CH DMA1_CH8 + +/**================================================================ + * Initialize the DMA of ADC + ================================================================*/ +void ADC_DMA_init(); diff --git a/Marlin/src/HAL/STM32F1/MarlinSerial.cpp b/Marlin/src/HAL/STM32F1/MarlinSerial.cpp index 8c468e9609f8..3b26b630df22 100644 --- a/Marlin/src/HAL/STM32F1/MarlinSerial.cpp +++ b/Marlin/src/HAL/STM32F1/MarlinSerial.cpp @@ -28,7 +28,7 @@ // Copied from ~/.platformio/packages/framework-arduinoststm32-maple/STM32F1/system/libmaple/usart_private.h // Changed to handle Emergency Parser -static __always_inline void my_usart_irq(ring_buffer *rb, ring_buffer *wb, usart_reg_map *regs, MSerialT &serial) { +FORCE_INLINE void my_usart_irq(ring_buffer *rb, ring_buffer *wb, usart_reg_map *regs, MSerialT &serial) { /* Handle RXNEIE and TXEIE interrupts. * RXNE signifies availability of a byte in DR. * diff --git a/Marlin/src/HAL/STM32F1/adc.h b/Marlin/src/HAL/STM32F1/adc.h new file mode 100644 index 000000000000..25f4a7ce16d1 --- /dev/null +++ b/Marlin/src/HAL/STM32F1/adc.h @@ -0,0 +1,57 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 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 . + * + */ +#pragma once + +/** + * HAL for stm32duino.com based on Libmaple and compatible (STM32F1) + * + * adc.h - Define enumerated indices for enabled ADC Features + */ + +#include "../../inc/MarlinConfig.h" + +enum ADCIndex : uint8_t { + OPTITEM(HAS_TEMP_ADC_0, TEMP_0 ) + OPTITEM(HAS_TEMP_ADC_1, TEMP_1 ) + OPTITEM(HAS_TEMP_ADC_2, TEMP_2 ) + OPTITEM(HAS_TEMP_ADC_3, TEMP_3 ) + OPTITEM(HAS_TEMP_ADC_4, TEMP_4 ) + OPTITEM(HAS_TEMP_ADC_5, TEMP_5 ) + OPTITEM(HAS_TEMP_ADC_6, TEMP_6 ) + OPTITEM(HAS_TEMP_ADC_7, TEMP_7 ) + OPTITEM(HAS_TEMP_ADC_BED, TEMP_BED ) + OPTITEM(HAS_TEMP_ADC_CHAMBER, TEMP_CHAMBER ) + OPTITEM(HAS_TEMP_ADC_PROBE, TEMP_PROBE ) + OPTITEM(HAS_TEMP_ADC_COOLER, TEMP_COOLER ) + OPTITEM(HAS_TEMP_ADC_BOARD, TEMP_BOARD ) + OPTITEM(HAS_TEMP_ADC_SOC, TEMP_SOC ) + OPTITEM(FILAMENT_WIDTH_SENSOR, FILWIDTH ) + OPTITEM(HAS_ADC_BUTTONS, ADC_KEY ) + OPTITEM(HAS_JOY_ADC_X, JOY_X ) + OPTITEM(HAS_JOY_ADC_Y, JOY_Y ) + OPTITEM(HAS_JOY_ADC_Z, JOY_Z ) + OPTITEM(POWER_MONITOR_CURRENT, POWERMON_CURRENT ) + OPTITEM(POWER_MONITOR_VOLTAGE, POWERMON_VOLTAGE ) + ADC_COUNT +}; + +extern uint16_t adc_results[ADC_COUNT]; diff --git a/Marlin/src/HAL/STM32F1/timers.h b/Marlin/src/HAL/STM32F1/timers.h index f92c32c2a3ef..89a609c2c39d 100644 --- a/Marlin/src/HAL/STM32F1/timers.h +++ b/Marlin/src/HAL/STM32F1/timers.h @@ -80,7 +80,7 @@ typedef uint16_t hal_timer_t; //#define MF_TIMER_TEMP 4 // 2->4, Timer 2 for Stepper Current PWM #endif -#if MB(BTT_SKR_MINI_E3_V1_0, BTT_SKR_E3_DIP, BTT_SKR_MINI_E3_V1_2, MKS_ROBIN_LITE, MKS_ROBIN_E3D, MKS_ROBIN_E3) +#if MB(BTT_SKR_MINI_E3_V1_0, BTT_SKR_E3_DIP, BTT_SKR_MINI_E3_V1_2, MKS_ROBIN_LITE, MKS_ROBIN_E3D, MKS_ROBIN_E3, VOXELAB_AQUILA) // SKR Mini E3 boards use PA8 as FAN0_PIN, so TIMER 1 is used for Fan PWM. #ifdef STM32_HIGH_DENSITY #define MF_TIMER_SERVO0 8 // tone.cpp uses Timer 4 diff --git a/Marlin/src/core/boards.h b/Marlin/src/core/boards.h index 0c685460bf08..c55035e8f075 100644 --- a/Marlin/src/core/boards.h +++ b/Marlin/src/core/boards.h @@ -400,6 +400,7 @@ #define BOARD_TRIGORILLA_V006 5068 // Trigorilla V0.0.6 (GD32F103RE) #define BOARD_KEDI_CONTROLLER_V1_2 5069 // EDUTRONICS Kedi Controller V1.2 (STM32F103RC) #define BOARD_MD_D301 5070 // Mingda D2 DZ301 V1.0 (STM32F103ZE) +#define BOARD_VOXELAB_AQUILA 5071 // Voxelab Aquila V1.0.0/V1.0.1 (GD32F103RC / N32G455RE / STM32F103RE) // // ARM Cortex-M4F @@ -514,7 +515,7 @@ // // HC32 ARM Cortex-M4 // -#define BOARD_AQUILA_V101 7200 // Aquila V1.0.1 as found in the Voxelab Aquila X2 +#define BOARD_AQUILA_V101 7200 // Voxelab Aquila V1.0.0/V1.0.1/V1.0.2/V1.0.3 as found in the Voxelab Aquila X2 and C2 // // Custom board diff --git a/Marlin/src/inc/Warnings.cpp b/Marlin/src/inc/Warnings.cpp index 606d308c08cf..3efbb67a0cd5 100644 --- a/Marlin/src/inc/Warnings.cpp +++ b/Marlin/src/inc/Warnings.cpp @@ -33,6 +33,13 @@ #if ENABLED(MARLIN_DEV_MODE) #warning "WARNING! Disable MARLIN_DEV_MODE for the final build!" + #ifdef __LONG_MAX__ + #if __LONG_MAX__ > __INT_MAX__ + #warning "The 'long' type is larger than the 'int' type on this platform." + #else + #warning "The 'long' type is the same as the 'int' type on this platform." + #endif + #endif #endif #if ENABLED(LA_DEBUG) @@ -777,6 +784,13 @@ #warning "Place the firmware bin file in a folder named 'STM32F4_UPDATE' on the SD card. Install with 'M936 V2'." #endif +/** + * Voxelab N32 bootloader + */ +#ifdef SDCARD_FLASH_LIMIT_256K + #warning "This board has 512K but the bootloader can only flash firmware.bin <= 256K. ICSP required for full 512K capacity." +#endif + /** * ProUI Boot Screen Duration */ diff --git a/Marlin/src/lcd/e3v2/creality/dwin.cpp b/Marlin/src/lcd/e3v2/creality/dwin.cpp index f3935f39dd5e..274390189107 100644 --- a/Marlin/src/lcd/e3v2/creality/dwin.cpp +++ b/Marlin/src/lcd/e3v2/creality/dwin.cpp @@ -103,7 +103,6 @@ #define UNITFDIGITS 1 #define MINUNITMULT pow(10, UNITFDIGITS) -#define ENCODER_WAIT_MS 20 #define DWIN_VAR_UPDATE_INTERVAL 1024 #define DWIN_SCROLL_UPDATE_INTERVAL SEC_TO_MS(2) #define DWIN_REMAIN_TIME_UPDATE_INTERVAL SEC_TO_MS(20) diff --git a/Marlin/src/lcd/e3v2/proui/dwinui.cpp b/Marlin/src/lcd/e3v2/proui/dwinui.cpp index 7e94fc3e5633..23cd1736fdf4 100644 --- a/Marlin/src/lcd/e3v2/proui/dwinui.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwinui.cpp @@ -181,7 +181,7 @@ void DWINUI::drawString(uint16_t color, const char * const string, uint16_t rlim // iNum: Number of digits // x/y: Upper-left coordinate // value: Integer value -void DWINUI::drawInt(uint8_t bShow, bool signedMode, fontid_t fid, uint16_t color, uint16_t bColor, uint8_t iNum, uint16_t x, uint16_t y, int32_t value) { +void DWINUI::drawInt(uint8_t bShow, bool signedMode, fontid_t fid, uint16_t color, uint16_t bColor, uint8_t iNum, uint16_t x, uint16_t y, long value) { char nstr[10]; sprintf_P(nstr, PSTR("%*li"), (signedMode ? iNum + 1 : iNum), value); dwinDrawString(bShow, fid, color, bColor, x, y, nstr); diff --git a/Marlin/src/lcd/e3v2/proui/dwinui.h b/Marlin/src/lcd/e3v2/proui/dwinui.h index 015e66c8cb71..636b4fbbad72 100644 --- a/Marlin/src/lcd/e3v2/proui/dwinui.h +++ b/Marlin/src/lcd/e3v2/proui/dwinui.h @@ -338,7 +338,7 @@ namespace DWINUI { // iNum: Number of digits // x/y: Upper-left coordinate // value: Integer value - void drawInt(uint8_t bShow, bool signedMode, fontid_t fid, uint16_t color, uint16_t bColor, uint8_t iNum, uint16_t x, uint16_t y, int32_t value); + void drawInt(uint8_t bShow, bool signedMode, fontid_t fid, uint16_t color, uint16_t bColor, uint8_t iNum, uint16_t x, uint16_t y, long value); // Draw a positive integer inline void drawInt(uint8_t bShow, fontid_t fid, uint16_t color, uint16_t bColor, uint8_t iNum, uint16_t x, uint16_t y, long value) { diff --git a/Marlin/src/lcd/e3v2/proui/menus.cpp b/Marlin/src/lcd/e3v2/proui/menus.cpp index d537bc5ae663..9f48ff03b748 100644 --- a/Marlin/src/lcd/e3v2/proui/menus.cpp +++ b/Marlin/src/lcd/e3v2/proui/menus.cpp @@ -107,7 +107,7 @@ void onDrawMenuItem(MenuItem* menuitem, int8_t line) { if (menuitem->icon) DWINUI::drawIcon(menuitem->icon, ICOX, MBASE(line) - 3); if (menuitem->frameid) dwinFrameAreaCopy(menuitem->frameid, menuitem->frame.left, menuitem->frame.top, menuitem->frame.right, menuitem->frame.bottom, LBLX, MBASE(line)); - else if (menuitem->caption) + else DWINUI::drawString(LBLX, MBASE(line) - 1, menuitem->caption); dwinDrawHLine(hmiData.colorSplitLine, 16, MYPOS(line + 1), 240); } diff --git a/Marlin/src/pins/gd32f1/pins_VOXELAB_AQUILA.h b/Marlin/src/pins/gd32f1/pins_VOXELAB_AQUILA.h new file mode 100644 index 000000000000..2f3998b45fcf --- /dev/null +++ b/Marlin/src/pins/gd32f1/pins_VOXELAB_AQUILA.h @@ -0,0 +1,39 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 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 . + * + */ +#pragma once + +/** + * FFP0173_Aquila_Main_Board_V1.0.1 (GD32F103RC / N32G455RE) + * + * Uses CREALITY V4 (STM32F103RE / STM32F103RC) board pin assignments + */ + +#define BOARD_INFO_NAME "Aquila v1.0.1" +#ifndef DEFAULT_MACHINE_NAME + #define DEFAULT_MACHINE_NAME "Aquila" +#endif + +#define INLINE_USART_IRQ + +#define NO_MAPLE_WARNING // Disable warning when compiling with Maple env + +#include "../stm32f1/pins_CREALITY_V4.h" diff --git a/Marlin/src/pins/hc32f4/pins_AQUILA_101.h b/Marlin/src/pins/hc32f4/pins_AQUILA_101.h index a9dfb9b0f9b8..32268f4cf84e 100644 --- a/Marlin/src/pins/hc32f4/pins_AQUILA_101.h +++ b/Marlin/src/pins/hc32f4/pins_AQUILA_101.h @@ -22,7 +22,7 @@ #pragma once // -// Voxelab Aquila V1.0.1 and V1.0.2 (HC32F460) as found in the Voxelab Aquila X2 +// Voxelab Aquila V1.0.0/V1.0.1/V1.0.2/V1.0.3 (HC32F460) as found in the Voxelab Aquila X2 and C2 // #include "env_validate.h" @@ -152,7 +152,23 @@ #define EXP1_07_PIN PB12 // EN2 #define EXP1_08_PIN PB15 // EN1 -#if ANY(HAS_DWIN_E3V2, IS_DWIN_MARLINUI) +#if ENABLED(CR10_STOCKDISPLAY) // LCD used for C2 +#undef LCD_SERIAL_PORT +#define LCD_SERIAL_PORT 1 + + #define LCD_PINS_RS EXP1_07_PIN + #define LCD_PINS_EN EXP1_08_PIN + #define LCD_PINS_D4 EXP1_06_PIN + + #define BTN_ENC EXP1_02_PIN + #define BTN_EN1 EXP1_03_PIN + #define BTN_EN2 EXP1_05_PIN + + #ifndef HAS_PIN_27_BOARD + #define BEEPER_PIN EXP1_01_PIN + #endif + +#elif ANY(HAS_DWIN_E3V2, IS_DWIN_MARLINUI) // LCD used for X2 /** * Display pinout (display side, so RX/TX are swapped) * diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index 1618078f45f6..28ae5e8d42f8 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -700,6 +700,8 @@ #include "stm32f1/pins_KEDI_CONTROLLER_V1_2.h" // STM32F1 env:STM32F103RC_btt env:STM32F103RC_btt_USB env:STM32F103RC_btt_maple env:STM32F103RC_btt_USB_maple #elif MB(MD_D301) #include "stm32f1/pins_MD_D301.h" // STM32F1 env:mingda_d301 env:mingda_d301_maple +#elif MB(VOXELAB_AQUILA) + #include "gd32f1/pins_VOXELAB_AQUILA.h" // GD32F1, N32G4, STM32F1 env:GD32F103RC_voxelab_maple env:N32G455RE_voxelab_maple env:STM32F103RE_creality_maple env:STM32F103RE_creality // // ARM Cortex-M4F diff --git a/ini/hc32.ini b/ini/hc32.ini index 676f9e19b6e5..56c6b3f2e5a2 100644 --- a/ini/hc32.ini +++ b/ini/hc32.ini @@ -50,7 +50,6 @@ build_flags = -D __PANIC_SHORT_FILENAMES # Use short filenames in core panic output -D __OMIT_PANIC_MESSAGE # Omit panic messages in core panic output - # Drivers and Middleware required by the HC32 HAL board_build.ddl.ots = true board_build.ddl.sdioc = true @@ -80,7 +79,7 @@ extends = HC32F460_base board_build.ld_args.flash_size = 512K # -# Aquila V1.0.1 Mainboard, as found in the Voxelab Aquila X2 +# Voxelab Aquila V1.0.0/V1.0.1/V1.0.2/V1.0.3 as found in the Voxelab Aquila X2 & C2 # [env:HC32F460C_aquila_101] extends = HC32F460C_base diff --git a/ini/stm32f1-maple.ini b/ini/stm32f1-maple.ini index 4c4d938fe6df..a113d1a7b154 100644 --- a/ini/stm32f1-maple.ini +++ b/ini/stm32f1-maple.ini @@ -142,6 +142,29 @@ extends = env:STM32F103RE_creality_maple board_build.address = 0x08010000 board_build.ldscript = crealityPro.ld +# +# Voxelab Aquila V1.0.1 +# +# GD32F103RC_voxelab_maple ........ GD32F103RCT6 with 256K +# N32G455RE_voxelab_maple ......... N32G455REL7 - Requires ICSP to flash over 256K +# +[env:GD32F103RC_voxelab_maple] +extends = env:STM32F103RC_maple +build_flags = ${env:STM32F103RC_maple.build_flags} -DTEMP_TIMER_CHAN=4 +board_build.address = 0x08007000 +board_build.ldscript = creality256k.ld +debug_tool = jlink +upload_protocol = jlink + +[env:N32G455RE_voxelab_maple] +extends = env:STM32F103RE_maple +build_flags = ${env:STM32F103RE_maple.build_flags} -DTEMP_TIMER_CHAN=4 + -DVOXELAB_N32 -DSDCARD_FLASH_LIMIT_256K +board_build.address = 0x08007000 +board_build.ldscript = creality.ld +debug_tool = jlink +upload_protocol = jlink + # # BigTreeTech SKR Mini E3 V2.0 & DIP / SKR CR6 (STM32F103RET6 ARM Cortex-M3) # From 483b8dcc05c2f0ef4c83d8ec7f4f0065ec9d240f Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Wed, 6 Dec 2023 06:06:45 +0000 Subject: [PATCH 62/77] [cron] Bump distribution date (2023-12-06) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 0c5d41c1b2e8..607eafb75039 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2023-12-05" +//#define STRING_DISTRIBUTION_DATE "2023-12-06" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index f24452835866..f7f83ac194bd 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2023-12-05" + #define STRING_DISTRIBUTION_DATE "2023-12-06" #endif /** From fe7203ee5533ecb0436a301aea46bedeff311624 Mon Sep 17 00:00:00 2001 From: Keith Bennett <13375512+thisiskeithb@users.noreply.github.com> Date: Thu, 7 Dec 2023 20:35:34 -0800 Subject: [PATCH 63/77] =?UTF-8?q?=F0=9F=94=A8=20Use=20PIO=20versioning=20(?= =?UTF-8?q?including=20HC32)=20(#26512)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/hc32f4/env_validate.h | 5 ++++- ini/hc32.ini | 2 +- ini/stm32f4.ini | 2 +- ini/stm32g0.ini | 6 +++--- 4 files changed, 9 insertions(+), 6 deletions(-) diff --git a/Marlin/src/pins/hc32f4/env_validate.h b/Marlin/src/pins/hc32f4/env_validate.h index 7883bc03c743..9bbc999fd6ee 100644 --- a/Marlin/src/pins/hc32f4/env_validate.h +++ b/Marlin/src/pins/hc32f4/env_validate.h @@ -19,8 +19,11 @@ * along with this program. If not, see . * */ -#pragma once +#ifndef ENV_VALIDATE_H +#define ENV_VALIDATE_H #ifndef ARDUINO_ARCH_HC32 #error "Oops! Select an HC32F460 board in 'Tools > Board.'" #endif + +#endif diff --git a/ini/hc32.ini b/ini/hc32.ini index 56c6b3f2e5a2..d25ef4e7be07 100644 --- a/ini/hc32.ini +++ b/ini/hc32.ini @@ -27,7 +27,7 @@ # Base Environment for all HC32F460 variants # [HC32F460_base] -platform = https://github.com/shadow578/platform-hc32f46x/archive/main.zip +platform = https://github.com/shadow578/platform-hc32f46x/archive/1.0.0.zip board = generic_hc32f460 build_src_filter = ${common.default_src_filter} + + build_type = release diff --git a/ini/stm32f4.ini b/ini/stm32f4.ini index 0ba6b66c3fed..60ccee94d89b 100644 --- a/ini/stm32f4.ini +++ b/ini/stm32f4.ini @@ -743,7 +743,7 @@ upload_protocol = stlink [env:STM32F401RC_btt] extends = stm32_variant platform = ststm32@~14.1.0 -platform_packages = framework-arduinoststm32@https://github.com/stm32duino/Arduino_Core_STM32/archive/2.6.0.zip +platform_packages = framework-arduinoststm32@~4.20600.231001 toolchain-gccarmnoneeabi@1.100301.220327 board = marlin_STM32F401RC board_build.offset = 0x4000 diff --git a/ini/stm32g0.ini b/ini/stm32g0.ini index 109200bb0c43..cf36541f3f50 100644 --- a/ini/stm32g0.ini +++ b/ini/stm32g0.ini @@ -32,7 +32,7 @@ build_flags = -DPIN_WIRE_SCL=PB3 -DPIN_WIRE_SDA=PB4 [env:BTT_EBB42_V1_1_filament_extruder] extends = stm32_variant platform = ststm32@~14.1.0 -platform_packages = framework-arduinoststm32@https://github.com/stm32duino/Arduino_Core_STM32/archive/2.6.0.zip +platform_packages = framework-arduinoststm32@~4.20600.231001 toolchain-gccarmnoneeabi@1.100301.220327 board = marlin_BTT_EBB42_V1_1 board_build.offset = 0x0000 @@ -48,7 +48,7 @@ upload_command = dfu-util -a 0 -s 0x08000000:leave -D "$SOURCE" [env:STM32G0B1RE_btt] extends = stm32_variant platform = ststm32@~14.1.0 -platform_packages = framework-arduinoststm32@https://github.com/stm32duino/Arduino_Core_STM32/archive/2.6.0.zip +platform_packages = framework-arduinoststm32@~4.20600.231001 toolchain-gccarmnoneeabi@1.100301.220327 board = marlin_STM32G0B1RE board_build.offset = 0x2000 @@ -105,7 +105,7 @@ upload_protocol = custom [env:STM32G0B1VE_btt] extends = stm32_variant platform = ststm32@~14.1.0 -platform_packages = framework-arduinoststm32@https://github.com/stm32duino/Arduino_Core_STM32/archive/2.6.0.zip +platform_packages = framework-arduinoststm32@~4.20600.231001 toolchain-gccarmnoneeabi@1.100301.220327 board = marlin_STM32G0B1VE board_build.offset = 0x2000 From 6c04cf40f441fb884e049d25c439969a6f618ed6 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Fri, 8 Dec 2023 06:06:47 +0000 Subject: [PATCH 64/77] [cron] Bump distribution date (2023-12-08) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 607eafb75039..bbeaf4623e92 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2023-12-06" +//#define STRING_DISTRIBUTION_DATE "2023-12-08" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index f7f83ac194bd..ec2e910ca337 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2023-12-06" + #define STRING_DISTRIBUTION_DATE "2023-12-08" #endif /** From dfec58e5dced9fd794cc4a8e7a88a4d34f0cacda Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 8 Dec 2023 00:47:18 -0600 Subject: [PATCH 65/77] =?UTF-8?q?=E2=9A=A1=EF=B8=8F=20Use=20strlcpy=20with?= =?UTF-8?q?=20buffer=20size=20(#26513)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/LINUX/include/Arduino.h | 3 ++ Marlin/src/core/mstring.h | 35 ++++++++----------- Marlin/src/gcode/queue.h | 2 +- .../lcd/extui/anycubic_chiron/chiron_tft.cpp | 13 ++++--- .../src/lcd/extui/anycubic_vyper/dgus_tft.cpp | 9 ++--- Marlin/src/lcd/extui/mks_ui/draw_keyboard.cpp | 2 +- .../src/lcd/extui/mks_ui/draw_print_file.cpp | 10 +++--- Marlin/src/lcd/extui/mks_ui/mks_hardware.cpp | 3 +- .../extui/mks_ui/tft_lvgl_configuration.cpp | 6 ++-- Marlin/src/lcd/extui/nextion/nextion_tft.cpp | 3 +- Marlin/src/lcd/lcdprint.cpp | 10 +++--- Marlin/src/lcd/menu/menu_item.h | 6 ++-- Marlin/src/module/settings.cpp | 2 +- Marlin/src/sd/cardreader.cpp | 8 ++--- 14 files changed, 51 insertions(+), 61 deletions(-) diff --git a/Marlin/src/HAL/LINUX/include/Arduino.h b/Marlin/src/HAL/LINUX/include/Arduino.h index f05aaed88083..6e9c80ee07dc 100644 --- a/Marlin/src/HAL/LINUX/include/Arduino.h +++ b/Marlin/src/HAL/LINUX/include/Arduino.h @@ -28,6 +28,9 @@ #include +#define strlcpy(A, B, C) strncpy(A, B, (C) - 1) +#define strlcpy_P(A, B, C) strncpy_P(A, B, (C) - 1) + #define HIGH 0x01 #define LOW 0x00 diff --git a/Marlin/src/core/mstring.h b/Marlin/src/core/mstring.h index 9606fa22af10..0ea53fef1b48 100644 --- a/Marlin/src/core/mstring.h +++ b/Marlin/src/core/mstring.h @@ -48,7 +48,7 @@ #define DEFAULT_MSTRING_SIZE 20 #endif -//#define UNSAFE_MSTRING // Don't initialize the string and don't terminate strncpy +//#define UNSAFE_MSTRING // Don't initialize the string to "" or set a terminating nul //#define USE_SPRINTF // Use sprintf instead of snprintf //#define DJB2_HASH // 32-bit hash with Djb2 algorithm //#define MSTRING_DEBUG // Debug string operations to diagnose memory leaks @@ -98,13 +98,7 @@ class MString { void debug(FSTR_P const f) { #if ENABLED(MSTRING_DEBUG) - SERIAL_ECHO(FTOP(f)); - SERIAL_CHAR(':'); - SERIAL_ECHO(uintptr_t(str)); - SERIAL_CHAR(' '); - SERIAL_ECHO(length()); - SERIAL_CHAR(' '); - SERIAL_ECHOLN(str); + SERIAL_ECHOLN(f, ':', uintptr_t(str), ' ', length(), ' ', str); #endif } @@ -112,12 +106,12 @@ class MString { // Chainable String Setters MString& set() { str[0] = '\0'; debug(F("clear")); return *this; } - MString& set(char *s) { strncpy(str, s, SIZE); debug(F("string")); return *this; } + MString& set(char *s) { strlcpy(str, s, SIZE + 1); debug(F("string")); return *this; } MString& set(const char *s) { return set(const_cast(s)); } - MString& set_P(PGM_P const s) { strncpy_P(str, s, SIZE); debug(F("pstring")); return *this; } + MString& set_P(PGM_P const s) { strlcpy_P(str, s, SIZE + 1); debug(F("pstring")); return *this; } MString& set(FSTR_P const f) { return set_P(FTOP(f)); } MString& set(const bool &b) { return set(b ? F("true") : F("false")); } - MString& set(const char c) { str[0] = c; if (1 < SIZE) str[1] = '\0'; debug(F("char")); return *this; } + MString& set(const char c) { str[0] = c; str[1] = '\0'; debug(F("char")); return *this; } MString& set(const int8_t &i) { SNPRINTF_P(str, SIZE, PSTR("%d"), i); debug(F("int8_t")); return *this; } MString& set(const short &i) { SNPRINTF_P(str, SIZE, PSTR("%d"), i); debug(F("short")); return *this; } MString& set(const int &i) { SNPRINTF_P(str, SIZE, PSTR("%d"), i); debug(F("int")); return *this; } @@ -134,11 +128,11 @@ class MString { MString& set(const xyze_pos_t &v) { set(); return append(v); } template - MString& set(const MString &m) { strncpy(str, &m, SIZE); debug(F("MString")); return *this; } + MString& set(const MString &m) { strlcpy(str, &m, SIZE + 1); debug(F("MString")); return *this; } - MString& setn(char *s, int len) { int c = _MIN(len, SIZE); strncpy(str, s, c); str[c] = '\0'; debug(F("string")); return *this; } + MString& setn(char *s, int len) { int c = _MIN(len, SIZE); strlcpy(str, s, c + 1); debug(F("string")); return *this; } MString& setn(const char *s, int len) { return setn(const_cast(s), len); } - MString& setn_P(PGM_P const s, int len) { int c = _MIN(len, SIZE); strncpy_P(str, s, c); str[c] = '\0'; debug(F("pstring")); return *this; } + MString& setn_P(PGM_P const s, int len) { int c = _MIN(len, SIZE); strlcpy_P(str, s, c + 1); debug(F("pstring")); return *this; } MString& setn(FSTR_P const f, int len) { return setn_P(FTOP(f), len); } // set(repchr_t('-', 10)) @@ -159,9 +153,9 @@ class MString { // Chainable String appenders MString& append() { debug(F("nil")); return *this; } // for macros that might emit no output - MString& append(char *s) { int sz = length(); if (sz < SIZE) strncpy(str + sz, s, SIZE - sz); debug(F("string")); return *this; } + MString& append(char *s) { int sz = length(); if (sz < SIZE) strlcpy(str + sz, s, SIZE - sz + 1); debug(F("string")); return *this; } MString& append(const char *s) { return append(const_cast(s)); } - MString& append_P(PGM_P const s) { int sz = length(); if (sz < SIZE) strncpy_P(str + sz, s, SIZE - sz); debug(F("pstring")); return *this; } + MString& append_P(PGM_P const s) { int sz = length(); if (sz < SIZE) strlcpy_P(str + sz, s, SIZE - sz + 1); debug(F("pstring")); return *this; } MString& append(FSTR_P const f) { return append_P(FTOP(f)); } MString& append(const bool &b) { return append(b ? F("true") : F("false")); } MString& append(const char c) { int sz = length(); if (sz < SIZE) { str[sz] = c; if (sz < SIZE - 1) str[sz + 1] = '\0'; } return *this; } @@ -195,15 +189,15 @@ class MString { MString& append(const MString &m) { return append(&m); } // Append only if the given space is available - MString& appendn(char *s, int len) { int sz = length(), c = _MIN(len, SIZE - sz); if (c > 0) { strncpy(str + sz, s, c); str[sz + c] = '\0'; } debug(F("string")); return *this; } + MString& appendn(char *s, int len) { int sz = length(), c = _MIN(len, SIZE - sz); if (c > 0) { strlcpy(str + sz, s, c + 1); } debug(F("string")); return *this; } MString& appendn(const char *s, int len) { return appendn(const_cast(s), len); } - MString& appendn_P(PGM_P const s, int len) { int sz = length(), c = _MIN(len, SIZE - sz); if (c > 0) { strncpy_P(str + sz, s, c); str[sz + c] = '\0'; } debug(F("pstring")); return *this; } + MString& appendn_P(PGM_P const s, int len) { int sz = length(), c = _MIN(len, SIZE - sz); if (c > 0) { strlcpy_P(str + sz, s, c + 1); } debug(F("pstring")); return *this; } MString& appendn(FSTR_P const f, int len) { return appendn_P(FTOP(f), len); } // append(repchr_t('-', 10)) MString& append(const repchr_t &s) { const int sz = length(), c = _MIN(s.count, SIZE - sz); - if (c > 0) { memset(str + sz, s.asc, c); safety(sz + c); } + if (c > 0) { memset(str + sz, s.asc, c); str[sz + c] = '\0'; } debug(F("repchr")); return *this; } @@ -299,7 +293,7 @@ class MString { } void copyto(char * const dst) const { strcpy(dst, str); } - void copyto(char * const dst, int len) const { strncpy(dst, str, len); } + void copyto(char * const dst, int len) const { strlcpy(dst, str, len + 1); } MString& clear() { return set(); } MString& eol() { return append('\n'); } @@ -318,6 +312,7 @@ class MString { #pragma GCC diagnostic pop +// Temporary inline string typically used to compose a G-code command #ifndef TS_SIZE #define TS_SIZE 63 #endif diff --git a/Marlin/src/gcode/queue.h b/Marlin/src/gcode/queue.h index aa7ef99f479e..91cad1f08d94 100644 --- a/Marlin/src/gcode/queue.h +++ b/Marlin/src/gcode/queue.h @@ -134,7 +134,7 @@ class GCodeQueue { * Aborts the current SRAM queue so only use for one or two commands. */ static void inject(const char * const gcode) { - strncpy(injected_commands, gcode, sizeof(injected_commands) - 1); + strlcpy(injected_commands, gcode, sizeof(injected_commands)); } /** diff --git a/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.cpp b/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.cpp index df0c4df30dfd..63b1ef9c195c 100644 --- a/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.cpp +++ b/Marlin/src/lcd/extui/anycubic_chiron/chiron_tft.cpp @@ -433,12 +433,12 @@ void ChironTFT::sendFileList(int8_t startindex) { } void ChironTFT::selectFile() { - const size_t namelen = command_len - 4 + (panel_type <= AC_panel_new); - strncpy(selectedfile, panel_command + 4, namelen); - selectedfile[namelen] = '\0'; + const size_t fnlen = command_len - 4 + (panel_type <= AC_panel_new); + strlcpy(selectedfile, panel_command + 4, fnlen + 1); #if ACDEBUG(AC_FILE) DEBUG_ECHOLNPGM(" Selected File: ", selectedfile); #endif + switch (selectedfile[0]) { case '/': // Valid file selected tftSendLn(AC_msg_sd_file_open_success); @@ -449,10 +449,9 @@ void ChironTFT::selectFile() { tftSendLn(AC_msg_sd_file_open_failed); sendFileList( 0 ); break; - default: // enter sub folder - // for new panel remove the '.GCO' tag that was added to the end of the path - if (panel_type <= AC_panel_new) - selectedfile[strlen(selectedfile) - 4] = '\0'; + default: // enter subfolder + // For new panel remove the '.GCO' tag that was added to the end of the path + if (panel_type <= AC_panel_new) selectedfile[fnlen - 4] = '\0'; filenavigator.changeDIR(selectedfile); tftSendLn(AC_msg_sd_file_open_failed); sendFileList( 0 ); diff --git a/Marlin/src/lcd/extui/anycubic_vyper/dgus_tft.cpp b/Marlin/src/lcd/extui/anycubic_vyper/dgus_tft.cpp index 4726cba3786a..3209aa76f248 100644 --- a/Marlin/src/lcd/extui/anycubic_vyper/dgus_tft.cpp +++ b/Marlin/src/lcd/extui/anycubic_vyper/dgus_tft.cpp @@ -971,8 +971,7 @@ namespace Anycubic { } void DgusTFT::selectFile() { - strncpy(selectedfile, panel_command + 4, command_len - 4); - selectedfile[command_len - 5] = '\0'; + strlcpy(selectedfile, panel_command + 4, command_len - 3); #if ACDEBUG(AC_FILE) DEBUG_ECHOLNPGM(" Selected File: ", selectedfile); #endif @@ -1293,8 +1292,7 @@ namespace Anycubic { TERN_(CASE_LIGHT_ENABLE, setCaseLightState(true)); char str_buf[20]; - strncpy_P(str_buf, filenavigator.filelist.longFilename(), 17); - str_buf[17] = '\0'; + strlcpy_P(str_buf, filenavigator.filelist.longFilename(), 18); sendTxtToTFT(str_buf, TXT_PRINT_NAME); #if ENABLED(POWER_LOSS_RECOVERY) @@ -1332,8 +1330,7 @@ namespace Anycubic { printFile(filenavigator.filelist.shortFilename()); char str_buf[20]; - strncpy_P(str_buf, filenavigator.filelist.longFilename(), 17); - str_buf[17] = '\0'; + strlcpy_P(str_buf, filenavigator.filelist.longFilename(), 18); sendTxtToTFT(str_buf, TXT_PRINT_NAME); sprintf(str_buf, "%5.2f", getFeedrate_percent()); diff --git a/Marlin/src/lcd/extui/mks_ui/draw_keyboard.cpp b/Marlin/src/lcd/extui/mks_ui/draw_keyboard.cpp index 90b181d6b548..ec7e549c4160 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_keyboard.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_keyboard.cpp @@ -155,7 +155,7 @@ static void lv_kb_event_cb(lv_obj_t *kb, lv_event_t event) { #endif // MKS_WIFI_MODULE case autoLevelGcodeCommand: uint8_t buf[100]; - strncpy((char *)buf, ret_ta_txt, sizeof(buf)); + strlcpy((char *)buf, ret_ta_txt, sizeof(buf)); update_gcode_command(AUTO_LEVELING_COMMAND_ADDR, buf); goto_previous_ui(); break; diff --git a/Marlin/src/lcd/extui/mks_ui/draw_print_file.cpp b/Marlin/src/lcd/extui/mks_ui/draw_print_file.cpp index da79cb617495..7732d5d2a4b3 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_print_file.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_print_file.cpp @@ -474,7 +474,7 @@ void cutFileName(char *path, int len, int bytePerLine, char *outStr) { wcscpy(outStr, beginIndex); #else if ((int)strlen(beginIndex) > len) - strncpy(outStr, beginIndex, len); + strlcpy(outStr, beginIndex, len + 1); else strcpy(outStr, beginIndex); #endif @@ -485,17 +485,17 @@ void cutFileName(char *path, int len, int bytePerLine, char *outStr) { wcsncpy(outStr, (const WCHAR *)beginIndex, len - 3); wcscat(outStr, (const WCHAR *)gFileTail); #else - //strncpy(outStr, beginIndex, len - 3); - strncpy(outStr, beginIndex, len - 4); + strlcpy(outStr, beginIndex, len - 3); strcat_P(outStr, PSTR("~.g")); #endif } else { + const size_t strsize = strIndex2 - beginIndex + 1; #if _LFN_UNICODE - wcsncpy(outStr, (const WCHAR *)beginIndex, strIndex2 - beginIndex + 1); + wcsncpy(outStr, (const WCHAR *)beginIndex, strsize); wcscat(outStr, (const WCHAR *)&gFileTail[3]); #else - strncpy(outStr, beginIndex, strIndex2 - beginIndex + 1); + strlcpy(outStr, beginIndex, strsize + 1); strcat_P(outStr, PSTR("g")); #endif } diff --git a/Marlin/src/lcd/extui/mks_ui/mks_hardware.cpp b/Marlin/src/lcd/extui/mks_ui/mks_hardware.cpp index a759f8677e6f..eb9cac641ad8 100644 --- a/Marlin/src/lcd/extui/mks_ui/mks_hardware.cpp +++ b/Marlin/src/lcd/extui/mks_ui/mks_hardware.cpp @@ -727,8 +727,7 @@ void disp_assets_update_progress(FSTR_P const fmsg) { static constexpr int buflen = 30; char buf[buflen]; memset(buf, ' ', buflen); - strncpy_P(buf, FTOP(fmsg), buflen - 1); - buf[buflen - 1] = '\0'; + strlcpy_P(buf, FTOP(fmsg), buflen); disp_string(100, 165, buf, 0xFFFF, 0x0000); #else disp_string(100, 165, FTOP(fmsg), 0xFFFF, 0x0000); diff --git a/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp b/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp index ba898162d1f7..be6394514360 100644 --- a/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp +++ b/Marlin/src/lcd/extui/mks_ui/tft_lvgl_configuration.cpp @@ -237,11 +237,11 @@ void tft_lvgl_init() { uiCfg.print_state = REPRINTING; #if ENABLED(LONG_FILENAME_HOST_SUPPORT) - strncpy(public_buf_m, recovery.info.sd_filename, sizeof(public_buf_m)); + strlcpy(public_buf_m, recovery.info.sd_filename, sizeof(public_buf_m)); card.printLongPath(public_buf_m); - strncpy(list_file.long_name[sel_id], card.longFilename, sizeof(list_file.long_name[0])); + strlcpy(list_file.long_name[sel_id], card.longFilename, sizeof(list_file.long_name[0])); #else - strncpy(list_file.long_name[sel_id], recovery.info.sd_filename, sizeof(list_file.long_name[0])); + strlcpy(list_file.long_name[sel_id], recovery.info.sd_filename, sizeof(list_file.long_name[0])); #endif lv_draw_printing(); } diff --git a/Marlin/src/lcd/extui/nextion/nextion_tft.cpp b/Marlin/src/lcd/extui/nextion/nextion_tft.cpp index 87a6544e5ef5..4833ab96ab77 100644 --- a/Marlin/src/lcd/extui/nextion/nextion_tft.cpp +++ b/Marlin/src/lcd/extui/nextion/nextion_tft.cpp @@ -158,8 +158,7 @@ void NextionTFT::sendFileList(int8_t startindex) { } void NextionTFT::selectFile() { - strncpy(selectedfile, nextion_command + 4, command_len - 4); - selectedfile[command_len - 5] = '\0'; + strlcpy(selectedfile, nextion_command + 4, command_len - 3); #if NEXDEBUG(N_FILE) DEBUG_ECHOLNPGM(" Selected File: ", selectedfile); #endif diff --git a/Marlin/src/lcd/lcdprint.cpp b/Marlin/src/lcd/lcdprint.cpp index f559272f7ed2..ea833f53a1df 100644 --- a/Marlin/src/lcd/lcdprint.cpp +++ b/Marlin/src/lcd/lcdprint.cpp @@ -67,24 +67,24 @@ lcd_uint_t expand_u8str_P(char * const outstr, PGM_P const ptpl, const int8_t in } else { PGM_P const b = ind == -2 ? GET_TEXT(MSG_CHAMBER) : GET_TEXT(MSG_BED); - strncpy_P(o, b, n); + strlcpy_P(o, b, n + 1); n -= utf8_strlen(o); o += strlen(o); } if (n > 0) { - strncpy_P(o, (PGM_P)p, n); + strlcpy_P(o, (PGM_P)p, n + 1); n -= utf8_strlen(o); o += strlen(o); break; } } else if (wc == '$' && fstr) { - strncpy_P(o, FTOP(fstr), n); - n -= utf8_strlen_P(FTOP(fstr)); + strlcpy_P(o, FTOP(fstr), n + 1); + n -= utf8_strlen(o); o += strlen(o); } else if (wc == '$' && cstr) { - strncpy(o, cstr, n); + strlcpy(o, cstr, n + 1); n -= utf8_strlen(o); o += strlen(o); } diff --git a/Marlin/src/lcd/menu/menu_item.h b/Marlin/src/lcd/menu/menu_item.h index 11f78d25d5da..823d2a4a25e7 100644 --- a/Marlin/src/lcd/menu/menu_item.h +++ b/Marlin/src/lcd/menu/menu_item.h @@ -386,11 +386,11 @@ class MenuItem_bool : public MenuEditItemBase { #define PSTRING_ITEM_F_P(FLABEL, PVAL, STYL) do{ \ constexpr int m = 20; \ - char msg[m+1]; \ + char msg[m + 1]; \ if (_menuLineNr == _thisItemNr) { \ msg[0] = ':'; msg[1] = ' '; \ - strncpy_P(msg+2, PVAL, m-2); \ - if (msg[m-1] & 0x80) msg[m-1] = '\0'; \ + strlcpy_P(msg + 2, PVAL, m - 1); \ + if (msg[m - 1] & 0x80) msg[m - 1] = '\0'; \ } \ STATIC_ITEM_F(FLABEL, STYL, msg); \ }while(0) diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index 6f7c4b1ebca5..f636b985e1be 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -2042,7 +2042,7 @@ void MarlinSettings::postprocess() { if (grid_max_x == (GRID_MAX_POINTS_X) && grid_max_y == (GRID_MAX_POINTS_Y)) { if (!validating) set_bed_leveling_enabled(false); bedlevel.set_grid(spacing, start); - EEPROM_READ(bedlevel.z_values); // 9 to 256 floats + EEPROM_READ(bedlevel.z_values); // 9 to 256 floats } else if (grid_max_x > (GRID_MAX_POINTS_X) || grid_max_y > (GRID_MAX_POINTS_Y)) { eeprom_error = ERR_EEPROM_CORRUPT; diff --git a/Marlin/src/sd/cardreader.cpp b/Marlin/src/sd/cardreader.cpp index 9b9b3509d6e0..175e4e5c05bc 100644 --- a/Marlin/src/sd/cardreader.cpp +++ b/Marlin/src/sd/cardreader.cpp @@ -446,8 +446,7 @@ void CardReader::ls(const uint8_t lsflags/*=0*/) { diveDir.close(); if (longFilename[0]) { - strncpy_P(pathLong, longFilename, 63); - pathLong[63] = '\0'; + strlcpy_P(pathLong, longFilename, 64); break; } } @@ -1075,8 +1074,7 @@ const char* CardReader::diveToFile(const bool update_cwd, MediaFile* &inDirPtr, // Isolate the next subitem name const uint8_t len = name_end - atom_ptr; char dosSubdirname[len + 1]; - strncpy(dosSubdirname, atom_ptr, len); - dosSubdirname[len] = 0; + strlcpy(dosSubdirname, atom_ptr, len + 1); if (echo) SERIAL_ECHOLN(dosSubdirname); @@ -1181,7 +1179,7 @@ void CardReader::cdroot() { #endif #else // Copy filenames into the static array - #define _SET_SORTNAME(I) strncpy(sortnames[I], longest_filename(), SORTED_LONGNAME_MAXLEN) + #define _SET_SORTNAME(I) strlcpy(sortnames[I], longest_filename(), sizeof(sortnames[I])) #if SORTED_LONGNAME_MAXLEN == LONG_FILENAME_LENGTH // Short name sorting always use LONG_FILENAME_LENGTH with no trailing nul #define SET_SORTNAME(I) _SET_SORTNAME(I) From 10fe229aadc05a32575d8a6c609c2dc7c730cde4 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sat, 9 Dec 2023 00:20:55 +0000 Subject: [PATCH 66/77] [cron] Bump distribution date (2023-12-09) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index bbeaf4623e92..4b493f35ab72 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2023-12-08" +//#define STRING_DISTRIBUTION_DATE "2023-12-09" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index ec2e910ca337..02525afb5437 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2023-12-08" + #define STRING_DISTRIBUTION_DATE "2023-12-09" #endif /** From bdfe4a108c347544d4aa50936ac15e71550cb545 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 8 Dec 2023 23:18:50 -0600 Subject: [PATCH 67/77] =?UTF-8?q?=F0=9F=A9=B9=20=20Fix=20UBL=20debug=20out?= =?UTF-8?q?put?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp index 7496c9e9b5e1..d136f0000d8c 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp @@ -1790,8 +1790,8 @@ void unified_bed_leveling::smart_fill_mesh() { SERIAL_ECHOLNPGM("Meshes go from ", hex_address((void*)settings.meshes_start_index()), " to ", hex_address((void*)settings.meshes_end_index())); serial_delay(50); - SERIAL_ECHOLNPGM("sizeof(ubl) : ", sizeof(ubl)); SERIAL_EOL(); - SERIAL_ECHOLNPGM("z_value[][] size: ", sizeof(z_values)); SERIAL_EOL(); + SERIAL_ECHOLNPGM("sizeof(unified_bed_leveling) : ", sizeof(unified_bed_leveling)); + SERIAL_ECHOLNPGM("z_value[][] size: ", sizeof(z_values)); serial_delay(25); SERIAL_ECHOLNPGM("EEPROM free for UBL: ", hex_address((void*)(settings.meshes_end_index() - settings.meshes_start_index()))); From a1c3a2b03a531606b3f6d850b324707efb89c1a0 Mon Sep 17 00:00:00 2001 From: David Buezas Date: Sat, 9 Dec 2023 07:48:57 +0100 Subject: [PATCH 68/77] =?UTF-8?q?=F0=9F=9A=B8=20Encoder=20improvements=20(?= =?UTF-8?q?#26501)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/marlinui.cpp | 110 ++++++++++++++++++++---------------- buildroot/tests/mega2560 | 1 + 2 files changed, 61 insertions(+), 50 deletions(-) diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index 178f0b74ecc5..4eb58f52aedf 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -67,6 +67,8 @@ MarlinUI ui; constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; +#define BLOCK_CLICK_AFTER_MOVEMENT_MS 100 + #if HAS_STATUS_MESSAGE #if ENABLED(STATUS_MESSAGE_SCROLLING) && ANY(HAS_WIRED_LCD, DWIN_LCD_PROUI) uint8_t MarlinUI::status_scroll_offset; // = 0 @@ -880,8 +882,8 @@ void MarlinUI::init() { void MarlinUI::external_encoder() { if (external_control && encoderDiff) { bedlevel.encoder_diff += encoderDiff; // Encoder for UBL G29 mesh editing - encoderDiff = 0; // Hide encoder events from the screen handler - refresh(LCDVIEW_REDRAW_NOW); // ...but keep the refresh. + encoderDiff = 0; // Hide encoder events from the screen handler + refresh(LCDVIEW_REDRAW_NOW); // ...but keep the refresh. } } @@ -932,7 +934,8 @@ void MarlinUI::init() { void MarlinUI::update() { static uint16_t max_display_update_time = 0; - millis_t ms = millis(); + static millis_t next_encoder_enable_ms = 0; + const millis_t ms = millis(); #if LED_POWEROFF_TIMEOUT > 0 leds.update_timeout(powerManager.psu_on); @@ -982,7 +985,12 @@ void MarlinUI::init() { if (!touch_buttons) { // Integrated LCD click handling via button_pressed if (!external_control && button_pressed()) { - if (!wait_for_unclick) do_click(); // Handle the click + if (!wait_for_unclick) { + if (ELAPSED(ms, next_encoder_enable_ms)) + do_click(); // Handle the click + else + wait_for_unclick = true; + } } else wait_for_unclick = false; @@ -1019,68 +1027,69 @@ void MarlinUI::init() { uint8_t abs_diff = ABS(encoderDiff); #if ENCODER_PULSES_PER_STEP > 1 - // When reversing the encoder direction, a movement step can be missed because - // encoderDiff has a non-zero residual value, making the controller unresponsive. - // The fix clears the residual value when the encoder is idle. - // Also check if past half the threshold to compensate for missed single steps. static int8_t lastEncoderDiff; - - // Timeout? No decoder change since last check. 10 or 20 times per second. - if (encoderDiff == lastEncoderDiff && abs_diff <= epps / 2) // Same direction & size but not over a half-step? - encoderDiff = 0; // Clear residual pulses. - else if (WITHIN(abs_diff, epps / 2 + 1, epps - 1)) { // Past half of threshold? - abs_diff = epps; // Treat as a full step size - encoderDiff = (encoderDiff < 0 ? -1 : 1) * abs_diff; // ...in the spin direction. - } TERN_(HAS_TOUCH_SLEEP, if (lastEncoderDiff != encoderDiff) wakeup_screen()); lastEncoderDiff = encoderDiff; #endif const bool encoderPastThreshold = (abs_diff >= epps); - if (encoderPastThreshold || lcd_clicked) { - if (encoderPastThreshold && TERN1(IS_TFTGLCD_PANEL, !external_control)) { + if (encoderPastThreshold && TERN1(IS_TFTGLCD_PANEL, !external_control)) { - #if ALL(HAS_MARLINUI_MENU, ENCODER_RATE_MULTIPLIER) + #if ALL(HAS_MARLINUI_MENU, ENCODER_RATE_MULTIPLIER) - int32_t encoderMultiplier = 1; + int32_t encoderMultiplier = 1; - if (encoderRateMultiplierEnabled) { + if (encoderRateMultiplierEnabled) { + if (lastEncoderMovementMillis) { const float encoderMovementSteps = float(abs_diff) / epps; + // Note that the rate is always calculated between two passes through the + // loop and that the abs of the encoderDiff value is tracked. + const float encoderStepRate = encoderMovementSteps / float(ms - lastEncoderMovementMillis) * 1000; + + if (encoderStepRate >= ENCODER_100X_STEPS_PER_SEC) encoderMultiplier = 100; + else if (encoderStepRate >= ENCODER_10X_STEPS_PER_SEC) encoderMultiplier = 10; + + // Enable to output the encoder steps per second value + //#define ENCODER_RATE_MULTIPLIER_DEBUG + #if ENABLED(ENCODER_RATE_MULTIPLIER_DEBUG) + SERIAL_ECHO_START(); + SERIAL_ECHOPGM("Enc Step Rate: ", encoderStepRate); + SERIAL_ECHOPGM(" Multiplier: ", encoderMultiplier); + SERIAL_ECHOPGM(" ENCODER_10X_STEPS_PER_SEC: ", ENCODER_10X_STEPS_PER_SEC); + SERIAL_ECHOPGM(" ENCODER_100X_STEPS_PER_SEC: ", ENCODER_100X_STEPS_PER_SEC); + SERIAL_EOL(); + #endif + } - if (lastEncoderMovementMillis) { - // Note that the rate is always calculated between two passes through the - // loop and that the abs of the encoderDiff value is tracked. - const float encoderStepRate = encoderMovementSteps / float(ms - lastEncoderMovementMillis) * 1000; - - if (encoderStepRate >= ENCODER_100X_STEPS_PER_SEC) encoderMultiplier = 100; - else if (encoderStepRate >= ENCODER_10X_STEPS_PER_SEC) encoderMultiplier = 10; - - // Enable to output the encoder steps per second value - //#define ENCODER_RATE_MULTIPLIER_DEBUG - #if ENABLED(ENCODER_RATE_MULTIPLIER_DEBUG) - SERIAL_ECHO_START(); - SERIAL_ECHOPGM("Enc Step Rate: ", encoderStepRate); - SERIAL_ECHOPGM(" Multiplier: ", encoderMultiplier); - SERIAL_ECHOPGM(" ENCODER_10X_STEPS_PER_SEC: ", ENCODER_10X_STEPS_PER_SEC); - SERIAL_ECHOPGM(" ENCODER_100X_STEPS_PER_SEC: ", ENCODER_100X_STEPS_PER_SEC); - SERIAL_EOL(); - #endif - } + lastEncoderMovementMillis = ms; + } // encoderRateMultiplierEnabled - lastEncoderMovementMillis = ms; - } // encoderRateMultiplierEnabled + #else - #else + constexpr int32_t encoderMultiplier = 1; - constexpr int32_t encoderMultiplier = 1; + #endif // ENCODER_RATE_MULTIPLIER - #endif // ENCODER_RATE_MULTIPLIER + int8_t fullSteps = encoderDiff / epps; + if (fullSteps != 0) { - if (can_encode()) encoderPosition += (encoderDiff * encoderMultiplier) / epps; + #if ENABLED(ENCODER_RATE_MULTIPLIER) + static bool lastFwd; + const bool fwd = fullSteps > 0; + if (encoderMultiplier != 1 && fwd != lastFwd) + fullSteps *= -1; // Fast move and direction changed? Assume glitch. + else + lastFwd = fwd; // Slow move or lastFwd==fwd already. Remember dir. + #endif - encoderDiff = 0; + next_encoder_enable_ms = ms + BLOCK_CLICK_AFTER_MOVEMENT_MS; + encoderDiff -= fullSteps * epps; + if (can_encode() && !lcd_clicked) + encoderPosition += (fullSteps * encoderMultiplier); } + } + if (encoderPastThreshold || lcd_clicked) { reset_status_timeout(ms); #if LCD_BACKLIGHT_TIMEOUT_MINS @@ -1094,7 +1103,7 @@ void MarlinUI::init() { #if LED_POWEROFF_TIMEOUT > 0 if (!powerManager.psu_on) leds.reset_timeout(ms); #endif - } // encoder activity + } #endif // HAS_ENCODER_ACTION @@ -1393,9 +1402,10 @@ void MarlinUI::init() { #if HAS_ENCODER_WHEEL static uint8_t lastEncoderBits; + bool ignore = false; // Manage encoder rotation - #define ENCODER_SPIN(_E1, _E2) switch (lastEncoderBits) { case _E1: encoderDiff += encoderDirection; break; case _E2: encoderDiff -= encoderDirection; } + #define ENCODER_SPIN(_E1, _E2) switch (lastEncoderBits) { case _E1: encoderDiff += encoderDirection; break; case _E2: encoderDiff -= encoderDirection; break; default: ignore = true; } uint8_t enc = 0; if (buttons & EN_A) enc |= B01; @@ -1410,7 +1420,7 @@ void MarlinUI::init() { #if ALL(HAS_MARLINUI_MENU, AUTO_BED_LEVELING_UBL) external_encoder(); #endif - lastEncoderBits = enc; + if (!ignore) lastEncoderBits = enc; } #endif // HAS_ENCODER_WHEEL diff --git a/buildroot/tests/mega2560 b/buildroot/tests/mega2560 index d647a6ddb16c..1fbdd6b58b20 100755 --- a/buildroot/tests/mega2560 +++ b/buildroot/tests/mega2560 @@ -33,6 +33,7 @@ opt_enable AUTO_BED_LEVELING_UBL AVOID_OBSTACLES RESTORE_LEVELING_AFTER_G28 DEBU EMERGENCY_PARSER MULTI_NOZZLE_DUPLICATION CLASSIC_JERK LIN_ADVANCE ADVANCE_K_EXTRA QUICK_HOME \ SET_PROGRESS_MANUALLY SET_PROGRESS_PERCENT PRINT_PROGRESS_SHOW_DECIMALS SHOW_REMAINING_TIME \ ENCODER_NOISE_FILTER BABYSTEPPING BABYSTEP_XY NANODLP_Z_SYNC I2C_POSITION_ENCODERS M114_DETAIL +opt_disable ENCODER_RATE_MULTIPLIER exec_test $1 $2 "Azteeg X3 Pro | EXTRUDERS 5 | RRDFGSC | UBL | LIN_ADVANCE ..." "$3" # From 473817f2f4758924c56351a3672354a141834929 Mon Sep 17 00:00:00 2001 From: mikemerryguy <57319047+mikemerryguy@users.noreply.github.com> Date: Sat, 9 Dec 2023 02:38:31 -0500 Subject: [PATCH 69/77] =?UTF-8?q?=F0=9F=9A=B8=20Adjust=20Progress=20/=20Co?= =?UTF-8?q?mpletion=20(#26466)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/src/gcode/stats/M31.cpp | 2 +- Marlin/src/inc/Conditionals_adv.h | 6 +- .../lcd/dogm/fontdata/fontdata_6x9_marlin.h | 21 +++--- Marlin/src/lcd/dogm/status_screen_DOGM.cpp | 68 ++++++++++--------- .../lcd/dogm/status_screen_lite_ST7920.cpp | 22 +++--- .../src/lcd/dogm/status_screen_lite_ST7920.h | 4 +- .../lcd/extui/dgus_e3s1pro/DGUSTxHandler.cpp | 6 +- 7 files changed, 72 insertions(+), 57 deletions(-) diff --git a/Marlin/src/gcode/stats/M31.cpp b/Marlin/src/gcode/stats/M31.cpp index a76ec7ee4def..ad48eae8663f 100644 --- a/Marlin/src/gcode/stats/M31.cpp +++ b/Marlin/src/gcode/stats/M31.cpp @@ -33,7 +33,7 @@ void GcodeSuite::M31() { char buffer[22]; duration_t(print_job_timer.duration()).toString(buffer); - ui.set_status(buffer, ENABLED(DWIN_LCD_PROUI)); // No expire on ProUI + ui.set_status_no_expire(buffer); SERIAL_ECHO_MSG("Print time: ", buffer); } diff --git a/Marlin/src/inc/Conditionals_adv.h b/Marlin/src/inc/Conditionals_adv.h index 44a87dbb1a0d..ba074e256088 100644 --- a/Marlin/src/inc/Conditionals_adv.h +++ b/Marlin/src/inc/Conditionals_adv.h @@ -852,7 +852,11 @@ #define HAS_MEDIA_SUBCALLS 1 #endif -#if ANY(SHOW_PROGRESS_PERCENT, SHOW_ELAPSED_TIME, SHOW_REMAINING_TIME, SHOW_INTERACTION_TIME) && !HAS_GRAPHICAL_TFT +#if ANY(SHOW_ELAPSED_TIME, SHOW_REMAINING_TIME, SHOW_INTERACTION_TIME) + #define HAS_TIME_DISPLAY 1 +#endif + +#if ANY(SHOW_PROGRESS_PERCENT, HAS_TIME_DISPLAY) && !HAS_GRAPHICAL_TFT #define HAS_EXTRA_PROGRESS 1 #endif diff --git a/Marlin/src/lcd/dogm/fontdata/fontdata_6x9_marlin.h b/Marlin/src/lcd/dogm/fontdata/fontdata_6x9_marlin.h index 524ff18778dc..c81c63f2ed8f 100644 --- a/Marlin/src/lcd/dogm/fontdata/fontdata_6x9_marlin.h +++ b/Marlin/src/lcd/dogm/fontdata/fontdata_6x9_marlin.h @@ -22,15 +22,15 @@ #pragma once /** - Fontname: -Misc-Fixed-Medium-R-Normal--9-90-75-75-C-60-ISO10646-1 - Copyright: Public domain font. Share and enjoy. - Capital A Height: 6, '1' Height: 6 - Calculated Max Values w= 6 h= 9 x= 5 y= 5 dx= 6 dy= 0 ascent= 7 len= 9 - Font Bounding box w= 6 h= 9 x= 0 y=-2 - Calculated Min Values x= 0 y=-2 dx= 0 dy= 0 - Pure Font ascent = 6 descent=-2 - X Font ascent = 6 descent=-2 - Max Font ascent = 7 descent=-2 + * Fontname: -Misc-Fixed-Medium-R-Normal--9-90-75-75-C-60-ISO10646-1 + * Copyright: Public domain font. Share and enjoy. + * Capital A Height: 6, '1' Height: 6 + * Calculated Max Values w= 6 h= 9 x= 5 y= 5 dx= 6 dy= 0 ascent= 7 len= 9 + * Font Bounding box w= 6 h= 9 x= 0 y=-2 + * Calculated Min Values x= 0 y=-2 dx= 0 dy= 0 + * Pure Font ascent = 6 descent=-2 + * X Font ascent = 6 descent=-2 + * Max Font ascent = 7 descent=-2 */ #include const u8g_fntpgm_uint8_t u8g_font_6x9[2434] U8G_FONT_SECTION(".progmem.u8g_font_6x9") = { @@ -186,4 +186,5 @@ const u8g_fntpgm_uint8_t u8g_font_6x9[2434] U8G_FONT_SECTION(".progmem.u8g_font_ 0x00,0x50,0x00,0x90,0x90,0x90,0x70,0x04,0x09,0x09,0x06,0x01,0xFE,0x20,0x40,0x00, 0x90,0x90,0x90,0x70,0x90,0x60,0x04,0x08,0x08,0x06,0x01,0xFE,0x80,0x80,0xE0,0x90, 0x90,0xE0,0x80,0x80,0x04,0x08,0x08,0x06,0x01,0xFE,0x50,0x00,0x90,0x90,0x90,0x70, - 0x90,0x60}; + 0x90,0x60 +}; diff --git a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp index d38d28c8cd3b..ad9e38266162 100644 --- a/Marlin/src/lcd/dogm/status_screen_DOGM.cpp +++ b/Marlin/src/lcd/dogm/status_screen_DOGM.cpp @@ -91,6 +91,18 @@ #define EXTRAS_BASELINE (40 + INFO_FONT_ASCENT) #define STATUS_BASELINE (LCD_PIXEL_HEIGHT - INFO_FONT_DESCENT) +#define PCENTERED // Center percent value over progress bar, else right-align +#define PROGRESS_BAR_X TERN(PCENTERED, 54, 40) +#define PROGRESS_BAR_Y (EXTRAS_BASELINE + TERN(PCENTERED, 1, -3)) +#define PCT_X TERN(PCENTERED, PROGRESS_BAR_X, LCD_PIXEL_WIDTH - TERN(PRINT_PROGRESS_SHOW_DECIMALS, 5, 4) * INFO_FONT_WIDTH) +#define PCT_Y (EXTRAS_BASELINE + TERN(PCENTERED, 0, 3)) +#define PROGRESS_BAR_WIDTH TERN(PCENTERED, LCD_PIXEL_WIDTH - PROGRESS_BAR_X, PCT_X - PROGRESS_BAR_X - 1) +#define PROGRESS_BAR_HEIGHT TERN(PCENTERED, 4, 5) + +#if DISABLED(PCENTERED) && HAS_TIME_DISPLAY + #error "PCENTERED is required for extra progress display options." +#endif + #if ANIM_HBCC enum HeatBits : uint8_t { DRAWBIT_HOTEND, @@ -188,10 +200,6 @@ } #endif -#define PROGRESS_BAR_X 54 -#define PROGRESS_BAR_Y (EXTRAS_BASELINE + 1) -#define PROGRESS_BAR_WIDTH (LCD_PIXEL_WIDTH - PROGRESS_BAR_X) - FORCE_INLINE void _draw_centered_temp(const celsius_t temp, const uint8_t tx, const uint8_t ty) { const char *str; uint8_t len; @@ -471,46 +479,44 @@ FORCE_INLINE void _draw_axis_value(const AxisEnum axis, const char *value, const // Prepare strings for progress display #if ANY(HAS_EXTRA_PROGRESS, HAS_PRINT_PROGRESS) static MarlinUI::progress_t progress = 0; - static char bufferc[13]; + static MString<12> progressString; #endif #if HAS_EXTRA_PROGRESS - static void prepare_time_string(const duration_t &time, char prefix) { - char str[13]; - memset(&bufferc[2], 0x20, 5); // partialy fill with spaces to avoid artifacts and terminator - bufferc[0] = prefix; - bufferc[1] = ':'; - int str_length = time.toDigital(str, time.value >= 60*60*24L); - strcpy(&bufferc[sizeof(bufferc) - str_length - 1], str); - } - + #if HAS_TIME_DISPLAY + static void prepare_time_string(const duration_t &time, char prefix) { + char str[10]; + const uint8_t time_len = time.toDigital(str, time.value >= 60*60*24L); // 5 to 8 chars + progressString.set(prefix, ':', spaces_t(10 - time_len), str); // 2 to 5 spaces + } + #endif #if ENABLED(SHOW_PROGRESS_PERCENT) void MarlinUI::drawPercent() { - if (progress != 0) { - #define PCENTERED 1 // center percent value over progress bar, else align to the right - #define PPOS TERN(PCENTERED, 4, 0) - #define PLEN TERN(PRINT_PROGRESS_SHOW_DECIMALS, 4, 3) - memset(&bufferc, 0x20, 12); - memcpy(&bufferc[PPOS], TERN(PRINT_PROGRESS_SHOW_DECIMALS, permyriadtostr4(progress), ui8tostr3rj(progress / (PROGRESS_SCALE))), PLEN); - bufferc[PPOS+PLEN] = '%'; - } + if (progress == 0) return; + progressString.set( + OPTITEM(PCENTERED, spaces_t(4)) + TERN(PRINT_PROGRESS_SHOW_DECIMALS, permyriadtostr4(progress), ui8tostr3rj(progress / (PROGRESS_SCALE))), '%' + ); } #endif #if ENABLED(SHOW_REMAINING_TIME) void MarlinUI::drawRemain() { if (printJobOngoing() && get_remaining_time() != 0) - prepare_time_string(get_remaining_time(), 'R'); } + prepare_time_string(get_remaining_time(), 'R'); + } #endif #if ENABLED(SHOW_INTERACTION_TIME) void MarlinUI::drawInter() { if (printingIsActive() && interaction_time) - prepare_time_string(interaction_time, 'C'); } + prepare_time_string(interaction_time, 'C'); + } #endif #if ENABLED(SHOW_ELAPSED_TIME) void MarlinUI::drawElapsed() { if (printJobOngoing()) - prepare_time_string(print_job_timer.duration(), 'E'); } + prepare_time_string(print_job_timer.duration(), 'E'); + } #endif #endif // HAS_EXTRA_PROGRESS @@ -779,17 +785,17 @@ void MarlinUI::draw_status_screen() { #if HAS_PRINT_PROGRESS // Progress bar frame - if (PAGE_CONTAINS(PROGRESS_BAR_Y, PROGRESS_BAR_Y + 3)) - u8g.drawFrame(PROGRESS_BAR_X, PROGRESS_BAR_Y, PROGRESS_BAR_WIDTH, 4); + if (PAGE_CONTAINS(PROGRESS_BAR_Y, PROGRESS_BAR_Y + PROGRESS_BAR_HEIGHT - 1)) + u8g.drawFrame(PROGRESS_BAR_X, PROGRESS_BAR_Y, PROGRESS_BAR_WIDTH, PROGRESS_BAR_HEIGHT); // Progress bar solid part - if (PAGE_CONTAINS(PROGRESS_BAR_Y + 1, PROGRESS_BAR_Y + 2)) - u8g.drawBox(PROGRESS_BAR_X + 1, PROGRESS_BAR_Y + 1, progress_bar_solid_width, 2); + if (PAGE_CONTAINS(PROGRESS_BAR_Y + 1, PROGRESS_BAR_Y + PROGRESS_BAR_HEIGHT - 3)) + u8g.drawBox(PROGRESS_BAR_X + 1, PROGRESS_BAR_Y + 1, progress_bar_solid_width, PROGRESS_BAR_HEIGHT - 2); // Progress strings - if (PAGE_CONTAINS(EXTRAS_BASELINE - INFO_FONT_ASCENT, EXTRAS_BASELINE - 1)) { + if (PAGE_CONTAINS(PCT_Y - INFO_FONT_ASCENT, PCT_Y - 1)) { ui.rotate_progress(); - lcd_put_u8str(PROGRESS_BAR_X, EXTRAS_BASELINE, bufferc); + lcd_put_u8str(PCT_X, PCT_Y, progressString); } #endif diff --git a/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp b/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp index a6e942b7066e..2039d9963581 100644 --- a/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp +++ b/Marlin/src/lcd/dogm/status_screen_lite_ST7920.cpp @@ -664,15 +664,17 @@ bool ST7920_Lite_Status_Screen::indicators_changed() { #if HAS_PRINT_PROGRESS static char screenstr[8]; - char * ST7920_Lite_Status_Screen::prepare_time_string(const duration_t &time, char prefix) { - static char str[6]; - memset(&screenstr, 0x20, 8); // fill with spaces to avoid artifacts, not doing right-justification to save cycles - screenstr[0] = prefix; - TERN_(HOTENDS == 1, screenstr[1] = 0x07;) // add bullet • separator when there is space - int str_length = time.toDigital(str); - memcpy(&screenstr[TERN(HOTENDS == 1, 2, 1)], str, str_length); //memcpy because we can't have terminator - return screenstr; - } + #if HAS_TIME_DISPLAY + char * ST7920_Lite_Status_Screen::prepare_time_string(const duration_t &time, char prefix) { + static char str[6]; + memset(&screenstr, ' ', 8); // fill with spaces to avoid artifacts, not doing right-justification to save cycles + screenstr[0] = prefix; + TERN_(HOTENDS == 1, screenstr[1] = 0x07;) // add bullet • separator when there is space + int str_length = time.toDigital(str); + memcpy(&screenstr[TERN(HOTENDS == 1, 2, 1)], str, str_length); //memcpy because we can't have terminator + return screenstr; + } + #endif void ST7920_Lite_Status_Screen::draw_progress_string(uint8_t addr, const char *str) { set_ddram_address(addr); @@ -687,7 +689,7 @@ bool ST7920_Lite_Status_Screen::indicators_changed() { void ST7920_Lite_Status_Screen::drawPercent() { #define LSHIFT TERN(HOTENDS == 1, 0, 1) const uint8_t progress = ui.get_progress_percent(); - memset(&screenstr, 0x20, 8); // fill with spaces to avoid artifacts + memset(&screenstr, ' ', 8); // fill with spaces to avoid artifacts if (progress){ memcpy(&screenstr[2 - LSHIFT], \ TERN(PRINT_PROGRESS_SHOW_DECIMALS, permyriadtostr4(ui.get_progress_permyriad()), ui8tostr3rj(progress)), \ diff --git a/Marlin/src/lcd/dogm/status_screen_lite_ST7920.h b/Marlin/src/lcd/dogm/status_screen_lite_ST7920.h index d838ee1a3a68..e096825f8adc 100644 --- a/Marlin/src/lcd/dogm/status_screen_lite_ST7920.h +++ b/Marlin/src/lcd/dogm/status_screen_lite_ST7920.h @@ -83,8 +83,10 @@ class ST7920_Lite_Status_Screen { static void draw_bed_temp(const int16_t temp, const int16_t target, bool forceUpdate=false); static void draw_fan_speed(const uint8_t value); #if HAS_PRINT_PROGRESS + #if HAS_TIME_DISPLAY + static char* prepare_time_string(const duration_t &time, char prefix=' '); + #endif static void draw_progress_bar(const uint8_t value); - static char* prepare_time_string(const duration_t &time, char prefix=' '); static void draw_progress_string(uint8_t addr, const char *str); static void update_progress(const bool forceUpdate); #endif diff --git a/Marlin/src/lcd/extui/dgus_e3s1pro/DGUSTxHandler.cpp b/Marlin/src/lcd/extui/dgus_e3s1pro/DGUSTxHandler.cpp index 0dd12b1612c0..3a9ca9c76288 100644 --- a/Marlin/src/lcd/extui/dgus_e3s1pro/DGUSTxHandler.cpp +++ b/Marlin/src/lcd/extui/dgus_e3s1pro/DGUSTxHandler.cpp @@ -105,7 +105,7 @@ void DGUSTxHandler::sdCardInsertionStatus(DGUS_VP &vp) { } #endif // PIDTEMPBED -static duration_t _PrintRemainingDurationEstimate() { +static duration_t _printRemainingDurationEstimate() { duration_t remainingDuration = 0; if (ExtUI::isPrinting()) { @@ -120,12 +120,12 @@ static duration_t _PrintRemainingDurationEstimate() { } void DGUSTxHandler::printRemainingHours(DGUS_VP &vp) { - const int16_t data = _PrintRemainingDurationEstimate().hour(); + const int16_t data = _printRemainingDurationEstimate().hour(); dgus.write((uint16_t)vp.addr, Endianness::toBE(data)); } void DGUSTxHandler::printRemainingMinutes(DGUS_VP &vp) { - const int16_t data = _PrintRemainingDurationEstimate().minute() % 60; + const int16_t data = _printRemainingDurationEstimate().minute() % 60; dgus.write((uint16_t)vp.addr, Endianness::toBE(data)); } From 01aa87c3077c9bac8e075818a87e52098dbde999 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sun, 10 Dec 2023 00:23:34 +0000 Subject: [PATCH 70/77] [cron] Bump distribution date (2023-12-10) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 4b493f35ab72..c171a6fc25fe 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2023-12-09" +//#define STRING_DISTRIBUTION_DATE "2023-12-10" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 02525afb5437..cc6ab3ec6611 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2023-12-09" + #define STRING_DISTRIBUTION_DATE "2023-12-10" #endif /** From b94a3354932dbcf6680e8d378219e9f41f29873e Mon Sep 17 00:00:00 2001 From: rondlh <77279634+rondlh@users.noreply.github.com> Date: Tue, 12 Dec 2023 08:48:02 +0800 Subject: [PATCH 71/77] =?UTF-8?q?=E2=9C=A8=20SERIAL=5FDMA=20(for=20some=20?= =?UTF-8?q?STM32Fx)=20(#26328)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration_adv.h | 24 +- Marlin/src/HAL/AVR/MarlinSerial.h | 4 - Marlin/src/HAL/AVR/inc/Conditionals_LCD.h | 4 + Marlin/src/HAL/LPC1768/MarlinSerial.h | 10 - Marlin/src/HAL/LPC1768/inc/Conditionals_LCD.h | 4 + Marlin/src/HAL/LPC1768/inc/Conditionals_adv.h | 7 + Marlin/src/HAL/STM32/HardwareSerial.cpp | 449 ++++++++++++++++++ Marlin/src/HAL/STM32/HardwareSerial.h | 85 ++++ Marlin/src/HAL/STM32/MarlinSerial.cpp | 60 ++- Marlin/src/HAL/STM32/MarlinSerial.h | 37 +- Marlin/src/inc/SanityCheck.h | 9 + buildroot/tests/STM32F103RE_btt | 1 + 12 files changed, 637 insertions(+), 57 deletions(-) create mode 100644 Marlin/src/HAL/STM32/HardwareSerial.cpp create mode 100644 Marlin/src/HAL/STM32/HardwareSerial.h diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 5871c99a215f..e4f85a8d87b7 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -2649,10 +2649,12 @@ //#define FULL_REPORT_TO_HOST_FEATURE // Auto-report the machine status like Grbl CNC #endif -// Bad Serial-connections can miss a received command by sending an 'ok' -// Therefore some clients abort after 30 seconds in a timeout. -// Some other clients start sending commands while receiving a 'wait'. -// This "wait" is only sent when the buffer is empty. 1 second is a good value here. +/** + * Bad Serial-connections can miss a received command by sending an 'ok' + * Therefore some clients abort after 30 seconds in a timeout. + * Some other clients start sending commands while receiving a 'wait'. + * This "wait" is only sent when the buffer is empty. 1 second is a good value here. + */ //#define NO_TIMEOUTS 1000 // (ms) // Some clients will have this feature soon. This could make the NO_TIMEOUTS unnecessary. @@ -2665,6 +2667,15 @@ // For serial echo, the number of digits after the decimal point //#define SERIAL_FLOAT_PRECISION 4 +/** + * This feature is EXPERIMENTAL so use with caution and test thoroughly. + * Enable this option to receive data on the serial ports via the onboard DMA + * controller for more stable and reliable high-speed serial communication. + * Only some STM32 MCUs are currently supported. + * Note: This has no effect on emulated USB serial ports. + */ +//#define SERIAL_DMA + /** * Set the number of proportional font spaces required to fill up a typical character space. * This can help to better align the output of commands like `G29 O` Mesh Output. @@ -3442,9 +3453,8 @@ /** * TWI/I2C BUS * - * This feature is an EXPERIMENTAL feature so it shall not be used on production - * machines. Enabling this will allow you to send and receive I2C data from slave - * devices on the bus. + * This feature is EXPERIMENTAL but may be useful for custom I2C peripherals. + * Enable this to send and receive I2C data from slave devices on the bus. * * ; Example #1 * ; This macro send the string "Marlin" to the slave device with address 0x63 (99) diff --git a/Marlin/src/HAL/AVR/MarlinSerial.h b/Marlin/src/HAL/AVR/MarlinSerial.h index f47541f12dc5..a40730e0a87f 100644 --- a/Marlin/src/HAL/AVR/MarlinSerial.h +++ b/Marlin/src/HAL/AVR/MarlinSerial.h @@ -37,10 +37,6 @@ #include "../../core/types.h" #include "../../core/serial_hook.h" -#ifndef SERIAL_PORT - #define SERIAL_PORT 0 -#endif - #ifndef USBCON // The presence of the UBRRH register is used to detect a UART. diff --git a/Marlin/src/HAL/AVR/inc/Conditionals_LCD.h b/Marlin/src/HAL/AVR/inc/Conditionals_LCD.h index 5f1c4b16019d..65b019b261a8 100644 --- a/Marlin/src/HAL/AVR/inc/Conditionals_LCD.h +++ b/Marlin/src/HAL/AVR/inc/Conditionals_LCD.h @@ -20,3 +20,7 @@ * */ #pragma once + +#ifndef SERIAL_PORT + #define SERIAL_PORT 0 +#endif diff --git a/Marlin/src/HAL/LPC1768/MarlinSerial.h b/Marlin/src/HAL/LPC1768/MarlinSerial.h index 3e6848a1e3d0..2fadd8209bdf 100644 --- a/Marlin/src/HAL/LPC1768/MarlinSerial.h +++ b/Marlin/src/HAL/LPC1768/MarlinSerial.h @@ -30,16 +30,6 @@ #endif #include "../../core/serial_hook.h" -#ifndef SERIAL_PORT - #define SERIAL_PORT 0 -#endif -#ifndef RX_BUFFER_SIZE - #define RX_BUFFER_SIZE 128 -#endif -#ifndef TX_BUFFER_SIZE - #define TX_BUFFER_SIZE 32 -#endif - class MarlinSerial : public HardwareSerial { public: MarlinSerial(LPC_UART_TypeDef *UARTx) : HardwareSerial(UARTx) { } diff --git a/Marlin/src/HAL/LPC1768/inc/Conditionals_LCD.h b/Marlin/src/HAL/LPC1768/inc/Conditionals_LCD.h index 5f1c4b16019d..65b019b261a8 100644 --- a/Marlin/src/HAL/LPC1768/inc/Conditionals_LCD.h +++ b/Marlin/src/HAL/LPC1768/inc/Conditionals_LCD.h @@ -20,3 +20,7 @@ * */ #pragma once + +#ifndef SERIAL_PORT + #define SERIAL_PORT 0 +#endif diff --git a/Marlin/src/HAL/LPC1768/inc/Conditionals_adv.h b/Marlin/src/HAL/LPC1768/inc/Conditionals_adv.h index 8e7cab185f2a..9d04c4f787c6 100644 --- a/Marlin/src/HAL/LPC1768/inc/Conditionals_adv.h +++ b/Marlin/src/HAL/LPC1768/inc/Conditionals_adv.h @@ -24,3 +24,10 @@ #if DISABLED(NO_SD_HOST_DRIVE) #define HAS_SD_HOST_DRIVE 1 #endif + +#ifndef RX_BUFFER_SIZE + #define RX_BUFFER_SIZE 128 +#endif +#ifndef TX_BUFFER_SIZE + #define TX_BUFFER_SIZE 32 +#endif diff --git a/Marlin/src/HAL/STM32/HardwareSerial.cpp b/Marlin/src/HAL/STM32/HardwareSerial.cpp new file mode 100644 index 000000000000..a6f97f356e2e --- /dev/null +++ b/Marlin/src/HAL/STM32/HardwareSerial.cpp @@ -0,0 +1,449 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * Copyright (c) 2017 Victor Perez + * + * 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 . + * + */ + +// +// HAL_HardwareSerial Class. Adapted from Arduino HardwareSerial. +// + +#include "../platforms.h" + +#ifdef HAL_STM32 + +#include "../../inc/MarlinConfig.h" + +#if ENABLED(SERIAL_DMA) && defined(HAL_UART_MODULE_ENABLED) && !defined(HAL_UART_MODULE_ONLY) + +#include +#include "HardwareSerial.h" +#include "uart.h" + +// USART/UART PIN MAPPING FOR STM32F0/F1/F2/F4/F7 +#ifndef PIN_SERIAL1_TX + #define PIN_SERIAL1_TX PA9 +#endif +#ifndef PIN_SERIAL1_RX + #define PIN_SERIAL1_RX PA10 +#endif +#ifndef PIN_SERIAL2_TX + #define PIN_SERIAL2_TX PA2 +#endif +#ifndef PIN_SERIAL2_RX + #define PIN_SERIAL2_RX PA3 +#endif +#ifndef PIN_SERIAL3_TX + #define PIN_SERIAL3_TX PB10 +#endif +#ifndef PIN_SERIAL3_RX + #define PIN_SERIAL3_RX PB11 +#endif +#ifndef PIN_SERIAL4_TX + #define PIN_SERIAL4_TX PC10 +#endif +#ifndef PIN_SERIAL4_RX + #define PIN_SERIAL4_RX PC11 +#endif +#ifndef PIN_SERIAL5_TX + #define PIN_SERIAL5_TX PC12 +#endif +#ifndef PIN_SERIAL5_RX + #define PIN_SERIAL5_RX PD2 +#endif +#ifndef PIN_SERIAL6_TX + #define PIN_SERIAL6_TX PC6 +#endif +#ifndef PIN_SERIAL6_RX + #define PIN_SERIAL6_RX PC7 +#endif + +// TODO: Get from include file + +#if ANY(STM32F2xx, STM32F4xx, STM32F7xx) + + #define RCC_AHB1Periph_DMA1 ((uint32_t)0x00200000) + #define RCC_AHB1Periph_DMA2 ((uint32_t)0x00400000) + + void RCC_AHB1PeriphClockCmd(uint32_t RCC_AHB1Periph, FunctionalState NewState) { + // Check the parameters + assert_param(IS_RCC_AHB1_CLOCK_PERIPH(RCC_AHB1Periph)); + + assert_param(IS_FUNCTIONAL_STATE(NewState)); + if (NewState != DISABLE) + RCC->AHB1ENR |= RCC_AHB1Periph; + else + RCC->AHB1ENR &= ~RCC_AHB1Periph; + } + +#endif + +#if ANY(STM32F0xx, STM32F1xx) + + #define RCC_AHBPeriph_DMA1 ((uint32_t)0x00000001) + #define RCC_AHBPeriph_DMA2 ((uint32_t)0x00000002) + + void RCC_AHBPeriphClockCmd(uint32_t RCC_AHBPeriph, FunctionalState NewState) { + /* Check the parameters */ + assert_param(IS_RCC_AHB_PERIPH(RCC_AHBPeriph)); + assert_param(IS_FUNCTIONAL_STATE(NewState)); + + if (NewState != DISABLE) + RCC->AHBENR |= RCC_AHBPeriph; + else + RCC->AHBENR &= ~RCC_AHBPeriph; + } + +#endif + +// END OF TODO------------------------------------------------------ + +// SerialEvent functions are weak, so when the user doesn't define them, +// the linker just sets their address to 0 (which is checked below). +#ifdef USING_HW_SERIAL1 + HAL_HardwareSerial HSerial1(USART1); + void serialEvent1() __attribute__((weak)); +#endif +#ifdef USING_HW_SERIAL2 + HAL_HardwareSerial HSerial2(USART2); + void serialEvent2() __attribute__((weak)); +#endif +#ifdef USING_HW_SERIAL3 + HAL_HardwareSerial Serial3(USART3); + void serialEvent3() __attribute__((weak)); +#endif +#ifdef USING_HW_SERIAL4 + #ifdef USART4 + HAL_HardwareSerial HSerial4(USART4); + #else + HAL_HardwareSerial HSerial4(UART4); + #endif + void serialEvent4() __attribute__((weak)); +#endif +#ifdef USING_HW_SERIAL5 + #ifdef USART5 + HAL_HardwareSerial HSerial5(USART5); + #else + HAL_HardwareSerial HSerial5(UART5); + #endif + void serialEvent5() __attribute__((weak)); +#endif +#ifdef USING_HW_SERIAL6 + #ifdef USART6 + HAL_HardwareSerial HSerial5(USART6); + #else + HAL_HardwareSerial HSerial5(UART6); + #endif + void serialEvent5() __attribute__((weak)); +#endif + +// Constructors //////////////////////////////////////////////////////////////// + +HAL_HardwareSerial::HAL_HardwareSerial(void *peripheral) { + if (peripheral == USART1) { + setRx(PIN_SERIAL1_RX); + setTx(PIN_SERIAL1_TX); + _uart_index = 0; + #ifdef DMA2_Stream2 + RX_DMA = { USART1, RCC_AHB1Periph_DMA2, 4, DMA2_Stream2 }; + #endif + #ifdef DMA1_Channel5 + RX_DMA = { USART1, RCC_AHBPeriph_DMA1, DMA1, DMA1_Channel5 }; + #endif + } + else if (peripheral == USART2) { + setRx(PIN_SERIAL2_RX); + setTx(PIN_SERIAL2_TX); + _uart_index = 1; + #ifdef DMA1_Stream5 + RX_DMA = { USART2, RCC_AHB1Periph_DMA1, 4, DMA1_Stream5 }; + #endif + #ifdef DMA1_Channel6 + RX_DMA = { USART2, RCC_AHBPeriph_DMA1, DMA1, DMA1_Channel6 }; + #endif + } + else if (peripheral == USART3) { + setRx(PIN_SERIAL3_RX); + setTx(PIN_SERIAL3_TX); + _uart_index = 2; + #ifdef DMA1_Stream1 + RX_DMA = { USART3, RCC_AHB1Periph_DMA1, 4, DMA1_Stream1 }; + #endif + #ifdef DMA1_Channel3 // F0 has no support for UART3, requires system remapping + RX_DMA = { USART3, RCC_AHBPeriph_DMA1, DMA1, DMA1_Channel3 }; + #endif + } + + #ifdef USART4 // Only F2 / F4 / F7 + else if (peripheral == USART4) { + #ifdef DMA1_Stream2 + RX_DMA = { USART4, RCC_AHB1Periph_DMA1, 4, DMA1_Stream2 }; + #endif + setRx(PIN_SERIAL4_RX); + setTx(PIN_SERIAL4_TX); + _uart_index = 3; + } + #endif + + #ifdef UART4 + else if (peripheral == UART4) { + #ifdef DMA1_Stream2 + RX_DMA = { UART4, RCC_AHB1Periph_DMA1, 4, DMA1_Stream2 }; + #endif + #ifdef DMA2_Channel3 // STM32F0xx has only 3 UARTs + RX_DMA = { UART4, RCC_AHBPeriph_DMA2, DMA2, DMA2_Channel3 }; + #endif + setRx(PIN_SERIAL4_RX); + setTx(PIN_SERIAL4_TX); + _uart_index = 3; + } + #endif + + #ifdef UART5 // Only F2 / F4 / F7 + else if (peripheral == UART5) { + #ifdef DMA1_Stream0 + RX_DMA = { UART5, RCC_AHB1Periph_DMA1, 4, DMA1_Stream0 }; + #endif + setRx(PIN_SERIAL5_RX); + setTx(PIN_SERIAL5_TX); + _uart_index = 4; + } + #endif + + #ifdef USART6 // Only F2 / F4 / F7 + else if (peripheral == USART6) { + #ifdef DMA2_Stream1 + RX_DMA = { USART6, RCC_AHB1Periph_DMA2, 4, DMA2_Stream1 }; + #endif + setRx(PIN_SERIAL6_RX); + setTx(PIN_SERIAL6_TX); + _uart_index = 5; + } + #endif + + else { // else get the pins of the first peripheral occurence in PinMap + _serial.pin_rx = pinmap_pin(peripheral, PinMap_UART_RX); + _serial.pin_tx = pinmap_pin(peripheral, PinMap_UART_TX); + } + + init(_serial.pin_rx, _serial.pin_tx); +} + +void HAL_HardwareSerial::setRx(uint32_t _rx) { + _serial.pin_rx = digitalPinToPinName(_rx); +} + +void HAL_HardwareSerial::setTx(uint32_t _tx) { + _serial.pin_tx = digitalPinToPinName(_tx); +} + +void HAL_HardwareSerial::init(PinName _rx, PinName _tx) { + _serial.pin_rx = _rx; + _serial.rx_buff = _rx_buffer; + _serial.rx_head = _serial.rx_tail = 0; + + _serial.pin_tx = _tx; + _serial.tx_buff = _tx_buffer; + _serial.tx_head = _serial.tx_tail = 0; +} + +// Actual interrupt handlers ////////////////////////////////////////////////////////////// + +/** + * @brief Read receive byte from uart + * @param obj : pointer to serial_t structure + * @retval last character received + */ +int HAL_HardwareSerial::_tx_complete_irq(serial_t *obj) { + // If interrupts are enabled, there must be more data in the output buffer. Send the next byte + obj->tx_tail = (obj->tx_tail + 1) % TX_BUFFER_SIZE; + + if (obj->tx_head == obj->tx_tail) return -1; + + return 0; +} + +// Public Methods ////////////////////////////////////////////////////////////// + +void HAL_HardwareSerial::begin(unsigned long baud, uint8_t config) { + uint32_t databits = 0, stopbits = 0, parity = 0; + + _baud = baud; + _config = config; + + // Manage databits + switch (config & 0x07) { + case 0x02: databits = 6; break; + case 0x04: databits = 7; break; + case 0x06: databits = 8; break; + default: databits = 0; break; + } + + if ((config & 0x30) == 0x30) { + parity = UART_PARITY_ODD; + databits++; + } + else if ((config & 0x20) == 0x20) { + parity = UART_PARITY_EVEN; + databits++; + } + else + parity = UART_PARITY_NONE; + + stopbits = (config & 0x08) == 0x08 ? UART_STOPBITS_2 : UART_STOPBITS_1; + + switch (databits) { + #ifdef UART_WORDLENGTH_7B + case 7: databits = UART_WORDLENGTH_7B; break; + #endif + case 8: databits = UART_WORDLENGTH_8B; break; + case 9: databits = UART_WORDLENGTH_9B; break; + default: + case 0: Error_Handler(); break; + } + + uart_init(&_serial, (uint32_t)baud, databits, parity, stopbits); + Serial_DMA_Read_Enable(); // Start the circular DMA serial reading process, no callback needed +} + +void HAL_HardwareSerial::end() { + flush(); // Wait for transmission of outgoing data + uart_deinit(&_serial); + _serial.rx_head = _serial.rx_tail; // Clear any received data +} + +// Update buffer head for DMA progress +void HAL_HardwareSerial::update_rx_head() { + + #if ENABLED(EMERGENCY_PARSER) + static uint32_t flag = 0; + while (flag != _serial.rx_head) { // send all available data to emergency parser immediately + emergency_parser.update(static_cast(this)->emergency_state, _serial.rx_buff[flag]); + flag = (flag + 1) % RX_BUFFER_SIZE; + } + #endif + + #if ANY(STM32F2xx, STM32F4xx, STM32F7xx) + _serial.rx_head = RX_BUFFER_SIZE - RX_DMA.dma_streamRX->NDTR; + #endif + + #if ANY(STM32F0xx, STM32F1xx) + _serial.rx_head = RX_BUFFER_SIZE - RX_DMA.dma_channelRX->CNDTR; + #endif + +} + +int HAL_HardwareSerial::available() { + update_rx_head(); + return ((unsigned int)(RX_BUFFER_SIZE + _serial.rx_head - _serial.rx_tail)) % RX_BUFFER_SIZE; +} + +int HAL_HardwareSerial::peek() { + update_rx_head(); + if (_serial.rx_head == _serial.rx_tail) return -1; + return _serial.rx_buff[_serial.rx_tail]; +} + +int HAL_HardwareSerial::read() { + update_rx_head(); + if (_serial.rx_head == _serial.rx_tail) return -1; // No chars if the head isn't ahead of the tail + + unsigned char c = _serial.rx_buff[_serial.rx_tail]; + _serial.rx_tail = (rx_buffer_index_t)(_serial.rx_tail + 1) % RX_BUFFER_SIZE; + return c; +} + +size_t HAL_HardwareSerial::write(uint8_t c) { // Interrupt based writing + tx_buffer_index_t i = (_serial.tx_head + 1) % TX_BUFFER_SIZE; + + // If the output buffer is full, there's nothing for it other than to + // wait for the interrupt handler to empty it a bit + while (i == _serial.tx_tail) { /* nada */ } // NOP, let the interrupt free up space for us + + _serial.tx_buff[_serial.tx_head] = c; + _serial.tx_head = i; + + if (!serial_tx_active(&_serial)) + uart_attach_tx_callback(&_serial, _tx_complete_irq); // Write next byte, launch interrupt + + return 1; +} + +void HAL_HardwareSerial::flush() { + while ((_serial.tx_head != _serial.tx_tail)) { /* nada */ } // nop, the interrupt handler will free up space for us +} + +#if ANY(STM32F2xx, STM32F4xx, STM32F7xx) + + void HAL_HardwareSerial::Serial_DMA_Read_Enable() { + RCC_AHB1PeriphClockCmd(RX_DMA.dma_rcc, ENABLE); // Enable DMA clock + + #ifdef STM32F7xx + RX_DMA.dma_streamRX->PAR = (uint32_t)(&RX_DMA.uart->RDR); // RX peripheral receive address (usart) F7 + #else + RX_DMA.dma_streamRX->PAR = (uint32_t)(&RX_DMA.uart->DR); // RX peripheral address (usart) F2 / F4 + #endif + RX_DMA.dma_streamRX->M0AR = (uint32_t)_serial.rx_buff; // RX destination address (memory) + RX_DMA.dma_streamRX->NDTR = RX_BUFFER_SIZE; // RX buffer size + + RX_DMA.dma_streamRX->CR = (RX_DMA.dma_channel << 25); // RX channel selection, set to 0 all the other CR bits + + RX_DMA.dma_streamRX->CR |= (3 << 16); // RX priority level: Very High + + //RX_DMA.dma_streamRX->CR &= ~(3 << 13); // RX memory data size: 8 bit + //RX_DMA.dma_streamRX->CR &= ~(3 << 11); // RX peripheral data size: 8 bit + RX_DMA.dma_streamRX->CR |= (1 << 10); // RX memory increment mode + //RX_DMA.dma_streamRX->CR &= ~(1 << 9); // RX peripheral no increment mode + RX_DMA.dma_streamRX->CR |= (1 << 8); // RX circular mode enabled + //RX_DMA.dma_streamRX->CR &= ~(1 << 6); // RX data transfer direction: Peripheral-to-memory + RX_DMA.uart->CR3 |= (1 << 6); // Enable DMA receiver (DMAR) + RX_DMA.dma_streamRX->CR |= (1 << 0); // RX enable DMA + } + +#endif // STM32F2xx || STM32F4xx || STM32F7xx + +#if ANY(STM32F0xx, STM32F1xx) + + void HAL_HardwareSerial::Serial_DMA_Read_Enable() { + RCC_AHBPeriphClockCmd(RX_DMA.dma_rcc, ENABLE); // enable DMA clock + + RX_DMA.dma_channelRX->CPAR = (uint32_t)(&RX_DMA.uart->DR); // RX peripheral address (usart) + RX_DMA.dma_channelRX->CMAR = (uint32_t)_serial.rx_buff; // RX destination address (memory) + RX_DMA.dma_channelRX->CNDTR = RX_BUFFER_SIZE; // RX buffer size + + RX_DMA.dma_channelRX->CCR = 0; // RX channel selection, set to 0 all the other CR bits + + RX_DMA.dma_channelRX->CCR |= (3<<12); // RX priority level: Very High + + //RX_DMA.dma_channelRX->CCR &= ~(1<<10); // RX memory data size: 8 bit + //RX_DMA.dma_channelRX->CCR &= ~(1<<8); // RX peripheral data size: 8 bit + RX_DMA.dma_channelRX->CCR |= (1<<7); // RX memory increment mode + //RX_DMA.dma_channelRX->CCR &= ~(1<<6); // RX peripheral no increment mode + RX_DMA.dma_channelRX->CCR |= (1<<5); // RX circular mode enabled + //RX_DMA.dma_channelRX->CCR &= ~(1<<4); // RX data transfer direction: Peripheral-to-memory + + RX_DMA.uart->CR3 |= (1<<6); // enable DMA receiver (DMAR) + RX_DMA.dma_channelRX->CCR |= (1<<0); // RX enable DMA + } + +#endif // STM32F0xx || STM32F1xx + +#endif // SERIAL_DMA && HAL_UART_MODULE_ENABLED && !HAL_UART_MODULE_ONLY +#endif // HAL_STM32 diff --git a/Marlin/src/HAL/STM32/HardwareSerial.h b/Marlin/src/HAL/STM32/HardwareSerial.h new file mode 100644 index 000000000000..cc564322b4d5 --- /dev/null +++ b/Marlin/src/HAL/STM32/HardwareSerial.h @@ -0,0 +1,85 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * + * Based on Sprinter and grbl. + * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm + * Copyright (c) 2017 Victor Perez + * + * 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 . + * + */ +#pragma once + +// +// HAL_HardwareSerial Class. Adapted from Arduino HardwareSerial. +// + +#if RX_BUFFER_SIZE == 0 + #undef RX_BUFFER_SIZE + #define RX_BUFFER_SIZE 128 +#endif + +#if TX_BUFFER_SIZE == 0 + #undef TX_BUFFER_SIZE + #define TX_BUFFER_SIZE 64 +#endif + +typedef struct { + USART_TypeDef * uart; + uint32_t dma_rcc; + #if ANY(STM32F0xx, STM32F1xx) // F0 / F1 + DMA_TypeDef * dma_controller; + DMA_Channel_TypeDef * dma_channelRX; + #else // F2 / F4 / F7 + uint32_t dma_channel; + DMA_Stream_TypeDef * dma_streamRX; + #endif +} DMA_CFG; + +class HAL_HardwareSerial : public Stream { + protected: + // Don't put any members after these buffers, since only the first + // 32 bytes of this struct can be accessed quickly using the ldd instruction. + unsigned char _rx_buffer[RX_BUFFER_SIZE]; + unsigned char _tx_buffer[TX_BUFFER_SIZE]; + + serial_t _serial; + + public: + HAL_HardwareSerial(void *peripheral); + void begin(unsigned long, uint8_t); + void end(); + virtual int available(); + virtual int read(); + virtual int peek(); + virtual size_t write(uint8_t); + virtual void flush(); + operator bool() { return true; } + + void setRx(uint32_t _rx); + void setTx(uint32_t _tx); + + static int _tx_complete_irq(serial_t *obj); // Interrupt handler + + private: + uint8_t _uart_index; + bool _rx_enabled; + uint8_t _config; + unsigned long _baud; + void init(PinName _rx, PinName _tx); + void update_rx_head(); + DMA_CFG RX_DMA; + void Serial_DMA_Read_Enable(); +}; diff --git a/Marlin/src/HAL/STM32/MarlinSerial.cpp b/Marlin/src/HAL/STM32/MarlinSerial.cpp index 9f0b003a316b..c4bc62994908 100644 --- a/Marlin/src/HAL/STM32/MarlinSerial.cpp +++ b/Marlin/src/HAL/STM32/MarlinSerial.cpp @@ -47,10 +47,15 @@ #define USART9 UART9 #endif -#define DECLARE_SERIAL_PORT(ser_num) \ - void _rx_complete_irq_ ## ser_num (serial_t * obj); \ - MSerialT MSerial ## ser_num (true, USART ## ser_num, &_rx_complete_irq_ ## ser_num); \ - void _rx_complete_irq_ ## ser_num (serial_t * obj) { MSerial ## ser_num ._rx_complete_irq(obj); } +#if ENABLED(SERIAL_DMA) + #define DECLARE_SERIAL_PORT(ser_num) \ + MSerialT MSerial ## ser_num (true, USART ## ser_num); +#else + #define DECLARE_SERIAL_PORT(ser_num) \ + void _rx_complete_irq_ ## ser_num (serial_t * obj); \ + MSerialT MSerial ## ser_num (true, USART ## ser_num, &_rx_complete_irq_ ## ser_num); \ + void _rx_complete_irq_ ## ser_num (serial_t * obj) { MSerial ## ser_num ._rx_complete_irq(obj); } +#endif #if USING_HW_SERIAL1 DECLARE_SERIAL_PORT(1) @@ -87,33 +92,38 @@ #endif void MarlinSerial::begin(unsigned long baud, uint8_t config) { - HardwareSerial::begin(baud, config); - // Replace the IRQ callback with the one we have defined - TERN_(EMERGENCY_PARSER, _serial.rx_callback = _rx_callback); + #if ENABLED(SERIAL_DMA) + HAL_HardwareSerial::begin(baud, config); + #else + HardwareSerial::begin(baud, config); + // Replace the IRQ callback with the one we have defined + TERN_(EMERGENCY_PARSER, _serial.rx_callback = _rx_callback); + #endif } -// This function is Copyright (c) 2006 Nicholas Zambetti. -void MarlinSerial::_rx_complete_irq(serial_t *obj) { - // No Parity error, read byte and store it in the buffer if there is room - unsigned char c; +#if DISABLED(SERIAL_DMA) - if (uart_getc(obj, &c) == 0) { + // This function Copyright (c) 2006 Nicholas Zambetti. + void MarlinSerial::_rx_complete_irq(serial_t *obj) { + // No Parity error, read byte and store it in the buffer if there is room + unsigned char c; + if (uart_getc(obj, &c) == 0) { - rx_buffer_index_t i = (unsigned int)(obj->rx_head + 1) % SERIAL_RX_BUFFER_SIZE; + rx_buffer_index_t i = (unsigned int)(obj->rx_head + 1) % SERIAL_RX_BUFFER_SIZE; - // if we should be storing the received character into the location - // just before the tail (meaning that the head would advance to the - // current location of the tail), we're about to overflow the buffer - // and so we don't write the character or advance the head. - if (i != obj->rx_tail) { - obj->rx_buff[obj->rx_head] = c; - obj->rx_head = i; - } + // If tail overlaps head the buffer is overflowed + // so don't write the character or advance the head. + if (i != obj->rx_tail) { + obj->rx_buff[obj->rx_head] = c; + obj->rx_head = i; + } - #if ENABLED(EMERGENCY_PARSER) - emergency_parser.update(static_cast(this)->emergency_state, c); - #endif + #if ENABLED(EMERGENCY_PARSER) + emergency_parser.update(static_cast(this)->emergency_state, c); + #endif + } } -} + +#endif // !SERIAL_DMA #endif // HAL_STM32 diff --git a/Marlin/src/HAL/STM32/MarlinSerial.h b/Marlin/src/HAL/STM32/MarlinSerial.h index bf861fb8a79a..4ab1e4e75a6b 100644 --- a/Marlin/src/HAL/STM32/MarlinSerial.h +++ b/Marlin/src/HAL/STM32/MarlinSerial.h @@ -27,23 +27,38 @@ #include "../../feature/e_parser.h" #endif +#if ENABLED(SERIAL_DMA) + #include "HardwareSerial.h" +#endif + #include "../../core/serial_hook.h" -typedef void (*usart_rx_callback_t)(serial_t * obj); +#if ENABLED(SERIAL_DMA) + + struct MarlinSerial : public HAL_HardwareSerial { + MarlinSerial(void *peripheral) : HAL_HardwareSerial(peripheral) { } + void begin(unsigned long baud, uint8_t config); + inline void begin(unsigned long baud) { begin(baud, SERIAL_8N1); } + }; + +#else // Arduino non-DMA -struct MarlinSerial : public HardwareSerial { - MarlinSerial(void *peripheral, usart_rx_callback_t rx_callback) : - HardwareSerial(peripheral), _rx_callback(rx_callback) - { } + typedef void (*usart_rx_callback_t)(serial_t * obj); - void begin(unsigned long baud, uint8_t config); - inline void begin(unsigned long baud) { begin(baud, SERIAL_8N1); } + struct MarlinSerial : public HardwareSerial { + MarlinSerial(void *peripheral, usart_rx_callback_t rx_callback) + : HardwareSerial(peripheral), _rx_callback(rx_callback) { } - void _rx_complete_irq(serial_t *obj); + void begin(unsigned long baud, uint8_t config); + inline void begin(unsigned long baud) { begin(baud, SERIAL_8N1); } -protected: - usart_rx_callback_t _rx_callback; -}; + void _rx_complete_irq(serial_t *obj); + + protected: + usart_rx_callback_t _rx_callback; + }; + +#endif typedef Serial1Class MSerialT; extern MSerialT MSerial1; diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 00e90b618356..70eba0d60c9f 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -254,6 +254,15 @@ static_assert(COUNT(arm) == LOGICAL_AXES, "AXIS_RELATIVE_MODES must contain " _L #error "SERIAL_XON_XOFF and SERIAL_STATS_* features not supported on USB-native AVR devices." #endif +// Serial DMA is only available for some STM32 MCUs +#if ENABLED(SERIAL_DMA) + #if !HAL_STM32 || NONE(STM32F0xx, STM32F1xx, STM32F2xx, STM32F4xx, STM32F7xx) + #error "SERIAL_DMA is only available for some STM32 MCUs and requires HAL/STM32." + #elif !defined(HAL_UART_MODULE_ENABLED) || defined(HAL_UART_MODULE_ONLY) + #error "SERIAL_DMA requires STM32 platform HAL UART (without HAL_UART_MODULE_ONLY)." + #endif +#endif + /** * Multiple Stepper Drivers Per Axis */ diff --git a/buildroot/tests/STM32F103RE_btt b/buildroot/tests/STM32F103RE_btt index 97d7ffec4bdd..197ca775989a 100755 --- a/buildroot/tests/STM32F103RE_btt +++ b/buildroot/tests/STM32F103RE_btt @@ -13,6 +13,7 @@ restore_configs opt_set MOTHERBOARD BOARD_BTT_SKR_E3_DIP \ SERIAL_PORT 1 SERIAL_PORT_2 -1 \ X_DRIVER_TYPE TMC2209 Y_DRIVER_TYPE TMC2130 +opt_enable SERIAL_DMA exec_test $1 $2 "BTT SKR E3 DIP 1.0 | Mixed TMC Drivers" "$3" # clean up From f3fd9e28f5d6fae59c55742a2e70e2d6a3330aeb Mon Sep 17 00:00:00 2001 From: ellensp <530024+ellensp@users.noreply.github.com> Date: Tue, 12 Dec 2023 14:30:28 +1300 Subject: [PATCH 72/77] =?UTF-8?q?=F0=9F=90=9B=20Fix=20MKS=20TS35=20with=20?= =?UTF-8?q?BTT=20SKR=201.3/1.4=20(#26176)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/LPC1768/tft/tft_spi.cpp | 8 ++ Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h | 34 +++--- Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h | 123 +++++++++++++++++--- 3 files changed, 133 insertions(+), 32 deletions(-) diff --git a/Marlin/src/HAL/LPC1768/tft/tft_spi.cpp b/Marlin/src/HAL/LPC1768/tft/tft_spi.cpp index 2342de002db7..beaadaf51961 100644 --- a/Marlin/src/HAL/LPC1768/tft/tft_spi.cpp +++ b/Marlin/src/HAL/LPC1768/tft/tft_spi.cpp @@ -55,11 +55,19 @@ void TFT_SPI::dataTransferBegin(uint16_t dataSize) { WRITE(TFT_CS_PIN, LOW); } +#ifdef TFT_DEFAULT_DRIVER + #include "../../../lcd/tft_io/tft_ids.h" +#endif + uint32_t TFT_SPI::getID() { uint32_t id; id = readID(LCD_READ_ID); if ((id & 0xFFFF) == 0 || (id & 0xFFFF) == 0xFFFF) id = readID(LCD_READ_ID4); + #ifdef TFT_DEFAULT_DRIVER + if ((id & 0xFFFF) == 0 || (id & 0xFFFF) == 0xFFFF) + id = TFT_DEFAULT_DRIVER; + #endif return id; } diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h index 4c621bf5eff6..1cc555aafe08 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_3.h @@ -347,6 +347,10 @@ #define TFT_CS_PIN EXP2_04_PIN #define TFT_DC_PIN EXP2_07_PIN + #define TFT_SCK_PIN EXP2_02_PIN + #define TFT_MISO_PIN EXP2_01_PIN + #define TFT_MOSI_PIN EXP2_06_PIN + #define TOUCH_CS_PIN EXP1_04_PIN #define TOUCH_SCK_PIN EXP1_05_PIN #define TOUCH_MISO_PIN EXP1_06_PIN @@ -355,6 +359,10 @@ #elif ENABLED(MKS_TS35_V2_0) + #ifndef NO_CONTROLLER_CUSTOM_WIRING_WARNING + #error "CAUTION! MKS_TS35_V2_0 requires wiring modifications. The SKR 1.3 EXP ports are rotated 180° from what the MKS_TS35_V2_0 expects. (Define NO_CONTROLLER_CUSTOM_WIRING_WARNING to suppress this error.)" + #endif + /** ------ ------ * BEEPER | 1 2 | BTN_ENC SPI1_MISO | 1 2 | SPI1_SCK * TFT_BKL / LCD_EN | 3 4 | TFT_RESET / LCD_RS BTN_EN1 | 3 4 | SPI1_CS @@ -368,36 +376,36 @@ #define TFT_DC_PIN EXP1_08_PIN #define TFT_RESET_PIN EXP1_04_PIN - #define TFT_BACKLIGHT_PIN EXP1_03_PIN - #define TOUCH_BUTTONS_HW_SPI - #define TOUCH_BUTTONS_HW_SPI_DEVICE 1 - //#define TFT_RST_PIN EXP2_07_PIN #define TFT_SCK_PIN EXP2_02_PIN #define TFT_MISO_PIN EXP2_01_PIN #define TFT_MOSI_PIN EXP2_06_PIN - #define LCD_READ_ID 0xD3 #define LCD_USE_DMA_SPI #define TFT_BUFFER_WORDS 2400 + #define TOUCH_CS_PIN EXP1_05_PIN + #define TOUCH_INT_PIN EXP1_06_PIN + #define TOUCH_BUTTONS_HW_SPI + #define TOUCH_BUTTONS_HW_SPI_DEVICE 1 + #endif #if ENABLED(TFT_CLASSIC_UI) #ifndef TOUCH_CALIBRATION_X - #define TOUCH_CALIBRATION_X -11386 + #define TOUCH_CALIBRATION_X -16794 #endif #ifndef TOUCH_CALIBRATION_Y - #define TOUCH_CALIBRATION_Y 8684 + #define TOUCH_CALIBRATION_Y 11000 #endif #ifndef TOUCH_OFFSET_X - #define TOUCH_OFFSET_X 689 + #define TOUCH_OFFSET_X 1024 #endif #ifndef TOUCH_OFFSET_Y - #define TOUCH_OFFSET_Y -273 + #define TOUCH_OFFSET_Y -352 #endif #elif ENABLED(TFT_COLOR_UI) #ifndef TOUCH_CALIBRATION_X @@ -515,14 +523,6 @@ #endif // HAS_WIRED_LCD -#if NEED_TOUCH_PINS - #define TOUCH_CS_PIN EXP1_05_PIN - #define TOUCH_SCK_PIN EXP2_02_PIN - #define TOUCH_MOSI_PIN EXP2_06_PIN - #define TOUCH_MISO_PIN EXP2_01_PIN - #define TOUCH_INT_PIN EXP1_06_PIN -#endif - /** * Special pins * P1_30 (37) (NOT 5V tolerant) diff --git a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h index 8d63ab764ebe..51953324a3af 100644 --- a/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h +++ b/Marlin/src/pins/lpc1768/pins_BTT_SKR_V1_4.h @@ -395,26 +395,119 @@ #define LCD_BACKLIGHT_PIN -1 #elif HAS_SPI_TFT // Config for Classic UI (emulated DOGM) and Color UI - #define TFT_CS_PIN EXP1_07_PIN - #define TFT_DC_PIN EXP1_08_PIN + + #define SDCARD_CONNECTION ONBOARD + + #define BEEPER_PIN EXP1_01_PIN + + #define BTN_ENC EXP1_02_PIN + #define BTN_EN1 EXP2_03_PIN + #define BTN_EN2 EXP2_05_PIN + #define TFT_A0_PIN TFT_DC_PIN - #define TFT_MISO_PIN EXP2_01_PIN - #define TFT_BACKLIGHT_PIN EXP1_03_PIN - #define TFT_RESET_PIN EXP1_04_PIN - #define LCD_USE_DMA_SPI + #ifndef TFT_WIDTH + #define TFT_WIDTH 480 + #endif + #ifndef TFT_HEIGHT + #define TFT_HEIGHT 320 + #endif + + #if ENABLED(BTT_TFT35_SPI_V1_0) + + /** + * ------ ------ + * BEEPER | 1 2 | LCD-BTN MISO | 1 2 | CLK + * T_MOSI | 3 4 | T_CS LCD-ENCA | 3 4 | TFTCS + * T_CLK | 5 6 T_MISO LCD-ENCB | 5 6 MOSI + * PENIRQ | 7 8 | F_CS RS | 7 8 | RESET + * GND | 9 10 | VCC GND | 9 10 | NC + * ------ ------ + * EXP1 EXP2 + * + * 480x320, 3.5", SPI Display with Rotary Encoder. + * Stock Display for the BIQU B1 SE Series. + * Schematic: https://github.com/bigtreetech/TFT35-SPI/blob/master/v1/Hardware/BTT%20TFT35-SPI%20V1-SCH.pdf + */ + #define TFT_CS_PIN EXP2_04_PIN + #define TFT_DC_PIN EXP2_07_PIN + + #define TFT_SCK_PIN EXP2_02_PIN + #define TFT_MISO_PIN EXP2_01_PIN + #define TFT_MOSI_PIN EXP2_06_PIN + + #define TOUCH_CS_PIN EXP1_04_PIN + #define TOUCH_SCK_PIN EXP1_05_PIN + #define TOUCH_MISO_PIN EXP1_06_PIN + #define TOUCH_MOSI_PIN EXP1_03_PIN + #define TOUCH_INT_PIN EXP1_07_PIN + + #elif ENABLED(MKS_TS35_V2_0) + + #ifndef NO_CONTROLLER_CUSTOM_WIRING_WARNING + #error "CAUTION! MKS_TS35_V2_0 requires wiring modifications. The SKR 1.4 EXP ports are rotated 180° from what the MKS_TS35_V2_0 expects. (Define NO_CONTROLLER_CUSTOM_WIRING_WARNING to suppress this error.)" + #endif + + /** ------ ------ + * BEEPER | 1 2 | BTN_ENC SPI1_MISO | 1 2 | SPI1_SCK + * TFT_BKL / LCD_EN | 3 4 | TFT_RESET / LCD_RS BTN_EN1 | 3 4 | SPI1_CS + * TOUCH_CS / LCD_D4 | 5 6 TOUCH_INT / LCD_D5 BTN_EN2 | 5 6 SPI1_MOSI + * SPI1_CS / LCD_D6 | 7 8 | SPI1_RS / LCD_D7 SPI1_RS | 7 8 | RESET + * GND | 9 10 | VCC GND | 9 10 | VCC + * ------ ------ + * EXP1 EXP2 + */ + #define TFT_CS_PIN EXP1_07_PIN + #define TFT_DC_PIN EXP1_08_PIN + + #define TFT_RESET_PIN EXP1_04_PIN + #define TFT_BACKLIGHT_PIN EXP1_03_PIN + + //#define TFT_RST_PIN EXP2_07_PIN + #define TFT_SCK_PIN EXP2_02_PIN + #define TFT_MISO_PIN EXP2_01_PIN + #define TFT_MOSI_PIN EXP2_06_PIN - #define TOUCH_INT_PIN EXP1_06_PIN - #define TOUCH_CS_PIN EXP1_05_PIN - #define TOUCH_BUTTONS_HW_SPI - #define TOUCH_BUTTONS_HW_SPI_DEVICE 1 + #define LCD_USE_DMA_SPI - // SPI 1 - #define SD_SCK_PIN EXP2_02_PIN - #define SD_MISO_PIN EXP2_01_PIN - #define SD_MOSI_PIN EXP2_06_PIN + #define TFT_BUFFER_WORDS 2400 - #define TFT_BUFFER_WORDS 2400 + #define TOUCH_CS_PIN EXP1_05_PIN + #define TOUCH_INT_PIN EXP1_06_PIN + #define TOUCH_BUTTONS_HW_SPI + #define TOUCH_BUTTONS_HW_SPI_DEVICE 1 + + #endif + + #if ENABLED(TFT_CLASSIC_UI) + #ifndef TOUCH_CALIBRATION_X + #define TOUCH_CALIBRATION_X -16794 + #endif + #ifndef TOUCH_CALIBRATION_Y + #define TOUCH_CALIBRATION_Y 11000 + #endif + #ifndef TOUCH_OFFSET_X + #define TOUCH_OFFSET_X 1024 + #endif + #ifndef TOUCH_OFFSET_Y + #define TOUCH_OFFSET_Y -352 + #endif + + #elif ENABLED(TFT_COLOR_UI) + #ifndef TOUCH_CALIBRATION_X + #define TOUCH_CALIBRATION_X -16741 + #endif + #ifndef TOUCH_CALIBRATION_Y + #define TOUCH_CALIBRATION_Y 11258 + #endif + #ifndef TOUCH_OFFSET_X + #define TOUCH_OFFSET_X 1024 + #endif + #ifndef TOUCH_OFFSET_Y + #define TOUCH_OFFSET_Y -367 + #endif + #define TFT_BUFFER_WORDS 2400 + #endif #elif IS_TFTGLCD_PANEL From 81cfa2388236820f4ed498ede01fde502a0fdca0 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Tue, 12 Dec 2023 06:09:34 +0000 Subject: [PATCH 73/77] [cron] Bump distribution date (2023-12-12) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index c171a6fc25fe..00fbba610d31 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2023-12-10" +//#define STRING_DISTRIBUTION_DATE "2023-12-12" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index cc6ab3ec6611..3c5a423ec05a 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2023-12-10" + #define STRING_DISTRIBUTION_DATE "2023-12-12" #endif /** From 06710e54de8c83af77a4f57d458f6463fbfcad93 Mon Sep 17 00:00:00 2001 From: Andrew <18502096+classicrocker883@users.noreply.github.com> Date: Wed, 13 Dec 2023 00:33:03 -0500 Subject: [PATCH 74/77] =?UTF-8?q?=E2=9C=A8=20EDITABLE=5FDISPLAY=5FTIMEOUT?= =?UTF-8?q?=20(#26517)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/Configuration_adv.h | 14 +++--- Marlin/src/core/types.h | 4 +- Marlin/src/feature/bedlevel/bdl/bdl.cpp | 2 +- Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp | 3 +- Marlin/src/gcode/calibrate/G76_M871.cpp | 2 +- Marlin/src/gcode/gcode.cpp | 2 +- Marlin/src/gcode/gcode.h | 2 +- Marlin/src/gcode/lcd/M255.cpp | 4 +- Marlin/src/inc/Conditionals_adv.h | 6 +-- Marlin/src/inc/SanityCheck.h | 2 +- Marlin/src/lcd/e3v2/common/encoder.cpp | 8 +--- Marlin/src/lcd/e3v2/proui/dwin.cpp | 8 ++-- Marlin/src/lcd/e3v2/proui/plot.cpp | 4 +- Marlin/src/lcd/marlinui.cpp | 27 ++++++----- Marlin/src/lcd/marlinui.h | 16 +++++-- Marlin/src/lcd/menu/menu_configuration.cpp | 10 +++-- Marlin/src/lcd/tft/touch.cpp | 2 +- Marlin/src/lcd/touch/touch_buttons.cpp | 2 +- Marlin/src/module/settings.cpp | 50 +++++++++++---------- Marlin/src/module/temperature.h | 14 +++--- ini/features.ini | 2 +- 21 files changed, 102 insertions(+), 82 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index e4f85a8d87b7..8b4fa1ab7ca1 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1471,11 +1471,6 @@ #define FEEDRATE_CHANGE_BEEP_FREQUENCY 440 #endif -// -// LCD Backlight Timeout -// -//#define LCD_BACKLIGHT_TIMEOUT_MINS 1 // (minutes) Timeout before turning off the backlight - #if HAS_BED_PROBE && ANY(HAS_MARLINUI_MENU, HAS_TFT_LVGL_UI) //#define PROBE_OFFSET_WIZARD // Add a Probe Z Offset calibration option to the LCD menu #if ENABLED(PROBE_OFFSET_WIZARD) @@ -2206,6 +2201,15 @@ //#define TFT_BTOKMENU_COLOR 0x145F // 00010 100010 11111 Cyan #endif +// +// LCD Backlight Timeout +// Requires a display with a controllable backlight +// +//#define LCD_BACKLIGHT_TIMEOUT_MINS 1 // (minutes) Timeout before turning off the backlight +#if defined(DISPLAY_SLEEP_MINUTES) || defined(LCD_BACKLIGHT_TIMEOUT_MINS) + #define EDITABLE_DISPLAY_TIMEOUT // Edit timeout with M255 S and a menu item +#endif + // // ADC Button Debounce // diff --git a/Marlin/src/core/types.h b/Marlin/src/core/types.h index d92dbde8b7a4..bcbf2f07aa45 100644 --- a/Marlin/src/core/types.h +++ b/Marlin/src/core/types.h @@ -198,7 +198,7 @@ typedef Flags<8> flags_8_t; typedef Flags<16> flags_16_t; // Flags for some axis states, with per-axis aliases xyzijkuvwe -typedef struct AxisFlags { +typedef struct { union { struct Flags flags; struct { bool LOGICAL_AXIS_LIST(e:1, x:1, y:1, z:1, i:1, j:1, k:1, u:1, v:1, w:1); }; @@ -212,7 +212,7 @@ typedef struct AxisFlags { FI bool operator[](const int n) const { return flags[n]; } FI int size() const { return sizeof(flags); } FI operator bool() const { return flags; } -} axis_flags_t; +} AxisFlags; // // Enumerated axis indices diff --git a/Marlin/src/feature/bedlevel/bdl/bdl.cpp b/Marlin/src/feature/bedlevel/bdl/bdl.cpp index 5345bb78c590..d469bb0c0673 100644 --- a/Marlin/src/feature/bedlevel/bdl/bdl.cpp +++ b/Marlin/src/feature/bedlevel/bdl/bdl.cpp @@ -195,7 +195,7 @@ void BDS_Leveling::process() { safe_delay(10); if (config_state == BDS_CALIBRATE_START) { config_state = BDS_CALIBRATING; - REMEMBER(gsit, gcode.stepper_inactive_time, SEC_TO_MS(60 * 5)); + REMEMBER(gsit, gcode.stepper_inactive_time, MIN_TO_MS(5)); SERIAL_ECHOLNPGM("c_z0:", planner.get_axis_position_mm(Z_AXIS), "-", pos_zero_offset); // Move the z axis instead of enabling the Z axis with M17 diff --git a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp index d136f0000d8c..3d0013b6d2da 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp @@ -772,7 +772,8 @@ void unified_bed_leveling::shift_mesh_height() { const grid_count_t point_num = (GRID_MAX_POINTS - count) + 1; SERIAL_ECHOLNPGM("Probing mesh point ", point_num, "/", GRID_MAX_POINTS, "."); TERN_(HAS_STATUS_MESSAGE, ui.status_printf(0, F(S_FMT " %i/%i"), GET_TEXT(MSG_PROBING_POINT), point_num, int(GRID_MAX_POINTS))); - TERN_(LCD_BACKLIGHT_TIMEOUT_MINS, ui.refresh_backlight_timeout()); + TERN_(HAS_BACKLIGHT_TIMEOUT, ui.refresh_backlight_timeout()); + TERN_(DWIN_LCD_PROUI, dwinRedrawScreen()); #if HAS_MARLINUI_MENU if (ui.button_pressed()) { diff --git a/Marlin/src/gcode/calibrate/G76_M871.cpp b/Marlin/src/gcode/calibrate/G76_M871.cpp index 6fe3dd89cf17..bb69b75d5056 100644 --- a/Marlin/src/gcode/calibrate/G76_M871.cpp +++ b/Marlin/src/gcode/calibrate/G76_M871.cpp @@ -256,7 +256,7 @@ say_waiting_for_probe_heating(); SERIAL_ECHOLNPGM(" Bed:", target_bed, " Probe:", target_probe); - const millis_t probe_timeout_ms = millis() + SEC_TO_MS(900UL); + const millis_t probe_timeout_ms = millis() + MIN_TO_MS(15); while (thermalManager.degProbe() < target_probe) { if (report_temps(next_temp_report, probe_timeout_ms)) { SERIAL_ECHOLNPGM("!Probe heating timed out."); diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index d519bd4e2941..6a0e8cb17142 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -793,7 +793,7 @@ void GcodeSuite::process_parsed_command(const bool no_ok/*=false*/) { case 250: M250(); break; // M250: Set LCD contrast #endif - #if HAS_GCODE_M255 + #if ENABLED(EDITABLE_DISPLAY_TIMEOUT) case 255: M255(); break; // M255: Set LCD Sleep/Backlight Timeout (Minutes) #endif diff --git a/Marlin/src/gcode/gcode.h b/Marlin/src/gcode/gcode.h index 61ff0b047cac..fffd0d714bea 100644 --- a/Marlin/src/gcode/gcode.h +++ b/Marlin/src/gcode/gcode.h @@ -909,7 +909,7 @@ class GcodeSuite { static void M250_report(const bool forReplay=true); #endif - #if HAS_GCODE_M255 + #if ENABLED(EDITABLE_DISPLAY_TIMEOUT) static void M255(); static void M255_report(const bool forReplay=true); #endif diff --git a/Marlin/src/gcode/lcd/M255.cpp b/Marlin/src/gcode/lcd/M255.cpp index 8dc8099de149..2b982ee5d9a0 100644 --- a/Marlin/src/gcode/lcd/M255.cpp +++ b/Marlin/src/gcode/lcd/M255.cpp @@ -21,7 +21,7 @@ */ #include "../../inc/MarlinConfig.h" -#if HAS_GCODE_M255 +#if ENABLED(EDITABLE_DISPLAY_TIMEOUT) #include "../gcode.h" #include "../../lcd/marlinui.h" @@ -51,4 +51,4 @@ void GcodeSuite::M255_report(const bool forReplay/*=true*/) { ); } -#endif // HAS_GCODE_M255 +#endif // EDITABLE_DISPLAY_TIMEOUT diff --git a/Marlin/src/inc/Conditionals_adv.h b/Marlin/src/inc/Conditionals_adv.h index ba074e256088..755b251b1879 100644 --- a/Marlin/src/inc/Conditionals_adv.h +++ b/Marlin/src/inc/Conditionals_adv.h @@ -893,11 +893,11 @@ #if ALL(HAS_RESUME_CONTINUE, PRINTER_EVENT_LEDS, HAS_MEDIA) #define HAS_LEDS_OFF_FLAG 1 #endif -#if DISPLAY_SLEEP_MINUTES || TOUCH_IDLE_SLEEP_MINS +#if defined(DISPLAY_SLEEP_MINUTES) || defined(TOUCH_IDLE_SLEEP_MINS) #define HAS_DISPLAY_SLEEP 1 #endif -#if HAS_DISPLAY_SLEEP || LCD_BACKLIGHT_TIMEOUT_MINS - #define HAS_GCODE_M255 1 +#ifdef LCD_BACKLIGHT_TIMEOUT_MINS + #define HAS_BACKLIGHT_TIMEOUT 1 #endif #if ANY(DIGIPOT_MCP4018, DIGIPOT_MCP4451) diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 70eba0d60c9f..2e1149e66874 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -2762,7 +2762,7 @@ static_assert(COUNT(arm) == LOGICAL_AXES, "AXIS_RELATIVE_MODES must contain " _L #endif #endif -#if LCD_BACKLIGHT_TIMEOUT_MINS +#if HAS_BACKLIGHT_TIMEOUT #if !HAS_ENCODER_ACTION && DISABLED(HAS_DWIN_E3V2) #error "LCD_BACKLIGHT_TIMEOUT_MINS requires an LCD with encoder or keypad." #elif ENABLED(NEOPIXEL_BKGD_INDEX_FIRST) diff --git a/Marlin/src/lcd/e3v2/common/encoder.cpp b/Marlin/src/lcd/e3v2/common/encoder.cpp index eb064950ec59..cb14596849a5 100644 --- a/Marlin/src/lcd/e3v2/common/encoder.cpp +++ b/Marlin/src/lcd/e3v2/common/encoder.cpp @@ -87,9 +87,7 @@ EncoderState encoderReceiveAnalyze() { #if PIN_EXISTS(LCD_LED) //LED_Action(); #endif - #if LCD_BACKLIGHT_TIMEOUT_MINS - ui.refresh_backlight_timeout(); - #endif + TERN_(HAS_BACKLIGHT_TIMEOUT, ui.refresh_backlight_timeout()); if (!ui.backlight) { ui.refresh_brightness(); return ENCODER_DIFF_NO; @@ -161,9 +159,7 @@ EncoderState encoderReceiveAnalyze() { temp_diff = 0; } if (temp_diffState != ENCODER_DIFF_NO) { - #if LCD_BACKLIGHT_TIMEOUT_MINS - ui.refresh_backlight_timeout(); - #endif + TERN_(HAS_BACKLIGHT_TIMEOUT, ui.refresh_backlight_timeout()); if (!ui.backlight) ui.refresh_brightness(); } return temp_diffState; diff --git a/Marlin/src/lcd/e3v2/proui/dwin.cpp b/Marlin/src/lcd/e3v2/proui/dwin.cpp index 8d4aa9106bfa..7c68c60f8195 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin.cpp @@ -1249,7 +1249,7 @@ void eachMomentUpdate() { static millis_t next_var_update_ms = 0, next_rts_update_ms = 0, next_status_update_ms = 0; const millis_t ms = millis(); - #if LCD_BACKLIGHT_TIMEOUT_MINS + #if HAS_BACKLIGHT_TIMEOUT if (ui.backlight_off_ms && ELAPSED(ms, ui.backlight_off_ms)) { turnOffBacklight(); // Backlight off ui.backlight_off_ms = 0; @@ -2235,7 +2235,7 @@ void setMoveZ() { hmiValue.axis = Z_AXIS; setPFloatOnClick(Z_MIN_POS, Z_MAX_POS, #endif -#if LCD_BACKLIGHT_TIMEOUT_MINS +#if ENABLED(EDITABLE_DISPLAY_TIMEOUT) void applyTimer() { ui.backlight_timeout_minutes = menuData.value; } void setTimer() { setIntOnClick(ui.backlight_timeout_min, ui.backlight_timeout_max, ui.backlight_timeout_minutes, applyTimer); } #endif @@ -3123,7 +3123,7 @@ void drawAdvancedSettingsMenu() { #if HAS_LOCKSCREEN MENU_ITEM(ICON_Lock, MSG_LOCKSCREEN, onDrawMenuItem, dwinLockScreen); #endif - #if LCD_BACKLIGHT_TIMEOUT_MINS + #if ENABLED(EDITABLE_DISPLAY_TIMEOUT) EDIT_ITEM(ICON_Brightness, MSG_SCREEN_TIMEOUT, onDrawPIntMenu, setTimer, &ui.backlight_timeout_minutes); #endif #if ENABLED(SOUND_MENU_ITEM) @@ -3347,7 +3347,7 @@ void drawTuneMenu() { EDIT_ITEM(ICON_Brightness, MSG_BRIGHTNESS, onDrawPInt8Menu, setBrightness, &ui.brightness); MENU_ITEM(ICON_Brightness, MSG_BRIGHTNESS_OFF, onDrawMenuItem, turnOffBacklight); #endif - #if LCD_BACKLIGHT_TIMEOUT_MINS + #if ENABLED(EDITABLE_DISPLAY_TIMEOUT) EDIT_ITEM(ICON_Brightness, MSG_SCREEN_TIMEOUT, onDrawPIntMenu, setTimer, &ui.backlight_timeout_minutes); #endif #if ENABLED(CASE_LIGHT_MENU) diff --git a/Marlin/src/lcd/e3v2/proui/plot.cpp b/Marlin/src/lcd/e3v2/proui/plot.cpp index 92c6c947177b..84c58389a6f7 100644 --- a/Marlin/src/lcd/e3v2/proui/plot.cpp +++ b/Marlin/src/lcd/e3v2/proui/plot.cpp @@ -73,9 +73,7 @@ void Plot::update(const_float_t value) { dwinDrawPoint(COLOR_YELLOW, 1, 1, x2 - 1, y); } graphpoints++; - #if LCD_BACKLIGHT_TIMEOUT_MINS - ui.refresh_backlight_timeout(); - #endif + TERN_(HAS_BACKLIGHT_TIMEOUT, ui.refresh_backlight_timeout()); } #endif // PROUI_TUNING_GRAPH diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index 4eb58f52aedf..60fb298dfcde 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -24,7 +24,7 @@ #include "../MarlinCore.h" // for printingIsPaused -#if LED_POWEROFF_TIMEOUT > 0 || ALL(HAS_WIRED_LCD, PRINTER_EVENT_LEDS) || (defined(LCD_BACKLIGHT_TIMEOUT_MINS) && defined(NEOPIXEL_BKGD_INDEX_FIRST)) +#if LED_POWEROFF_TIMEOUT > 0 || ALL(HAS_WIRED_LCD, PRINTER_EVENT_LEDS) || (HAS_BACKLIGHT_TIMEOUT && defined(NEOPIXEL_BKGD_INDEX_FIRST)) #include "../feature/leds/leds.h" #endif @@ -185,10 +185,14 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; volatile int8_t encoderDiff; // Updated in update_buttons, added to encoderPosition every LCD update #endif -#if LCD_BACKLIGHT_TIMEOUT_MINS +#if HAS_BACKLIGHT_TIMEOUT + #if ENABLED(EDITABLE_DISPLAY_TIMEOUT) + uint8_t MarlinUI::backlight_timeout_minutes; // Initialized by settings.load() + #else + constexpr uint8_t MarlinUI::backlight_timeout_minutes; + #endif constexpr uint8_t MarlinUI::backlight_timeout_min, MarlinUI::backlight_timeout_max; - uint8_t MarlinUI::backlight_timeout_minutes; // Initialized by settings.load() millis_t MarlinUI::backlight_off_ms = 0; void MarlinUI::refresh_backlight_timeout() { @@ -203,12 +207,16 @@ constexpr uint8_t epps = ENCODER_PULSES_PER_STEP; #elif HAS_DISPLAY_SLEEP + #if ENABLED(EDITABLE_DISPLAY_TIMEOUT) + uint8_t MarlinUI::sleep_timeout_minutes; // Initialized by settings.load() + #else + constexpr uint8_t MarlinUI::sleep_timeout_minutes; + #endif constexpr uint8_t MarlinUI::sleep_timeout_min, MarlinUI::sleep_timeout_max; - uint8_t MarlinUI::sleep_timeout_minutes; // Initialized by settings.load() - millis_t MarlinUI::screen_timeout_millis = 0; + millis_t MarlinUI::screen_timeout_ms = 0; void MarlinUI::refresh_screen_timeout() { - screen_timeout_millis = sleep_timeout_minutes ? millis() + sleep_timeout_minutes * 60UL * 1000UL : 0; + screen_timeout_ms = sleep_timeout_minutes ? millis() + sleep_timeout_minutes * 60UL * 1000UL : 0; sleep_display(false); } @@ -1092,7 +1100,7 @@ void MarlinUI::init() { if (encoderPastThreshold || lcd_clicked) { reset_status_timeout(ms); - #if LCD_BACKLIGHT_TIMEOUT_MINS + #if HAS_BACKLIGHT_TIMEOUT refresh_backlight_timeout(); #elif HAS_DISPLAY_SLEEP refresh_screen_timeout(); @@ -1202,8 +1210,7 @@ void MarlinUI::init() { return_to_status(); #endif - #if LCD_BACKLIGHT_TIMEOUT_MINS - + #if HAS_BACKLIGHT_TIMEOUT if (backlight_off_ms && ELAPSED(ms, backlight_off_ms)) { #ifdef NEOPIXEL_BKGD_INDEX_FIRST neo.set_background_off(); @@ -1214,7 +1221,7 @@ void MarlinUI::init() { backlight_off_ms = 0; } #elif HAS_DISPLAY_SLEEP - if (screen_timeout_millis && ELAPSED(ms, screen_timeout_millis)) + if (screen_timeout_ms && ELAPSED(ms, screen_timeout_ms)) sleep_display(); #endif diff --git a/Marlin/src/lcd/marlinui.h b/Marlin/src/lcd/marlinui.h index 595b89b6e00f..a463701f566a 100644 --- a/Marlin/src/lcd/marlinui.h +++ b/Marlin/src/lcd/marlinui.h @@ -272,17 +272,25 @@ class MarlinUI { FORCE_INLINE static void refresh_brightness() { set_brightness(brightness); } #endif - #if LCD_BACKLIGHT_TIMEOUT_MINS + #if HAS_BACKLIGHT_TIMEOUT + #if ENABLED(EDITABLE_DISPLAY_TIMEOUT) + static uint8_t backlight_timeout_minutes; + #else + static constexpr uint8_t backlight_timeout_minutes = LCD_BACKLIGHT_TIMEOUT_MINS; + #endif static constexpr uint8_t backlight_timeout_min = 0; static constexpr uint8_t backlight_timeout_max = 99; - static uint8_t backlight_timeout_minutes; static millis_t backlight_off_ms; static void refresh_backlight_timeout(); #elif HAS_DISPLAY_SLEEP + #if ENABLED(EDITABLE_DISPLAY_TIMEOUT) + static uint8_t sleep_timeout_minutes; + #else + static constexpr uint8_t sleep_timeout_minutes = DISPLAY_SLEEP_MINUTES; + #endif static constexpr uint8_t sleep_timeout_min = 0; static constexpr uint8_t sleep_timeout_max = 99; - static uint8_t sleep_timeout_minutes; - static millis_t screen_timeout_millis; + static millis_t screen_timeout_ms; static void refresh_screen_timeout(); static void sleep_display(const bool sleep=true); #endif diff --git a/Marlin/src/lcd/menu/menu_configuration.cpp b/Marlin/src/lcd/menu/menu_configuration.cpp index 52123d101b68..7347f219e0ab 100644 --- a/Marlin/src/lcd/menu/menu_configuration.cpp +++ b/Marlin/src/lcd/menu/menu_configuration.cpp @@ -618,10 +618,12 @@ void menu_configuration() { // // Set display backlight / sleep timeout // - #if LCD_BACKLIGHT_TIMEOUT_MINS - EDIT_ITEM(uint8, MSG_SCREEN_TIMEOUT, &ui.backlight_timeout_minutes, ui.backlight_timeout_min, ui.backlight_timeout_max, ui.refresh_backlight_timeout); - #elif HAS_DISPLAY_SLEEP - EDIT_ITEM(uint8, MSG_SCREEN_TIMEOUT, &ui.sleep_timeout_minutes, ui.sleep_timeout_min, ui.sleep_timeout_max, ui.refresh_screen_timeout); + #if ENABLED(EDITABLE_DISPLAY_TIMEOUT) + #if HAS_BACKLIGHT_TIMEOUT + EDIT_ITEM(uint8, MSG_SCREEN_TIMEOUT, &ui.backlight_timeout_minutes, ui.backlight_timeout_min, ui.backlight_timeout_max, ui.refresh_backlight_timeout); + #elif HAS_DISPLAY_SLEEP + EDIT_ITEM(uint8, MSG_SCREEN_TIMEOUT, &ui.sleep_timeout_minutes, ui.sleep_timeout_min, ui.sleep_timeout_max, ui.refresh_screen_timeout); + #endif #endif #if ENABLED(FWRETRACT) diff --git a/Marlin/src/lcd/tft/touch.cpp b/Marlin/src/lcd/tft/touch.cpp index 3c0b21ba8fd3..d325355002f5 100644 --- a/Marlin/src/lcd/tft/touch.cpp +++ b/Marlin/src/lcd/tft/touch.cpp @@ -308,7 +308,7 @@ bool Touch::get_point(int16_t * const x, int16_t * const y) { next_touch_ms = millis() + 100; safe_delay(20); } - next_sleep_ms = millis() + SEC_TO_MS(ui.sleep_timeout_minutes * 60); + next_sleep_ms = millis() + MIN_TO_MS(ui.sleep_timeout_minutes); } #endif // HAS_TOUCH_SLEEP diff --git a/Marlin/src/lcd/touch/touch_buttons.cpp b/Marlin/src/lcd/touch/touch_buttons.cpp index 7d31b21c04a6..652a043714d8 100644 --- a/Marlin/src/lcd/touch/touch_buttons.cpp +++ b/Marlin/src/lcd/touch/touch_buttons.cpp @@ -147,7 +147,7 @@ uint8_t TouchButtons::read_buttons() { WRITE(TFT_BACKLIGHT_PIN, HIGH); #endif } - next_sleep_ms = millis() + SEC_TO_MS(ui.sleep_timeout_minutes * 60); + next_sleep_ms = millis() + MIN_TO_MS(ui.sleep_timeout_minutes); } #endif // HAS_TOUCH_SLEEP diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index f636b985e1be..b99ae8ddcda7 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -431,10 +431,12 @@ typedef struct SettingsDataStruct { // // Display Sleep // - #if LCD_BACKLIGHT_TIMEOUT_MINS - uint8_t backlight_timeout_minutes; // M255 S - #elif HAS_DISPLAY_SLEEP - uint8_t sleep_timeout_minutes; // M255 S + #if ENABLED(EDITABLE_DISPLAY_TIMEOUT) + #if HAS_BACKLIGHT_TIMEOUT + uint8_t backlight_timeout_minutes; // M255 S + #elif HAS_DISPLAY_SLEEP + uint8_t sleep_timeout_minutes; // M255 S + #endif #endif // @@ -704,12 +706,8 @@ void MarlinSettings::postprocess() { // Moved as last update due to interference with Neopixel init TERN_(HAS_LCD_CONTRAST, ui.refresh_contrast()); TERN_(HAS_LCD_BRIGHTNESS, ui.refresh_brightness()); - - #if LCD_BACKLIGHT_TIMEOUT_MINS - ui.refresh_backlight_timeout(); - #elif HAS_DISPLAY_SLEEP - ui.refresh_screen_timeout(); - #endif + TERN_(HAS_BACKLIGHT_TIMEOUT, ui.refresh_backlight_timeout()); + TERN_(HAS_DISPLAY_SLEEP, ui.refresh_screen_timeout()); } #if ALL(PRINTCOUNTER, EEPROM_SETTINGS) @@ -1249,10 +1247,12 @@ void MarlinSettings::postprocess() { // // LCD Backlight / Sleep Timeout // - #if LCD_BACKLIGHT_TIMEOUT_MINS - EEPROM_WRITE(ui.backlight_timeout_minutes); - #elif HAS_DISPLAY_SLEEP - EEPROM_WRITE(ui.sleep_timeout_minutes); + #if ENABLED(EDITABLE_DISPLAY_TIMEOUT) + #if HAS_BACKLIGHT_TIMEOUT + EEPROM_WRITE(ui.backlight_timeout_minutes); + #elif HAS_DISPLAY_SLEEP + EEPROM_WRITE(ui.sleep_timeout_minutes); + #endif #endif // @@ -2294,10 +2294,12 @@ void MarlinSettings::postprocess() { // // LCD Backlight / Sleep Timeout // - #if LCD_BACKLIGHT_TIMEOUT_MINS - EEPROM_READ(ui.backlight_timeout_minutes); - #elif HAS_DISPLAY_SLEEP - EEPROM_READ(ui.sleep_timeout_minutes); + #if ENABLED(EDITABLE_DISPLAY_TIMEOUT) + #if HAS_BACKLIGHT_TIMEOUT + EEPROM_READ(ui.backlight_timeout_minutes); + #elif HAS_DISPLAY_SLEEP + EEPROM_READ(ui.sleep_timeout_minutes); + #endif #endif // @@ -3451,10 +3453,12 @@ void MarlinSettings::reset() { // // LCD Backlight / Sleep Timeout // - #if LCD_BACKLIGHT_TIMEOUT_MINS - ui.backlight_timeout_minutes = LCD_BACKLIGHT_TIMEOUT_MINS; - #elif HAS_DISPLAY_SLEEP - ui.sleep_timeout_minutes = TERN(TOUCH_SCREEN, TOUCH_IDLE_SLEEP_MINS, DISPLAY_SLEEP_MINUTES); + #if ENABLED(EDITABLE_DISPLAY_TIMEOUT) + #if HAS_BACKLIGHT_TIMEOUT + ui.backlight_timeout_minutes = LCD_BACKLIGHT_TIMEOUT_MINS; + #elif HAS_DISPLAY_SLEEP + ui.sleep_timeout_minutes = TERN(TOUCH_SCREEN, TOUCH_IDLE_SLEEP_MINS, DISPLAY_SLEEP_MINUTES); + #endif #endif // @@ -3827,7 +3831,7 @@ void MarlinSettings::reset() { // // Display Sleep // - TERN_(HAS_GCODE_M255, gcode.M255_report(forReplay)); + TERN_(EDITABLE_DISPLAY_TIMEOUT, gcode.M255_report(forReplay)); // // LCD Brightness diff --git a/Marlin/src/module/temperature.h b/Marlin/src/module/temperature.h index d174bfd11dbd..2acc1205b730 100644 --- a/Marlin/src/module/temperature.h +++ b/Marlin/src/module/temperature.h @@ -699,7 +699,7 @@ class Temperature { // Convert the given heater_id_t to idle array index static IdleIndex idle_index_for_id(const int8_t heater_id) { - TERN_(HAS_HEATED_BED, if (heater_id == H_BED) return IDLE_INDEX_BED); + OPTCODE(HAS_HEATED_BED, if (heater_id == H_BED) return IDLE_INDEX_BED) return (IdleIndex)_MAX(heater_id, 0); } @@ -1052,7 +1052,7 @@ class Temperature { } // Start watching the Bed to make sure it's really heating up - static void start_watching_bed() { TERN_(WATCH_BED, watch_bed.restart(degBed(), degTargetBed())); } + static void start_watching_bed() { OPTCODE(WATCH_BED, watch_bed.restart(degBed(), degTargetBed())) } static void setTargetBed(const celsius_t celsius) { #if PREHEAT_TIME_BED_MS > 0 @@ -1108,7 +1108,7 @@ class Temperature { start_watching_chamber(); } // Start watching the Chamber to make sure it's really heating up - static void start_watching_chamber() { TERN_(WATCH_CHAMBER, watch_chamber.restart(degChamber(), degTargetChamber())); } + static void start_watching_chamber() { OPTCODE(WATCH_CHAMBER, watch_chamber.restart(degChamber(), degTargetChamber())) } #endif #if HAS_TEMP_COOLER @@ -1158,7 +1158,7 @@ class Temperature { start_watching_cooler(); } // Start watching the Cooler to make sure it's really cooling down - static void start_watching_cooler() { TERN_(WATCH_COOLER, watch_cooler.restart(degCooler(), degTargetCooler())); } + static void start_watching_cooler() { OPTCODE(WATCH_COOLER, watch_cooler.restart(degCooler(), degTargetCooler())) } #endif /** @@ -1391,9 +1391,9 @@ class Temperature { // Convert the given heater_id_t to runaway state array index static RunawayIndex runaway_index_for_id(const int8_t heater_id) { - TERN_(THERMAL_PROTECTION_CHAMBER, if (heater_id == H_CHAMBER) return RUNAWAY_IND_CHAMBER); - TERN_(THERMAL_PROTECTION_COOLER, if (heater_id == H_COOLER) return RUNAWAY_IND_COOLER); - TERN_(THERMAL_PROTECTION_BED, if (heater_id == H_BED) return RUNAWAY_IND_BED); + OPTCODE(THERMAL_PROTECTION_CHAMBER, if (heater_id == H_CHAMBER) return RUNAWAY_IND_CHAMBER) + OPTCODE(THERMAL_PROTECTION_COOLER, if (heater_id == H_COOLER) return RUNAWAY_IND_COOLER) + OPTCODE(THERMAL_PROTECTION_BED, if (heater_id == H_BED) return RUNAWAY_IND_BED) return (RunawayIndex)_MAX(heater_id, 0); } diff --git a/ini/features.ini b/ini/features.ini index 3e50b19bc085..ed755f9ac001 100644 --- a/ini/features.ini +++ b/ini/features.ini @@ -330,7 +330,7 @@ SET_PROGRESS_MANUALLY = build_src_filter=+ HAS_PREHEAT = build_src_filter=+ HAS_LCD_CONTRAST = build_src_filter=+ -HAS_GCODE_M255 = build_src_filter=+ +EDITABLE_DISPLAY_TIMEOUT = build_src_filter=+ HAS_LCD_BRIGHTNESS = build_src_filter=+ HAS_SOUND = build_src_filter=+ HAS_MULTI_LANGUAGE = build_src_filter=+ From 775c6bb20ef1bc09632baaf4359efeea6e441451 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Wed, 13 Dec 2023 06:12:17 +0000 Subject: [PATCH 75/77] [cron] Bump distribution date (2023-12-13) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index 00fbba610d31..acd87bb99443 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2023-12-12" +//#define STRING_DISTRIBUTION_DATE "2023-12-13" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 3c5a423ec05a..7b1faa8884cc 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2023-12-12" + #define STRING_DISTRIBUTION_DATE "2023-12-13" #endif /** From fef74398e41a1b492792837941af55057eb694f5 Mon Sep 17 00:00:00 2001 From: jesterhead82 Date: Wed, 13 Dec 2023 08:44:11 +0100 Subject: [PATCH 76/77] =?UTF-8?q?=E2=9C=A8=20MARKFORGED=5FINVERSE=20(#2651?= =?UTF-8?q?6)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration.h | 10 +++++++++- Marlin/src/module/planner.cpp | 12 ++++++------ Marlin/src/module/stepper.cpp | 8 ++++---- buildroot/tests/mks_robin_mini | 1 + 4 files changed, 20 insertions(+), 11 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 4d0351bb493c..e62637f6462a 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -892,8 +892,16 @@ //#define COREYX //#define COREZX //#define COREZY -//#define MARKFORGED_XY // MarkForged. See https://reprap.org/forum/read.php?152,504042 + +// +// MarkForged Kinematics +// See https://reprap.org/forum/read.php?152,504042 +// +//#define MARKFORGED_XY //#define MARKFORGED_YX +#if ANY(MARKFORGED_XY, MARKFORGED_YX) + //#define MARKFORGED_INVERSE // Enable for an inverted Markforged kinematics belt path +#endif // Enable for a belt style printer with endless "Z" motion //#define BELTPRINTER diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index 8e9021b03069..70a1b105db74 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -1990,11 +1990,11 @@ bool Planner::_populate_block( dm.c = (CORESIGN(dist.b - dist.c) > 0); // Motor C direction #endif #elif ENABLED(MARKFORGED_XY) - dm.a = (dist.a + dist.b > 0); // Motor A direction + dm.a = (dist.a TERN(MARKFORGED_INVERSE, -, +) dist.b > 0); // Motor A direction dm.b = (dist.b > 0); // Motor B direction #elif ENABLED(MARKFORGED_YX) dm.a = (dist.a > 0); // Motor A direction - dm.b = (dist.b + dist.a > 0); // Motor B direction + dm.b = (dist.b TERN(MARKFORGED_INVERSE, -, +) dist.a > 0); // Motor B direction #else XYZ_CODE( dm.x = (dist.a > 0), @@ -2062,9 +2062,9 @@ bool Planner::_populate_block( #elif CORE_IS_YZ ABS(dist.a), ABS(dist.b + dist.c), ABS(dist.b - dist.c) #elif ENABLED(MARKFORGED_XY) - ABS(dist.a + dist.b), ABS(dist.b), ABS(dist.c) + ABS(dist.a TERN(MARKFORGED_INVERSE, -, +) dist.b), ABS(dist.b), ABS(dist.c) #elif ENABLED(MARKFORGED_YX) - ABS(dist.a), ABS(dist.b + dist.a), ABS(dist.c) + ABS(dist.a), ABS(dist.b TERN(MARKFORGED_INVERSE, -, +) dist.a), ABS(dist.c) #elif IS_SCARA ABS(dist.a), ABS(dist.b), ABS(dist.c) #else // default non-h-bot planning @@ -2110,11 +2110,11 @@ bool Planner::_populate_block( dist_mm.c = CORESIGN(dist.b - dist.c) * mm_per_step[C_AXIS]; #endif #elif ENABLED(MARKFORGED_XY) - dist_mm.a = (dist.a - dist.b) * mm_per_step[A_AXIS]; + dist_mm.a = (dist.a TERN(MARKFORGED_INVERSE, +, -) dist.b) * mm_per_step[A_AXIS]; dist_mm.b = dist.b * mm_per_step[B_AXIS]; #elif ENABLED(MARKFORGED_YX) dist_mm.a = dist.a * mm_per_step[A_AXIS]; - dist_mm.b = (dist.b - dist.a) * mm_per_step[B_AXIS]; + dist_mm.b = (dist.b TERN(MARKFORGED_INVERSE, +, -) dist.a) * mm_per_step[B_AXIS]; #else XYZ_CODE( dist_mm.a = dist.a * mm_per_step[A_AXIS], diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index a6c628e081cc..c68db6bb89b4 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -3287,9 +3287,9 @@ void Stepper::_set_position(const abce_long_t &spos) { // coreyz planning count_position.set(spos.a, spos.b + spos.c, CORESIGN(spos.b - spos.c)); #elif ENABLED(MARKFORGED_XY) - count_position.set(spos.a - spos.b, spos.b, spos.c); + count_position.set(spos.a TERN(MARKFORGED_INVERSE, +, -) spos.b, spos.b, spos.c); #elif ENABLED(MARKFORGED_YX) - count_position.set(spos.a, spos.b - spos.a, spos.c); + count_position.set(spos.a, spos.b TERN(MARKFORGED_INVERSE, +, -) spos.a, spos.c); #endif SECONDARY_AXIS_CODE( count_position.i = spos.i, @@ -3382,12 +3382,12 @@ void Stepper::endstop_triggered(const AxisEnum axis) { ) * double(0.5) #elif ENABLED(MARKFORGED_XY) axis == CORE_AXIS_1 - ? count_position[CORE_AXIS_1] - count_position[CORE_AXIS_2] + ? count_position[CORE_AXIS_1] ENABLED(MARKFORGED_INVERSE, +, -) count_position[CORE_AXIS_2] : count_position[CORE_AXIS_2] #elif ENABLED(MARKFORGED_YX) axis == CORE_AXIS_1 ? count_position[CORE_AXIS_1] - : count_position[CORE_AXIS_2] - count_position[CORE_AXIS_1] + : count_position[CORE_AXIS_2] ENABLED(MARKFORGED_INVERSE, +, -) count_position[CORE_AXIS_1] #else // !IS_CORE count_position[axis] #endif diff --git a/buildroot/tests/mks_robin_mini b/buildroot/tests/mks_robin_mini index 29baee8818d6..902874ce474d 100755 --- a/buildroot/tests/mks_robin_mini +++ b/buildroot/tests/mks_robin_mini @@ -9,6 +9,7 @@ set -e use_example_configs Mks/Robin opt_set MOTHERBOARD BOARD_MKS_ROBIN_MINI EXTRUDERS 1 TEMP_SENSOR_1 0 +opt_enable MARKFORGED_XY MARKFORGED_INVERSE exec_test $1 $2 "MKS Robin mini" "$3" # cleanup From 8bce9dec906d59c3091e870d614f834c73aaeb89 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Thu, 14 Dec 2023 00:21:11 +0000 Subject: [PATCH 77/77] [cron] Bump distribution date (2023-12-14) --- Marlin/Version.h | 2 +- Marlin/src/inc/Version.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/Version.h b/Marlin/Version.h index acd87bb99443..52512a611302 100644 --- a/Marlin/Version.h +++ b/Marlin/Version.h @@ -41,7 +41,7 @@ * here we define this default string as the date where the latest release * version was tagged. */ -//#define STRING_DISTRIBUTION_DATE "2023-12-13" +//#define STRING_DISTRIBUTION_DATE "2023-12-14" /** * Defines a generic printer name to be output to the LCD after booting Marlin. diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 7b1faa8884cc..80b1de278bb1 100644 --- a/Marlin/src/inc/Version.h +++ b/Marlin/src/inc/Version.h @@ -42,7 +42,7 @@ * version was tagged. */ #ifndef STRING_DISTRIBUTION_DATE - #define STRING_DISTRIBUTION_DATE "2023-12-13" + #define STRING_DISTRIBUTION_DATE "2023-12-14" #endif /**