From f11f42a23ee35090acfb27a451420ad1e1dd5231 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 31 Oct 2025 18:02:05 -0500 Subject: [PATCH 01/99] =?UTF-8?q?=F0=9F=90=9B=20Fix=20MMU3=20resume=20posi?= =?UTF-8?q?tion=20(#28148)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/feature/mmu3/mmu3.cpp | 6 +++--- Marlin/src/feature/mmu3/mmu3_marlin.h | 4 ++-- Marlin/src/feature/mmu3/mmu3_marlin1.cpp | 9 ++++----- 3 files changed, 9 insertions(+), 10 deletions(-) diff --git a/Marlin/src/feature/mmu3/mmu3.cpp b/Marlin/src/feature/mmu3/mmu3.cpp index 0d69758487..f2c7be3f6a 100644 --- a/Marlin/src/feature/mmu3/mmu3.cpp +++ b/Marlin/src/feature/mmu3/mmu3.cpp @@ -255,7 +255,7 @@ namespace MMU3 { uint8_t block_index = planner.block_buffer_tail; while (block_index != planner.block_buffer_head) { block = &planner.block_buffer[block_index]; - if (block->steps[E_AXIS] != 0) e_active++; + if (block->steps.e != 0) e_active++; block_index = (block_index + 1) & (BLOCK_BUFFER_SIZE - 1); } } @@ -760,10 +760,10 @@ namespace MMU3 { LogEchoEvent(F("Resuming XYZ")); // Move XY to starting position, then Z - motion_do_blocking_move_to_xy(resume_position.x, resume_position.x, feedRate_t(NOZZLE_PARK_XY_FEEDRATE)); + motion_blocking_move_xy(resume_position.x, resume_position.y, feedRate_t(NOZZLE_PARK_XY_FEEDRATE)); // Move Z_AXIS to saved position - motion_do_blocking_move_to_z(resume_position.z, feedRate_t(NOZZLE_PARK_Z_FEEDRATE)); + motion_blocking_move_z(resume_position.z, feedRate_t(NOZZLE_PARK_Z_FEEDRATE)); // From this point forward, power panic should not use // the partial backup in RAM since the extruder is no diff --git a/Marlin/src/feature/mmu3/mmu3_marlin.h b/Marlin/src/feature/mmu3/mmu3_marlin.h index 1a0050cd0e..499af0f285 100644 --- a/Marlin/src/feature/mmu3/mmu3_marlin.h +++ b/Marlin/src/feature/mmu3/mmu3_marlin.h @@ -46,8 +46,8 @@ namespace MMU3 { void planner_set_current_position_E(float e); xyz_pos_t planner_current_position(); - void motion_do_blocking_move_to_xy(float rx, float ry, float feedRate_mm_s); - void motion_do_blocking_move_to_z(float z, float feedRate_mm_s); + void motion_blocking_move_xy(float rx, float ry, float feedRate_mm_s); + void motion_blocking_move_z(float z, float feedRate_mm_s); void nozzle_park(); diff --git a/Marlin/src/feature/mmu3/mmu3_marlin1.cpp b/Marlin/src/feature/mmu3/mmu3_marlin1.cpp index 03e50da218..6365481248 100644 --- a/Marlin/src/feature/mmu3/mmu3_marlin1.cpp +++ b/Marlin/src/feature/mmu3/mmu3_marlin1.cpp @@ -103,14 +103,13 @@ namespace MMU3 { return xyz_pos_t(current_position); } - void motion_do_blocking_move_to_xy(float rx, float ry, float feedRate_mm_s) { - current_position[X_AXIS] = rx; - current_position[Y_AXIS] = ry; + void motion_blocking_move_xy(float rx, float ry, float feedRate_mm_s) { + current_position.set(rx, ry); planner_line_to_current_position_sync(feedRate_mm_s); } - void motion_do_blocking_move_to_z(float z, float feedRate_mm_s) { - current_position[Z_AXIS] = z; + void motion_blocking_move_z(float z, float feedRate_mm_s) { + current_position.z = z; planner_line_to_current_position_sync(feedRate_mm_s); } From 14a83342e1506fde6745575b0283fa572aaa61e8 Mon Sep 17 00:00:00 2001 From: ellensp <530024+ellensp@users.noreply.github.com> Date: Sat, 1 Nov 2025 12:08:50 +1300 Subject: [PATCH 02/99] =?UTF-8?q?=F0=9F=94=A8=20Add=20LIB=5FMAX31855=20ini?= =?UTF-8?q?=20link=20(#28146)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- ini/features.ini | 1 + 1 file changed, 1 insertion(+) diff --git a/ini/features.ini b/ini/features.ini index c3fc6df537..a346793954 100644 --- a/ini/features.ini +++ b/ini/features.ini @@ -30,6 +30,7 @@ SR_LCD_3W_NL = SailfishLCD=https://github.com/mikeshub HAS_MOTOR_CURRENT_(I2C|DAC|SPI|PWM) = build_src_filter=+ HAS_MOTOR_CURRENT_I2C = SlowSoftI2CMaster build_src_filter=+ +LIB_MAX31855 = GadgetAngel MAX31855=https://github.com/GadgetAngel/Adafruit-MAX31855-V1.0.3-Mod-M/archive/dc9cc10ac2.zip LIB_INTERNAL_MAX31865 = build_src_filter=+ NEOPIXEL_LED = adafruit/Adafruit NeoPixel@~1.12.3 build_src_filter=+ From 1c19cfcbc7f31133f943da5b37efa15bc1da6f85 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sat, 1 Nov 2025 00:34:02 +0000 Subject: [PATCH 03/99] [cron] Bump distribution date (2025-11-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 968d5ae899..c88b6f1a19 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 "2025-10-30" +//#define STRING_DISTRIBUTION_DATE "2025-11-01" /** * The protocol for communication to the host. Protocol indicates communication diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 6a819d0a64..e9c314fcd3 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 "2025-10-30" + #define STRING_DISTRIBUTION_DATE "2025-11-01" #endif /** From 5d59779a80c293739e66e4bc4c40e681fd2ab557 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 31 Oct 2025 20:17:18 -0500 Subject: [PATCH 04/99] =?UTF-8?q?=F0=9F=A7=91=E2=80=8D=F0=9F=92=BB=20Combi?= =?UTF-8?q?ne=20G60-G61=20(#28149)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/feature/pause/G60.cpp | 103 ------------------ .../feature/pause/{G61.cpp => G60_G61.cpp} | 74 ++++++++++++- Marlin/src/module/motion.cpp | 6 - Marlin/src/module/motion.h | 6 - Marlin/src/sd/cardreader.cpp | 9 +- .../PlatformIO/scripts/preflight-checks.py | 8 +- ini/features.ini | 2 +- 7 files changed, 81 insertions(+), 127 deletions(-) delete mode 100644 Marlin/src/gcode/feature/pause/G60.cpp rename Marlin/src/gcode/feature/pause/{G61.cpp => G60_G61.cpp} (65%) diff --git a/Marlin/src/gcode/feature/pause/G60.cpp b/Marlin/src/gcode/feature/pause/G60.cpp deleted file mode 100644 index 21dbe1bf81..0000000000 --- a/Marlin/src/gcode/feature/pause/G60.cpp +++ /dev/null @@ -1,103 +0,0 @@ -/** - * Marlin 3D Printer Firmware - * Copyright (c) 2020 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] - * - * Based on Sprinter and grbl. - * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm - * - * This program is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This program is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this program. If not, see . - * - */ - -#include "../../../inc/MarlinConfig.h" - -#if SAVED_POSITIONS - -#include "../../gcode.h" -#include "../../../module/motion.h" - -#define DEBUG_OUT ENABLED(SAVED_POSITIONS_DEBUG) -#include "../../../core/debug_out.h" - -bool report_stored_position(const uint8_t slot) { - if (!did_save_position[slot]) return false; - const xyze_pos_t &pos = stored_position[slot]; - SERIAL_ECHO(STR_SAVED_POSITION, slot, C(':')); - #if NUM_AXES - SERIAL_ECHOPGM_P(LOGICAL_AXIS_PAIRED_LIST( - SP_E_LBL, pos.e, - SP_X_LBL, pos.x, SP_Y_LBL, pos.y, SP_Z_LBL, pos.z, - SP_I_LBL, pos.i, SP_J_LBL, pos.j, SP_K_LBL, pos.k, - SP_U_LBL, pos.u, SP_V_LBL, pos.v, SP_W_LBL, pos.w - )); - #endif - SERIAL_EOL(); - return true; -} - -/** - * G60: Saved Positions - * - * S - Save to a memory slot. (default 0) - * Q - Restore from a memory slot. (default 0) - * D - Delete a memory slot. With no number, delete all. - */ -void GcodeSuite::G60() { - // With no parameters report any saved positions - if (!parser.seen_any()) { - uint8_t count = 0; - for (uint8_t s = 0; s < SAVED_POSITIONS; ++s) - if (report_stored_position(s)) ++count; - if (!count) SERIAL_ECHOLNPGM("No Saved Positions"); - return; - } - - // Only one of these parameters is permitted - const uint8_t seenD = parser.seen_test('D'), - seenQ = parser.seen_test('Q'), - seenS = parser.seen_test('S'); - if (seenD + seenQ + seenS > 1) return; - - // G60 D : Delete all saved positions - if (seenD && !parser.seenval('D')) { - did_save_position.reset(); - return; - } - - // G60 Dn / Q / S : Get the slot value - const uint8_t slot = parser.byteval(seenD ? 'D' : seenQ ? 'Q' : 'S'); - - // G60 Q : Redirect to G61(slot) - if (seenQ) return G61(slot); - - // Valid slot number? - if (SAVED_POSITIONS < 256 && slot >= SAVED_POSITIONS) { - SERIAL_ERROR_MSG(STR_INVALID_POS_SLOT STRINGIFY(SAVED_POSITIONS)); - return; - } - - // G60 Dn - if (seenD) { - SERIAL_ECHOLNPGM(STR_SAVED_POSITION, slot, ": DELETED"); - did_save_position.clear(slot); - return; - } - - // G60 S - stored_position[slot] = current_position; - did_save_position.set(slot); - report_stored_position(slot); -} - -#endif // SAVED_POSITIONS diff --git a/Marlin/src/gcode/feature/pause/G61.cpp b/Marlin/src/gcode/feature/pause/G60_G61.cpp similarity index 65% rename from Marlin/src/gcode/feature/pause/G61.cpp rename to Marlin/src/gcode/feature/pause/G60_G61.cpp index 7f2a45bc93..8a24433cdb 100644 --- a/Marlin/src/gcode/feature/pause/G61.cpp +++ b/Marlin/src/gcode/feature/pause/G60_G61.cpp @@ -24,7 +24,6 @@ #if SAVED_POSITIONS -#include "../../../module/planner.h" #include "../../gcode.h" #include "../../../module/motion.h" #include "../../../module/planner.h" @@ -32,6 +31,79 @@ #define DEBUG_OUT ENABLED(SAVED_POSITIONS_DEBUG) #include "../../../core/debug_out.h" +Flags did_save_position; +xyze_pos_t stored_position[SAVED_POSITIONS]; + +bool report_stored_position(const uint8_t slot) { + if (!did_save_position[slot]) return false; + const xyze_pos_t &pos = stored_position[slot]; + SERIAL_ECHO(STR_SAVED_POSITION, slot, C(':')); + #if NUM_AXES + SERIAL_ECHOPGM_P(LOGICAL_AXIS_PAIRED_LIST( + SP_E_LBL, pos.e, + SP_X_LBL, pos.x, SP_Y_LBL, pos.y, SP_Z_LBL, pos.z, + SP_I_LBL, pos.i, SP_J_LBL, pos.j, SP_K_LBL, pos.k, + SP_U_LBL, pos.u, SP_V_LBL, pos.v, SP_W_LBL, pos.w + )); + #endif + SERIAL_EOL(); + return true; +} + +/** + * G60: Saved Positions + * + * S - Save to a memory slot. (default 0) + * Q - Restore from a memory slot. (default 0) + * D - Delete a memory slot. With no number, delete all. + */ +void GcodeSuite::G60() { + // With no parameters report any saved positions + if (!parser.seen_any()) { + uint8_t count = 0; + for (uint8_t s = 0; s < SAVED_POSITIONS; ++s) + if (report_stored_position(s)) ++count; + if (!count) SERIAL_ECHOLNPGM("No Saved Positions"); + return; + } + + // Only one of these parameters is permitted + const uint8_t seenD = parser.seen_test('D'), + seenQ = parser.seen_test('Q'), + seenS = parser.seen_test('S'); + if (seenD + seenQ + seenS > 1) return; + + // G60 D : Delete all saved positions + if (seenD && !parser.seenval('D')) { + did_save_position.reset(); + return; + } + + // G60 Dn / Q / S : Get the slot value + const uint8_t slot = parser.byteval(seenD ? 'D' : seenQ ? 'Q' : 'S'); + + // G60 Q : Redirect to G61(slot) + if (seenQ) return G61(slot); + + // Valid slot number? + if (SAVED_POSITIONS < 256 && slot >= SAVED_POSITIONS) { + SERIAL_ERROR_MSG(STR_INVALID_POS_SLOT STRINGIFY(SAVED_POSITIONS)); + return; + } + + // G60 Dn + if (seenD) { + SERIAL_ECHOLNPGM(STR_SAVED_POSITION, slot, ": DELETED"); + did_save_position.clear(slot); + return; + } + + // G60 S + stored_position[slot] = current_position; + did_save_position.set(slot); + report_stored_position(slot); +} + /** * G61: Return to saved position * diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index 1282e605eb..cb99000451 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -107,12 +107,6 @@ xyze_pos_t current_position = LOGICAL_AXIS_ARRAY(0, X_HOME_POS, Y_HOME_POS, Z_IN */ xyze_pos_t destination; // {0} -// G60/G61 Position Save and Return -#if SAVED_POSITIONS - Flags did_save_position; - xyze_pos_t stored_position[SAVED_POSITIONS]; -#endif - // The active extruder (tool). Set with T command. #if HAS_MULTI_EXTRUDER uint8_t active_extruder = 0; // = 0 diff --git a/Marlin/src/module/motion.h b/Marlin/src/module/motion.h index e74562728d..7cafb2f019 100644 --- a/Marlin/src/module/motion.h +++ b/Marlin/src/module/motion.h @@ -48,12 +48,6 @@ extern bool relative_mode; extern xyze_pos_t current_position, // High-level current tool position destination; // Destination for a move -// G60/G61 Position Save and Return -#if SAVED_POSITIONS - extern Flags did_save_position; - extern xyze_pos_t stored_position[SAVED_POSITIONS]; -#endif - // Scratch space for a cartesian result extern xyz_pos_t cartes; diff --git a/Marlin/src/sd/cardreader.cpp b/Marlin/src/sd/cardreader.cpp index 1d6fa06998..24ee80a2cc 100644 --- a/Marlin/src/sd/cardreader.cpp +++ b/Marlin/src/sd/cardreader.cpp @@ -1378,14 +1378,7 @@ void CardReader::cdroot() { #endif #endif - #else // !SDSORT_USES_RAM - - // By default re-read the names from SD for every compare - // retaining only two filenames at a time. This is very - // slow but is safest and uses minimal RAM. - char name1[LONG_FILENAME_LENGTH]; - - #endif + #endif // SDSORT_USES_RAM if (fileCnt > 1) { diff --git a/buildroot/share/PlatformIO/scripts/preflight-checks.py b/buildroot/share/PlatformIO/scripts/preflight-checks.py index 210dc8fd0b..2cb54d7c08 100644 --- a/buildroot/share/PlatformIO/scripts/preflight-checks.py +++ b/buildroot/share/PlatformIO/scripts/preflight-checks.py @@ -149,14 +149,18 @@ if pioutil.is_pio_build(): # Check for old files indicating an entangled Marlin (mixing old and new code) # mixedin = [] - p = project_dir / "Marlin/src/lcd/dogm" + p = mpath / "src/lcd/dogm" for f in [ "ultralcd_DOGM.cpp", "ultralcd_DOGM.h", "u8g_dev_ssd1306_sh1106_128x64_I2C.cpp", "u8g_dev_ssd1309_12864.cpp", "u8g_dev_st7565_64128n_HAL.cpp", "u8g_dev_st7920_128x64_HAL.cpp", "u8g_dev_tft_upscale_from_128x64.cpp", "u8g_dev_uc1701_mini12864_HAL.cpp", "ultralcd_st7920_u8glib_rrd_AVR.cpp" ]: if (p / f).is_file(): mixedin += [ f ] - p = project_dir / "Marlin/src/feature/bedlevel/abl" + p = mpath / "src/feature/bedlevel/abl" for f in [ "abl.cpp", "abl.h" ]: if (p / f).is_file(): mixedin += [ f ] + f = mpath / "src/gcode/feature/pause" + for f in [ "G60.cpp", "G61.cpp" ]: + if (p / f).is_file(): + mixedin += [ f ] if mixedin: err = "ERROR: Old files fell into your Marlin folder. Remove %s and try again" % ", ".join(mixedin) raise SystemExit(err) diff --git a/ini/features.ini b/ini/features.ini index a346793954..bd45dd02c1 100644 --- a/ini/features.ini +++ b/ini/features.ini @@ -319,7 +319,7 @@ HAS_ZV_SHAPING = build_src_filter=+ GRADIENT_MIX = build_src_filter=+ NONLINEAR_EXTRUSION = build_src_filter=+ -HAS_SAVED_POSITIONS = build_src_filter=+ + +HAS_SAVED_POSITIONS = build_src_filter=+ PARK_HEAD_ON_PAUSE = build_src_filter=+ FILAMENT_LOAD_UNLOAD_GCODES = build_src_filter=+ HAS_STEALTHCHOP = build_src_filter=+ From 367bcedea73d42c7227081546098570f389437b0 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 31 Oct 2025 16:41:13 -0500 Subject: [PATCH 05/99] =?UTF-8?q?=F0=9F=A7=91=E2=80=8D=F0=9F=92=BB=20Reuse?= =?UTF-8?q?=20FTM=20smoothing=20edit=20item=20macro?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/menu/menu_motion.cpp | 29 +++++++++-------------------- 1 file changed, 9 insertions(+), 20 deletions(-) diff --git a/Marlin/src/lcd/menu/menu_motion.cpp b/Marlin/src/lcd/menu/menu_motion.cpp index 9e956711cf..305b77688c 100644 --- a/Marlin/src/lcd/menu/menu_motion.cpp +++ b/Marlin/src/lcd/menu/menu_motion.cpp @@ -411,6 +411,13 @@ void menu_move() { #define CACHE_FOR_SPEED 1 #endif + #if ENABLED(FTM_SMOOTHING) + #define _SMOO_MENU_ITEM(A) do{ \ + editable.decimal = c.smoothingTime.A; \ + EDIT_ITEM_FAST_N(float43, _AXIS(A), MSG_FTM_SMOOTH_TIME_N, &editable.decimal, 0.0f, FTM_MAX_SMOOTHING_TIME, []{ ftMotion.set_smoothing_time(_AXIS(A), editable.decimal); }); \ + }while(0); + #endif + void menu_ft_motion() { // Define stuff ahead of the menu loop ft_config_t &c = ftMotion.cfg; @@ -499,23 +506,9 @@ void menu_move() { #endif EDIT_ITEM(bool, MSG_FTM_AXIS_SYNC, &c.axis_sync_enabled); + #if ENABLED(FTM_SMOOTHING) - #if HAS_X_AXIS - editable.decimal = c.smoothingTime.X; - EDIT_ITEM_FAST_N(float43, X_AXIS, MSG_FTM_SMOOTH_TIME_N, &editable.decimal, 0.0f, FTM_MAX_SMOOTHING_TIME, []{ ftMotion.set_smoothing_time(X_AXIS, editable.decimal); }); - #endif - #if HAS_Y_AXIS - editable.decimal = c.smoothingTime.Y; - EDIT_ITEM_FAST_N(float43, Y_AXIS, MSG_FTM_SMOOTH_TIME_N, &editable.decimal, 0.0f, FTM_MAX_SMOOTHING_TIME, []{ ftMotion.set_smoothing_time(Y_AXIS, editable.decimal); }); - #endif - #if HAS_Z_AXIS - editable.decimal = c.smoothingTime.Z; - EDIT_ITEM_FAST_N(float43, Z_AXIS, MSG_FTM_SMOOTH_TIME_N, &editable.decimal, 0.0f, FTM_MAX_SMOOTHING_TIME, []{ ftMotion.set_smoothing_time(Z_AXIS, editable.decimal); }); - #endif - #if HAS_EXTRUDERS - editable.decimal = c.smoothingTime.E; - EDIT_ITEM_FAST_N(float43, E_AXIS, MSG_FTM_SMOOTH_TIME_N, &editable.decimal, 0.0f, FTM_MAX_SMOOTHING_TIME, []{ ftMotion.set_smoothing_time(E_AXIS, editable.decimal); }); - #endif + CARTES_MAP(_SMOO_MENU_ITEM); #endif } END_MENU(); @@ -592,10 +585,6 @@ void menu_move() { #endif #if ENABLED(FTM_SMOOTHING) - #define _SMOO_MENU_ITEM(A) do{ \ - editable.decimal = c.smoothingTime.A; \ - EDIT_ITEM_FAST_N(float43, _AXIS(A), MSG_FTM_SMOOTH_TIME_N, &editable.decimal, 0.0f, FTM_MAX_SMOOTHING_TIME, []{ ftMotion.set_smoothing_time(_AXIS(A), editable.decimal); }); \ - }while(0); CARTES_MAP(_SMOO_MENU_ITEM); #endif From baa20d9ea2a3894d171531445fa279bc83f69390 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 22 Oct 2025 15:04:42 -0500 Subject: [PATCH 06/99] =?UTF-8?q?=F0=9F=8E=A8=20Misc.=20HAL=20types,=20pla?= =?UTF-8?q?nner=20sq,=20etc.?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/GD32_MFL/HAL.cpp | 9 ++++-- Marlin/src/HAL/RP2040/HAL.cpp | 2 +- Marlin/src/HAL/STM32/HAL.cpp | 2 +- .../src/HAL/STM32F1/eeprom/eeprom_flash.cpp | 14 +++++----- Marlin/src/core/types.h | 2 +- Marlin/src/feature/babystep.cpp | 2 +- Marlin/src/feature/mmu3/mmu3_marlin1.cpp | 28 ++++--------------- Marlin/src/module/planner.cpp | 2 +- 8 files changed, 24 insertions(+), 37 deletions(-) diff --git a/Marlin/src/HAL/GD32_MFL/HAL.cpp b/Marlin/src/HAL/GD32_MFL/HAL.cpp index 460ed52297..9ba20784f0 100644 --- a/Marlin/src/HAL/GD32_MFL/HAL.cpp +++ b/Marlin/src/HAL/GD32_MFL/HAL.cpp @@ -53,12 +53,15 @@ uint16_t MarlinHAL::adc_result; // Initializes the Marlin HAL void MarlinHAL::init() { + // Ensure F_CPU is a constant expression. + // If the compiler breaks here, it means that delay code that should compute at compile time will not work. + // So better safe than sorry here. constexpr unsigned int cpuFreq = F_CPU; UNUSED(cpuFreq); -#if PIN_EXISTS(LED) - OUT_WRITE(LED_PIN, LOW); -#endif + #if PIN_EXISTS(LED) + OUT_WRITE(LED_PIN, LOW); + #endif SetTimerInterruptPriorities(); diff --git a/Marlin/src/HAL/RP2040/HAL.cpp b/Marlin/src/HAL/RP2040/HAL.cpp index 1b519e4004..e8d0eea7cd 100644 --- a/Marlin/src/HAL/RP2040/HAL.cpp +++ b/Marlin/src/HAL/RP2040/HAL.cpp @@ -56,7 +56,7 @@ void MarlinHAL::init() { // Ensure F_CPU is a constant expression. // If the compiler breaks here, it means that delay code that should compute at compile time will not work. // So better safe than sorry here. - constexpr int cpuFreq = F_CPU; + constexpr unsigned int cpuFreq = F_CPU; UNUSED(cpuFreq); #if HAS_MEDIA && DISABLED(ONBOARD_SDIO) && PIN_EXISTS(SD_SS) diff --git a/Marlin/src/HAL/STM32/HAL.cpp b/Marlin/src/HAL/STM32/HAL.cpp index bdccdd546d..b2ae10d0f1 100644 --- a/Marlin/src/HAL/STM32/HAL.cpp +++ b/Marlin/src/HAL/STM32/HAL.cpp @@ -66,7 +66,7 @@ void MarlinHAL::init() { // Ensure F_CPU is a constant expression. // If the compiler breaks here, it means that delay code that should compute at compile time will not work. // So better safe than sorry here. - constexpr int cpuFreq = F_CPU; + constexpr unsigned int cpuFreq = F_CPU; UNUSED(cpuFreq); #if HAS_MEDIA && DISABLED(ONBOARD_SDIO) && PIN_EXISTS(SD_SS) diff --git a/Marlin/src/HAL/STM32F1/eeprom/eeprom_flash.cpp b/Marlin/src/HAL/STM32F1/eeprom/eeprom_flash.cpp index 03326db80e..2292c02203 100644 --- a/Marlin/src/HAL/STM32F1/eeprom/eeprom_flash.cpp +++ b/Marlin/src/HAL/STM32F1/eeprom/eeprom_flash.cpp @@ -47,14 +47,14 @@ static uint8_t ram_eeprom[MARLIN_EEPROM_SIZE] __attribute__((aligned(4))) = {0}; static bool eeprom_dirty = false; bool PersistentStore::access_start() { - const uint32_t *source = reinterpret_cast(EEPROM_PAGE0_BASE); - uint32_t *destination = reinterpret_cast(ram_eeprom); + const uint32_t *src = reinterpret_cast(EEPROM_PAGE0_BASE); + uint32_t *dst = reinterpret_cast(ram_eeprom); static_assert(0 == (MARLIN_EEPROM_SIZE) % 4, "MARLIN_EEPROM_SIZE is corrupted. (Must be a multiple of 4.)"); // Ensure copying as uint32_t is safe constexpr size_t eeprom_size_u32 = (MARLIN_EEPROM_SIZE) / 4; - for (size_t i = 0; i < eeprom_size_u32; ++i, ++destination, ++source) - *destination = *source; + for (size_t i = 0; i < eeprom_size_u32; ++i, ++dst, ++src) + *dst = *src; eeprom_dirty = false; return true; @@ -80,9 +80,9 @@ bool PersistentStore::access_finish() { status = FLASH_ErasePage(EEPROM_PAGE1_BASE); if (status != FLASH_COMPLETE) ACCESS_FINISHED(true); - const uint16_t *source = reinterpret_cast(ram_eeprom); - for (size_t i = 0; i < long(MARLIN_EEPROM_SIZE); i += 2, ++source) { - if (FLASH_ProgramHalfWord(EEPROM_PAGE0_BASE + i, *source) != FLASH_COMPLETE) + const uint16_t *src = reinterpret_cast(ram_eeprom); + for (size_t i = 0; i < long(MARLIN_EEPROM_SIZE); i += 2, ++src) { + if (FLASH_ProgramHalfWord(EEPROM_PAGE0_BASE + i, *src) != FLASH_COMPLETE) ACCESS_FINISHED(false); } diff --git a/Marlin/src/core/types.h b/Marlin/src/core/types.h index fab32dea9b..ab3820273a 100644 --- a/Marlin/src/core/types.h +++ b/Marlin/src/core/types.h @@ -492,7 +492,7 @@ typedef ab_float_t ab_pos_t; typedef abc_float_t abc_pos_t; typedef abce_float_t abce_pos_t; -// External conversion methods +// External conversion methods (motion.h) void toLogical(xy_pos_t &raw); void toLogical(xyz_pos_t &raw); void toLogical(xyze_pos_t &raw); diff --git a/Marlin/src/feature/babystep.cpp b/Marlin/src/feature/babystep.cpp index 91b3c7f403..bceb73ec78 100644 --- a/Marlin/src/feature/babystep.cpp +++ b/Marlin/src/feature/babystep.cpp @@ -26,7 +26,7 @@ #include "babystep.h" #include "../MarlinCore.h" -#include "../module/motion.h" // for axes_should_home(), BABYSTEP_ALLOWED +#include "../module/motion.h" // for axis_should_home(), BABYSTEP_ALLOWED #include "../module/planner.h" // for axis_steps_per_mm[] #include "../module/stepper.h" diff --git a/Marlin/src/feature/mmu3/mmu3_marlin1.cpp b/Marlin/src/feature/mmu3/mmu3_marlin1.cpp index 6365481248..2c4effe106 100644 --- a/Marlin/src/feature/mmu3/mmu3_marlin1.cpp +++ b/Marlin/src/feature/mmu3/mmu3_marlin1.cpp @@ -151,34 +151,18 @@ namespace MMU3 { #endif } - int16_t thermal_degTargetHotend() { - return thermalManager.degTargetHotend(0); - } - - int16_t thermal_degHotend() { - return thermalManager.degHotend(0); - } - - void thermal_setExtrudeMintemp(int16_t t) { - thermalManager.extrude_min_temp = t; - } - - void thermal_setTargetHotend(int16_t t) { - thermalManager.setTargetHotend(t, 0); - } + int16_t thermal_degTargetHotend() { return thermalManager.degTargetHotend(0); } + int16_t thermal_degHotend() { return thermalManager.degHotend(0); } + void thermal_setExtrudeMintemp(int16_t t) { thermalManager.extrude_min_temp = t; } + void thermal_setTargetHotend(int16_t t) { thermalManager.setTargetHotend(t, 0); } void safe_delay_keep_alive(uint16_t t) { idle(true); safe_delay(t); } - void Enable_E0() { - stepper.enable_extruder(TERN_(HAS_EXTRUDERS, 0)); - } - - void Disable_E0() { - stepper.disable_extruder(TERN_(HAS_EXTRUDERS, 0)); - } + void Enable_E0() { stepper.enable_extruder(TERN_(HAS_EXTRUDERS, 0)); } + void Disable_E0() { stepper.disable_extruder(TERN_(HAS_EXTRUDERS, 0)); } bool xy_are_trusted() { return axis_is_trusted(X_AXIS) && axis_is_trusted(Y_AXIS); diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index 99df08205d..6acd2a0251 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -3262,7 +3262,7 @@ void Planner::refresh_positioning() { #if ENABLED(EDITABLE_STEPS_PER_UNIT) LOOP_DISTINCT_AXES(i) mm_per_step[i] = 1.0f / settings.axis_steps_per_mm[i]; #if ALL(NONLINEAR_EXTRUSION, SMOOTH_LIN_ADVANCE) - stepper.ne.q30.A = _BV32(30) * (stepper.ne.settings.coeff.A * mm_per_step[E_AXIS_N(0)] * mm_per_step[E_AXIS_N(0)]); + stepper.ne.q30.A = _BV32(30) * (stepper.ne.settings.coeff.A * sq(mm_per_step[E_AXIS_N(0)])); stepper.ne.q30.B = _BV32(30) * (stepper.ne.settings.coeff.B * mm_per_step[E_AXIS_N(0)]); #endif #endif From 20e99497dddf653d33f838e12a564ac78f6132bf Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 31 Oct 2025 17:21:16 -0500 Subject: [PATCH 07/99] =?UTF-8?q?=F0=9F=8E=A8=20=20AxisEnum=20style?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/core/utility.cpp | 2 +- Marlin/src/feature/babystep.cpp | 2 +- Marlin/src/feature/dac/stepper_dac.cpp | 2 +- Marlin/src/feature/encoder_i2c.cpp | 24 +++++++++++------------ Marlin/src/gcode/calibrate/M425.cpp | 2 +- Marlin/src/gcode/control/M17_M18_M84.cpp | 4 ++-- Marlin/src/gcode/gcode.cpp | 2 +- Marlin/src/lcd/e3v2/proui/proui_extui.cpp | 2 +- Marlin/src/lcd/extui/ui_api.cpp | 8 ++++---- 9 files changed, 24 insertions(+), 24 deletions(-) diff --git a/Marlin/src/core/utility.cpp b/Marlin/src/core/utility.cpp index cc49cf2cfb..c8b903ecc2 100644 --- a/Marlin/src/core/utility.cpp +++ b/Marlin/src/core/utility.cpp @@ -143,7 +143,7 @@ void safe_delay(millis_t ms) { SERIAL_ECHOPGM("ABL Adjustment"); LOOP_NUM_AXES(a) { SERIAL_ECHOPGM_P((PGM_P)pgm_read_ptr(&SP_AXIS_STR[a])); - serial_offset(planner.get_axis_position_mm(AxisEnum(a)) - current_position[a]); + serial_offset(planner.get_axis_position_mm((AxisEnum)a) - current_position[a]); } #else #if ENABLED(AUTO_BED_LEVELING_UBL) diff --git a/Marlin/src/feature/babystep.cpp b/Marlin/src/feature/babystep.cpp index bceb73ec78..6a4929e60f 100644 --- a/Marlin/src/feature/babystep.cpp +++ b/Marlin/src/feature/babystep.cpp @@ -49,7 +49,7 @@ int16_t Babystep::accum; void Babystep::step_axis(const AxisEnum axis) { const int16_t curTodo = steps[BS_AXIS_IND(axis)]; // get rid of volatile for performance if (curTodo) { - stepper.do_babystep((AxisEnum)axis, curTodo > 0); + stepper.do_babystep(axis, curTodo > 0); if (curTodo > 0) steps[BS_AXIS_IND(axis)]--; else steps[BS_AXIS_IND(axis)]++; } } diff --git a/Marlin/src/feature/dac/stepper_dac.cpp b/Marlin/src/feature/dac/stepper_dac.cpp index cd73eb17e2..65423d3189 100644 --- a/Marlin/src/feature/dac/stepper_dac.cpp +++ b/Marlin/src/feature/dac/stepper_dac.cpp @@ -87,7 +87,7 @@ void StepperDAC::print_values() { LOOP_LOGICAL_AXES(a) { SERIAL_CHAR(' ', IAXIS_CHAR(a), ':'); SERIAL_ECHO(dac_perc(a)); - SERIAL_ECHOPGM_P(PSTR(" ("), dac_amps(AxisEnum(a)), PSTR(")")); + SERIAL_ECHOPGM_P(PSTR(" ("), dac_amps((AxisEnum)a), PSTR(")")); } #if HAS_EXTRUDERS SERIAL_ECHOLNPGM_P(SP_E_LBL, dac_perc(E_AXIS), PSTR(" ("), dac_amps(E_AXIS), PSTR(")")); diff --git a/Marlin/src/feature/encoder_i2c.cpp b/Marlin/src/feature/encoder_i2c.cpp index 1930176aa6..5a47600792 100644 --- a/Marlin/src/feature/encoder_i2c.cpp +++ b/Marlin/src/feature/encoder_i2c.cpp @@ -801,7 +801,7 @@ void I2CPositionEncodersMgr::M860() { if (I2CPE_idx == 0xFF) { LOOP_LOGICAL_AXES(i) { if (!I2CPE_anyaxis || parser.seen_test(AXIS_CHAR(i))) { - const uint8_t idx = idx_from_axis(AxisEnum(i)); + const uint8_t idx = idx_from_axis((AxisEnum)i); if ((int8_t)idx >= 0) report_position(idx, hasU, hasO); } } @@ -828,7 +828,7 @@ void I2CPositionEncodersMgr::M861() { if (I2CPE_idx == 0xFF) { LOOP_LOGICAL_AXES(i) { if (!I2CPE_anyaxis || parser.seen(AXIS_CHAR(i))) { - const uint8_t idx = idx_from_axis(AxisEnum(i)); + const uint8_t idx = idx_from_axis((AxisEnum)i); if ((int8_t)idx >= 0) report_status(idx); } } @@ -856,7 +856,7 @@ void I2CPositionEncodersMgr::M862() { if (I2CPE_idx == 0xFF) { LOOP_LOGICAL_AXES(i) { if (!I2CPE_anyaxis || parser.seen(AXIS_CHAR(i))) { - const uint8_t idx = idx_from_axis(AxisEnum(i)); + const uint8_t idx = idx_from_axis((AxisEnum)i); if ((int8_t)idx >= 0) test_axis(idx); } } @@ -887,7 +887,7 @@ void I2CPositionEncodersMgr::M863() { if (I2CPE_idx == 0xFF) { LOOP_LOGICAL_AXES(i) { if (!I2CPE_anyaxis || parser.seen(AXIS_CHAR(i))) { - const uint8_t idx = idx_from_axis(AxisEnum(i)); + const uint8_t idx = idx_from_axis((AxisEnum)i); if ((int8_t)idx >= 0) calibrate_steps_mm(idx, iterations); } } @@ -963,7 +963,7 @@ void I2CPositionEncodersMgr::M865() { if (!I2CPE_addr) { LOOP_LOGICAL_AXES(i) { if (!I2CPE_anyaxis || parser.seen(AXIS_CHAR(i))) { - const uint8_t idx = idx_from_axis(AxisEnum(i)); + const uint8_t idx = idx_from_axis((AxisEnum)i); if ((int8_t)idx >= 0) report_module_firmware(encoders[idx].get_address()); } } @@ -994,12 +994,12 @@ void I2CPositionEncodersMgr::M866() { if (I2CPE_idx == 0xFF) { LOOP_LOGICAL_AXES(i) { if (!I2CPE_anyaxis || parser.seen(AXIS_CHAR(i))) { - const uint8_t idx = idx_from_axis(AxisEnum(i)); + const uint8_t idx = idx_from_axis((AxisEnum)i); if ((int8_t)idx >= 0) { if (hasR) - reset_error_count(idx, AxisEnum(i)); + reset_error_count(idx, (AxisEnum)i); else - report_error_count(idx, AxisEnum(i)); + report_error_count(idx, (AxisEnum)i); } } } @@ -1032,10 +1032,10 @@ void I2CPositionEncodersMgr::M867() { if (I2CPE_idx == 0xFF) { LOOP_LOGICAL_AXES(i) { if (!I2CPE_anyaxis || parser.seen(AXIS_CHAR(i))) { - const uint8_t idx = idx_from_axis(AxisEnum(i)); + const uint8_t idx = idx_from_axis((AxisEnum)i); if ((int8_t)idx >= 0) { const bool ena = onoff == -1 ? !encoders[I2CPE_idx].get_ec_enabled() : !!onoff; - enable_ec(idx, ena, AxisEnum(i)); + enable_ec(idx, ena, (AxisEnum)i); } } } @@ -1068,7 +1068,7 @@ void I2CPositionEncodersMgr::M868() { if (I2CPE_idx == 0xFF) { LOOP_LOGICAL_AXES(i) { if (!I2CPE_anyaxis || parser.seen(AXIS_CHAR(i))) { - const uint8_t idx = idx_from_axis(AxisEnum(i)); + const uint8_t idx = idx_from_axis((AxisEnum)i); if ((int8_t)idx >= 0) { if (newThreshold != -9999) set_ec_threshold(idx, newThreshold, encoders[idx].get_axis()); @@ -1102,7 +1102,7 @@ void I2CPositionEncodersMgr::M869() { if (I2CPE_idx == 0xFF) { LOOP_LOGICAL_AXES(i) { if (!I2CPE_anyaxis || parser.seen(AXIS_CHAR(i))) { - const uint8_t idx = idx_from_axis(AxisEnum(i)); + const uint8_t idx = idx_from_axis((AxisEnum)i); if ((int8_t)idx >= 0) report_error(idx); } } diff --git a/Marlin/src/gcode/calibrate/M425.cpp b/Marlin/src/gcode/calibrate/M425.cpp index fcf6296697..5dab92a307 100644 --- a/Marlin/src/gcode/calibrate/M425.cpp +++ b/Marlin/src/gcode/calibrate/M425.cpp @@ -94,7 +94,7 @@ void GcodeSuite::M425() { #if ENABLED(MEASURE_BACKLASH_WHEN_PROBING) SERIAL_ECHOPGM(" Average measured backlash (mm):"); if (backlash.has_any_measurement()) { - LOOP_NUM_AXES(a) if (axis_can_calibrate(a) && backlash.has_measurement(AxisEnum(a))) { + LOOP_NUM_AXES(a) if (axis_can_calibrate(a) && backlash.has_measurement((AxisEnum)a)) { SERIAL_ECHOPGM_P((PGM_P)pgm_read_ptr(&SP_AXIS_STR[a]), backlash.get_measurement((AxisEnum)a)); } } diff --git a/Marlin/src/gcode/control/M17_M18_M84.cpp b/Marlin/src/gcode/control/M17_M18_M84.cpp index 1742d288b3..90563889f3 100644 --- a/Marlin/src/gcode/control/M17_M18_M84.cpp +++ b/Marlin/src/gcode/control/M17_M18_M84.cpp @@ -78,7 +78,7 @@ void do_enable(const stepper_flags_t to_enable) { // Enable all flagged axes LOOP_NUM_AXES(a) { if (TEST(shall_enable, a)) { - stepper.enable_axis(AxisEnum(a)); // Mark and enable the requested axis + stepper.enable_axis((AxisEnum)a); // Mark and enable the requested axis DEBUG_ECHOLNPGM("Enabled ", AXIS_CHAR(a), " (", a, ") with overlap ", hex_word(enable_overlap[a]), " ... Enabled: ", hex_word(stepper.axis_enabled.bits)); also_enabled |= enable_overlap[a]; } @@ -153,7 +153,7 @@ void try_to_disable(const stepper_flags_t to_disable) { LOOP_NUM_AXES(a) if (TEST(to_disable.bits, a)) { DEBUG_ECHOPGM("Try to disable ", AXIS_CHAR(a), " (", a, ") with overlap ", hex_word(enable_overlap[a]), " ... "); - if (stepper.disable_axis(AxisEnum(a))) { // Mark the requested axis and request to disable + if (stepper.disable_axis((AxisEnum)a)) { // Mark the requested axis and request to disable DEBUG_ECHOPGM("OK"); still_enabled &= ~(_BV(a) | enable_overlap[a]); // If actually disabled, clear one or more tracked bits } diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index d4f74336de..b3dae56849 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -179,7 +179,7 @@ void GcodeSuite::get_destination_from_command() { if (skip_move) destination[i] = current_position[i]; else - destination[i] = axis_is_relative(AxisEnum(i)) ? current_position[i] + v : LOGICAL_TO_NATIVE(v, i); + destination[i] = axis_is_relative((AxisEnum)i) ? current_position[i] + v : LOGICAL_TO_NATIVE(v, i); } else destination[i] = current_position[i]; diff --git a/Marlin/src/lcd/e3v2/proui/proui_extui.cpp b/Marlin/src/lcd/e3v2/proui/proui_extui.cpp index f5a1ac21b9..9f19d354ad 100644 --- a/Marlin/src/lcd/e3v2/proui/proui_extui.cpp +++ b/Marlin/src/lcd/e3v2/proui/proui_extui.cpp @@ -238,7 +238,7 @@ namespace ExtUI { void onSteppersDisabled() {} void onSteppersEnabled() {} void onAxisDisabled(const axis_t axis) { - set_axis_untrusted(AxisEnum(axis)); // MRISCOC workaround: https://github.com/MarlinFirmware/Marlin/issues/23095 + set_axis_untrusted((AxisEnum)axis); // MRISCOC workaround: https://github.com/MarlinFirmware/Marlin/issues/23095 } void onAxisEnabled(const axis_t) {} diff --git a/Marlin/src/lcd/extui/ui_api.cpp b/Marlin/src/lcd/extui/ui_api.cpp index 75caf8a85c..0e8a84bf5b 100644 --- a/Marlin/src/lcd/extui/ui_api.cpp +++ b/Marlin/src/lcd/extui/ui_api.cpp @@ -654,19 +654,19 @@ namespace ExtUI { #if HAS_SHAPING float getShapingZeta(const axis_t axis) { - return stepper.get_shaping_damping_ratio(AxisEnum(axis)); + return stepper.get_shaping_damping_ratio((AxisEnum)axis); } void setShapingZeta(const float zeta, const axis_t axis) { if (!WITHIN(zeta, 0, 1)) return; - stepper.set_shaping_damping_ratio(AxisEnum(axis), zeta); + stepper.set_shaping_damping_ratio((AxisEnum)axis, zeta); } float getShapingFrequency(const axis_t axis) { - return stepper.get_shaping_frequency(AxisEnum(axis)); + return stepper.get_shaping_frequency((AxisEnum)axis); } void setShapingFrequency(const float freq, const axis_t axis) { constexpr float min_freq = float(uint32_t(STEPPER_TIMER_RATE) / 2) / shaping_time_t(-2); if (freq == 0.0f || freq > min_freq) - stepper.set_shaping_frequency(AxisEnum(axis), freq); + stepper.set_shaping_frequency((AxisEnum)axis, freq); } #endif From 33ad711ee867abaa3f12caadab614f34ebfaada2 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 31 Oct 2025 16:53:36 -0500 Subject: [PATCH 08/99] =?UTF-8?q?=E2=9C=85=20Update=20some=20CI=20tests?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- buildroot/tests/FYSETC_F6 | 2 +- buildroot/tests/rambo | 2 +- buildroot/tests/teensy41 | 3 ++- 3 files changed, 4 insertions(+), 3 deletions(-) diff --git a/buildroot/tests/FYSETC_F6 b/buildroot/tests/FYSETC_F6 index 4c647d57d4..6337fab5fc 100755 --- a/buildroot/tests/FYSETC_F6 +++ b/buildroot/tests/FYSETC_F6 @@ -57,7 +57,7 @@ opt_set MOTHERBOARD BOARD_FYSETC_F6_13 \ opt_enable REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER \ MARLIN_BRICKOUT MARLIN_INVADERS MARLIN_SNAKE \ MONITOR_DRIVER_STATUS STEALTHCHOP_XY STEALTHCHOP_Z STEALTHCHOP_E HYBRID_THRESHOLD \ - SENSORLESS_HOMING X_STALL_SENSITIVITY Y_STALL_SENSITIVITY TMC_DEBUG M114_DETAIL + SENSORLESS_HOMING X_STALL_SENSITIVITY Y_STALL_SENSITIVITY TMC_DEBUG M114_DETAIL AUTO_REPORT_POSITION exec_test $1 $2 "Mixed TMC | Sensorless | RRDFGSC | Games" "$3" # diff --git a/buildroot/tests/rambo b/buildroot/tests/rambo index 1fab879537..06037a838f 100755 --- a/buildroot/tests/rambo +++ b/buildroot/tests/rambo @@ -113,7 +113,7 @@ opt_enable EEPROM_SETTINGS EEPROM_CHITCHAT REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CO INCH_MODE_SUPPORT TEMPERATURE_UNITS_SUPPORT EXPERIMENTAL_I2CBUS M100_FREE_MEMORY_WATCHER \ NOZZLE_PARK_FEATURE NOZZLE_CLEAN_FEATURE \ ADVANCED_PAUSE_FEATURE PARK_HEAD_ON_PAUSE ADVANCED_PAUSE_CONTINUOUS_PURGE FILAMENT_LOAD_UNLOAD_GCODES \ - PRINTCOUNTER SERVICE_NAME_1 SERVICE_INTERVAL_1 M114_DETAIL + PRINTCOUNTER SERVICE_NAME_1 SERVICE_INTERVAL_1 M114_DETAIL AUTO_REPORT_POSITION opt_disable NOZZLE_CLEAN_PATTERN_CIRCLE opt_add M100_FREE_MEMORY_DUMPER opt_add M100_FREE_MEMORY_CORRUPTOR diff --git a/buildroot/tests/teensy41 b/buildroot/tests/teensy41 index f66a9272ea..0985d47b81 100755 --- a/buildroot/tests/teensy41 +++ b/buildroot/tests/teensy41 @@ -26,7 +26,8 @@ opt_enable MAX31865_SENSOR_OHMS_0 MAX31865_CALIBRATION_OHMS_0 \ FIX_MOUNTED_PROBE Z_SAFE_HOMING AUTO_BED_LEVELING_BILINEAR Z_MIN_PROBE_REPEATABILITY_TEST DEBUG_LEVELING_FEATURE \ BABYSTEPPING BABYSTEP_XY BABYSTEP_ZPROBE_OFFSET \ PRINTCOUNTER NOZZLE_PARK_FEATURE NOZZLE_CLEAN_FEATURE SLOW_PWM_HEATERS PIDTEMPBED EEPROM_SETTINGS INCH_MODE_SUPPORT TEMPERATURE_UNITS_SUPPORT \ - ADVANCED_PAUSE_FEATURE ARC_SUPPORT BEZIER_CURVE_SUPPORT EXPERIMENTAL_I2CBUS EXTENDED_CAPABILITIES_REPORT AUTO_REPORT_TEMPERATURES PARK_HEAD_ON_PAUSE \ + ADVANCED_PAUSE_FEATURE ARC_SUPPORT BEZIER_CURVE_SUPPORT EXPERIMENTAL_I2CBUS PARK_HEAD_ON_PAUSE \ + EXTENDED_CAPABILITIES_REPORT AUTO_REPORT_POSITION AUTO_REPORT_TEMPERATURES \ PHOTO_GCODE PHOTO_POSITION PHOTO_SWITCH_POSITION PHOTO_SWITCH_MS PHOTO_DELAY_MS PHOTO_RETRACT_MM \ HOST_ACTION_COMMANDS HOST_PROMPT_SUPPORT HOST_STATUS_NOTIFICATIONS PINS_DEBUGGING opt_add EXTUI_EXAMPLE From 8bf127afe6103d2f13d373a3b3ee4018c6c6d2ad Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 1 Nov 2025 16:21:52 -0500 Subject: [PATCH 09/99] =?UTF-8?q?=F0=9F=8E=A8=20Aesthetic=20tweaks?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/module/planner.cpp | 3 ++- Marlin/src/module/planner.h | 12 ++++++------ Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h | 2 +- 3 files changed, 9 insertions(+), 8 deletions(-) diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index 6acd2a0251..404d1fc5a7 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -781,7 +781,7 @@ block_t* Planner::get_current_block() { block_t* Planner::get_future_block(const uint8_t offset) { const uint8_t nr_moves = movesplanned(); if (nr_moves <= offset) return nullptr; - block_t * const block = &block_buffer[block_inc_mod(block_buffer_tail, offset)]; + block_t * const block = &block_buffer[block_add_mod(block_buffer_tail, offset)]; if (block->flag.recalculate) return nullptr; return block; } @@ -878,6 +878,7 @@ void Planner::calculate_trapezoid_for_block(block_t * const block, const float e block->acceleration_time_inverse = acceleration_time_inverse; block->deceleration_time_inverse = deceleration_time_inverse; #endif + #if ENABLED(SMOOTH_LIN_ADVANCE) block->cruise_time = plateau_steps > 0 ? float(plateau_steps) * float(STEPPER_TIMER_RATE) / float(cruise_rate) : 0; #endif diff --git a/Marlin/src/module/planner.h b/Marlin/src/module/planner.h index b6fdc2fc6f..21b6fd660b 100644 --- a/Marlin/src/module/planner.h +++ b/Marlin/src/module/planner.h @@ -325,11 +325,11 @@ typedef struct PlannerBlock { #define HAS_POSITION_FLOAT 1 #endif -constexpr uint8_t block_dec_mod(const uint8_t v1, const uint8_t v2) { +constexpr uint8_t block_sub_mod(const uint8_t v1, const uint8_t v2) { return v1 >= v2 ? v1 - v2 : v1 - v2 + BLOCK_BUFFER_SIZE; } -constexpr uint8_t block_inc_mod(const uint8_t v1, const uint8_t v2) { +constexpr uint8_t block_add_mod(const uint8_t v1, const uint8_t v2) { return v1 + v2 < BLOCK_BUFFER_SIZE ? v1 + v2 : v1 + v2 - BLOCK_BUFFER_SIZE; } @@ -850,10 +850,10 @@ class Planner { #endif // HAS_POSITION_MODIFIERS // Number of moves currently in the planner including the busy block, if any - FORCE_INLINE static uint8_t movesplanned() { return block_dec_mod(block_buffer_head, block_buffer_tail); } + FORCE_INLINE static uint8_t movesplanned() { return block_sub_mod(block_buffer_head, block_buffer_tail); } // Number of nonbusy moves currently in the planner - FORCE_INLINE static uint8_t nonbusy_movesplanned() { return block_dec_mod(block_buffer_head, block_buffer_nonbusy); } + FORCE_INLINE static uint8_t nonbusy_movesplanned() { return block_sub_mod(block_buffer_head, block_buffer_nonbusy); } // Remove all blocks from the buffer FORCE_INLINE static void clear_block_buffer() { @@ -1131,8 +1131,8 @@ class Planner { /** * Get the index of the next / previous block in the ring buffer */ - static constexpr uint8_t next_block_index(const uint8_t block_index) { return block_inc_mod(block_index, 1); } - static constexpr uint8_t prev_block_index(const uint8_t block_index) { return block_dec_mod(block_index, 1); } + static constexpr uint8_t next_block_index(const uint8_t block_index) { return block_add_mod(block_index, 1); } + static constexpr uint8_t prev_block_index(const uint8_t block_index) { return block_sub_mod(block_index, 1); } /** * Calculate the maximum allowable speed squared at this point, in order diff --git a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h index e5f4972fc6..180837d535 100644 --- a/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h +++ b/Marlin/src/pins/stm32f1/pins_MKS_ROBIN_E3P.h @@ -288,7 +288,7 @@ #define BTN_ENC EXP1_02_PIN #define BTN_EN1 EXP2_03_PIN #define BTN_EN2 EXP2_05_PIN -#elif ENABLED(HAS_GRAPHICAL_TFT) +#elif HAS_GRAPHICAL_TFT #define TFT_BUFFER_WORDS 14400 #endif From bdfb0cc63f1e4ccd9dbee9323d73bf6b3694f890 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 1 Nov 2025 16:22:35 -0500 Subject: [PATCH 10/99] =?UTF-8?q?=F0=9F=A9=B9=20ProUI:=20Edit=20K=20for=20?= =?UTF-8?q?active=20E?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/e3v2/proui/dwin.cpp | 18 +++++++++++------- Marlin/src/lcd/e3v2/proui/dwin_defines.h | 2 +- 2 files changed, 12 insertions(+), 8 deletions(-) diff --git a/Marlin/src/lcd/e3v2/proui/dwin.cpp b/Marlin/src/lcd/e3v2/proui/dwin.cpp index d6718305c2..0fa21fa922 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin.cpp @@ -2689,10 +2689,10 @@ void applyMaxAccel() { planner.set_max_acceleration(hmiValue.axis, menuData.valu #if ENABLED(LIN_ADVANCE) #define LA_FDIGITS 3 void applyLA_K() { planner.set_advance_k(menuData.value / POW(10, LA_FDIGITS)); } - void setLA_K() { setFloatOnClick(0, 10, LA_FDIGITS, planner.extruder_advance_K[0], applyLA_K); } + void setLA_K() { setFloatOnClick(0, 10, LA_FDIGITS, planner.get_advance_K(), applyLA_K); } void onDrawLA_K(MenuItem* menuitem, int8_t line) { onDrawFloatMenu(menuitem, line, LA_FDIGITS, planner.get_advance_k()); } #if ENABLED(SMOOTH_LIN_ADVANCE) - void applySmoothLA() { Stepper::set_advance_tau(menuData.value / POW(10, 2)); } + void applySmoothLA() { stepper.set_advance_tau(menuData.value / POW(10, 2)); } void setSmoothLA() { setPFloatOnClick(0, 0.5, 2, applySmoothLA); } #endif #endif @@ -3551,11 +3551,13 @@ void drawTuneMenu() { #if ENABLED(PROUI_ITEM_JD) EDIT_ITEM(ICON_JDmm, MSG_JUNCTION_DEVIATION, onDrawPFloat3Menu, setJDmm, &planner.junction_deviation_mm); #endif - #if ALL(PROUI_ITEM_ADVK, LIN_ADVANCE) - static float editable_k = planner.get_advance_k(); + #if PROUI_ITEM_ADVK + static float editable_k; + editable_k = planner.get_advance_k(); EDIT_ITEM(ICON_MaxAccelerated, MSG_ADVANCE_K, onDrawLA_K, setLA_K, &editable_k); #if ENABLED(SMOOTH_LIN_ADVANCE) - static float editable_u = Stepper::get_advance_tau(); + static float editable_u; + editable_u = stepper.get_advance_tau(); EDIT_ITEM(ICON_MaxSpeed, MSG_ADVANCE_TAU, onDrawPFloat2Menu, setSmoothLA, &editable_u); #endif #endif @@ -3695,10 +3697,12 @@ void drawMotionMenu() { MENU_ITEM(ICON_Homing, MSG_HOMING_FEEDRATE, onDrawSubMenu, drawHomingFRMenu); #endif #if ENABLED(LIN_ADVANCE) - static float editable_k = planner.get_advance_k(); + static float editable_k; + editable_k = planner.get_advance_k(); EDIT_ITEM(ICON_MaxAccelerated, MSG_ADVANCE_K, onDrawLA_K, setLA_K, &editable_k); #if ENABLED(SMOOTH_LIN_ADVANCE) - static float editable_u = Stepper::get_advance_tau(); + static float editable_u; + editable_u = stepper.get_advance_tau(); EDIT_ITEM(ICON_MaxSpeed, MSG_ADVANCE_TAU, onDrawPFloat2Menu, setSmoothLA, &editable_u); #endif #endif diff --git a/Marlin/src/lcd/e3v2/proui/dwin_defines.h b/Marlin/src/lcd/e3v2/proui/dwin_defines.h index 832702db8f..52ad604296 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin_defines.h +++ b/Marlin/src/lcd/e3v2/proui/dwin_defines.h @@ -125,7 +125,7 @@ #define PROUI_ITEM_JD // Tune > Junction Deviation #endif #if ENABLED(LIN_ADVANCE) - #define PROUI_ITEM_ADVK // Tune > Linear Advance + #define PROUI_ITEM_ADVK 1 // Tune > Linear Advance #endif #if ANY(HAS_PID_HEATING, MPC_AUTOTUNE) && DISABLED(DISABLE_TUNING_GRAPH) #define PROUI_TUNING_GRAPH 1 From 9c3d74f6d1831be21d1fc2413f9a2b21ba5862bb Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 1 Nov 2025 18:57:12 -0500 Subject: [PATCH 11/99] =?UTF-8?q?=F0=9F=A9=B9=20ProUI:=20Edit=20K=20for=20?= =?UTF-8?q?active=20E=20(2)?= 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 0fa21fa922..a8d8e277db 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin.cpp @@ -2689,7 +2689,7 @@ void applyMaxAccel() { planner.set_max_acceleration(hmiValue.axis, menuData.valu #if ENABLED(LIN_ADVANCE) #define LA_FDIGITS 3 void applyLA_K() { planner.set_advance_k(menuData.value / POW(10, LA_FDIGITS)); } - void setLA_K() { setFloatOnClick(0, 10, LA_FDIGITS, planner.get_advance_K(), applyLA_K); } + void setLA_K() { setFloatOnClick(0, 10, LA_FDIGITS, planner.get_advance_k(), applyLA_K); } void onDrawLA_K(MenuItem* menuitem, int8_t line) { onDrawFloatMenu(menuitem, line, LA_FDIGITS, planner.get_advance_k()); } #if ENABLED(SMOOTH_LIN_ADVANCE) void applySmoothLA() { stepper.set_advance_tau(menuData.value / POW(10, 2)); } From 3fc45df62fa9b390aaebdfa1eed24ba06b9cfa8c Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sun, 2 Nov 2025 00:34:34 +0000 Subject: [PATCH 12/99] [cron] Bump distribution date (2025-11-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 c88b6f1a19..87c8749906 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 "2025-11-01" +//#define STRING_DISTRIBUTION_DATE "2025-11-02" /** * The protocol for communication to the host. Protocol indicates communication diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index e9c314fcd3..e87409f70f 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 "2025-11-01" + #define STRING_DISTRIBUTION_DATE "2025-11-02" #endif /** From 05a64e20137ef1d03ff24ab02ae59d1cfc26b4cb Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 20 Oct 2025 15:03:31 -0500 Subject: [PATCH 13/99] =?UTF-8?q?=F0=9F=9A=B8=20Fix=20'M493=20G',=20collis?= =?UTF-8?q?ions=20'E'=20'O'=20(and=20'M'),=20'W'=20report?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Part of #21827 --- Marlin/src/gcode/feature/ft_motion/M493.cpp | 72 +++++++++++++++++---- 1 file changed, 59 insertions(+), 13 deletions(-) diff --git a/Marlin/src/gcode/feature/ft_motion/M493.cpp b/Marlin/src/gcode/feature/ft_motion/M493.cpp index f1dc4d0753..c9b056d7d1 100644 --- a/Marlin/src/gcode/feature/ft_motion/M493.cpp +++ b/Marlin/src/gcode/feature/ft_motion/M493.cpp @@ -128,6 +128,22 @@ void GcodeSuite::M493_report(const bool forReplay/*=true*/) { const ft_config_t &c = ftMotion.cfg; SERIAL_ECHOLNPGM( " M493 S", c.active + + // Shaper type for each axis + #if HAS_X_AXIS + , " X", c.shaper.x + #endif + #if HAS_Y_AXIS + , " Y", c.shaper.y + #endif + #if ENABLED(FTM_SHAPER_Z) + , " Z", c.shaper.z + #endif + #if ENABLED(FTM_SHAPER_E) + , " E", c.shaper.e + #endif + + // Base Frequency for axis shapers #if HAS_X_AXIS , " A", c.baseFreq.x #endif @@ -138,9 +154,10 @@ void GcodeSuite::M493_report(const bool forReplay/*=true*/) { , " C", c.baseFreq.z #endif #if ENABLED(FTM_SHAPER_E) - , " E", c.baseFreq.e + , " W", c.baseFreq.e #endif + // Dynamic Frequency Mode and Axis K Factors #if HAS_DYNAMIC_FREQ , " D", c.dynFreqMode #if HAS_X_AXIS @@ -153,10 +170,39 @@ void GcodeSuite::M493_report(const bool forReplay/*=true*/) { , " L", c.dynFreqK.z #endif #if ENABLED(FTM_SHAPER_E) - , " O", c.dynFreqK.e + , " N", c.dynFreqK.e #endif #endif + // Zeta Value + #if HAS_X_AXIS + , " I", c.zeta.x + #endif + #if HAS_Y_AXIS + , " J", c.zeta.y + #endif + #if ENABLED(FTM_SHAPER_Z) + , " O", c.zeta.z + #endif + #if ENABLED(FTM_SHAPER_E) + , " U", c.zeta.e + #endif + + // Vibration Tolerance + #if HAS_X_AXIS + , " Q", c.vtol.x + #endif + #if HAS_Y_AXIS + , " R", c.vtol.y + #endif + #if ENABLED(FTM_SHAPER_Z) + , " T", c.vtol.z + #endif + #if ENABLED(FTM_SHAPER_E) + , " V", c.vtol.e + #endif + + // Axis Synchronization , " G", c.axis_sync_enabled #if HAS_EXTRUDERS @@ -199,22 +245,22 @@ void GcodeSuite::M493_report(const bool forReplay/*=true*/) { * A Set X static/base frequency * F Set X frequency scaling * I Set X damping ratio - * Q Set X vibration tolerance + * Q Set X vibration tolerance (vtol) * * B Set Y static/base frequency * H Set Y frequency scaling * J Set Y damping ratio * R Set Y vibration tolerance * - * With FTM_SHAPING_Z: + * With FTM_SHAPER_Z: * C Set Z static/base frequency * L Set Z frequency scaling * O Set Z damping ratio - * M Set Z vibration tolerance + * T Set Z vibration tolerance * - * With FTM_SHAPING_E: + * With FTM_SHAPER_E: * W Set E static/base frequency - * O Set E frequency scaling + * N Set E frequency scaling * U Set E damping ratio * V Set E vibration tolerance * @@ -286,8 +332,8 @@ void GcodeSuite::M493() { #endif // HAS_EXTRUDERS - // Parse '?' axis synchronization parameter. - if (parser.seen('?')) { + // Parse 'G' axis synchronization parameter. + if (parser.seenval('G')) { const bool enabled = parser.value_bool(); if (enabled != ftMotion.cfg.axis_sync_enabled) { ftMotion.cfg.axis_sync_enabled = enabled; @@ -497,7 +543,7 @@ void GcodeSuite::M493() { } // Parse Z vtol parameter - if (parser.seenval('M')) { + if (parser.seenval('T')) { const float val = parser.value_float(); if (AXIS_IS_EISHAPING(Z)) { if (WITHIN(val, 0.00f, 1.0f)) { @@ -505,7 +551,7 @@ void GcodeSuite::M493() { flag.update = true; } else - SERIAL_ECHOLNPGM("?Invalid ", C(STEPPER_C_NAME), " vtol [", C('M'), "] value."); // VTol out of range. + SERIAL_ECHOLNPGM("?Invalid ", C(STEPPER_C_NAME), " vtol [", C('T'), "] value."); // VTol out of range. } else SERIAL_ECHOLNPGM("?Wrong mode for ", C(STEPPER_C_NAME), " vtol parameter."); @@ -532,13 +578,13 @@ void GcodeSuite::M493() { #if HAS_DYNAMIC_FREQ // Parse E frequency scaling parameter - if (parser.seenval('O')) { + if (parser.seenval('N')) { if (modeUsesDynFreq) { ftMotion.cfg.dynFreqK.e = parser.value_float(); flag.report = true; } else - SERIAL_ECHOLNPGM("?Wrong mode for ", C('E'), " [", C('O'), "] frequency scaling."); + SERIAL_ECHOLNPGM("?Wrong mode for ", C('E'), " [", C('N'), "] frequency scaling."); } #endif From 40beddeaa397cf8bb7b324209f86bb47e1d50f7f Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 20 Oct 2025 16:01:13 -0500 Subject: [PATCH 14/99] =?UTF-8?q?=F0=9F=9A=B8=20Simplified=20M493?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Part of #21827 --- Marlin/src/gcode/feature/ft_motion/M493.cpp | 566 +++++++++----------- Marlin/src/module/ft_motion.h | 2 + 2 files changed, 251 insertions(+), 317 deletions(-) diff --git a/Marlin/src/gcode/feature/ft_motion/M493.cpp b/Marlin/src/gcode/feature/ft_motion/M493.cpp index c9b056d7d1..796676bf57 100644 --- a/Marlin/src/gcode/feature/ft_motion/M493.cpp +++ b/Marlin/src/gcode/feature/ft_motion/M493.cpp @@ -46,8 +46,10 @@ void say_shaper_type(const AxisEnum a, bool &sep, const char axis_name) { } void say_shaping() { + const ft_config_t &c = ftMotion.cfg; + // FT Enabled - SERIAL_ECHO_TERNARY(ftMotion.cfg.active, "Fixed-Time Motion ", "en", "dis", "abled"); + SERIAL_ECHO_TERNARY(c.active, "Fixed-Time Motion ", "en", "dis", "abled"); // FT Shaping const bool is_shaping = AXIS_IS_SHAPING(X) || AXIS_IS_SHAPING(Y) || AXIS_IS_SHAPING(Z) || AXIS_IS_SHAPING(E); @@ -61,15 +63,15 @@ void say_shaping() { } SERIAL_EOL(); - const bool z_based = TERN0(HAS_DYNAMIC_FREQ_MM, ftMotion.cfg.dynFreqMode == dynFreqMode_Z_BASED), - g_based = TERN0(HAS_DYNAMIC_FREQ_G, ftMotion.cfg.dynFreqMode == dynFreqMode_MASS_BASED), + const bool z_based = TERN0(HAS_DYNAMIC_FREQ_MM, c.dynFreqMode == dynFreqMode_Z_BASED), + g_based = TERN0(HAS_DYNAMIC_FREQ_G, c.dynFreqMode == dynFreqMode_MASS_BASED), dynamic = z_based || g_based; // FT Dynamic Frequency Mode if (is_shaping) { #if HAS_DYNAMIC_FREQ SERIAL_ECHOPGM("Dynamic Frequency Mode "); - switch (ftMotion.cfg.dynFreqMode) { + switch (c.dynFreqMode) { default: case dynFreqMode_DISABLED: SERIAL_ECHOPGM("disabled"); break; #if HAS_DYNAMIC_FREQ_MM @@ -85,9 +87,9 @@ void say_shaping() { #if HAS_X_AXIS SERIAL_CHAR(STEPPER_A_NAME); SERIAL_ECHO_TERNARY(dynamic, " ", "base dynamic", "static", " shaper frequency: "); - SERIAL_ECHO(p_float_t(ftMotion.cfg.baseFreq.x, 2), F("Hz")); + SERIAL_ECHO(p_float_t(c.baseFreq.x, 2), F("Hz")); #if HAS_DYNAMIC_FREQ - if (dynamic) SERIAL_ECHO(F(" scaling: "), p_float_t(ftMotion.cfg.dynFreqK.x, 2), F("Hz/"), z_based ? F("mm") : F("g")); + if (dynamic) SERIAL_ECHO(F(" scaling: "), p_float_t(c.dynFreqK.x, 2), F("Hz/"), z_based ? F("mm") : F("g")); #endif SERIAL_EOL(); #endif @@ -95,9 +97,9 @@ void say_shaping() { #if HAS_Y_AXIS SERIAL_CHAR(STEPPER_B_NAME); SERIAL_ECHO_TERNARY(dynamic, " ", "base dynamic", "static", " shaper frequency: "); - SERIAL_ECHO(p_float_t(ftMotion.cfg.baseFreq.y, 2), F(" Hz")); + SERIAL_ECHO(p_float_t(c.baseFreq.y, 2), F(" Hz")); #if HAS_DYNAMIC_FREQ - if (dynamic) SERIAL_ECHO(F(" scaling: "), p_float_t(ftMotion.cfg.dynFreqK.y, 2), F("Hz/"), z_based ? F("mm") : F("g")); + if (dynamic) SERIAL_ECHO(F(" scaling: "), p_float_t(c.dynFreqK.y, 2), F("Hz/"), z_based ? F("mm") : F("g")); #endif SERIAL_EOL(); #endif @@ -105,18 +107,18 @@ void say_shaping() { #if ENABLED(FTM_SHAPER_Z) SERIAL_CHAR(STEPPER_C_NAME); SERIAL_ECHO_TERNARY(dynamic, " ", "base dynamic", "static", " shaper frequency: "); - SERIAL_ECHO(p_float_t(ftMotion.cfg.baseFreq.z, 2), F(" Hz")); + SERIAL_ECHO(p_float_t(c.baseFreq.z, 2), F(" Hz")); #if HAS_DYNAMIC_FREQ - if (dynamic) SERIAL_ECHO(F(" scaling: "), p_float_t(ftMotion.cfg.dynFreqK.z, 2), F("Hz/"), z_based ? F("mm") : F("g")); + if (dynamic) SERIAL_ECHO(F(" scaling: "), p_float_t(c.dynFreqK.z, 2), F("Hz/"), z_based ? F("mm") : F("g")); #endif SERIAL_EOL(); #endif } #if HAS_EXTRUDERS - if (ftMotion.cfg.active) { - SERIAL_ECHO_TERNARY(ftMotion.cfg.linearAdvEna, "Linear Advance ", "en", "dis", "abled"); - SERIAL_ECHOLNPGM(". Gain: ", ftMotion.cfg.linearAdvK); + if (c.active) { + SERIAL_ECHO_TERNARY(c.linearAdvEna, "Linear Advance ", "en", "dis", "abled"); + SERIAL_ECHOLNPGM(". Gain: ", c.linearAdvK); } #endif } @@ -126,90 +128,34 @@ void GcodeSuite::M493_report(const bool forReplay/*=true*/) { report_heading_etc(forReplay, F(STR_FT_MOTION)); const ft_config_t &c = ftMotion.cfg; + SERIAL_ECHOLNPGM( " M493 S", c.active - - // Shaper type for each axis - #if HAS_X_AXIS - , " X", c.shaper.x - #endif - #if HAS_Y_AXIS - , " Y", c.shaper.y - #endif - #if ENABLED(FTM_SHAPER_Z) - , " Z", c.shaper.z - #endif - #if ENABLED(FTM_SHAPER_E) - , " E", c.shaper.e - #endif - - // Base Frequency for axis shapers - #if HAS_X_AXIS - , " A", c.baseFreq.x - #endif - #if HAS_Y_AXIS - , " B", c.baseFreq.y - #endif - #if ENABLED(FTM_SHAPER_Z) - , " C", c.baseFreq.z - #endif - #if ENABLED(FTM_SHAPER_E) - , " W", c.baseFreq.e - #endif - - // Dynamic Frequency Mode and Axis K Factors #if HAS_DYNAMIC_FREQ , " D", c.dynFreqMode - #if HAS_X_AXIS - , " F", c.dynFreqK.x - #endif - #if HAS_Y_AXIS - , " H", c.dynFreqK.y - #endif - #if ENABLED(FTM_SHAPER_Z) - , " L", c.dynFreqK.z - #endif - #if ENABLED(FTM_SHAPER_E) - , " N", c.dynFreqK.e - #endif #endif - - // Zeta Value - #if HAS_X_AXIS - , " I", c.zeta.x - #endif - #if HAS_Y_AXIS - , " J", c.zeta.y - #endif - #if ENABLED(FTM_SHAPER_Z) - , " O", c.zeta.z - #endif - #if ENABLED(FTM_SHAPER_E) - , " U", c.zeta.e - #endif - - // Vibration Tolerance - #if HAS_X_AXIS - , " Q", c.vtol.x - #endif - #if HAS_Y_AXIS - , " R", c.vtol.y - #endif - #if ENABLED(FTM_SHAPER_Z) - , " T", c.vtol.z - #endif - #if ENABLED(FTM_SHAPER_E) - , " V", c.vtol.e - #endif - - // Axis Synchronization - , " G", c.axis_sync_enabled - #if HAS_EXTRUDERS , " P", c.linearAdvEna, " K", c.linearAdvK #endif - + // Axis Synchronization + , " H", c.axis_sync_enabled ); + + #if HAS_DYNAMIC_FREQ + #define F_REPORT(A) , F(" F"), c.dynFreqK.A + #else + #define F_REPORT(A) + #endif + #define _REPORT_M493_AXIS(A) \ + SERIAL_ECHOLN(F(" M493 "), C(AXIS_CHAR(_AXIS(A))) \ + , F(" C"), c.shaper.A \ + , F(" A"), c.baseFreq.A \ + F_REPORT(A) \ + , F(" I"), c.zeta.A \ + , F(" Q"), c.vtol.A \ + ); + // Shaper type for each axis + SHAPED_MAP(_REPORT_M493_AXIS); } /** @@ -219,7 +165,23 @@ void GcodeSuite::M493_report(const bool forReplay/*=true*/) { * 0: Fixed-Time Motion OFF (Standard Motion) * 1: Fixed-Time Motion ON * - * X/Y/Z/E Set the vibration compensator [input shaper] mode for an axis. + * V Flag to request version (Version 2+). (No reply = Version < 2) + * + * H Enable (1) or Disable (0) Axis Synchronization. + * + * Linear / Pressure Advance: + * + * P Enable (1) or Disable (0) Linear Advance pressure control + * K Set Linear Advance gain + * + * Specifying Axes (for A,C,F,I,Q): + * + * X/Y/Z/E : Flag the axes (or core steppers) on which to apply the given parameters + * If none are given then XY is assumed. + * + * Compensator / Input Shaper: + * + * C Set Compensator Mode (Input Shaper) for the specified axes * Users / slicers must remember to set the mode for all relevant axes! * 0: NONE : No input shaper * 1: ZV : Zero Vibration @@ -231,41 +193,27 @@ void GcodeSuite::M493_report(const bool forReplay/*=true*/) { * 7: 3HEI : 3-Hump Extra-Intensive * 8: MZV : Mass-based Zero Vibration * - * P Enable (1) or Disable (0) Linear Advance pressure control + * A Set static/base frequency for the specified axes + * I Set damping ratio for the specified axes + * Q Set vibration tolerance (vtol) for the specified axes * - * K Set Linear Advance gain + * Dynamic Frequency Mode: * - * G Enable (1) or Disable (0) axis synchronization. - * - * D Set Dynamic Frequency mode + * D Set Dynamic Frequency mode (for all axis compensators) * 0: DISABLED * 1: Z-based (Requires a Z axis) * 2: Mass-based (Requires X and E axes) * - * A Set X static/base frequency - * F Set X frequency scaling - * I Set X damping ratio - * Q Set X vibration tolerance (vtol) - * - * B Set Y static/base frequency - * H Set Y frequency scaling - * J Set Y damping ratio - * R Set Y vibration tolerance - * - * With FTM_SHAPER_Z: - * C Set Z static/base frequency - * L Set Z frequency scaling - * O Set Z damping ratio - * T Set Z vibration tolerance - * - * With FTM_SHAPER_E: - * W Set E static/base frequency - * N Set E frequency scaling - * U Set E damping ratio - * V Set E vibration tolerance + * F Set frequency scaling for the specified axes * */ void GcodeSuite::M493() { + // Request version of FTM. (No response = Version < 2) + if (parser.seen('V') && !parser.has_value()) { + SERIAL_ECHOLNPGM("FTM V" STRINGIFY(FTM_VERSION)); + return; + } + struct { bool update:1, report:1; } flag = { false }; if (!parser.seen_any()) @@ -283,30 +231,23 @@ void GcodeSuite::M493() { #if NUM_AXES_SHAPED > 0 - auto set_shaper = [&](const AxisEnum axis, const char c) { - const ftMotionShaper_t newsh = (ftMotionShaper_t)parser.value_byte(); + const bool seenC = parser.seenval('C'); + const ftMotionShaper_t shaperVal = seenC ? (ftMotionShaper_t)parser.value_byte() : ftMotionShaper_NONE; + const bool goodShaper = WITHIN(shaperVal, ftMotionShaper_NONE, ftMotionShaper_MZV); + if (seenC && !goodShaper) { + SERIAL_ECHOLNPGM("?Invalid (C)ompensator value. (0-", int(ftMotionShaper_MZV)); + return; + } + auto set_shaper = [&](const AxisEnum axis, ftMotionShaper_t newsh) { if (newsh != ftMotion.cfg.shaper[axis]) { - switch (newsh) { - default: SERIAL_ECHOLNPGM("?Invalid [", C(c), "] shaper."); return true; - case ftMotionShaper_NONE: - case ftMotionShaper_ZV: - case ftMotionShaper_ZVD: - case ftMotionShaper_ZVDD: - case ftMotionShaper_ZVDDD: - case ftMotionShaper_EI: - case ftMotionShaper_2HEI: - case ftMotionShaper_3HEI: - case ftMotionShaper_MZV: - ftMotion.cfg.shaper[axis] = newsh; - flag.update = flag.report = true; - break; - } + ftMotion.cfg.shaper[axis] = newsh; + flag.update = flag.report = true; } - return false; }; - - #define _SET_SHAPER(A) if (parser.seenval(CHARIFY(A)) && set_shaper(_AXIS(A), CHARIFY(A))) return; - SHAPED_MAP(_SET_SHAPER); + if (seenC) { + #define _SET_SHAPER(A) set_shaper(_AXIS(A), shaperVal); + SHAPED_MAP(_SET_SHAPER); + } #endif // NUM_AXES_SHAPED > 0 @@ -332,8 +273,8 @@ void GcodeSuite::M493() { #endif // HAS_EXTRUDERS - // Parse 'G' axis synchronization parameter. - if (parser.seenval('G')) { + // Parse 'H' Axis Synchronization parameter. + if (parser.seenval('H')) { const bool enabled = parser.value_bool(); if (enabled != ftMotion.cfg.axis_sync_enabled) { ftMotion.cfg.axis_sync_enabled = enabled; @@ -359,12 +300,12 @@ void GcodeSuite::M493() { flag.report = true; break; default: - SERIAL_ECHOLNPGM("?Invalid Dynamic Frequency Mode [D] value."); + SERIAL_ECHOLNPGM("?Invalid (D)ynamic Frequency Mode value."); break; } } else { - SERIAL_ECHOLNPGM("?Wrong shaper for [D] Dynamic Frequency mode."); + SERIAL_ECHOLNPGM("?Wrong shaper for (D)ynamic Frequency mode ", ftMotion.cfg.dynFreqMode, "."); } } @@ -375,247 +316,238 @@ void GcodeSuite::M493() { #endif // HAS_DYNAMIC_FREQ + // Frequency parameter + const bool seenA = parser.seenval('A'); + const float baseFreqVal = seenA ? parser.value_float() : 0.0f; + const bool goodBaseFreq = seenA && WITHIN(baseFreqVal, FTM_MIN_SHAPE_FREQ, (FTM_FS) / 2); + if (seenA && !goodBaseFreq) + SERIAL_ECHOLN(F("?Invalid (A) Base Frequency value. ("), int(FTM_MIN_SHAPE_FREQ), C('-'), int((FTM_FS) / 2), C(')')); + + #if HAS_DYNAMIC_FREQ + // Dynamic Frequency parameter + const bool seenF = parser.seenval('F'); + const float baseDynFreqVal = seenF ? parser.value_float() : 0.0f; + if (seenF && !modeUsesDynFreq) + SERIAL_ECHOLNPGM("?Wrong mode for (F)requency scaling."); + #endif + + // Zeta parameter + const bool seenI = parser.seenval('I'); + const float zetaVal = seenI ? parser.value_float() : 0.0f; + const bool goodZeta = seenI && WITHIN(zetaVal, 0.01f, 1.0f); + if (seenI && !goodZeta) + SERIAL_ECHOLNPGM("?Invalid (I) Zeta value. (0.01-1.0)"); // Zeta out of range + + // Vibration Tolerance parameter + const bool seenQ = parser.seenval('Q'); + const float vtolVal = seenQ ? parser.value_float() : 0.0f; + const bool goodVtol = seenQ && WITHIN(vtolVal, 0.00f, 1.0f); + if (seenQ && !goodVtol) + SERIAL_ECHOLNPGM("?Invalid (Q) Vibration Tolerance value. (0.0-1.0)"); // VTol out of range + + const bool apply_xy = !parser.seen("XYZE"); + #if HAS_X_AXIS - // Parse X frequency parameter - if (parser.seenval('A')) { - if (AXIS_IS_SHAPING(X)) { - const float val = parser.value_float(); - // TODO: Frequency minimum is dependent on the shaper used; the above check isn't always correct. - if (WITHIN(val, FTM_MIN_SHAPE_FREQ, (FTM_FS) / 2)) { - ftMotion.cfg.baseFreq.x = val; - flag.update = flag.report = true; - } - else // Frequency out of range. - SERIAL_ECHOLNPGM("?Invalid ", C(STEPPER_A_NAME), " [", C('A'), "] frequency value."); - } - else // Mode doesn't use frequency. - SERIAL_ECHOLNPGM("?Wrong mode for ", C(STEPPER_A_NAME), " [", C('A'), "] frequency."); - } + if (apply_xy || parser.seen_test('X')) { - #if HAS_DYNAMIC_FREQ - // Parse X frequency scaling parameter - if (parser.seenval('F')) { - if (modeUsesDynFreq) { - ftMotion.cfg.dynFreqK.x = parser.value_float(); + // Parse X frequency parameter + if (seenA) { + if (AXIS_IS_SHAPING(X)) { + // TODO: Frequency minimum is dependent on the shaper used; the above check isn't always correct. + if (goodBaseFreq) { + ftMotion.cfg.baseFreq.x = baseFreqVal; + flag.update = flag.report = true; + } + } + else // Mode doesn't use frequency. + SERIAL_ECHOLNPGM("?Wrong mode for ", C(STEPPER_A_NAME), " [A] frequency."); + } + + #if HAS_DYNAMIC_FREQ + // Parse X frequency scaling parameter + if (seenF && modeUsesDynFreq) { + ftMotion.cfg.dynFreqK.x = baseDynFreqVal; flag.report = true; } - else - SERIAL_ECHOLNPGM("?Wrong mode for ", C(STEPPER_A_NAME), " [", C('F'), "] frequency scaling."); - } - #endif + #endif - // Parse X zeta parameter - if (parser.seenval('I')) { - const float val = parser.value_float(); - if (AXIS_IS_SHAPING(X)) { - if (WITHIN(val, 0.01f, 1.0f)) { - ftMotion.cfg.zeta.x = val; - flag.update = true; + // Parse X zeta parameter + if (seenI) { + if (AXIS_IS_SHAPING(X)) { + if (goodZeta) { + ftMotion.cfg.zeta.x = zetaVal; + flag.update = true; + } } else - SERIAL_ECHOLNPGM("?Invalid ", C(STEPPER_A_NAME), " zeta [", C('I'), "] value."); // Zeta out of range + SERIAL_ECHOLNPGM("?Wrong mode for ", C(STEPPER_A_NAME), " zeta parameter."); } - else - SERIAL_ECHOLNPGM("?Wrong mode for ", C(STEPPER_A_NAME), " zeta parameter."); - } - // Parse X vtol parameter - if (parser.seenval('Q')) { - const float val = parser.value_float(); - if (AXIS_IS_EISHAPING(X)) { - if (WITHIN(val, 0.00f, 1.0f)) { - ftMotion.cfg.vtol.x = val; - flag.update = true; + // Parse X vtol parameter + if (seenQ) { + if (AXIS_IS_EISHAPING(X)) { + if (goodVtol) { + ftMotion.cfg.vtol.x = vtolVal; + flag.update = true; + } } else - SERIAL_ECHOLNPGM("?Invalid ", C(STEPPER_A_NAME), " vtol [", C('Q'), "] value."); // VTol out of range. + SERIAL_ECHOLNPGM("?Wrong mode for ", C(STEPPER_A_NAME), " vtol parameter."); } - else - SERIAL_ECHOLNPGM("?Wrong mode for ", C(STEPPER_A_NAME), " vtol parameter."); } #endif // HAS_X_AXIS #if HAS_Y_AXIS - // Parse Y frequency parameter - if (parser.seenval('B')) { - if (AXIS_IS_SHAPING(Y)) { - const float val = parser.value_float(); - if (WITHIN(val, FTM_MIN_SHAPE_FREQ, (FTM_FS) / 2)) { - ftMotion.cfg.baseFreq.y = val; - flag.update = flag.report = true; - } - else // Frequency out of range. - SERIAL_ECHOLNPGM("?Invalid ", C(STEPPER_B_NAME), " frequency [", C('B'), "] value."); - } - else // Mode doesn't use frequency. - SERIAL_ECHOLNPGM("?Wrong mode for ", C(STEPPER_B_NAME), " [", C('B'), "] frequency."); - } + if (apply_xy || parser.seen_test('Y')) { - #if HAS_DYNAMIC_FREQ - // Parse Y frequency scaling parameter - if (parser.seenval('H')) { - if (modeUsesDynFreq) { - ftMotion.cfg.dynFreqK.y = parser.value_float(); + // Parse Y frequency parameter + if (seenA) { + if (AXIS_IS_SHAPING(Y)) { + if (goodBaseFreq) { + ftMotion.cfg.baseFreq.y = baseFreqVal; + flag.update = flag.report = true; + } + } + else // Mode doesn't use frequency. + SERIAL_ECHOLNPGM("?Wrong mode for ", C(STEPPER_B_NAME), " [A] frequency."); + } + + #if HAS_DYNAMIC_FREQ + // Parse Y frequency scaling parameter + if (seenF && modeUsesDynFreq) { + ftMotion.cfg.dynFreqK.y = baseDynFreqVal; flag.report = true; } - else - SERIAL_ECHOLNPGM("?Wrong mode for ", C(STEPPER_B_NAME), " [", C('H'), "] frequency scaling."); - } - #endif + #endif - // Parse Y zeta parameter - if (parser.seenval('J')) { - const float val = parser.value_float(); - if (AXIS_IS_SHAPING(Y)) { - if (WITHIN(val, 0.01f, 1.0f)) { - ftMotion.cfg.zeta.y = val; - flag.update = true; + // Parse Y zeta parameter + if (seenI) { + if (AXIS_IS_SHAPING(Y)) { + if (goodZeta) { + ftMotion.cfg.zeta.y = zetaVal; + flag.update = true; + } } else - SERIAL_ECHOLNPGM("?Invalid ", C(STEPPER_B_NAME), " zeta [", C('J'), "] value."); // Zeta out of range + SERIAL_ECHOLNPGM("?Wrong mode for ", C(STEPPER_B_NAME), " zeta parameter."); } - else - SERIAL_ECHOLNPGM("?Wrong mode for ", C(STEPPER_B_NAME), " zeta parameter."); - } - // Parse Y vtol parameter - if (parser.seenval('R')) { - const float val = parser.value_float(); - if (AXIS_IS_EISHAPING(Y)) { - if (WITHIN(val, 0.00f, 1.0f)) { - ftMotion.cfg.vtol.y = val; - flag.update = true; + // Parse Y vtol parameter + if (seenQ) { + if (AXIS_IS_EISHAPING(Y)) { + if (goodVtol) { + ftMotion.cfg.vtol.y = vtolVal; + flag.update = true; + } } else - SERIAL_ECHOLNPGM("?Invalid ", C(STEPPER_B_NAME), " vtol [", C('R'), "] value."); // VTol out of range. + SERIAL_ECHOLNPGM("?Wrong mode for ", C(STEPPER_B_NAME), " vtol parameter."); } - else - SERIAL_ECHOLNPGM("?Wrong mode for ", C(STEPPER_B_NAME), " vtol parameter."); } #endif // HAS_Y_AXIS #if ENABLED(FTM_SHAPER_Z) - // Parse Z frequency parameter - if (parser.seenval('C')) { - if (AXIS_IS_SHAPING(Z)) { - const float val = parser.value_float(); - if (WITHIN(val, FTM_MIN_SHAPE_FREQ, (FTM_FS) / 2)) { - ftMotion.cfg.baseFreq.z = val; - flag.update = flag.report = true; - } - else // Frequency out of range. - SERIAL_ECHOLNPGM("?Invalid ", C(STEPPER_C_NAME), " frequency [", C('C'), "] value."); - } - else // Mode doesn't use frequency. - SERIAL_ECHOLNPGM("?Wrong mode for ", C(STEPPER_C_NAME), " [", C('C'), "] frequency."); - } + if (parser.seen_test('Z')) { - #if HAS_DYNAMIC_FREQ - // Parse Z frequency scaling parameter - if (parser.seenval('L')) { - if (modeUsesDynFreq) { - ftMotion.cfg.dynFreqK.z = parser.value_float(); + // Parse Z frequency parameter + if (seenA) { + if (AXIS_IS_SHAPING(Z)) { + if (goodBaseFreq) { + ftMotion.cfg.baseFreq.z = baseFreqVal; + flag.update = flag.report = true; + } + } + else // Mode doesn't use frequency. + SERIAL_ECHOLNPGM("?Wrong mode for ", C(STEPPER_C_NAME), " [A] frequency."); + } + + #if HAS_DYNAMIC_FREQ + // Parse Z frequency scaling parameter + if (seenF && modeUsesDynFreq) { + ftMotion.cfg.dynFreqK.z = baseDynFreqVal; flag.report = true; } - else - SERIAL_ECHOLNPGM("?Wrong mode for ", C(STEPPER_C_NAME), " [", C('L'), "] frequency scaling."); - } - #endif + #endif - // Parse Z zeta parameter - if (parser.seenval('O')) { - const float val = parser.value_float(); - if (AXIS_IS_SHAPING(Z)) { - if (WITHIN(val, 0.01f, 1.0f)) { - ftMotion.cfg.zeta.z = val; - flag.update = true; + // Parse Z zeta parameter + if (seenI) { + if (AXIS_IS_SHAPING(Z)) { + if (goodZeta) { + ftMotion.cfg.zeta.z = zetaVal; + flag.update = true; + } } else - SERIAL_ECHOLNPGM("?Invalid ", C(STEPPER_C_NAME), " zeta [", C('O'), "] value."); // Zeta out of range + SERIAL_ECHOLNPGM("?Wrong mode for ", C(STEPPER_C_NAME), " zeta parameter."); } - else - SERIAL_ECHOLNPGM("?Wrong mode for ", C(STEPPER_C_NAME), " zeta parameter."); - } - // Parse Z vtol parameter - if (parser.seenval('T')) { - const float val = parser.value_float(); - if (AXIS_IS_EISHAPING(Z)) { - if (WITHIN(val, 0.00f, 1.0f)) { - ftMotion.cfg.vtol.z = val; - flag.update = true; + // Parse Z vtol parameter + if (seenQ) { + if (AXIS_IS_EISHAPING(Z)) { + if (goodVtol) { + ftMotion.cfg.vtol.z = vtolVal; + flag.update = true; + } } else - SERIAL_ECHOLNPGM("?Invalid ", C(STEPPER_C_NAME), " vtol [", C('T'), "] value."); // VTol out of range. + SERIAL_ECHOLNPGM("?Wrong mode for ", C(STEPPER_C_NAME), " vtol parameter."); } - else - SERIAL_ECHOLNPGM("?Wrong mode for ", C(STEPPER_C_NAME), " vtol parameter."); } #endif // FTM_SHAPER_Z #if ENABLED(FTM_SHAPER_E) - // Parse E frequency parameter - if (parser.seenval('W')) { - if (AXIS_IS_SHAPING(E)) { - const float val = parser.value_float(); - if (WITHIN(val, FTM_MIN_SHAPE_FREQ, (FTM_FS) / 2)) { - ftMotion.cfg.baseFreq.e = val; - flag.update = flag.report = true; - } - else // Frequency out of range. - SERIAL_ECHOLNPGM("?Invalid ", C('E'), " frequency [", C('W'), "] value."); - } - else // Mode doesn't use frequency. - SERIAL_ECHOLNPGM("?Wrong mode for ", C('E'), " [", C('W'), "] frequency."); - } + if (parser.seen_test('E')) { - #if HAS_DYNAMIC_FREQ - // Parse E frequency scaling parameter - if (parser.seenval('N')) { - if (modeUsesDynFreq) { - ftMotion.cfg.dynFreqK.e = parser.value_float(); + // Parse E frequency parameter + if (seenA) { + if (AXIS_IS_SHAPING(E)) { + if (goodBaseFreq) { + ftMotion.cfg.baseFreq.e = baseFreqVal; + flag.update = flag.report = true; + } + } + else // Mode doesn't use frequency. + SERIAL_ECHOLNPGM("?Wrong mode for ", C('E'), " [A] frequency."); + } + + #if HAS_DYNAMIC_FREQ + // Parse E frequency scaling parameter + if (seenF && modeUsesDynFreq) { + ftMotion.cfg.dynFreqK.e = baseDynFreqVal; flag.report = true; } - else - SERIAL_ECHOLNPGM("?Wrong mode for ", C('E'), " [", C('N'), "] frequency scaling."); - } - #endif + #endif - // Parse E zeta parameter - if (parser.seenval('U')) { - const float val = parser.value_float(); - if (AXIS_IS_SHAPING(E)) { - if (WITHIN(val, 0.01f, 1.0f)) { - ftMotion.cfg.zeta.e = val; - flag.update = true; + // Parse E zeta parameter + if (seenI) { + if (AXIS_IS_SHAPING(E)) { + if (goodZeta) { + ftMotion.cfg.zeta.e = zetaVal; + flag.update = true; + } } else - SERIAL_ECHOLNPGM("?Invalid ", C('E'), " zeta [", C('U'), "] value."); // Zeta out of range + SERIAL_ECHOLNPGM("?Wrong mode for ", C('E'), " zeta parameter."); } - else - SERIAL_ECHOLNPGM("?Wrong mode for ", C('E'), " zeta parameter."); - } - // Parse E vtol parameter - if (parser.seenval('V')) { - const float val = parser.value_float(); - if (AXIS_IS_EISHAPING(E)) { - if (WITHIN(val, 0.00f, 1.0f)) { - ftMotion.cfg.vtol.e = val; - flag.update = true; + // Parse E vtol parameter + if (seenQ) { + if (AXIS_IS_EISHAPING(E)) { + if (goodVtol) { + ftMotion.cfg.vtol.e = vtolVal; + flag.update = true; + } } else - SERIAL_ECHOLNPGM("?Invalid ", C('E'), " vtol [", C('V'), "] value."); // VTol out of range. + SERIAL_ECHOLNPGM("?Wrong mode for ", C('E'), " vtol parameter."); } - else - SERIAL_ECHOLNPGM("?Wrong mode for ", C('E'), " vtol parameter."); } #endif // FTM_SHAPER_E diff --git a/Marlin/src/module/ft_motion.h b/Marlin/src/module/ft_motion.h index dfe10282e1..4254680fbf 100644 --- a/Marlin/src/module/ft_motion.h +++ b/Marlin/src/module/ft_motion.h @@ -31,6 +31,8 @@ #include "ft_motion/poly5_trajectory_generator.h" #include "ft_motion/poly6_trajectory_generator.h" +#define FTM_VERSION 2 // Change version when hosts need to know + #if HAS_X_AXIS && (HAS_Z_AXIS || HAS_EXTRUDERS) #define HAS_DYNAMIC_FREQ 1 #if HAS_Z_AXIS From 5a0923ed2846affca10cb378cf8ff40042cfbba3 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 1 Nov 2025 16:05:20 -0500 Subject: [PATCH 15/99] =?UTF-8?q?=F0=9F=94=A7=20Unified=20Linear=20Advance?= =?UTF-8?q?=20K?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Part of #21827 --- Marlin/Configuration_adv.h | 15 +++++---- Marlin/src/gcode/feature/advance/M900.cpp | 4 +-- Marlin/src/gcode/feature/ft_motion/M493.cpp | 33 ------------------ Marlin/src/gcode/gcode.cpp | 2 +- Marlin/src/gcode/gcode.h | 4 +-- Marlin/src/inc/Changes.h | 4 +++ Marlin/src/inc/Conditionals-4-adv.h | 7 ++-- Marlin/src/inc/SanityCheck.h | 33 +++++++++--------- Marlin/src/lcd/e3v2/proui/dwin.cpp | 6 ++-- Marlin/src/lcd/e3v2/proui/dwin_defines.h | 4 +-- Marlin/src/lcd/menu/menu_motion.cpp | 12 ------- Marlin/src/module/ft_motion.cpp | 5 +-- Marlin/src/module/ft_motion.h | 10 ------ Marlin/src/module/planner.cpp | 37 ++++++++++----------- Marlin/src/module/planner.h | 17 +++++----- Marlin/src/module/settings.cpp | 10 +++--- ini/features.ini | 2 +- 17 files changed, 79 insertions(+), 126 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index f1feb94688..6184e5df93 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1154,9 +1154,6 @@ #define FTM_DEFAULT_DYNFREQ_MODE dynFreqMode_DISABLED // Default mode of dynamic frequency calculation. (DISABLED, Z_BASED, MASS_BASED) - #define FTM_LINEAR_ADV_DEFAULT_ENA false // Default linear advance enable (true) or disable (false) - #define FTM_LINEAR_ADV_DEFAULT_K 0.0f // Default linear advance gain. (Acceleration-based scaling factor.) - #define FTM_DEFAULT_SHAPER_X ftMotionShaper_NONE // Default shaper mode on X axis (NONE, ZV, ZVD, ZVDD, ZVDDD, EI, 2HEI, 3HEI, MZV) #define FTM_SHAPING_DEFAULT_FREQ_X 37.0f // (Hz) Default peak frequency used by input shapers #define FTM_SHAPING_ZETA_X 0.1f // Zeta used by input shapers for X axis @@ -2388,13 +2385,17 @@ * See https://marlinfw.org/docs/features/lin_advance.html for full instructions. */ //#define LIN_ADVANCE -#if ENABLED(LIN_ADVANCE) + +#if ANY(LIN_ADVANCE, FT_MOTION) #if ENABLED(DISTINCT_E_FACTORS) - #define ADVANCE_K { 0.22 } // (mm) Compression length per 1mm/s extruder speed, per extruder + #define ADVANCE_K { 0.22 } // (mm) Compression length per 1mm/s extruder speed, per extruder. Override with 'M900 T K'. #else - #define ADVANCE_K 0.22 // (mm) Compression length applying to all extruders + #define ADVANCE_K 0.22 // (mm) Compression length for all extruders. Override with 'M900 K'. #endif - //#define ADVANCE_K_EXTRA // Add a second linear advance constant, configurable with M900 L. + //#define ADVANCE_K_EXTRA // Add a second linear advance constant, configurable with 'M900 L'. +#endif + +#if ENABLED(LIN_ADVANCE) //#define LA_DEBUG // Print debug information to serial during operation. Disable for production use. //#define EXPERIMENTAL_I2S_LA // Allow I2S_STEPPER_STREAM to be used with LA. Performance degrades as the LA step rate reaches ~20kHz. diff --git a/Marlin/src/gcode/feature/advance/M900.cpp b/Marlin/src/gcode/feature/advance/M900.cpp index ac6a5246aa..7631cd0e8c 100644 --- a/Marlin/src/gcode/feature/advance/M900.cpp +++ b/Marlin/src/gcode/feature/advance/M900.cpp @@ -22,7 +22,7 @@ #include "../../../inc/MarlinConfig.h" -#if ENABLED(LIN_ADVANCE) +#if HAS_LIN_ADVANCE_K #include "../../gcode.h" #include "../../../module/planner.h" @@ -194,4 +194,4 @@ void GcodeSuite::M900_report(const bool forReplay/*=true*/) { } } -#endif // LIN_ADVANCE +#endif // HAS_LIN_ADVANCE_K diff --git a/Marlin/src/gcode/feature/ft_motion/M493.cpp b/Marlin/src/gcode/feature/ft_motion/M493.cpp index 796676bf57..6f021c1a0f 100644 --- a/Marlin/src/gcode/feature/ft_motion/M493.cpp +++ b/Marlin/src/gcode/feature/ft_motion/M493.cpp @@ -114,13 +114,6 @@ void say_shaping() { SERIAL_EOL(); #endif } - - #if HAS_EXTRUDERS - if (c.active) { - SERIAL_ECHO_TERNARY(c.linearAdvEna, "Linear Advance ", "en", "dis", "abled"); - SERIAL_ECHOLNPGM(". Gain: ", c.linearAdvK); - } - #endif } void GcodeSuite::M493_report(const bool forReplay/*=true*/) { @@ -134,9 +127,6 @@ void GcodeSuite::M493_report(const bool forReplay/*=true*/) { #if HAS_DYNAMIC_FREQ , " D", c.dynFreqMode #endif - #if HAS_EXTRUDERS - , " P", c.linearAdvEna, " K", c.linearAdvK - #endif // Axis Synchronization , " H", c.axis_sync_enabled ); @@ -172,7 +162,6 @@ void GcodeSuite::M493_report(const bool forReplay/*=true*/) { * Linear / Pressure Advance: * * P Enable (1) or Disable (0) Linear Advance pressure control - * K Set Linear Advance gain * * Specifying Axes (for A,C,F,I,Q): * @@ -251,28 +240,6 @@ void GcodeSuite::M493() { #endif // NUM_AXES_SHAPED > 0 - #if HAS_EXTRUDERS - - // Pressure control (linear advance) parameter. - if (parser.seen('P')) { - const bool val = parser.value_bool(); - ftMotion.cfg.linearAdvEna = val; - flag.report = true; - } - - // Pressure control (linear advance) gain parameter. - if (parser.seenval('K')) { - const float val = parser.value_float(); - if (WITHIN(val, 0.0f, 10.0f)) { - ftMotion.cfg.linearAdvK = val; - flag.report = true; - } - else // Value out of range. - SERIAL_ECHOLNPGM("Linear Advance gain out of range."); - } - - #endif // HAS_EXTRUDERS - // Parse 'H' Axis Synchronization parameter. if (parser.seenval('H')) { const bool enabled = parser.value_bool(); diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index b3dae56849..20b268256e 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -1038,7 +1038,7 @@ void GcodeSuite::process_parsed_command(bool no_ok/*=false*/) { case 871: M871(); break; // M871: Print/reset/clear first layer temperature offset values #endif - #if ENABLED(LIN_ADVANCE) + #if HAS_LIN_ADVANCE_K case 900: M900(); break; // M900: Set advance K factor. #endif diff --git a/Marlin/src/gcode/gcode.h b/Marlin/src/gcode/gcode.h index 87d626effc..effbd85449 100644 --- a/Marlin/src/gcode/gcode.h +++ b/Marlin/src/gcode/gcode.h @@ -309,7 +309,7 @@ * * M871 - Print/Reset/Clear first layer temperature offset values. (Requires PTC_PROBE, PTC_BED, or PTC_HOTEND) * M876 - Handle Prompt Response. (Requires HOST_PROMPT_SUPPORT and not EMERGENCY_PARSER) - * M900 - Set / Report Linear Advance K-factor. (Requires LIN_ADVANCE) + * M900 - Set / Report Linear Advance K-factor (Requires LIN_ADVANCE or FT_MOTION) and Smoothing Tau factor (Requires SMOOTH_LIN_ADVANCE). * M906 - Set / Report motor current in milliamps using axis codes XYZE, etc. Report values if no axis codes given. (Requires *_DRIVER_TYPE TMC(2130|2160|5130|5160|2208|2209|2240|2660)) * M907 - Set digital trimpot motor current using axis codes. (Requires a board with digital trimpots) * M908 - Control digital trimpot directly. (Requires HAS_MOTOR_CURRENT_DAC or DIGIPOTSS_PIN) @@ -1249,7 +1249,7 @@ private: static void M871(); #endif - #if ENABLED(LIN_ADVANCE) + #if HAS_LIN_ADVANCE_K static void M900(); static void M900_report(const bool forReplay=true); #endif diff --git a/Marlin/src/inc/Changes.h b/Marlin/src/inc/Changes.h index cbfdcfc47f..2d8fe87863 100644 --- a/Marlin/src/inc/Changes.h +++ b/Marlin/src/inc/Changes.h @@ -745,6 +745,10 @@ #error "FTM_SHAPING_DEFAULT_[XY]_FREQ is now FTM_SHAPING_DEFAULT_FREQ_[XY]." #elif defined(SDSS) #error "SDSS is now SD_SS_PIN." +#elif defined(FTM_LINEAR_ADV_DEFAULT_ENA) + #error "FTM_LINEAR_ADV_DEFAULT_ENA is obsolete and should be removed." +#elif defined(FTM_LINEAR_ADV_DEFAULT_K) + #error "FTM_LINEAR_ADV_DEFAULT_K is now set with ADVANCE_K and should be removed." #endif // SDSS renamed to SD_SS_PIN diff --git a/Marlin/src/inc/Conditionals-4-adv.h b/Marlin/src/inc/Conditionals-4-adv.h index d72f2e4582..8bec3c1dd3 100644 --- a/Marlin/src/inc/Conditionals-4-adv.h +++ b/Marlin/src/inc/Conditionals-4-adv.h @@ -346,11 +346,12 @@ #if ALL(FT_MOTION, HAS_EXTRUDERS) #define FTM_HAS_LIN_ADVANCE 1 #endif - -#if HAS_JUNCTION_DEVIATION && ANY(LIN_ADVANCE, FTM_HAS_LIN_ADVANCE) +#if ANY(FTM_HAS_LIN_ADVANCE, LIN_ADVANCE) + #define HAS_LIN_ADVANCE_K 1 +#endif +#if HAS_JUNCTION_DEVIATION && ENABLED(LIN_ADVANCE) #define HAS_LINEAR_E_JERK 1 #endif - #if ENABLED(LIN_ADVANCE) && DISABLED(SMOOTH_LIN_ADVANCE) #define HAS_ROUGH_LIN_ADVANCE 1 #endif diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index a8467ac606..aadb3aea9d 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -848,26 +848,15 @@ static_assert(COUNT(arm) == LOGICAL_AXES, "AXIS_RELATIVE_MODES must contain " _L #endif /** - * Linear Advance 1.5 - Check K value range + * Linear Advance requirements */ #if ENABLED(LIN_ADVANCE) - #if ENABLED(DISTINCT_E_FACTORS) - constexpr float lak[] = ADVANCE_K; - static_assert(COUNT(lak) <= DISTINCT_E, "The ADVANCE_K array has too many elements (i.e., more than " STRINGIFY(DISTINCT_E) ")."); - #define _LIN_ASSERT(N) static_assert(N >= COUNT(lak) || WITHIN(lak[N], 0, 10), "ADVANCE_K values must be from 0 to 10 (Changed in LIN_ADVANCE v1.5, Marlin 1.1.9)."); - REPEAT(DISTINCT_E, _LIN_ASSERT) - #undef _LIN_ASSERT - #else - static_assert(WITHIN(ADVANCE_K, 0, 10), "ADVANCE_K must be from 0 to 10 (Changed in LIN_ADVANCE v1.5, Marlin 1.1.9)."); - #endif - + // Incompatible with Direct Stepping #if ENABLED(DIRECT_STEPPING) #error "DIRECT_STEPPING is incompatible with LIN_ADVANCE. (Extrusion is controlled externally by the Step Daemon.)" #endif - /** - * Smooth Linear Advance - */ + // Smooth Linear Advance #if ENABLED(SMOOTH_LIN_ADVANCE) #ifndef CPU_32_BIT #error "SMOOTH_LIN_ADVANCE requires a 32-bit CPU." @@ -875,9 +864,23 @@ static_assert(COUNT(arm) == LOGICAL_AXES, "AXIS_RELATIVE_MODES must contain " _L #error "INPUT_SHAPING_E_SYNC requires INPUT_SHAPING_X or INPUT_SHAPING_Y." #endif #endif - #endif // LIN_ADVANCE +/** + * Linear Advance and FT Motion - Check K value range + */ +#if HAS_LIN_ADVANCE_K + #if ENABLED(DISTINCT_E_FACTORS) + constexpr float lak[] = ADVANCE_K; + static_assert(COUNT(lak) <= DISTINCT_E, "The ADVANCE_K array has too many elements (i.e., more than " STRINGIFY(DISTINCT_E) ")."); + #define _LIN_ASSERT(N) static_assert(N >= COUNT(lak) || WITHIN(lak[N], 0, 10), "ADVANCE_K values must be from 0 to 10."); + REPEAT(DISTINCT_E, _LIN_ASSERT) + #undef _LIN_ASSERT + #else + static_assert(WITHIN(ADVANCE_K, 0, 10), "ADVANCE_K must be from 0 to 10."); + #endif +#endif + /** * Nonlinear Extrusion requirements */ diff --git a/Marlin/src/lcd/e3v2/proui/dwin.cpp b/Marlin/src/lcd/e3v2/proui/dwin.cpp index a8d8e277db..8ff1fe6412 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin.cpp @@ -2686,7 +2686,7 @@ void applyMaxAccel() { planner.set_max_acceleration(hmiValue.axis, menuData.valu void setJDmm() { setPFloatOnClick(MIN_JD_MM, MAX_JD_MM, 3, applyJDmm); } #endif -#if ENABLED(LIN_ADVANCE) +#if HAS_LIN_ADVANCE_K #define LA_FDIGITS 3 void applyLA_K() { planner.set_advance_k(menuData.value / POW(10, LA_FDIGITS)); } void setLA_K() { setFloatOnClick(0, 10, LA_FDIGITS, planner.get_advance_k(), applyLA_K); } @@ -3677,7 +3677,7 @@ void drawTuneMenu() { void drawMotionMenu() { constexpr uint8_t items = (4 - + COUNT_ENABLED(EDITABLE_STEPS_PER_UNIT, EDITABLE_HOMING_FEEDRATE, LIN_ADVANCE, SHAPING_MENU, ADAPTIVE_STEP_SMOOTHING_TOGGLE) + + COUNT_ENABLED(EDITABLE_STEPS_PER_UNIT, EDITABLE_HOMING_FEEDRATE, HAS_LIN_ADVANCE_K, SMOOTH_LIN_ADVANCE, SHAPING_MENU, ADAPTIVE_STEP_SMOOTHING_TOGGLE) + 2 ); checkkey = ID_Menu; @@ -3696,7 +3696,7 @@ void drawMotionMenu() { #if ENABLED(EDITABLE_HOMING_FEEDRATE) MENU_ITEM(ICON_Homing, MSG_HOMING_FEEDRATE, onDrawSubMenu, drawHomingFRMenu); #endif - #if ENABLED(LIN_ADVANCE) + #if HAS_LIN_ADVANCE_K static float editable_k; editable_k = planner.get_advance_k(); EDIT_ITEM(ICON_MaxAccelerated, MSG_ADVANCE_K, onDrawLA_K, setLA_K, &editable_k); diff --git a/Marlin/src/lcd/e3v2/proui/dwin_defines.h b/Marlin/src/lcd/e3v2/proui/dwin_defines.h index 52ad604296..42645be0f4 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin_defines.h +++ b/Marlin/src/lcd/e3v2/proui/dwin_defines.h @@ -121,10 +121,10 @@ #if ENABLED(POWER_LOSS_RECOVERY) #define PROUI_ITEM_PLR // Tune > Power-loss Recovery #endif -#if ENABLED(HAS_JUNCTION_DEVIATION) +#if HAS_JUNCTION_DEVIATION #define PROUI_ITEM_JD // Tune > Junction Deviation #endif -#if ENABLED(LIN_ADVANCE) +#if HAS_LIN_ADVANCE_K #define PROUI_ITEM_ADVK 1 // Tune > Linear Advance #endif #if ANY(HAS_PID_HEATING, MPC_AUTOTUNE) && DISABLED(DISABLE_TUNING_GRAPH) diff --git a/Marlin/src/lcd/menu/menu_motion.cpp b/Marlin/src/lcd/menu/menu_motion.cpp index 305b77688c..0d23484f3f 100644 --- a/Marlin/src/lcd/menu/menu_motion.cpp +++ b/Marlin/src/lcd/menu/menu_motion.cpp @@ -499,12 +499,6 @@ void menu_move() { } #endif - #if HAS_EXTRUDERS - EDIT_ITEM(bool, MSG_LINEAR_ADVANCE, &c.linearAdvEna); - if (c.linearAdvEna || ENABLED(FT_MOTION_NO_MENU_TOGGLE)) - EDIT_ITEM(float42_52, MSG_ADVANCE_K, &c.linearAdvK, 0.0f, 10.0f); - #endif - EDIT_ITEM(bool, MSG_FTM_AXIS_SYNC, &c.axis_sync_enabled); #if ENABLED(FTM_SMOOTHING) @@ -578,12 +572,6 @@ void menu_move() { SUBMENU_S(_dmode(), MSG_FTM_DYN_MODE, menu_ftm_dyn_mode); #endif - #if HAS_EXTRUDERS - EDIT_ITEM(bool, MSG_LINEAR_ADVANCE, &c.linearAdvEna); - if (c.linearAdvEna || ENABLED(FT_MOTION_NO_MENU_TOGGLE)) - EDIT_ITEM(float42_52, MSG_ADVANCE_K, &c.linearAdvK, 0.0f, 10.0f); - #endif - #if ENABLED(FTM_SMOOTHING) CARTES_MAP(_SMOO_MENU_ITEM); #endif diff --git a/Marlin/src/module/ft_motion.cpp b/Marlin/src/module/ft_motion.cpp index cd0c162668..239badc23b 100644 --- a/Marlin/src/module/ft_motion.cpp +++ b/Marlin/src/module/ft_motion.cpp @@ -612,12 +612,13 @@ void FTMotion::generateTrajectoryPointsFromBlock() { LOGICAL_AXIS_MAP_LC(_SET_TRAJ); #if FTM_HAS_LIN_ADVANCE - if (cfg.linearAdvEna) { + const float advK = planner.get_advance_k(); + if (advK) { float traj_e = traj.e[traj_idx_set]; if (use_advance_lead) { // Don't apply LA to retract/unretract blocks float e_rate = (traj_e - prev_traj_e) * (FTM_FS); - traj.e[traj_idx_set] += e_rate * cfg.linearAdvK; + traj.e[traj_idx_set] += e_rate * advK; } prev_traj_e = traj_e; } diff --git a/Marlin/src/module/ft_motion.h b/Marlin/src/module/ft_motion.h index 4254680fbf..a24f3271cf 100644 --- a/Marlin/src/module/ft_motion.h +++ b/Marlin/src/module/ft_motion.h @@ -73,11 +73,6 @@ typedef struct FTConfig { #endif // HAS_FTM_SHAPING - #if HAS_EXTRUDERS - bool linearAdvEna = FTM_LINEAR_ADV_DEFAULT_ENA; // Linear advance enable configuration. - float linearAdvK = FTM_LINEAR_ADV_DEFAULT_K; // Linear advance gain. - #endif - TrajectoryType trajectory_type = TrajectoryType::FTM_TRAJECTORY_TYPE; // Trajectory generator type float poly6_acceleration_overshoot; // Overshoot factor for Poly6 (1.25 to 2.0) } ft_config_t; @@ -126,11 +121,6 @@ class FTMotion { #undef _SET_SMOOTH #endif - #if HAS_EXTRUDERS - cfg.linearAdvEna = FTM_LINEAR_ADV_DEFAULT_ENA; - cfg.linearAdvK = FTM_LINEAR_ADV_DEFAULT_K; - #endif - cfg.poly6_acceleration_overshoot = FTM_POLY6_ACCELERATION_OVERSHOOT; setTrajectoryType(TrajectoryType::FTM_TRAJECTORY_TYPE); diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index 404d1fc5a7..b4c53fab6b 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -234,7 +234,7 @@ float Planner::previous_nominal_speed; int32_t Planner::xy_freq_min_interval_us = LROUND(1000000.0f / (XY_FREQUENCY_LIMIT)); #endif -#if ENABLED(LIN_ADVANCE) +#if HAS_LIN_ADVANCE_K float Planner::extruder_advance_K[DISTINCT_E]; // Initialized by settings.load #if ENABLED(SMOOTH_LIN_ADVANCE) uint32_t Planner::extruder_advance_K_q27[DISTINCT_E]; @@ -881,11 +881,9 @@ void Planner::calculate_trapezoid_for_block(block_t * const block, const float e #if ENABLED(SMOOTH_LIN_ADVANCE) block->cruise_time = plateau_steps > 0 ? float(plateau_steps) * float(STEPPER_TIMER_RATE) / float(cruise_rate) : 0; - #endif - - #if HAS_ROUGH_LIN_ADVANCE + #elif HAS_ROUGH_LIN_ADVANCE if (block->la_advance_rate) { - const float comp = extruder_advance_K[E_INDEX_N(block->extruder)] * block->steps.e / block->step_event_count; + const float comp = get_advance_k(block->extruder) * block->steps.e / block->step_event_count; block->max_adv_steps = cruise_rate * comp; block->final_adv_steps = final_rate * comp; } @@ -2403,7 +2401,7 @@ bool Planner::_populate_block( // Start with print or travel acceleration accel = CEIL((esteps ? settings.acceleration : settings.travel_acceleration) * steps_per_mm); - #if ANY(LIN_ADVANCE, FTM_HAS_LIN_ADVANCE) + #if HAS_LIN_ADVANCE_K // Linear advance is currently not ready for HAS_I_AXIS #define MAX_E_JERK(N) TERN(HAS_LINEAR_E_JERK, max_e_jerk[E_INDEX_N(N)], max_jerk.e) @@ -2416,11 +2414,7 @@ bool Planner::_populate_block( * Check the appropriate K value for Standard or Fixed-Time Motion. */ if (esteps && dm.e) { - const bool ftm_active = TERN0(FTM_HAS_LIN_ADVANCE, ftMotion.cfg.active), - ftm_la_active = TERN0(FTM_HAS_LIN_ADVANCE, ftm_active && ftMotion.cfg.linearAdvEna); - const float advK = ftm_active - ? (ftm_la_active ? TERN0(FTM_HAS_LIN_ADVANCE, ftMotion.cfg.linearAdvK) : 0) - : TERN0(HAS_ROUGH_LIN_ADVANCE, extruder_advance_K[E_INDEX_N(extruder)]); + const float advK = get_advance_k(extruder); if (advK) { float e_D_ratio = (target_float.e - position_float.e) / TERN(IS_KINEMATIC, block->millimeters, @@ -2434,17 +2428,20 @@ bool Planner::_populate_block( // This assumes no one will use a retract length of 0mm < retr_length < ~0.2mm // and no one will print 100mm wide lines using 3mm filament or 35mm wide lines using 1.75mm filament. use_adv_lead = e_D_ratio <= 3.0f; - if (use_adv_lead && TERN0(HAS_ROUGH_LIN_ADVANCE, !ftm_active)) { - // For Standard Motion LA: Scale E acceleration so it'll be possible to jump to the advance speed - const uint32_t max_accel_steps_per_s2 = (MAX_E_JERK(extruder) / (advK * e_D_ratio)) * steps_per_mm; - if (accel > max_accel_steps_per_s2) { - accel = max_accel_steps_per_s2; - if (TERN0(LA_DEBUG, DEBUGGING(INFO))) SERIAL_ECHOLNPGM("Acceleration limited to max_accel_steps_per_s2 (", max_accel_steps_per_s2, ")"); + + #if HAS_ROUGH_LIN_ADVANCE + if (use_adv_lead && TERN1(FT_MOTION, !ftMotion.cfg.active)) { + // For Standard Motion LA: Scale E acceleration so it'll be possible to jump to the advance speed + const uint32_t max_accel_steps_per_s2 = (MAX_E_JERK(extruder) / (advK * e_D_ratio)) * steps_per_mm; + if (accel > max_accel_steps_per_s2) { + accel = max_accel_steps_per_s2; + if (TERN0(LA_DEBUG, DEBUGGING(INFO))) SERIAL_ECHOLNPGM("Acceleration limited to max_accel_steps_per_s2 (", max_accel_steps_per_s2, ")"); + } } - } + #endif } } - #endif // LIN_ADVANCE || FTM_HAS_LIN_ADVANCE + #endif // HAS_LIN_ADVANCE_K // Limit acceleration per axis if (block->step_event_count <= acceleration_long_cutoff) { @@ -2475,7 +2472,7 @@ bool Planner::_populate_block( block->la_scaling = 0; if (use_adv_lead) { // The Bresenham algorithm will convert this step rate into extruder steps - block->la_advance_rate = extruder_advance_K[E_INDEX_N(extruder)] * block->acceleration_steps_per_s2; + block->la_advance_rate = get_advance_k(extruder) * block->acceleration_steps_per_s2; // Reduce LA ISR frequency by calling it only often enough to ensure that there will // never be more than four extruder steps per call diff --git a/Marlin/src/module/planner.h b/Marlin/src/module/planner.h index 21b6fd660b..c001dadd66 100644 --- a/Marlin/src/module/planner.h +++ b/Marlin/src/module/planner.h @@ -530,7 +530,7 @@ class Planner { static constexpr bool leveling_active = false; #endif - #if ENABLED(LIN_ADVANCE) + #if HAS_LIN_ADVANCE_K static float extruder_advance_K[DISTINCT_E]; static void set_advance_k(const float k, const uint8_t e=active_extruder) { UNUSED(e); @@ -541,13 +541,14 @@ class Planner { UNUSED(e); return extruder_advance_K[E_INDEX_N(e)]; } - #if ENABLED(SMOOTH_LIN_ADVANCE) - static uint32_t get_advance_k_q27(const uint8_t e=active_extruder) { - UNUSED(e); - return extruder_advance_K_q27[E_INDEX_N(e)]; - } - #endif - #endif // LIN_ADVANCE + #endif + + #if ENABLED(SMOOTH_LIN_ADVANCE) + static uint32_t get_advance_k_q27(const uint8_t e=active_extruder) { + UNUSED(e); + return extruder_advance_K_q27[E_INDEX_N(e)]; + } + #endif /** * The current position of the tool in absolute steps diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index 63f69d13c2..3414d322da 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -498,7 +498,7 @@ typedef struct SettingsDataStruct { // // LIN_ADVANCE // - #if ENABLED(LIN_ADVANCE) + #if HAS_LIN_ADVANCE_K float planner_extruder_advance_K[DISTINCT_E]; // M900 K planner.extruder_advance_K #if ENABLED(SMOOTH_LIN_ADVANCE) float stepper_extruder_advance_tau[DISTINCT_E]; // M900 U stepper.extruder_advance_tau @@ -1564,7 +1564,7 @@ void MarlinSettings::postprocess() { // Linear Advance // { - #if ENABLED(LIN_ADVANCE) + #if HAS_LIN_ADVANCE_K _FIELD_TEST(planner_extruder_advance_K); EEPROM_WRITE(planner.extruder_advance_K); #if ENABLED(SMOOTH_LIN_ADVANCE) @@ -2649,7 +2649,7 @@ void MarlinSettings::postprocess() { // // Linear Advance // - #if ENABLED(LIN_ADVANCE) + #if HAS_LIN_ADVANCE_K { float extruder_advance_K[DISTINCT_E]; _FIELD_TEST(planner_extruder_advance_K); @@ -2665,7 +2665,7 @@ void MarlinSettings::postprocess() { DISTINCT_E_LOOP() stepper.set_advance_tau(tau[e], e); #endif } - #endif + #endif // HAS_LIN_ADVANCE_K // // Motor Current PWM @@ -4098,7 +4098,7 @@ void MarlinSettings::reset() { // // Linear Advance // - TERN_(LIN_ADVANCE, gcode.M900_report(forReplay)); + TERN_(HAS_LIN_ADVANCE_K, gcode.M900_report(forReplay)); // // Motor Current (SPI or PWM) diff --git a/ini/features.ini b/ini/features.ini index bd45dd02c1..d1b02bb4d4 100644 --- a/ini/features.ini +++ b/ini/features.ini @@ -312,7 +312,7 @@ SPI_FLASH_BACKUP = build_src_filter=+ HAS_TOOLCHANGE = build_src_filter=+ FT_MOTION = build_src_filter=+ + + -LIN_ADVANCE = build_src_filter=+ +HAS_LIN_ADVANCE_K = build_src_filter=+ PHOTO_GCODE = build_src_filter=+ CONTROLLER_FAN_EDITABLE = build_src_filter=+ HAS_ZV_SHAPING = build_src_filter=+ From 1ead60ec460028f652c5c405a843004ff8a70948 Mon Sep 17 00:00:00 2001 From: David Buezas Date: Sun, 2 Nov 2025 05:50:48 +0100 Subject: [PATCH 16/99] =?UTF-8?q?=E2=9A=A1=EF=B8=8F=20FT=20Motion=20trajec?= =?UTF-8?q?tories,=20smoothing,=20optimization=20(#28115)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine Co-authored-by: narno2202 <130909513+narno2202@users.noreply.github.com> --- Marlin/Configuration_adv.h | 30 +- Marlin/src/core/types.h | 54 ++ Marlin/src/inc/Conditionals-4-adv.h | 4 - Marlin/src/inc/Conditionals-5-post.h | 4 + Marlin/src/inc/SanityCheck.h | 3 +- Marlin/src/module/ft_motion.cpp | 776 ++++++------------ Marlin/src/module/ft_motion.h | 128 ++- Marlin/src/module/ft_motion/shaping.cpp | 170 ++++ .../{ft_types.h => ft_motion/shaping.h} | 52 +- Marlin/src/module/ft_motion/smoothing.cpp | 41 + Marlin/src/module/ft_motion/smoothing.h | 47 ++ Marlin/src/module/ft_motion/stepping.cpp | 112 +++ Marlin/src/module/ft_motion/stepping.h | 53 ++ .../module/ft_motion/trajectory_generator.h | 2 - Marlin/src/module/stepper.cpp | 57 +- Marlin/src/module/stepper.h | 2 +- ini/features.ini | 3 +- 17 files changed, 859 insertions(+), 679 deletions(-) create mode 100644 Marlin/src/module/ft_motion/shaping.cpp rename Marlin/src/module/{ft_types.h => ft_motion/shaping.h} (67%) create mode 100644 Marlin/src/module/ft_motion/smoothing.cpp create mode 100644 Marlin/src/module/ft_motion/smoothing.h create mode 100644 Marlin/src/module/ft_motion/stepping.cpp create mode 100644 Marlin/src/module/ft_motion/stepping.h diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 6184e5df93..830db40333 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1191,7 +1191,7 @@ #define FTM_TRAJECTORY_TYPE TRAPEZOIDAL // Block acceleration profile (TRAPEZOIDAL, POLY5, POLY6) // TRAPEZOIDAL: Continuous Velocity. Max acceleration is respected. - // POLY5: Like POLY6 with 1.5x but cpu cheaper. + // POLY5: Like POLY6 with 1.5x but uses less CPU. // POLY6: Continuous Acceleration (aka S_CURVE). // POLY trajectories not only reduce resonances without rounding corners, but also // reduce extruder strain due to linear advance. @@ -1201,30 +1201,12 @@ /** * Advanced configuration */ - #define FTM_UNIFIED_BWS // DON'T DISABLE unless you use Ulendo FBS (not implemented) - #if ENABLED(FTM_UNIFIED_BWS) - #define FTM_BW_SIZE 100 // Unified Window and Batch size with a ratio of 2 - #else - #define FTM_WINDOW_SIZE 200 // Custom Window size for trajectory generation needed by Ulendo FBS - #define FTM_BATCH_SIZE 100 // Custom Batch size for trajectory generation needed by Ulendo FBS - #endif + #define FTM_BUFFER_SIZE 128 // Window size for trajectory generation, must be a power of 2 (e.g 64, 128, 256, ...) + // The total buffered time in seconds is (FTM_BUFFER_SIZE/FTM_FS) + #define FTM_FS 1000 // (Hz) Frequency for trajectory generation. + #define FTM_STEPPER_FS 2'000'000 // (Hz) Time resolution of stepper I/O update. Shouldn't affect CPU much (slower board testing needed) + #define FTM_MIN_SHAPE_FREQ 20 // (Hz) Minimum shaping frequency, lower consumes more RAM - #define FTM_FS 1000 // (Hz) Frequency for trajectory generation - - #if DISABLED(COREXY) - #define FTM_STEPPER_FS 20000 // (Hz) Frequency for stepper I/O update - - // Use this to adjust the time required to consume the command buffer. - // Try increasing this value if stepper motion is choppy. - #define FTM_STEPPERCMD_BUFF_SIZE 3000 // Size of the stepper command buffers - - #else - // CoreXY motion needs a larger buffer size. These values are based on our testing. - #define FTM_STEPPER_FS 30000 - #define FTM_STEPPERCMD_BUFF_SIZE 6000 - #endif - - #define FTM_MIN_SHAPE_FREQ 10 // (Hz) Minimum shaping frequency, lower consumes more RAM #endif // FT_MOTION /** diff --git a/Marlin/src/core/types.h b/Marlin/src/core/types.h index ab3820273a..23d83c4b9e 100644 --- a/Marlin/src/core/types.h +++ b/Marlin/src/core/types.h @@ -238,6 +238,24 @@ struct Flags { FI bool operator[](const int n) const { return test(n); } FI int size() const { return sizeof(b); } FI operator bool() const { return b != 0; } + + FI Flags& operator|=(Flags &p) const { b |= p.b; return *this; } + FI Flags& operator&=(Flags &p) const { b &= p.b; return *this; } + FI Flags& operator^=(Flags &p) const { b ^= p.b; return *this; } + + FI Flags& operator|=(const flagbits_t &p) { b |= flagbits_t(p); return *this; } + FI Flags& operator&=(const flagbits_t &p) { b &= flagbits_t(p); return *this; } + FI Flags& operator^=(const flagbits_t &p) { b ^= flagbits_t(p); return *this; } + + FI Flags operator|(Flags &p) const { return Flags(b | p.b); } + FI Flags operator&(Flags &p) const { return Flags(b & p.b); } + FI Flags operator^(Flags &p) const { return Flags(b ^ p.b); } + FI Flags operator~() const { return Flags(~b); } + + FI flagbits_t operator|(const flagbits_t &p) const { return b | flagbits_t(p); } + FI flagbits_t operator&(const flagbits_t &p) const { return b & flagbits_t(p); } + FI flagbits_t operator^(const flagbits_t &p) const { return b ^ flagbits_t(p); } + }; // Flag bits for more than 64 states @@ -635,6 +653,21 @@ struct XYval { FI bool operator==(const T &p) const { return x == p && y == p; } FI bool operator!=(const T &p) const { return !operator==(p); } + FI bool operator< (const XYval &rs) const { return x < rs.x && y < rs.y; } + FI bool operator<=(const XYval &rs) const { return x <= rs.x && y <= rs.y; } + FI bool operator> (const XYval &rs) const { return x > rs.x && y > rs.y; } + FI bool operator>=(const XYval &rs) const { return x >= rs.x && y >= rs.y; } + + FI bool operator< (const XYZval &rs) const { return true XY_GANG(&& x < rs.x, && y < rs.y); } + FI bool operator<=(const XYZval &rs) const { return true XY_GANG(&& x <= rs.x, && y <= rs.y); } + FI bool operator> (const XYZval &rs) const { return true XY_GANG(&& x > rs.x, && y > rs.y); } + FI bool operator>=(const XYZval &rs) const { return true XY_GANG(&& x >= rs.x, && y >= rs.y); } + + FI bool operator< (const XYZEval &rs) const { return true XY_GANG(&& x < rs.x, && y < rs.y); } + FI bool operator<=(const XYZEval &rs) const { return true XY_GANG(&& x <= rs.x, && y <= rs.y); } + FI bool operator> (const XYZEval &rs) const { return true XY_GANG(&& x > rs.x, && y > rs.y); } + FI bool operator>=(const XYZEval &rs) const { return true XY_GANG(&& x >= rs.x, && y >= rs.y); } + }; // @@ -794,6 +827,16 @@ struct XYZval { FI bool operator==(const T &p) const { return ENABLED(HAS_X_AXIS) NUM_AXIS_GANG(&& x == p, && y == p, && z == p, && i == p, && j == p, && k == p, && u == p, && v == p, && w == p); } FI bool operator!=(const T &p) const { return !operator==(p); } + FI bool operator< (const XYZval &rs) const { return true NUM_AXIS_GANG(&& x < rs.x, && y < rs.y, && z < rs.z, && i < rs.i, && j < rs.j, && k < rs.k, && u < rs.u, && v < rs.v, && w < rs.w); } + FI bool operator<=(const XYZval &rs) const { return true NUM_AXIS_GANG(&& x <= rs.x, && y <= rs.y, && z <= rs.z, && i <= rs.i, && j <= rs.j, && k <= rs.k, && u <= rs.u, && v <= rs.v, && w <= rs.w); } + FI bool operator> (const XYZval &rs) const { return true NUM_AXIS_GANG(&& x > rs.x, && y > rs.y, && z > rs.z, && i > rs.i, && j > rs.j, && k > rs.k, && u > rs.u, && v > rs.v, && w > rs.w); } + FI bool operator>=(const XYZval &rs) const { return true NUM_AXIS_GANG(&& x >= rs.x, && y >= rs.y, && z >= rs.z, && i >= rs.i, && j >= rs.j, && k >= rs.k, && u >= rs.u, && v >= rs.v, && w >= rs.w); } + + FI bool operator< (const XYZEval &rs) const { return true NUM_AXIS_GANG(&& x < rs.x, && y < rs.y, && z < rs.z, && i < rs.i, && j < rs.j, && k < rs.k, && u < rs.u, && v < rs.v, && w < rs.w); } + FI bool operator<=(const XYZEval &rs) const { return true NUM_AXIS_GANG(&& x <= rs.x, && y <= rs.y, && z <= rs.z, && i <= rs.i, && j <= rs.j, && k <= rs.k, && u <= rs.u, && v <= rs.v, && w <= rs.w); } + FI bool operator> (const XYZEval &rs) const { return true NUM_AXIS_GANG(&& x > rs.x, && y > rs.y, && z > rs.z, && i > rs.i, && j > rs.j, && k > rs.k, && u > rs.u, && v > rs.v, && w > rs.w); } + FI bool operator>=(const XYZEval &rs) const { return true NUM_AXIS_GANG(&& x >= rs.x, && y >= rs.y, && z >= rs.z, && i >= rs.i, && j >= rs.j, && k >= rs.k, && u >= rs.u, && v >= rs.v, && w >= rs.w); } + }; // @@ -957,6 +1000,16 @@ struct XYZEval { FI bool operator==(const T &p) const { return ENABLED(HAS_X_AXIS) LOGICAL_AXIS_GANG(&& e == p, && x == p, && y == p, && z == p, && i == p, && j == p, && k == p, && u == p, && v == p, && w == p); } FI bool operator!=(const T &p) const { return !operator==(p); } + FI bool operator< (const XYZEval &rs) const { return true LOGICAL_AXIS_GANG(&& e < rs.e, && x < rs.x, && y < rs.y, && z < rs.z, && i < rs.i, && j < rs.j, && k < rs.k, && u < rs.u, && v < rs.v, && w < rs.w); } + FI bool operator<=(const XYZEval &rs) const { return true LOGICAL_AXIS_GANG(&& e <= rs.e, && x <= rs.x, && y <= rs.y, && z <= rs.z, && i <= rs.i, && j <= rs.j, && k <= rs.k, && u <= rs.u, && v <= rs.v, && w <= rs.w); } + FI bool operator> (const XYZEval &rs) const { return true LOGICAL_AXIS_GANG(&& e > rs.e, && x > rs.x, && y > rs.y, && z > rs.z, && i > rs.i, && j > rs.j, && k > rs.k, && u > rs.u, && v > rs.v, && w > rs.w); } + FI bool operator>=(const XYZEval &rs) const { return true LOGICAL_AXIS_GANG(&& e >= rs.e, && x >= rs.x, && y >= rs.y, && z >= rs.z, && i >= rs.i, && j >= rs.j, && k >= rs.k, && u >= rs.u, && v >= rs.v, && w >= rs.w); } + + FI bool operator< (const XYZval &rs) const { return true NUM_AXIS_GANG(&& x < rs.x, && y < rs.y, && z < rs.z, && i < rs.i, && j < rs.j, && k < rs.k, && u < rs.u, && v < rs.v, && w < rs.w); } + FI bool operator<=(const XYZval &rs) const { return true NUM_AXIS_GANG(&& x <= rs.x, && y <= rs.y, && z <= rs.z, && i <= rs.i, && j <= rs.j, && k <= rs.k, && u <= rs.u, && v <= rs.v, && w <= rs.w); } + FI bool operator> (const XYZval &rs) const { return true NUM_AXIS_GANG(&& x > rs.x, && y > rs.y, && z > rs.z, && i > rs.i, && j > rs.j, && k > rs.k, && u > rs.u, && v > rs.v, && w > rs.w); } + FI bool operator>=(const XYZval &rs) const { return true NUM_AXIS_GANG(&& x >= rs.x, && y >= rs.y, && z >= rs.z, && i >= rs.i, && j >= rs.j, && k >= rs.k, && u >= rs.u, && v >= rs.v, && w >= rs.w); } + }; #include // for memset @@ -1263,6 +1316,7 @@ public: FI AxisBits operator|(const AxisBits &p) const { return AxisBits(bits | p.bits); } FI AxisBits operator&(const AxisBits &p) const { return AxisBits(bits & p.bits); } FI AxisBits operator^(const AxisBits &p) const { return AxisBits(bits ^ p.bits); } + FI AxisBits operator~() const { return AxisBits(~bits); } FI operator bool() const { return !!bits; } FI operator uint16_t() const { return uint16_t(bits & 0xFFFF); } diff --git a/Marlin/src/inc/Conditionals-4-adv.h b/Marlin/src/inc/Conditionals-4-adv.h index 8bec3c1dd3..df2327254d 100644 --- a/Marlin/src/inc/Conditionals-4-adv.h +++ b/Marlin/src/inc/Conditionals-4-adv.h @@ -1537,10 +1537,6 @@ #if !HAS_EXTRUDERS #undef FTM_SHAPER_E #endif - #if ENABLED(FTM_UNIFIED_BWS) - #define FTM_WINDOW_SIZE FTM_BW_SIZE - #define FTM_BATCH_SIZE FTM_BW_SIZE - #endif #endif // Multi-Stepping Limit diff --git a/Marlin/src/inc/Conditionals-5-post.h b/Marlin/src/inc/Conditionals-5-post.h index 6e5fa8de6c..4bed697726 100644 --- a/Marlin/src/inc/Conditionals-5-post.h +++ b/Marlin/src/inc/Conditionals-5-post.h @@ -3680,4 +3680,8 @@ // 2HEI : FTM_RATIO * 3 / 2 // 3HEI : FTM_RATIO * 2 #define FTM_SMOOTHING_ORDER 5 // 3 to 5 is closest to gaussian + #ifndef FTM_BUFFER_SIZE + #define FTM_BUFFER_SIZE 128 + #endif + #define FTM_BUFFER_MASK (FTM_BUFFER_SIZE - 1u) #endif diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index aadb3aea9d..cd77bd24ba 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -4491,10 +4491,9 @@ static_assert(_PLUS_TEST(3), "DEFAULT_MAX_ACCELERATION values must be positive." * Fixed-Time Motion limitations */ #if ENABLED(FT_MOTION) + static_assert(FTM_BUFFER_SIZE >= 4 && (FTM_BUFFER_SIZE & FTM_BUFFER_MASK) == 0, "FTM_BUFFER_SIZE must be a power of two (128, 256, 512, ...)."); #if ENABLED(MIXING_EXTRUDER) #error "FT_MOTION does not currently support MIXING_EXTRUDER." - #elif DISABLED(FTM_UNIFIED_BWS) - #error "FT_MOTION requires FTM_UNIFIED_BWS to be enabled because FBS is not yet implemented." #endif #if !HAS_X_AXIS static_assert(FTM_DEFAULT_SHAPER_X != ftMotionShaper_NONE, "Without any linear axes FTM_DEFAULT_SHAPER_X must be ftMotionShaper_NONE."); diff --git a/Marlin/src/module/ft_motion.cpp b/Marlin/src/module/ft_motion.cpp index 239badc23b..69b2116bba 100644 --- a/Marlin/src/module/ft_motion.cpp +++ b/Marlin/src/module/ft_motion.cpp @@ -52,30 +52,12 @@ FTMotion ftMotion; ft_config_t FTMotion::cfg; bool FTMotion::busy; // = false -ft_command_t FTMotion::stepperCmdBuff[FTM_STEPPERCMD_BUFF_SIZE] = {0U}; // Stepper commands buffer. -int32_t FTMotion::stepperCmdBuff_produceIdx = 0, // Index of next stepper command write to the buffer. - FTMotion::stepperCmdBuff_consumeIdx = 0; // Index of next stepper command read from the buffer. - -bool FTMotion::stepperCmdBuffHasData = false; // The stepper buffer has items and is in use. XYZEval FTMotion::axis_move_end_ti = { 0 }; AxisBits FTMotion::axis_move_dir; // Private variables. -// NOTE: These are sized for Ulendo FBS use. -xyze_trajectory_t FTMotion::traj; // = {0.0f} Storage for fixed-time-based trajectory. -xyze_trajectoryMod_t FTMotion::trajMod; // = {0.0f} Storage for fixed time trajectory window. - -bool FTMotion::blockProcRdy = false; // Set when new block data is loaded from stepper module into FTM, - // and reset when block is completely converted to FTM trajectory. -bool FTMotion::batchRdy = false; // Indicates a batch of the fixed time trajectory has been - // generated, is now available in the upper-batch of traj.A[], and - // is ready to be post-processed (if applicable) and interpolated. - // Reset once the data has been shifted out. -bool FTMotion::batchRdyForInterp = false; // Indicates the batch is done being post processed - // (if applicable) and is ready to be converted to step commands. - // Block data variables. xyze_pos_t FTMotion::startPos, // (mm) Start position of block FTMotion::endPos_prevBlock = { 0.0f }; // (mm) End position of previous block @@ -89,15 +71,12 @@ Poly6TrajectoryGenerator FTMotion::poly6Generator; TrajectoryGenerator* FTMotion::currentGenerator = &FTMotion::trapezoidalGenerator; TrajectoryType FTMotion::trajectoryType = TrajectoryType::FTM_TRAJECTORY_TYPE; -// Make vector variables. -uint32_t FTMotion::traj_idx_get = 0, // Index of fixed time trajectory generation of the overall block. - FTMotion::traj_idx_set = 0; // Index of fixed time trajectory generation within the batch. +// Compact plan buffer +stepper_plan_t FTMotion::stepper_plan_buff[FTM_BUFFER_SIZE]; +XYZEval FTMotion::curr_steps_q32_32 = {0}; -// Interpolation variables. -xyze_long_t FTMotion::steps = { 0 }; // Step count accumulator. -xyze_long_t FTMotion::step_error_q10 = { 0 }; // Fractional remainder in q10.21 format - -uint32_t FTMotion::interpIdx = 0; // Index of current data point being interpolated. +uint32_t FTMotion::stepper_plan_tail = 0, // The index to consume from + FTMotion::stepper_plan_head = 0; // The index to produce into #if ENABLED(DISTINCT_E_FACTORS) uint8_t FTMotion::block_extruder_axis; // Cached E Axis from last-fetched block @@ -108,7 +87,7 @@ uint32_t FTMotion::interpIdx = 0; // Index of current data point b // Shaping variables. #if HAS_FTM_SHAPING - FTMotion::shaping_t FTMotion::shaping = { + shaping_t FTMotion::shaping = { zi_idx: 0 #if HAS_X_AXIS , X:{ false, { 0.0f }, { 0.0f }, { 0 }, 0 } // ena, d_zi[], Ai[], Ni[], max_i @@ -126,7 +105,7 @@ uint32_t FTMotion::interpIdx = 0; // Index of current data point b #endif #if ENABLED(FTM_SMOOTHING) - FTMotion::smoothing_t FTMotion::smoothing = { + smoothing_t FTMotion::smoothing = { #if HAS_X_AXIS X:{ { 0.0f }, 0.0f, 0 }, // smoothing_pass[], alpha, delay_samples #endif @@ -147,7 +126,8 @@ uint32_t FTMotion::interpIdx = 0; // Index of current data point b float FTMotion::prev_traj_e = 0.0f; // (ms) Unit delay of raw extruder position. #endif -constexpr uint32_t BATCH_SIDX_IN_WINDOW = (FTM_WINDOW_SIZE) - (FTM_BATCH_SIZE); // Batch start index in window. +// Stepping variables. +stepping_t FTMotion::stepping; //----------------------------------------------------------------- // Function definitions. @@ -170,247 +150,18 @@ void FTMotion::loop() { if (stepper.abort_current_block) { discard_planner_block_protected(); reset(); + currentGenerator->planRunout(0.0f); // Reset generator state stepper.abort_current_block = false; // Abort finished. } - while (!blockProcRdy && (stepper.current_block = planner.get_current_block())) { - if (stepper.current_block->is_sync()) { // Sync block? - if (stepper.current_block->is_sync_pos()) // Position sync? Set the position. - stepper._set_position(stepper.current_block->position); - discard_planner_block_protected(); - continue; - } - loadBlockData(stepper.current_block); - - #if ENABLED(POWER_LOSS_RECOVERY) - recovery.info.sdpos = stepper.current_block->sdpos; - recovery.info.current_position = stepper.current_block->start_position; - #endif - - blockProcRdy = true; - - // Some kinematics track axis motion in HX, HY, HZ - #if ANY(CORE_IS_XY, CORE_IS_XZ, MARKFORGED_XY, MARKFORGED_YX) - stepper.last_direction_bits.hx = stepper.current_block->direction_bits.hx; - #endif - #if ANY(CORE_IS_XY, CORE_IS_YZ, MARKFORGED_XY, MARKFORGED_YX) - stepper.last_direction_bits.hy = stepper.current_block->direction_bits.hy; - #endif - #if ANY(CORE_IS_XZ, CORE_IS_YZ) - stepper.last_direction_bits.hz = stepper.current_block->direction_bits.hz; - #endif - } - - if (blockProcRdy) { - - if (!batchRdy) generateTrajectoryPointsFromBlock(); // may clear blockProcRdy - - // Check if the block has been completely converted: - if (!blockProcRdy) { - discard_planner_block_protected(); - if (!batchRdy && !planner.has_blocks_queued()) { - runoutBlock(); - generateTrajectoryPointsFromBlock(); // Additional call to guarantee batchRdy is set this loop. - } - } - } - - // FBS / post processing. - if (batchRdy && !batchRdyForInterp) { - - // Call Ulendo FBS here. - - #if ENABLED(FTM_UNIFIED_BWS) - trajMod = traj; // Move the window to traj - #else - // Copy the uncompensated vectors. - #define TCOPY(A) memcpy(trajMod.A, traj.A, sizeof(trajMod.A)); - LOGICAL_AXIS_MAP_LC(TCOPY); - - // Shift the time series back in the window - #define TSHIFT(A) memcpy(traj.A, &traj.A[FTM_BATCH_SIZE], BATCH_SIDX_IN_WINDOW * sizeof(traj.A[0])); - LOGICAL_AXIS_MAP_LC(TSHIFT); - #endif - - // ... data is ready in trajMod. - batchRdyForInterp = true; - - batchRdy = false; // Clear so generateTrajectoryPointsFromBlock() can resume generating points. - } - - // Interpolation (generation of step commands from fixed time trajectory). - while (batchRdyForInterp - && (stepperCmdBuffItems() < (FTM_STEPPERCMD_BUFF_SIZE) - (FTM_STEPS_PER_UNIT_TIME)) - ) { - generateStepsFromTrajectory(interpIdx); - if (++interpIdx == FTM_BATCH_SIZE) { - batchRdyForInterp = false; - interpIdx = 0; - } - } + fill_stepper_plan_buffer(); // Set busy status for use by planner.busy() - busy = (stepperCmdBuffHasData || blockProcRdy || batchRdy || batchRdyForInterp); - + busy = stepping.bresenham_iterations_pending > 0 || !stepper_plan_is_empty(); } #if HAS_FTM_SHAPING - // Refresh the gains used by shaping functions. - void FTMotion::AxisShaping::set_axis_shaping_A(const ftMotionShaper_t shaper, const float zeta, const float vtol) { - - const float K = exp(-zeta * M_PI / sqrt(1.f - sq(zeta))), - K2 = sq(K), - K3 = K2 * K, - K4 = K3 * K; - - switch (shaper) { - - case ftMotionShaper_ZV: - max_i = 1U; - Ai[0] = 1.0f / (1.0f + K); - Ai[1] = Ai[0] * K; - break; - - case ftMotionShaper_ZVD: - max_i = 2U; - Ai[0] = 1.0f / (1.0f + 2.0f * K + K2); - Ai[1] = Ai[0] * 2.0f * K; - Ai[2] = Ai[0] * K2; - break; - - case ftMotionShaper_ZVDD: - max_i = 3U; - Ai[0] = 1.0f / (1.0f + 3.0f * K + 3.0f * K2 + K3); - Ai[1] = Ai[0] * 3.0f * K; - Ai[2] = Ai[0] * 3.0f * K2; - Ai[3] = Ai[0] * K3; - break; - - case ftMotionShaper_ZVDDD: - max_i = 4U; - Ai[0] = 1.0f / (1.0f + 4.0f * K + 6.0f * K2 + 4.0f * K3 + K4); - Ai[1] = Ai[0] * 4.0f * K; - Ai[2] = Ai[0] * 6.0f * K2; - Ai[3] = Ai[0] * 4.0f * K3; - Ai[4] = Ai[0] * K4; - break; - - case ftMotionShaper_EI: { - max_i = 2U; - Ai[0] = 0.25f * (1.0f + vtol); - Ai[1] = 0.50f * (1.0f - vtol) * K; - Ai[2] = Ai[0] * K2; - - const float adj = 1.0f / (Ai[0] + Ai[1] + Ai[2]); - for (uint32_t i = 0; i < 3U; i++) Ai[i] *= adj; - } break; - - case ftMotionShaper_2HEI: { - max_i = 3U; - const float vtolx2 = sq(vtol); - const float X = POW(vtolx2 * (sqrt(1.0f - vtolx2) + 1.0f), 1.0f / 3.0f); - Ai[0] = (3.0f * sq(X) + 2.0f * X + 3.0f * vtolx2) / (16.0f * X); - Ai[1] = (0.5f - Ai[0]) * K; - Ai[2] = Ai[1] * K; - Ai[3] = Ai[0] * K3; - - const float adj = 1.0f / (Ai[0] + Ai[1] + Ai[2] + Ai[3]); - for (uint32_t i = 0; i < 4U; i++) Ai[i] *= adj; - } break; - - case ftMotionShaper_3HEI: { - max_i = 4U; - Ai[0] = 0.0625f * ( 1.0f + 3.0f * vtol + 2.0f * sqrt( 2.0f * ( vtol + 1.0f ) * vtol ) ); - Ai[1] = 0.25f * ( 1.0f - vtol ) * K; - Ai[2] = ( 0.5f * ( 1.0f + vtol ) - 2.0f * Ai[0] ) * K2; - Ai[3] = Ai[1] * K2; - Ai[4] = Ai[0] * K4; - - const float adj = 1.0f / (Ai[0] + Ai[1] + Ai[2] + Ai[3] + Ai[4]); - for (uint32_t i = 0; i < 5U; i++) Ai[i] *= adj; - } break; - - case ftMotionShaper_MZV: { - max_i = 2U; - const float Bx = 1.4142135623730950488016887242097f * K; - Ai[0] = 1.0f / (1.0f + Bx + K2); - Ai[1] = Ai[0] * Bx; - Ai[2] = Ai[0] * K2; - } - break; - - case ftMotionShaper_NONE: - max_i = 0; - Ai[0] = 1.0f; // No echoes so the whole impulse is applied in the first tap - break; - } - - } - - // Refresh the indices used by shaping functions. - // Ai[] must be precomputed (if zeta or vtol change, call set_axis_shaping_A first) - void FTMotion::AxisShaping::set_axis_shaping_N(const ftMotionShaper_t shaper, const float f, const float zeta) { - // Note that protections are omitted for DBZ and for index exceeding array length. - const float df = sqrt ( 1.f - sq(zeta) ); - switch (shaper) { - case ftMotionShaper_ZV: - Ni[1] = LROUND((0.5f / f / df) * (FTM_FS)); - break; - case ftMotionShaper_ZVD: - case ftMotionShaper_EI: - Ni[1] = LROUND((0.5f / f / df) * (FTM_FS)); - Ni[2] = Ni[1] + Ni[1]; - break; - case ftMotionShaper_ZVDD: - case ftMotionShaper_2HEI: - Ni[1] = LROUND((0.5f / f / df) * (FTM_FS)); - Ni[2] = Ni[1] + Ni[1]; - Ni[3] = Ni[2] + Ni[1]; - break; - case ftMotionShaper_ZVDDD: - case ftMotionShaper_3HEI: - Ni[1] = LROUND((0.5f / f / df) * (FTM_FS)); - Ni[2] = Ni[1] + Ni[1]; - Ni[3] = Ni[2] + Ni[1]; - Ni[4] = Ni[3] + Ni[1]; - break; - case ftMotionShaper_MZV: - Ni[1] = LROUND((0.375f / f / df) * (FTM_FS)); - Ni[2] = Ni[1] + Ni[1]; - break; - case ftMotionShaper_NONE: - // No echoes. - // max_i is set to 0 by set_axis_shaping_A, so delay centroid (Ni[0]) will also correctly be 0 - break; - } - - // Group delay in samples (i.e., Axis delay caused by shaping): sum(Ai * Ni[i]). - // Skipping i=0 since the uncompensated delay of the first impulse is always zero, so Ai[0] * Ni[0] == 0 - float centroid = 0.0f; - for (uint8_t i = 1; i <= max_i; ++i) centroid -= Ai[i] * Ni[i]; - - Ni[0] = LROUND(centroid); - - // The resulting echo index can be negative, this is ok because it will be offset - // by the max delay of all axes before it is used. - for (uint8_t i = 1; i <= max_i; ++i) Ni[i] += Ni[0]; - } - - #if ENABLED(FTM_SMOOTHING) - // Set smoothing time and recalculate alpha and delay. - void FTMotion::AxisSmoothing::set_smoothing_time(const float s_time) { - if (s_time > 0.001f) { - alpha = 1.0f - expf(-(FTM_TS) * (FTM_SMOOTHING_ORDER) / s_time ); - delay_samples = s_time * FTM_FS; - } - else { - alpha = 0.0f; - delay_samples = 0; - } - } - #endif - void FTMotion::update_shaping_params() { #define UPDATE_SHAPER(A) \ shaping.A.ena = ftMotion.cfg.shaper.A != ftMotionShaper_NONE; \ @@ -418,6 +169,7 @@ void FTMotion::loop() { shaping.A.set_axis_shaping_N(cfg.shaper.A, cfg.baseFreq.A, cfg.zeta.A); SHAPED_MAP(UPDATE_SHAPER); + shaping.refresh_largest_delay_samples(); } #endif // HAS_FTM_SHAPING @@ -427,6 +179,7 @@ void FTMotion::loop() { void FTMotion::update_smoothing_params() { #define _SMOOTH_PARAM(A) smoothing.A.set_smoothing_time(cfg.smoothingTime.A); CARTES_MAP(_SMOOTH_PARAM); + smoothing.refresh_largest_delay_samples(); } void FTMotion::set_smoothing_time(uint8_t axis, const float s_time) { @@ -443,21 +196,11 @@ void FTMotion::loop() { // Reset all trajectory processing variables. void FTMotion::reset() { const bool did_suspend = stepper.suspend(); - - stepperCmdBuff_produceIdx = stepperCmdBuff_consumeIdx = 0; - - traj.reset(); - - blockProcRdy = batchRdy = batchRdyForInterp = false; - endPos_prevBlock.reset(); tau = 0; - traj_idx_get = 0; - traj_idx_set = TERN(FTM_UNIFIED_BWS, 0, _MIN(BATCH_SIDX_IN_WINDOW, FTM_BATCH_SIZE)); - - steps.reset(); - step_error_q10.reset(); - interpIdx = 0; + stepper_plan_tail = stepper_plan_head = 0; + stepping.reset(); + curr_steps_q32_32.reset(); #if HAS_FTM_SHAPING #define _RESET_ZI(A) ZERO(shaping.A.d_zi); @@ -488,6 +231,23 @@ void FTMotion::discard_planner_block_protected() { } } +uint32_t FTMotion::calc_runout_samples() { + xyze_long_t delay = {0}; + #if ENABLED(FTM_SMOOTHING) + #define _ADD(A) delay.A += smoothing.A.delay_samples; + LOGICAL_AXIS_MAP(_ADD) + #undef _ADD + #endif + + #if HAS_FTM_SHAPING + // Ni[max_i] is the delay of the last pulse, but it is relative to Ni[0] (the negative delay centroid) + #define _ADD(A) if(shaping.A.ena) delay.A += shaping.A.Ni[shaping.A.max_i] - shaping.A.Ni[0]; + SHAPED_MAP(_ADD) + #undef _ADD + #endif + return delay.large(); +} + /** * Set up a pseudo block to allow motion to settle and buffers to empty. * Called when the planner has one block left. The buffers will be filled @@ -495,33 +255,10 @@ void FTMotion::discard_planner_block_protected() { * the last position of the previous block and all ratios to zero such that no * axes' positions are incremented. */ -void FTMotion::runoutBlock() { - +void FTMotion::plan_runout_block() { startPos = endPos_prevBlock; - - const int32_t n_to_fill_batch = (FTM_WINDOW_SIZE) - traj_idx_set; - - // This line or function is to be modified for FBS use; do not optimize out. - const int32_t n_to_settle_shaper = num_samples_shaper_settle(); - - const int32_t n_diff = n_to_settle_shaper - n_to_fill_batch, - n_to_fill_batch_after_settling = n_diff > 0 ? (FTM_BATCH_SIZE) - (n_diff % (FTM_BATCH_SIZE)) : -n_diff; - - ratio.reset(); - uint32_t max_intervals = PROP_BATCHES * (FTM_BATCH_SIZE) + n_to_settle_shaper + n_to_fill_batch_after_settling; - const float reminder_from_last_block = -tau; - const float total_duration = max_intervals * FTM_TS + reminder_from_last_block; - - // Plan a zero-motion trajectory for runout - currentGenerator->planRunout(total_duration); - - blockProcRdy = true; // since ratio is 0, the trajectory positions won't advance in any axis -} - -// Auxiliary function to get number of step commands in the buffer. -int32_t FTMotion::stepperCmdBuffItems() { - const int32_t udiff = stepperCmdBuff_produceIdx - stepperCmdBuff_consumeIdx; - return (udiff < 0) ? udiff + (FTM_STEPPERCMD_BUFF_SIZE) : udiff; + currentGenerator->planRunout(calc_runout_samples() * FTM_TS); + ratio.reset(); // setting ratio to zero means no motion on any axis } // Initializes storage variables before startup. @@ -541,259 +278,266 @@ void FTMotion::setTrajectoryType(const TrajectoryType type) { case TrajectoryType::POLY5: currentGenerator = &poly5Generator; break; case TrajectoryType::POLY6: currentGenerator = &poly6Generator; break; } - currentGenerator->reset(); // Reset the selected generator } // Load / convert block data from planner to fixed-time control variables. // Called from FTMotion::loop() at the fetch of the next planner block. -void FTMotion::loadBlockData(block_t * const current_block) { - // Cache the extruder index for this block - TERN_(DISTINCT_E_FACTORS, block_extruder_axis = E_AXIS_N(current_block->extruder)); +// Return whether a plan is available. +bool FTMotion::plan_next_block() { + while (true) { - const float totalLength = current_block->millimeters, - oneOverLength = 1.0f / totalLength; + const bool had_block = !!stepper.current_block; + discard_planner_block_protected(); // Always clears stepper.current_block... + block_t * const current_block = planner.get_current_block(); // ...so get the current block from the queue - startPos = endPos_prevBlock; - const xyze_pos_t& moveDist = current_block->dist_mm; - ratio = moveDist * oneOverLength; + // The planner had a block and there was not another one? + const bool planner_finished = had_block && !current_block; + if (planner_finished) { + plan_runout_block(); + return true; + } - const float mmps = totalLength / current_block->step_event_count; // (mm/step) Distance for each step - const float initial_speed = mmps * current_block->initial_rate; // (mm/s) Start feedrate - const float final_speed = mmps * current_block->final_rate; // (mm/s) End feedrate + // There was never a block? Run out the plan and bail. + if (!current_block) { + currentGenerator->planRunout(0); + return false; + } - // Plan the trajectory using the trajectory generator - currentGenerator->plan(initial_speed, final_speed, current_block->acceleration, current_block->nominal_speed, totalLength); + // Fetching this block for Stepper and for this loop + stepper.current_block = current_block; - // Accel + Coasting + Decel + datapoints - const float reminder_from_last_block = - tau; + // Handle sync blocks and skip others + if (current_block->is_sync()) { + if (current_block->is_sync_pos()) stepper._set_position(current_block->position); + continue; + } - endPos_prevBlock += moveDist; - - TERN_(FTM_HAS_LIN_ADVANCE, use_advance_lead = current_block->use_advance_lead); - - // Watch endstops until the move ends - const float total_duration = currentGenerator->getTotalDuration(); - uint32_t max_intervals = ceil((total_duration + reminder_from_last_block) * FTM_FS); - const millis_t move_end_ti = millis() + SEC_TO_MS((FTM_TS) * float(max_intervals + num_samples_shaper_settle() + ((PROP_BATCHES) + 1) * (FTM_BATCH_SIZE)) + (float(FTM_STEPPERCMD_BUFF_SIZE) / float(FTM_STEPPER_FS))); - - #define _SET_MOVE_END(A) do{ \ - if (moveDist.A) { \ - axis_move_end_ti.A = move_end_ti; \ - axis_move_dir.A = moveDist.A > 0; \ - } \ - }while(0); - - LOGICAL_AXIS_MAP(_SET_MOVE_END); -} - -// Generate data points of the trajectory. -// Called from FTMotion::loop() at the fetch of a new planner block, after loadBlockData. -void FTMotion::generateTrajectoryPointsFromBlock() { - const float total_duration = currentGenerator->getTotalDuration(); - if (tau + FTM_TS > total_duration) { - // TODO: refactor code so this thing is not twice. - // the reason of it being in the beginning, is that a block can be so short that it has - // zero trajectories. - // the next iteration will fall beyond this block - blockProcRdy = false; - traj_idx_get = 0; - tau -= total_duration; - return; - } - do { - tau += FTM_TS; // (s) Time since start of block - // If the end of the last block doesn't exactly land on a trajectory index, - // tau can start negative, but it always holds that `tau > -FTM_TS` - - // Get distance from trajectory generator - const float dist = currentGenerator->getDistanceAtTime(tau); - - #define _SET_TRAJ(q) traj.q[traj_idx_set] = startPos.q + ratio.q * dist; - LOGICAL_AXIS_MAP_LC(_SET_TRAJ); - - #if FTM_HAS_LIN_ADVANCE - const float advK = planner.get_advance_k(); - if (advK) { - float traj_e = traj.e[traj_idx_set]; - if (use_advance_lead) { - // Don't apply LA to retract/unretract blocks - float e_rate = (traj_e - prev_traj_e) * (FTM_FS); - traj.e[traj_idx_set] += e_rate * advK; - } - prev_traj_e = traj_e; - } + #if ENABLED(POWER_LOSS_RECOVERY) + recovery.info.sdpos = current_block->sdpos; + recovery.info.current_position = current_block->start_position; #endif - // Update shaping parameters if needed. + // Some kinematics track axis motion in HX, HY, HZ + #if ANY(CORE_IS_XY, CORE_IS_XZ, MARKFORGED_XY, MARKFORGED_YX) + stepper.last_direction_bits.hx = current_block->direction_bits.hx; + #endif + #if ANY(CORE_IS_XY, CORE_IS_YZ, MARKFORGED_XY, MARKFORGED_YX) + stepper.last_direction_bits.hy = current_block->direction_bits.hy; + #endif + #if ANY(CORE_IS_XZ, CORE_IS_YZ) + stepper.last_direction_bits.hz = current_block->direction_bits.hz; + #endif - switch (cfg.dynFreqMode) { + // Cache the extruder index for this block + TERN_(DISTINCT_E_FACTORS, block_extruder_axis = E_AXIS_N(current_block->extruder)); - #if HAS_DYNAMIC_FREQ_MM - case dynFreqMode_Z_BASED: { - static float oldz = 0.0f; - const float z = traj.z[traj_idx_set]; - if (z != oldz) { // Only update if Z changed. - oldz = z; - #if HAS_X_AXIS - const float xf = cfg.baseFreq.x + cfg.dynFreqK.x * z; - shaping.X.set_axis_shaping_N(cfg.shaper.x, _MAX(xf, FTM_MIN_SHAPE_FREQ), cfg.zeta.x); - #endif - #if HAS_Y_AXIS - const float yf = cfg.baseFreq.y + cfg.dynFreqK.y * z; - shaping.Y.set_axis_shaping_N(cfg.shaper.y, _MAX(yf, FTM_MIN_SHAPE_FREQ), cfg.zeta.y); - #endif - } - } break; - #endif + const float totalLength = current_block->millimeters; - #if HAS_DYNAMIC_FREQ_G - case dynFreqMode_MASS_BASED: - // Update constantly. The optimization done for Z value makes - // less sense for E, as E is expected to constantly change. + startPos = endPos_prevBlock; + const xyze_pos_t& moveDist = current_block->dist_mm; + ratio = moveDist / totalLength; + + const float mmps = totalLength / current_block->step_event_count, // (mm/step) Distance for each step + initial_speed = mmps * current_block->initial_rate, // (mm/s) Start feedrate + final_speed = mmps * current_block->final_rate; // (mm/s) End feedrate + + // Plan the trajectory using the trajectory generator + currentGenerator->plan(initial_speed, final_speed, current_block->acceleration, current_block->nominal_speed, totalLength); + + endPos_prevBlock += moveDist; + + TERN_(FTM_HAS_LIN_ADVANCE, use_advance_lead = current_block->use_advance_lead); + + // Watch endstops until the move ends + const millis_t move_end_ti = millis() + \ + stepper_plan_count() * FTM_TS + // Time to empty stepper command buffer + SEC_TO_MS(currentGenerator->getTotalDuration()) + // Time to finish this block + SEC_TO_MS((FTM_TS) * calc_runout_samples()); // Time for a rounout block + + #define _SET_MOVE_END(A) do{ \ + if (moveDist.A) { \ + axis_move_end_ti.A = move_end_ti; \ + axis_move_dir.A = moveDist.A > 0; \ + } \ + }while(0); + + LOGICAL_AXIS_MAP(_SET_MOVE_END); + + return true; + } +} + +xyze_float_t FTMotion::calc_traj_point(const float dist) { + xyze_float_t traj_coords; + #define _SET_TRAJ(q) traj_coords.q = startPos.q + ratio.q * dist; + LOGICAL_AXIS_MAP_LC(_SET_TRAJ); + + #if FTM_HAS_LIN_ADVANCE + const float advK = planner.get_advance_k(); + if (advK) { + const float traj_e = traj_coords.e; + if (use_advance_lead) { + // Don't apply LA to retract/unretract blocks + const float e_rate = (traj_e - prev_traj_e) * (FTM_FS); + traj_coords.e += e_rate * advK; + } + prev_traj_e = traj_e; + } + #endif + + // Update shaping parameters if needed. + switch (cfg.dynFreqMode) { + #if HAS_DYNAMIC_FREQ_MM + case dynFreqMode_Z_BASED: { + static float oldz = 0.0f; + const float z = traj_coords.z; + if (z != oldz) { // Only update if Z changed. + oldz = z; #if HAS_X_AXIS - shaping.X.set_axis_shaping_N(cfg.shaper.x, cfg.baseFreq.x + cfg.dynFreqK.x * traj.e[traj_idx_set], cfg.zeta.x); + const float xf = cfg.baseFreq.x + cfg.dynFreqK.x * z; + shaping.X.set_axis_shaping_N(cfg.shaper.x, _MAX(xf, FTM_MIN_SHAPE_FREQ), cfg.zeta.x); #endif #if HAS_Y_AXIS - shaping.Y.set_axis_shaping_N(cfg.shaper.y, cfg.baseFreq.y + cfg.dynFreqK.y * traj.e[traj_idx_set], cfg.zeta.y); + const float yf = cfg.baseFreq.y + cfg.dynFreqK.y * z; + shaping.Y.set_axis_shaping_N(cfg.shaper.y, _MAX(yf, FTM_MIN_SHAPE_FREQ), cfg.zeta.y); #endif - break; - #endif - - default: break; - } - uint32_t max_total_delay = 0; - - #if ENABLED(FTM_SMOOTHING) - #define _SMOOTHEN(A) /* Approximate gaussian smoothing via chained EMAs */ \ - if (smoothing.A.alpha > 0.0f) { \ - float smooth_val = traj.A[traj_idx_set]; \ - for (uint8_t _i = 0; _i < FTM_SMOOTHING_ORDER; ++_i) { \ - smoothing.A.smoothing_pass[_i] += (smooth_val - smoothing.A.smoothing_pass[_i]) * smoothing.A.alpha; \ - smooth_val = smoothing.A.smoothing_pass[_i]; \ - } \ - traj.A[traj_idx_set] = smooth_val; \ + shaping.refresh_largest_delay_samples(); } + } break; + #endif - CARTES_MAP(_SMOOTHEN); - max_total_delay += _MAX(CARTES_LIST( - smoothing.X.delay_samples, smoothing.Y.delay_samples, - smoothing.Z.delay_samples, smoothing.E.delay_samples - )); + #if HAS_DYNAMIC_FREQ_G + case dynFreqMode_MASS_BASED: + // Update constantly. The optimization done for Z value makes + // less sense for E, as E is expected to constantly change. + #if HAS_X_AXIS + shaping.X.set_axis_shaping_N(cfg.shaper.x, cfg.baseFreq.x + cfg.dynFreqK.x * traj_coords.e, cfg.zeta.x); + #endif + #if HAS_Y_AXIS + shaping.Y.set_axis_shaping_N(cfg.shaper.y, cfg.baseFreq.y + cfg.dynFreqK.y * traj_coords.e, cfg.zeta.y); + #endif + shaping.refresh_largest_delay_samples(); + break; + #endif - #endif // FTM_SMOOTHING + default: break; + } - #if HAS_FTM_SHAPING + #if ANY(FTM_SMOOTHING, HAS_FTM_SHAPING) + uint32_t max_total_delay = 0; + #endif - if (ftMotion.cfg.axis_sync_enabled) { - max_total_delay -= _MIN(SHAPED_LIST( - shaping.X.Ni[0], shaping.Y.Ni[0], - shaping.Z.Ni[0], shaping.E.Ni[0] - )); + #if ENABLED(FTM_SMOOTHING) + + #define _SMOOTHEN(A) /* Approximate gaussian smoothing via chained EMAs */ \ + if (smoothing.A.alpha > 0.0f) { \ + float smooth_val = traj_coords.A; \ + for (uint8_t _i = 0; _i < FTM_SMOOTHING_ORDER; ++_i) { \ + smoothing.A.smoothing_pass[_i] += (smooth_val - smoothing.A.smoothing_pass[_i]) * smoothing.A.alpha; \ + smooth_val = smoothing.A.smoothing_pass[_i]; \ + } \ + traj_coords.A = smooth_val; \ } - // Apply shaping if active on each axis - #define _SHAPE(A) \ - do { \ - const uint32_t group_delay = ftMotion.cfg.axis_sync_enabled \ - ? max_total_delay - TERN0(FTM_SMOOTHING, smoothing.A.delay_samples) \ - : -shaping.A.Ni[0]; \ - /* α=1−exp(−(dt / (τ / order))) */ \ - shaping.A.d_zi[shaping.zi_idx] = traj.A[traj_idx_set]; \ - traj.A[traj_idx_set] = 0; \ - for (uint32_t i = 0; i <= shaping.A.max_i; i++) { \ - /* echo_delay is always positive since Ni[i] = echo_relative_delay - group_delay + max_total_delay */ \ - /* where echo_relative_delay > 0 and group_delay ≤ max_total_delay */ \ - const uint32_t echo_delay = group_delay + shaping.A.Ni[i]; \ - int32_t udiff = shaping.zi_idx - echo_delay; \ - if (udiff < 0) udiff += FTM_ZMAX; \ - traj.A[traj_idx_set] += shaping.A.Ai[i] * shaping.A.d_zi[udiff]; \ - } \ - } while (0); + CARTES_MAP(_SMOOTHEN); + max_total_delay += smoothing.largest_delay_samples; - SHAPED_MAP(_SHAPE); + #endif // FTM_SMOOTHING - if (++shaping.zi_idx == (FTM_ZMAX)) shaping.zi_idx = 0; + #if HAS_FTM_SHAPING - #endif // HAS_FTM_SHAPING + if (ftMotion.cfg.axis_sync_enabled) + max_total_delay += shaping.largest_delay_samples; - // Filled up the queue with regular and shaped steps - if (++traj_idx_set == FTM_WINDOW_SIZE) { - traj_idx_set = BATCH_SIDX_IN_WINDOW; - batchRdy = true; - } - traj_idx_get++; - if (tau + FTM_TS > total_duration) { - // the next iteration will fall beyond this block - blockProcRdy = false; - traj_idx_get = 0; - tau -= total_duration; - } - } while (blockProcRdy && !batchRdy); -} // generateTrajectoryPointsFromBlock + // Apply shaping if active on each axis + #define _SHAPE(A) \ + do { \ + const uint32_t group_delay = ftMotion.cfg.axis_sync_enabled \ + ? max_total_delay - TERN0(FTM_SMOOTHING, smoothing.A.delay_samples) \ + : -shaping.A.Ni[0]; \ + /* α=1−exp(−(dt / (τ / order))) */ \ + shaping.A.d_zi[shaping.zi_idx] = traj_coords.A; \ + traj_coords.A = 0; \ + for (uint32_t i = 0; i <= shaping.A.max_i; i++) { \ + /* echo_delay is always positive since Ni[i] = echo_relative_delay - group_delay + max_total_delay */ \ + /* where echo_relative_delay > 0 and group_delay ≤ max_total_delay */ \ + const uint32_t echo_delay = group_delay + shaping.A.Ni[i]; \ + int32_t udiff = shaping.zi_idx - echo_delay; \ + if (udiff < 0) udiff += FTM_ZMAX; \ + traj_coords.A += shaping.A.Ai[i] * shaping.A.d_zi[udiff]; \ + } \ + } while (0); + + SHAPED_MAP(_SHAPE); + + if (++shaping.zi_idx == (FTM_ZMAX)) shaping.zi_idx = 0; + + #endif // HAS_FTM_SHAPING + + return traj_coords; +} + +stepper_plan_t FTMotion::calc_stepper_plan(xyze_float_t traj_coords) { + // 1) Convert trajectory to step delta + #define _TOSTEPS_q32(A, B) int64_t(traj_coords.A * planner.settings.axis_steps_per_mm[B] * (1ull << 32)) + XYZEval next_steps_q32_32 = LOGICAL_AXIS_ARRAY( + _TOSTEPS_q32(e, block_extruder_axis), + _TOSTEPS_q32(x, X_AXIS), _TOSTEPS_q32(y, Y_AXIS), _TOSTEPS_q32(z, Z_AXIS), + _TOSTEPS_q32(i, I_AXIS), _TOSTEPS_q32(j, J_AXIS), _TOSTEPS_q32(k, K_AXIS), + _TOSTEPS_q32(u, U_AXIS), _TOSTEPS_q32(v, V_AXIS), _TOSTEPS_q32(w, W_AXIS) + ); + #undef _TOSTEPS_q32 + + constexpr uint32_t ITERATIONS_PER_TRAJ_INV_uq0_32 = (1ull << 32) / ITERATIONS_PER_TRAJ; + stepper_plan_t stepper_plan; + + #define _RUN_AXIS(A) do{ \ + int64_t delta_q32_32 = (next_steps_q32_32.A - curr_steps_q32_32.A); \ + /* 2) Set stepper plan direction bits */ \ + int16_t sign = (delta_q32_32 > 0) - (delta_q32_32 < 0); \ + stepper_plan.dir_bits.A = delta_q32_32 > 0; \ + /* 3) Set per-iteration advance dividend Q0.32 */ \ + uint64_t delta_uq32_32 = ABS(delta_q32_32); \ + /* dividend = delta_q32_32 / ITERATIONS_PER_TRAJ, but avoiding division and an intermediate int128 */ \ + /* Note the integer part would overflow if there is eq or more than 1 steps per isr */ \ + uint32_t integer_part = (delta_uq32_32 >> 32) * ITERATIONS_PER_TRAJ_INV_uq0_32; \ + uint32_t fractional_part = ((delta_uq32_32 & UINT32_MAX) * ITERATIONS_PER_TRAJ_INV_uq0_32) >> 32; \ + stepper_plan.advance_dividend_q0_32.A = integer_part + fractional_part; \ + /* 4) Advance curr_steps by the exact integer steps that Bresenham will emit */ \ + /* It's like doing current_steps = next_steps, but considering any fractional error */ \ + /* from the dividend. This way there can be no drift. */ \ + curr_steps_q32_32.A += (int64_t)stepper_plan.advance_dividend_q0_32.A * sign * ITERATIONS_PER_TRAJ; \ + } while(0); + LOGICAL_AXIS_MAP(_RUN_AXIS); + #undef _RUN_AXIS + + return stepper_plan; +} /** - * @brief Interpolate a single trajectory data point into stepper commands. - * @param idx The index of the trajectory point to convert. - * - * Calculate the required stepper movements for each axis based on the - * difference between the current and previous trajectory points. - * Add up to one stepper command to the buffer with STEP/DIR bits for all axes. + * Generate stepper data of the trajectory. + * Called from FTMotion::loop() */ -void FTMotion::generateStepsFromTrajectory(const uint32_t idx) { - constexpr float INV_FTM_STEPS_PER_UNIT_TIME = 1.0f / (FTM_STEPS_PER_UNIT_TIME); +void FTMotion::fill_stepper_plan_buffer() { + while (!stepper_plan_is_full()) { + float total_duration = currentGenerator->getTotalDuration(); // if the current plan is empty, it will have zero duration. + while (tau + FTM_TS > total_duration) { + // Previous block plan consumed, try to get the next one. + tau -= total_duration; // The exact end of the last block may be in-between trajectory points, so the next one may start anywhere of (-FTM_TS, 0]. + const bool plan_available = plan_next_block(); + if (!plan_available) return; + total_duration = currentGenerator->getTotalDuration(); + } + tau += FTM_TS; // (s) Time since start of block - // q10 per-stepper-slot increment toward this sample’s target step count. - // (traj * steps_per_mm - steps) = steps still due at the start of this UNIT_TIME. - // Convert to q10 (×2^10), then subtract the current accumulator error: step_error_q10 / FTM_STEPS_PER_UNIT_TIME. - // Over FTM_STEPS_PER_UNIT_TIME stepper-slots this sums to the exact target (no drift). - // Any fraction of a step that may remain will be accounted for by the next UNIT_TIME - #define TOSTEPS_q10(A, B) int32_t( \ - (trajMod.A[idx] * planner.settings.axis_steps_per_mm[B] - steps.A) * _BV(10) \ - - step_error_q10.A * INV_FTM_STEPS_PER_UNIT_TIME ) + // Get distance from trajectory generator + xyze_float_t traj_coords = calc_traj_point(currentGenerator->getDistanceAtTime(tau)); - xyze_long_t delta_q10 = LOGICAL_AXIS_ARRAY( - TOSTEPS_q10(e, block_extruder_axis), - TOSTEPS_q10(x, X_AXIS), TOSTEPS_q10(y, Y_AXIS), TOSTEPS_q10(z, Z_AXIS), - TOSTEPS_q10(i, I_AXIS), TOSTEPS_q10(j, J_AXIS), TOSTEPS_q10(k, K_AXIS), - TOSTEPS_q10(u, U_AXIS), TOSTEPS_q10(v, V_AXIS), TOSTEPS_q10(w, W_AXIS) - ); + stepper_plan_t plan = calc_stepper_plan(traj_coords); - // Fixed-point denominator for step accumulation - constexpr int32_t denom_q10 = (FTM_STEPS_PER_UNIT_TIME) << 10; + // Store in buffer + enqueue_stepper_plan(plan); - // 1. Subtract one whole step from the accumulated distance - // 2. Accumulate one positive or negative step - // 3. Set the step and direction bits for the stepper command - #define RUN_AXIS(A) \ - do { \ - if (step_error_q10.A >= denom_q10) { \ - step_error_q10.A -= denom_q10; \ - steps.A++; \ - cmd |= _BV(FT_BIT_DIR_##A) | _BV(FT_BIT_STEP_##A); \ - } \ - if (step_error_q10.A <= -denom_q10) { \ - step_error_q10.A += denom_q10; \ - steps.A--; \ - cmd |= _BV(FT_BIT_STEP_##A); /* neg dir implicit */ \ - } \ - } while (0); - - for (uint32_t i = 0; i < uint32_t(FTM_STEPS_PER_UNIT_TIME); i++) { - // Reference the next stepper command in the circular buffer - ft_command_t& cmd = stepperCmdBuff[stepperCmdBuff_produceIdx]; - - // Init the command to no STEP (Reverse DIR) - cmd = 0; - - // Accumulate the "error" for all axes according the fixed-point distance - step_error_q10 += delta_q10; - - // Where the error has accumulated whole axis steps, add them to the command - LOGICAL_AXIS_MAP(RUN_AXIS); - - // Next circular buffer index - if (++stepperCmdBuff_produceIdx == (FTM_STEPPERCMD_BUFF_SIZE)) - stepperCmdBuff_produceIdx = 0; } } diff --git a/Marlin/src/module/ft_motion.h b/Marlin/src/module/ft_motion.h index a24f3271cf..55798adc6c 100644 --- a/Marlin/src/module/ft_motion.h +++ b/Marlin/src/module/ft_motion.h @@ -25,12 +25,19 @@ #include "planner.h" // Access block type from planner. #include "stepper.h" // For stepper motion and direction -#include "ft_types.h" #include "ft_motion/trajectory_generator.h" #include "ft_motion/trapezoidal_trajectory_generator.h" #include "ft_motion/poly5_trajectory_generator.h" #include "ft_motion/poly6_trajectory_generator.h" +#if HAS_FTM_SHAPING + #include "ft_motion/shaping.h" +#endif +#if ENABLED(FTM_SMOOTHING) + #include "ft_motion/smoothing.h" +#endif +#include "ft_motion/stepping.h" + #define FTM_VERSION 2 // Change version when hosts need to know #if HAS_X_AXIS && (HAS_Z_AXIS || HAS_EXTRUDERS) @@ -60,10 +67,6 @@ typedef struct FTConfig { ft_shaped_float_t vtol = // Vibration Level SHAPED_ARRAY(FTM_SHAPING_V_TOL_X, FTM_SHAPING_V_TOL_Y, FTM_SHAPING_V_TOL_Z, FTM_SHAPING_V_TOL_E); - #if ENABLED(FTM_SMOOTHING) - ft_smoothed_float_t smoothingTime; // Smoothing time. [s] - #endif - #if HAS_DYNAMIC_FREQ dynFreqMode_t dynFreqMode = FTM_DEFAULT_DYNFREQ_MODE; // Dynamic frequency mode configuration. ft_shaped_float_t dynFreqK = { 0.0f }; // Scaling / gain for dynamic frequency. [Hz/mm] or [Hz/g] @@ -73,6 +76,10 @@ typedef struct FTConfig { #endif // HAS_FTM_SHAPING + #if ENABLED(FTM_SMOOTHING) + ft_smoothed_float_t smoothingTime; // Smoothing time. [s] + #endif + TrajectoryType trajectory_type = TrajectoryType::FTM_TRAJECTORY_TYPE; // Trajectory generator type float poly6_acceleration_overshoot; // Overshoot factor for Poly6 (1.25 to 2.0) } ft_config_t; @@ -128,12 +135,6 @@ class FTMotion { reset(); } - static ft_command_t stepperCmdBuff[FTM_STEPPERCMD_BUFF_SIZE]; // Buffer of stepper commands. - static int32_t stepperCmdBuff_produceIdx, // Index of next stepper command write to the buffer. - stepperCmdBuff_consumeIdx; // Index of next stepper command read from the buffer. - - static bool stepperCmdBuffHasData; // The stepper buffer has items and is in use. - static XYZEval axis_move_end_ti; static AxisBits axis_move_dir; @@ -155,6 +156,7 @@ class FTMotion { static void reset(); // Reset all states of the fixed time conversion to defaults. + // Safely toggle the active state of FT Motion static bool toggle() { stepper.ftMotion_syncPosition(); FLIP(cfg.active); @@ -173,14 +175,33 @@ class FTMotion { return cfg.active ? axis_move_dir[axis] : stepper.last_direction_bits[axis]; } + + static stepping_t stepping; + FORCE_INLINE static bool stepper_plan_is_empty() { + return stepper_plan_head == stepper_plan_tail; + } + FORCE_INLINE static bool stepper_plan_is_full() { + return ((stepper_plan_head + 1) & FTM_BUFFER_MASK) == stepper_plan_tail; + } + FORCE_INLINE static uint32_t stepper_plan_count() { + return (stepper_plan_head - stepper_plan_tail) & FTM_BUFFER_MASK; + } + // Enqueue a plan + FORCE_INLINE static void enqueue_stepper_plan(const stepper_plan_t& d) { + stepper_plan_buff[stepper_plan_head] = d; + stepper_plan_head = (stepper_plan_head + 1u) & FTM_BUFFER_MASK; + } + // Dequeue a plan. + // Zero-copy consume; caller must use it before next dequeue if they keep a ref. + // Done like this to avoid double copy. + // e.g do: stepper_plan_t data = dequeue_stepper_plan(); this is ok + FORCE_INLINE static stepper_plan_t& dequeue_stepper_plan() { + const uint32_t i = stepper_plan_tail; + stepper_plan_tail = (i + 1u) & FTM_BUFFER_MASK; + return stepper_plan_buff[i]; + } + private: - - static xyze_trajectory_t traj; - static xyze_trajectoryMod_t trajMod; - - static bool blockProcRdy; - static bool batchRdy, batchRdyForInterp; - // Block data variables. static xyze_pos_t startPos, // (mm) Start position of block endPos_prevBlock; // (mm) End position of previous block @@ -194,19 +215,6 @@ class FTMotion { static TrajectoryGenerator* currentGenerator; static TrajectoryType trajectoryType; - // Number of batches needed to propagate the current trajectory to the stepper. - static constexpr uint32_t PROP_BATCHES = CEIL((FTM_WINDOW_SIZE) / (FTM_BATCH_SIZE)) - 1; - - // generateTrajectoryPointsFromBlock variables. - static uint32_t traj_idx_get, - traj_idx_set; - - // Interpolation variables. - static uint32_t interpIdx; - - static xyze_long_t steps; - static xyze_long_t step_error_q10; - #if ENABLED(DISTINCT_E_FACTORS) static uint8_t block_extruder_axis; // Cached extruder axis index #elif HAS_EXTRUDERS @@ -215,42 +223,12 @@ class FTMotion { #endif #if HAS_FTM_SHAPING - // Shaping data - typedef struct AxisShaping { - bool ena = false; // Enabled indication - float d_zi[FTM_ZMAX] = { 0.0f }; // Data point delay vector - float Ai[5]; // Shaping gain vector - int32_t Ni[5]; // Shaping time index vector - uint32_t max_i; // Vector length for the selected shaper - - void set_axis_shaping_N(const ftMotionShaper_t shaper, const float f, const float zeta); // Sets the gains used by shaping functions. - void set_axis_shaping_A(const ftMotionShaper_t shaper, const float zeta, const float vtol); // Sets the indices used by shaping functions. - - } axis_shaping_t; - - typedef struct Shaping { - uint32_t zi_idx; // Index of storage in the data point delay vectors. - axis_shaping_t SHAPED_AXIS_NAMES; - } shaping_t; - static shaping_t shaping; // Shaping data - - #endif // HAS_FTM_SHAPING + #endif #if ENABLED(FTM_SMOOTHING) - // Smoothing data for each axis - typedef struct AxisSmoothing { - float smoothing_pass[FTM_SMOOTHING_ORDER] = { 0.0f }; // Last value of each of the exponential smoothing passes - float alpha = 0.0f; // Pre-calculated alpha for smoothing. - uint32_t delay_samples = 0; // Pre-calculated delay in samples for smoothing. - void set_smoothing_time(const float s_time); // Set smoothing time, recalculate alpha and delay. - } axis_smoothing_t; - // Smoothing data for XYZE axes - typedef struct Smoothing { - axis_smoothing_t CARTES_AXIS_NAMES; - } smoothing_t; - static smoothing_t smoothing; // Smoothing data + static smoothing_t smoothing; #endif // Linear advance variables. @@ -258,20 +236,18 @@ class FTMotion { static float prev_traj_e; #endif - // Private methods + // Buffers static void discard_planner_block_protected(); - static void runoutBlock(); - static int32_t stepperCmdBuffItems(); - static void loadBlockData(block_t *const current_block); - static void generateTrajectoryPointsFromBlock(); - static void generateStepsFromTrajectory(const uint32_t idx); - - FORCE_INLINE static int32_t num_samples_shaper_settle() { - #define _OR_ENA(A) || shaping.A.ena - return false SHAPED_MAP(_OR_ENA) ? FTM_ZMAX : 0; - #undef _OR_ENA - } - + static uint32_t calc_runout_samples(); + static void plan_runout_block(); + static void fill_stepper_plan_buffer(); + static xyze_float_t calc_traj_point(const float dist); + static stepper_plan_t calc_stepper_plan(xyze_float_t delta); + static bool plan_next_block(); + // stepper_plan buffer variables. + static stepper_plan_t stepper_plan_buff[FTM_BUFFER_SIZE]; + static uint32_t stepper_plan_tail, stepper_plan_head; + static XYZEval curr_steps_q32_32; }; // class FTMotion extern FTMotion ftMotion; // Use ftMotion.thing, not FTMotion::thing. diff --git a/Marlin/src/module/ft_motion/shaping.cpp b/Marlin/src/module/ft_motion/shaping.cpp new file mode 100644 index 0000000000..a077ce99b8 --- /dev/null +++ b/Marlin/src/module/ft_motion/shaping.cpp @@ -0,0 +1,170 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2025 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/MarlinConfig.h" + +#if ENABLED(FT_MOTION) + +#include "shaping.h" + +// Refresh the gains used by shaping functions. +void AxisShaping::set_axis_shaping_A(const ftMotionShaper_t shaper, const float zeta, const float vtol) { + + const float K = exp(-zeta * M_PI / sqrt(1.f - sq(zeta))), + K2 = sq(K), + K3 = K2 * K, + K4 = K3 * K; + + switch (shaper) { + + case ftMotionShaper_ZV: + max_i = 1U; + Ai[0] = 1.0f / (1.0f + K); + Ai[1] = Ai[0] * K; + break; + + case ftMotionShaper_ZVD: + max_i = 2U; + Ai[0] = 1.0f / (1.0f + 2.0f * K + K2); + Ai[1] = Ai[0] * 2.0f * K; + Ai[2] = Ai[0] * K2; + break; + + case ftMotionShaper_ZVDD: + max_i = 3U; + Ai[0] = 1.0f / (1.0f + 3.0f * K + 3.0f * K2 + K3); + Ai[1] = Ai[0] * 3.0f * K; + Ai[2] = Ai[0] * 3.0f * K2; + Ai[3] = Ai[0] * K3; + break; + + case ftMotionShaper_ZVDDD: + max_i = 4U; + Ai[0] = 1.0f / (1.0f + 4.0f * K + 6.0f * K2 + 4.0f * K3 + K4); + Ai[1] = Ai[0] * 4.0f * K; + Ai[2] = Ai[0] * 6.0f * K2; + Ai[3] = Ai[0] * 4.0f * K3; + Ai[4] = Ai[0] * K4; + break; + + case ftMotionShaper_EI: { + max_i = 2U; + Ai[0] = 0.25f * (1.0f + vtol); + Ai[1] = 0.50f * (1.0f - vtol) * K; + Ai[2] = Ai[0] * K2; + + const float adj = 1.0f / (Ai[0] + Ai[1] + Ai[2]); + for (uint32_t i = 0; i < 3U; i++) Ai[i] *= adj; + } break; + + case ftMotionShaper_2HEI: { + max_i = 3U; + const float vtolx2 = sq(vtol); + const float X = POW(vtolx2 * (sqrt(1.0f - vtolx2) + 1.0f), 1.0f / 3.0f); + Ai[0] = (3.0f * sq(X) + 2.0f * X + 3.0f * vtolx2) / (16.0f * X); + Ai[1] = (0.5f - Ai[0]) * K; + Ai[2] = Ai[1] * K; + Ai[3] = Ai[0] * K3; + + const float adj = 1.0f / (Ai[0] + Ai[1] + Ai[2] + Ai[3]); + for (uint32_t i = 0; i < 4U; i++) Ai[i] *= adj; + } break; + + case ftMotionShaper_3HEI: { + max_i = 4U; + Ai[0] = 0.0625f * ( 1.0f + 3.0f * vtol + 2.0f * sqrt( 2.0f * ( vtol + 1.0f ) * vtol ) ); + Ai[1] = 0.25f * ( 1.0f - vtol ) * K; + Ai[2] = ( 0.5f * ( 1.0f + vtol ) - 2.0f * Ai[0] ) * K2; + Ai[3] = Ai[1] * K2; + Ai[4] = Ai[0] * K4; + + const float adj = 1.0f / (Ai[0] + Ai[1] + Ai[2] + Ai[3] + Ai[4]); + for (uint32_t i = 0; i < 5U; i++) Ai[i] *= adj; + } break; + + case ftMotionShaper_MZV: { + max_i = 2U; + const float Bx = 1.4142135623730950488016887242097f * K; + Ai[0] = 1.0f / (1.0f + Bx + K2); + Ai[1] = Ai[0] * Bx; + Ai[2] = Ai[0] * K2; + } + break; + + case ftMotionShaper_NONE: + max_i = 0; + Ai[0] = 1.0f; // No echoes so the whole impulse is applied in the first tap + break; + } + +} + +// Refresh the indices used by shaping functions. +// Ai[] must be precomputed (if zeta or vtol change, call set_axis_shaping_A first) +void AxisShaping::set_axis_shaping_N(const ftMotionShaper_t shaper, const float f, const float zeta) { + // Note that protections are omitted for DBZ and for index exceeding array length. + const float df = sqrt ( 1.f - sq(zeta) ); + switch (shaper) { + case ftMotionShaper_ZV: + Ni[1] = LROUND((0.5f / f / df) * (FTM_FS)); + break; + case ftMotionShaper_ZVD: + case ftMotionShaper_EI: + Ni[1] = LROUND((0.5f / f / df) * (FTM_FS)); + Ni[2] = Ni[1] + Ni[1]; + break; + case ftMotionShaper_ZVDD: + case ftMotionShaper_2HEI: + Ni[1] = LROUND((0.5f / f / df) * (FTM_FS)); + Ni[2] = Ni[1] + Ni[1]; + Ni[3] = Ni[2] + Ni[1]; + break; + case ftMotionShaper_ZVDDD: + case ftMotionShaper_3HEI: + Ni[1] = LROUND((0.5f / f / df) * (FTM_FS)); + Ni[2] = Ni[1] + Ni[1]; + Ni[3] = Ni[2] + Ni[1]; + Ni[4] = Ni[3] + Ni[1]; + break; + case ftMotionShaper_MZV: + Ni[1] = LROUND((0.375f / f / df) * (FTM_FS)); + Ni[2] = Ni[1] + Ni[1]; + break; + case ftMotionShaper_NONE: + // No echoes. + // max_i is set to 0 by set_axis_shaping_A, so delay centroid (Ni[0]) will also correctly be 0 + break; + } + + // Group delay in samples (i.e., Axis delay caused by shaping): sum(Ai * Ni[i]). + // Skipping i=0 since the uncompensated delay of the first impulse is always zero, so Ai[0] * Ni[0] == 0 + float centroid = 0.0f; + for (uint8_t i = 1; i <= max_i; ++i) centroid -= Ai[i] * Ni[i]; + + Ni[0] = LROUND(centroid); + + // The resulting echo index can be negative, this is ok because it will be offset + // by the max delay of all axes before it is used. + for (uint8_t i = 1; i <= max_i; ++i) Ni[i] += Ni[0]; +} + +#endif // FT_MOTION diff --git a/Marlin/src/module/ft_types.h b/Marlin/src/module/ft_motion/shaping.h similarity index 67% rename from Marlin/src/module/ft_types.h rename to Marlin/src/module/ft_motion/shaping.h index 86b37997e9..4a62acddcc 100644 --- a/Marlin/src/module/ft_types.h +++ b/Marlin/src/module/ft_motion/shaping.h @@ -1,6 +1,6 @@ /** * Marlin 3D Printer Firmware - * Copyright (c) 2023 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] + * Copyright (c) 2025 MarlinFirmware [https://github.com/MarlinFirmware/Marlin] * * Based on Sprinter and grbl. * Copyright (c) 2011 Camiel Gubbels / Erik van der Zalm @@ -21,7 +21,7 @@ */ #pragma once -#include "../core/types.h" +#include "../../inc/MarlinConfig.h" enum ftMotionShaper_t : uint8_t { ftMotionShaper_NONE = 0, // No compensator @@ -44,22 +44,6 @@ enum dynFreqMode_t : uint8_t { #define AXIS_IS_SHAPING(A) TERN0(FTM_SHAPER_##A, (ftMotion.cfg.shaper.A != ftMotionShaper_NONE)) #define AXIS_IS_EISHAPING(A) TERN0(FTM_SHAPER_##A, WITHIN(ftMotion.cfg.shaper.A, ftMotionShaper_EI, ftMotionShaper_3HEI)) -typedef struct XYZEarray xyze_trajectory_t; -typedef struct XYZEarray xyze_trajectoryMod_t; - -// TODO: Convert ft_command_t to a struct with bitfields instead of using a primitive type -enum { - LOGICAL_AXIS_PAIRED_LIST( - FT_BIT_DIR_E, FT_BIT_STEP_E, - FT_BIT_DIR_X, FT_BIT_STEP_X, FT_BIT_DIR_Y, FT_BIT_STEP_Y, FT_BIT_DIR_Z, FT_BIT_STEP_Z, - FT_BIT_DIR_I, FT_BIT_STEP_I, FT_BIT_DIR_J, FT_BIT_STEP_J, FT_BIT_DIR_K, FT_BIT_STEP_K, - FT_BIT_DIR_U, FT_BIT_STEP_U, FT_BIT_DIR_V, FT_BIT_STEP_V, FT_BIT_DIR_W, FT_BIT_STEP_W - ), - FT_BIT_COUNT -}; - -typedef bits_t(FT_BIT_COUNT) ft_command_t; - // Emitters for code that only cares about shaped XYZE #if HAS_FTM_SHAPING #define NUM_AXES_SHAPED COUNT_ENABLED(HAS_X_AXIS, HAS_Y_AXIS, FTM_SHAPER_Z, FTM_SHAPER_E) @@ -104,8 +88,30 @@ typedef FTShapedAxes ft_shaped_float_t; typedef FTShapedAxes ft_shaped_shaper_t; typedef FTShapedAxes ft_shaped_dfm_t; -#if ENABLED(FTM_SMOOTHING) - typedef struct FTSmoothedAxes { - float CARTES_AXIS_NAMES; - } ft_smoothed_float_t; -#endif + +// Shaping data +typedef struct AxisShaping { + bool ena = false; // Enabled indication + float d_zi[FTM_ZMAX] = { 0.0f }; // Data point delay vector + float Ai[5]; // Shaping gain vector + int32_t Ni[5]; // Shaping time index vector + uint32_t max_i; // Vector length for the selected shaper + + // Set the gains used by shaping functions + void set_axis_shaping_N(const ftMotionShaper_t shaper, const float f, const float zeta); + + // Set the indices (per pulse delays) used by shaping functions + void set_axis_shaping_A(const ftMotionShaper_t shaper, const float zeta, const float vtol); + +} axis_shaping_t; + +typedef struct Shaping { + uint32_t zi_idx; // Index of storage in the data point delay vectors. + axis_shaping_t SHAPED_AXIS_NAMES; + uint32_t largest_delay_samples; + // Shaping an axis makes it lag with respect to the others by certain amount, the "centroid delay" + // Ni[0] stores how far in the past the first step would need to happen to avoid desynchronisation (it is therefore negative). + // Of course things can't be done in the past, so when shaping is applied, the all axes are delayed by largest_delay_samples + // minus their own centroid delay. This makes them all be equally delayed and therefore in synch. + void refresh_largest_delay_samples() { largest_delay_samples = -_MIN(SHAPED_LIST(X.Ni[0], Y.Ni[0], Z.Ni[0], E.Ni[0])); } +} shaping_t; diff --git a/Marlin/src/module/ft_motion/smoothing.cpp b/Marlin/src/module/ft_motion/smoothing.cpp new file mode 100644 index 0000000000..f0016391b3 --- /dev/null +++ b/Marlin/src/module/ft_motion/smoothing.cpp @@ -0,0 +1,41 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2025 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/MarlinConfig.h" + +#if ENABLED(FTM_SMOOTHING) + +#include "smoothing.h" + +// Set smoothing time and recalculate alpha and delay. +void AxisSmoothing::set_smoothing_time(const float s_time) { + if (s_time > 0.001f) { + alpha = 1.0f - expf(-(FTM_TS) * (FTM_SMOOTHING_ORDER) / s_time ); + delay_samples = s_time * FTM_FS; + } + else { + alpha = 0.0f; + delay_samples = 0; + } +} + +#endif // FTM_SMOOTHING diff --git a/Marlin/src/module/ft_motion/smoothing.h b/Marlin/src/module/ft_motion/smoothing.h new file mode 100644 index 0000000000..ae8c088b30 --- /dev/null +++ b/Marlin/src/module/ft_motion/smoothing.h @@ -0,0 +1,47 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2025 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 "../../inc/MarlinConfig.h" + +typedef struct FTSmoothedAxes { + float CARTES_AXIS_NAMES; +} ft_smoothed_float_t; + +// Smoothing data for each axis +// The smoothing algorithm used is an approximation of moving window averaging with gaussian weights, based +// on chained exponential smoothers. +typedef struct AxisSmoothing { + float smoothing_pass[FTM_SMOOTHING_ORDER] = { 0.0f }; // Last value of each of the exponential smoothing passes + float alpha = 0.0f; // Pre-calculated alpha for smoothing. + uint32_t delay_samples = 0; // Pre-calculated delay in samples for smoothing. + void set_smoothing_time(const float s_time); // Set smoothing time, recalculate alpha and delay. +} axis_smoothing_t; + +typedef struct Smoothing { + axis_smoothing_t CARTES_AXIS_NAMES; + int32_t largest_delay_samples; + // Smoothing causes a phase delay equal to smoothing_time. This delay is componensated for during axis synchronisation, which + // is done by delaying all axes to match the laggiest one (i.e largest_delay_samples). + void refresh_largest_delay_samples() { largest_delay_samples = _MAX(CARTES_LIST(X.delay_samples, Y.delay_samples, Z.delay_samples, E.delay_samples)); } + // Note: the delay equals smoothing_time iff the input signal frequency is lower than 1/smoothing_time, luckily for us, this holds in this case +} smoothing_t; diff --git a/Marlin/src/module/ft_motion/stepping.cpp b/Marlin/src/module/ft_motion/stepping.cpp new file mode 100644 index 0000000000..96ef4466d8 --- /dev/null +++ b/Marlin/src/module/ft_motion/stepping.cpp @@ -0,0 +1,112 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2025 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" + +#if ENABLED(FT_MOTION) + +#include "stepping.h" +#include "../ft_motion.h" + +void Stepping::reset() { + stepper_plan.reset(); + delta_error_q32.set(LOGICAL_AXIS_ARRAY_1(_BV32(31))); // start as 0.5 in q32 so steps are rounded + step_bits = 0; + bresenham_iterations_pending = 0; +} + +uint32_t Stepping::advance_until_step() { + xyze_ulong_t space_q32 = -delta_error_q32 + UINT32_MAX; // How much accumulation until a step in any axis is ALMOST due + // scalar in the right hand because types.h is missing scalar on left cases + + xyze_ulong_t advance_q32 = stepper_plan.advance_dividend_q0_32; + uint32_t iterations = bresenham_iterations_pending; + // Per-axis lower-bound approx of floor(space_q32/adv), min across axes (lower bound because this fast division underestimates result by up to 1) + // #define RUN_AXIS(A) if(advance_q32.A > 0) NOMORE(iterations, space_q32.A/advance_q32.A); + #define RUN_AXIS(A) if(advance_q32.A > 0) NOMORE(iterations, uint32_t((uint64_t(space_q32.A) * advance_dividend_reciprocal.A) >> 32)); + LOGICAL_AXIS_MAP(RUN_AXIS); + #undef RUN_AXIS + + #define RUN_AXIS(A) delta_error_q32.A += advance_q32.A * iterations; + LOGICAL_AXIS_MAP(RUN_AXIS); + #undef RUN_AXIS + + bresenham_iterations_pending -= iterations; + step_bits = 0; + // iterations may be underestimated by 1 by the cheap division, therefore we may have to do 2 iterations here + while (bresenham_iterations_pending && !(bool)step_bits) { + iterations++; + bresenham_iterations_pending--; + #define RUN_AXIS(A) do{ \ + delta_error_q32.A += stepper_plan.advance_dividend_q0_32.A; \ + step_bits.A = delta_error_q32.A < stepper_plan.advance_dividend_q0_32.A; \ + }while(0); + LOGICAL_AXIS_MAP(RUN_AXIS); + #undef RUN_AXIS + } + + return iterations * INTERVAL_PER_ITERATION; +} + +uint32_t Stepping::plan() { + uint32_t intervals = 0; + if (bresenham_iterations_pending > 0) { + intervals = advance_until_step(); + if (bool(step_bits)) return intervals; // steps to make => return the wait time so it gets done in due time + // Else all bresenham iterations were advanced without steps => this is just the frame end, so plan the next one directly and accumulate the wait + } + + if (ftMotion.stepper_plan_is_empty()) { + bresenham_iterations_pending = 0; + step_bits = 0; + return INTERVAL_PER_TRAJ_POINT; + } + + AxisBits old_dir_bits = stepper_plan.dir_bits; + stepper_plan = ftMotion.dequeue_stepper_plan(); + const AxisBits dir_flip_mask = old_dir_bits ^ stepper_plan.dir_bits; // axes that must toggle now + if (dir_flip_mask) { + #define _HANDLE_DIR_CHANGES(A) if (dir_flip_mask.A) delta_error_q32.A *= -1; + LOGICAL_AXIS_MAP(_HANDLE_DIR_CHANGES); + #undef _HANDLE_DIR_CHANGES + } + + if (!(bool)stepper_plan.advance_dividend_q0_32) { + // don't waste time in zero motion traj points + bresenham_iterations_pending = 0; + step_bits = 0; + return INTERVAL_PER_TRAJ_POINT; + } + + // This vector division is unavoidable, but it saves a division per step during bresenham + // The reciprocal is actually 2^32/dividend, but that requires dividing a uint64_t, which quite expensive + // Since even the real reciprocal may underestimate the quotient by 1 anyway already, this optimisation doesn't + // make things worse. This underestimation is compensated for in advance_until_step. + #define _DIVIDEND_RECIP(A) advance_dividend_reciprocal.A = UINT32_MAX / stepper_plan.advance_dividend_q0_32.A; + LOGICAL_AXIS_MAP(_DIVIDEND_RECIP); + #undef _DIVIDEND_RECIP + + bresenham_iterations_pending = ITERATIONS_PER_TRAJ; + return intervals + advance_until_step(); +} + +#endif // FT_MOTION diff --git a/Marlin/src/module/ft_motion/stepping.h b/Marlin/src/module/ft_motion/stepping.h new file mode 100644 index 0000000000..6d0f3d31a5 --- /dev/null +++ b/Marlin/src/module/ft_motion/stepping.h @@ -0,0 +1,53 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2025 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 "../../inc/MarlinConfig.h" + +typedef struct stepper_plan { + AxisBits dir_bits; + xyze_ulong_t advance_dividend_q0_32{0}; + void reset() { advance_dividend_q0_32.reset(); } +} stepper_plan_t; + + +// Stepping plan handles steps for a while frame (trajectory point delta) +typedef struct Stepping { + stepper_plan_t stepper_plan; + xyze_ulong_t advance_dividend_reciprocal{0}; // Note this 32 bit reciprocal underestimates quotients by at most one. + xyze_ulong_t delta_error_q32{ LOGICAL_AXIS_LIST_1(_BV32(31)) }; + AxisBits step_bits; + uint32_t bresenham_iterations_pending; + + void reset(); + // Updates error and bresenham_iterations_pending, sets step_bits and returns interval until the next step (or end of frame). + uint32_t advance_until_step(); + /** + * If bresenham_iterations_pending, advance to next actual step. + * Else, consume stepper data point + * Then return interval until that next step + */ + uint32_t plan(); + #define INTERVAL_PER_ITERATION (STEPPER_TIMER_RATE / FTM_STEPPER_FS) + #define INTERVAL_PER_TRAJ_POINT (STEPPER_TIMER_RATE / FTM_FS) + #define ITERATIONS_PER_TRAJ (FTM_STEPPER_FS * FTM_TS) +} stepping_t; diff --git a/Marlin/src/module/ft_motion/trajectory_generator.h b/Marlin/src/module/ft_motion/trajectory_generator.h index 991ea6075c..934394940a 100644 --- a/Marlin/src/module/ft_motion/trajectory_generator.h +++ b/Marlin/src/module/ft_motion/trajectory_generator.h @@ -21,8 +21,6 @@ */ #pragma once -#include "../../inc/MarlinConfig.h" - #include /** diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index 3025cb83bd..8a44a40b8b 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -1512,7 +1512,7 @@ void Stepper::isr() { uint8_t max_loops = 10; #if ENABLED(FT_MOTION) - static uint32_t ftMotion_nextAuxISR = 0U; // Storage for the next ISR of the auxiliary tasks. + static uint32_t ftMotion_nextStepperISR = 0U; // Storage for the next ISR for stepping. const bool using_ftMotion = ftMotion.cfg.active; #else constexpr bool using_ftMotion = false; @@ -1527,19 +1527,22 @@ void Stepper::isr() { #if ENABLED(FT_MOTION) if (using_ftMotion) { - ftMotion_stepper(); // Run FTM Stepping + if (!ftMotion_nextStepperISR) ftMotion_stepper(); + TERN_(BABYSTEPPING, if (!nextBabystepISR) nextBabystepISR = babystepping_isr()); - // Define 2.5 msec task for auxiliary functions. - if (!ftMotion_nextAuxISR) { - TERN_(BABYSTEPPING, if (babystep.has_steps()) babystepping_isr()); - ftMotion_nextAuxISR = (STEPPER_TIMER_RATE) / 400; - } + // ^== Time critical. NOTHING besides pulse generation should be above here!!! // Enable ISRs to reduce latency for higher priority ISRs hal.isr_on(); - interval = FTM_MIN_TICKS; - ftMotion_nextAuxISR -= interval; + if (!ftMotion_nextStepperISR) ftMotion_nextStepperISR = ftMotion.stepping.plan(); + + interval = HAL_TIMER_TYPE_MAX; // Time until the next step + NOMORE(interval, ftMotion_nextStepperISR); + TERN_(BABYSTEPPING, NOMORE(interval, nextBabystepISR)); + + TERN_(BABYSTEPPING, nextBabystepISR -= interval); + ftMotion_nextStepperISR -= interval; } #endif @@ -1583,7 +1586,8 @@ void Stepper::isr() { #endif // Get the interval to the next ISR call - interval = _MIN(nextMainISR, uint32_t(HAL_TIMER_TYPE_MAX)); // Time until the next Pulse / Block phase + interval = uint32_t(STEPPER_TIMER_RATE * 0.030); // Max wait of 30ms regardless of stepper timer frequency + NOMORE(interval, nextMainISR); // Time until the next Pulse / Block phase TERN_(INPUT_SHAPING_X, NOMORE(interval, ShapingQueue::peek_x())); // Time until next input shaping echo for X TERN_(INPUT_SHAPING_Y, NOMORE(interval, ShapingQueue::peek_y())); // Time until next input shaping echo for Y TERN_(INPUT_SHAPING_Z, NOMORE(interval, ShapingQueue::peek_z())); // Time until next input shaping echo for Z @@ -3546,30 +3550,23 @@ void Stepper::report_positions() { * - Apply STEP/DIR along with any delays required. A command may be empty, with no STEP/DIR. */ void Stepper::ftMotion_stepper() { + AxisBits &step_bits = ftMotion.stepping.step_bits; // Aliases for prettier code + AxisBits &dir_bits = ftMotion.stepping.stepper_plan.dir_bits; - // Check if the buffer is empty. - ftMotion.stepperCmdBuffHasData = (ftMotion.stepperCmdBuff_produceIdx != ftMotion.stepperCmdBuff_consumeIdx); - if (!ftMotion.stepperCmdBuffHasData) return; - - // "Pop" one command from current motion buffer - const ft_command_t command = ftMotion.stepperCmdBuff[ftMotion.stepperCmdBuff_consumeIdx]; - if (++ftMotion.stepperCmdBuff_consumeIdx == (FTM_STEPPERCMD_BUFF_SIZE)) - ftMotion.stepperCmdBuff_consumeIdx = 0; + if (step_bits.bits == 0) return; USING_TIMED_PULSE(); - // Get FT Motion command flags for axis STEP / DIR - #define _FTM_STEP(AXIS) TEST(command, FT_BIT_STEP_##AXIS) - #define _FTM_DIR(AXIS) TEST(command, FT_BIT_DIR_##AXIS) - /** * Update direction bits for steppers that were stepped by this command. * HX, HY, HZ direction bits were set for Core kinematics * when the block was fetched and are not overwritten here. */ - #define _FTM_SET_DIR(AXIS) if (_FTM_STEP(AXIS)) last_direction_bits.bset(_AXIS(AXIS), _FTM_DIR(AXIS)); - LOGICAL_AXIS_MAP(_FTM_SET_DIR); + // Replace last_direction_bits with current dir bits for all stepped axes + last_direction_bits = (last_direction_bits & ~step_bits) | (dir_bits & step_bits); + //#define _FTM_SET_DIR(A) if (step_bits.A) last_direction_bits.A = dir_bits.A; + //LOGICAL_AXIS_MAP(_FTM_SET_DIR); if (last_set_direction != last_direction_bits) { // Apply directions (generally applying to the entire linear move) @@ -3583,7 +3580,7 @@ void Stepper::report_positions() { } // Start step pulses. Edge stepping will toggle the STEP pin. - #define _FTM_STEP_START(A) A##_APPLY_STEP(_FTM_STEP(A), false); + #define _FTM_STEP_START(A) A##_APPLY_STEP(step_bits.A, false); LOGICAL_AXIS_MAP(_FTM_STEP_START); // Apply steps via I2S @@ -3593,7 +3590,7 @@ void Stepper::report_positions() { START_TIMED_PULSE(); // Update step counts - #define _FTM_STEP_COUNT(A) if (_FTM_STEP(A)) count_position.A += last_direction_bits.A ? 1 : -1; + #define _FTM_STEP_COUNT(A) if (step_bits.A) count_position.A += count_direction.A; LOGICAL_AXIS_MAP(_FTM_STEP_COUNT); // Provide EDGE flags for E stepper(s) @@ -3609,10 +3606,10 @@ void Stepper::report_positions() { // Only wait for axes without edge stepping const bool any_wait = false LOGICAL_AXIS_GANG( - || (!e_axis_has_dedge && _FTM_STEP(E)), - || (!AXIS_HAS_DEDGE(X) && _FTM_STEP(X)), || (!AXIS_HAS_DEDGE(Y) && _FTM_STEP(Y)), || (!AXIS_HAS_DEDGE(Z) && _FTM_STEP(Z)), - || (!AXIS_HAS_DEDGE(I) && _FTM_STEP(I)), || (!AXIS_HAS_DEDGE(J) && _FTM_STEP(J)), || (!AXIS_HAS_DEDGE(K) && _FTM_STEP(K)), - || (!AXIS_HAS_DEDGE(U) && _FTM_STEP(U)), || (!AXIS_HAS_DEDGE(V) && _FTM_STEP(V)), || (!AXIS_HAS_DEDGE(W) && _FTM_STEP(W)) + || (!e_axis_has_dedge && step_bits.E), + || (!AXIS_HAS_DEDGE(X) && step_bits.X), || (!AXIS_HAS_DEDGE(Y) && step_bits.Y), || (!AXIS_HAS_DEDGE(Z) && step_bits.Z), + || (!AXIS_HAS_DEDGE(I) && step_bits.I), || (!AXIS_HAS_DEDGE(J) && step_bits.J), || (!AXIS_HAS_DEDGE(K) && step_bits.K), + || (!AXIS_HAS_DEDGE(U) && step_bits.U), || (!AXIS_HAS_DEDGE(V) && step_bits.V), || (!AXIS_HAS_DEDGE(W) && step_bits.W) ); // Allow pulses to be registered by stepper drivers diff --git a/Marlin/src/module/stepper.h b/Marlin/src/module/stepper.h index 50617800ba..5d5c000577 100644 --- a/Marlin/src/module/stepper.h +++ b/Marlin/src/module/stepper.h @@ -52,7 +52,7 @@ #endif #if ENABLED(FT_MOTION) - #include "ft_types.h" + class FTMotion; #endif // TODO: Review and ensure proper handling for special E axes with commands like M17/M18, stepper timeout, etc. diff --git a/ini/features.ini b/ini/features.ini index d1b02bb4d4..f727f00f16 100644 --- a/ini/features.ini +++ b/ini/features.ini @@ -311,7 +311,8 @@ HAS_DUPLICATION_MODE = build_src_filter=+ PLATFORM_M997_SUPPORT = build_src_filter=+ HAS_TOOLCHANGE = build_src_filter=+ -FT_MOTION = build_src_filter=+ + + +FT_MOTION = build_src_filter=+ + - + +FTM_SMOOTHING = build_src_filter=+ HAS_LIN_ADVANCE_K = build_src_filter=+ PHOTO_GCODE = build_src_filter=+ CONTROLLER_FAN_EDITABLE = build_src_filter=+ From 252085f462275f72151cd1b146d1204f00dce084 Mon Sep 17 00:00:00 2001 From: David Buezas Date: Sun, 2 Nov 2025 08:19:03 +0100 Subject: [PATCH 17/99] =?UTF-8?q?=F0=9F=90=9B=20Fix=20some=20FT=20Motion?= =?UTF-8?q?=20probing=20issues=20(#28096)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/Configuration.h | 2 ++ Marlin/src/inc/Warnings.cpp | 23 ++++++++++++++++------- Marlin/src/module/endstops.cpp | 11 +++++++---- Marlin/src/module/ft_motion.cpp | 22 ++++++++++++---------- Marlin/src/module/ft_motion.h | 6 +++--- Marlin/src/module/probe.cpp | 1 + Marlin/src/module/probe.h | 3 ++- Marlin/src/module/stepper.cpp | 29 +++++++++++++++-------------- buildroot/tests/mega2560 | 2 +- 9 files changed, 59 insertions(+), 40 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 7947ba65c5..00f8ce2088 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -1667,6 +1667,8 @@ //#define PROBE_TOOLCHANGE_NO_MOVE // Suppress motion on probe tool-change #endif +//#define PROBE_WAKEUP_TIME_MS 30 // (ms) Time for the probe to wake up + // Most probes should stay away from the edges of the bed, but // with NOZZLE_AS_PROBE this can be negative for a wider probing area. #define PROBING_MARGIN 10 diff --git a/Marlin/src/inc/Warnings.cpp b/Marlin/src/inc/Warnings.cpp index 38711e4fca..ac5aab6efc 100644 --- a/Marlin/src/inc/Warnings.cpp +++ b/Marlin/src/inc/Warnings.cpp @@ -919,6 +919,13 @@ #warning "The BEEPER cannot produce tones so you can disable SPEAKER." #endif +/** + * Delay for probes that need time to boot up when enabled + */ +#if defined(DELAY_BEFORE_PROBING) && DELAY_BEFORE_PROBING < 25 + #warning "The actual DELAY_BEFORE_PROBING will be the minimum 25 ms. Leave DELAY_BEFORE_PROBING disabled to use the minimum." +#endif + /** * Fixed-Time Motion */ @@ -926,17 +933,19 @@ #if ENABLED(I2S_STEPPER_STREAM) #warning "FT_MOTION has not been tested with I2S_STEPPER_STREAM." #endif - #if ENABLED(FTM_HOME_AND_PROBE) && ANY(BIQU_MICROPROBE_V1, BIQU_MICROPROBE_V2) - #warning "FT_MOTION in known to have issues with BIQU Microprobe." - #endif - #if ENABLED(FTM_HOME_AND_PROBE) && DELAY_BEFORE_PROBING <= 25 - #warning "A longer DELAY_BEFORE_PROBING is recommended when using a probe with FT_MOTION." - #endif #if ENABLED(NONLINEAR_EXTRUSION) #warning "NONLINEAR_EXTRUSION does not (currently) operate when FT_MOTION is the active motion system." #endif #if ENABLED(LIN_ADVANCE) - #warning "Be aware that FT_MOTION K factor (M493 K) is a separate setting from LIN_ADVANCE K factor (M900 K)." + #warning "Be aware that FT_MOTION K factor is now set with M900 K (same as LIN_ADVANCE)." + #endif +#endif +#if ENABLED(FTM_HOME_AND_PROBE) + #if ANY(BIQU_MICROPROBE_V1, BIQU_MICROPROBE_V2) + #warning "Let us know if you experience any issues with BIQU Microprobe and FT_MOTION." + #endif + #if DELAY_BEFORE_PROBING <= 25 + #warning "A DELAY_BEFORE_PROBING over 25 ms is recommended with FT_MOTION." #endif #endif diff --git a/Marlin/src/module/endstops.cpp b/Marlin/src/module/endstops.cpp index a12e432003..91d2fcd858 100644 --- a/Marlin/src/module/endstops.cpp +++ b/Marlin/src/module/endstops.cpp @@ -328,6 +328,9 @@ void Endstops::enable(const bool onoff) { #if PIN_EXISTS(PROBE_ENABLE) WRITE(PROBE_ENABLE_PIN, onoff); #endif + #if PROBE_WAKEUP_TIME_MS + if (onoff) safe_delay(PROBE_WAKEUP_TIME_MS); + #endif resync(); } #endif @@ -853,11 +856,14 @@ void Endstops::update() { #define PROCESS_ENDSTOP_Z(MINMAX) PROCESS_DUAL_ENDSTOP(Z, MINMAX) #endif + #define AXIS_IS_MOVING(A) TERN(FT_MOTION, ftMotion, stepper).axis_is_moving(_AXIS(A)) + #define AXIS_DIR_REV(A) !TERN(FT_MOTION, ftMotion, stepper).motor_direction(A) + #if ENABLED(G38_PROBE_TARGET) // For G38 moves check the probe's pin for ALL movement if (G38_move && TEST_ENDSTOP(Z_MIN_PROBE) == TERN1(G38_PROBE_AWAY, (G38_move < 4))) { G38_did_trigger = true; - #define _G38_SET(Q) | (stepper.axis_is_moving(_AXIS(Q)) << _AXIS(Q)) + #define _G38_SET(Q) | (AXIS_IS_MOVING(Q) << _AXIS(Q)) #define _G38_RESP(Q) if (moving[_AXIS(Q)]) { _ENDSTOP_HIT(Q, ENDSTOP); planner.endstop_triggered(_AXIS(Q)); } const Flags moving = { uvalue_t(NUM_AXES)(0 MAIN_AXIS_MAP(_G38_SET)) }; MAIN_AXIS_MAP(_G38_RESP); @@ -872,9 +878,6 @@ void Endstops::update() { // Signal, after validation, if an endstop limit is pressed or not - #define AXIS_IS_MOVING(A) TERN(FT_MOTION, ftMotion, stepper).axis_is_moving(_AXIS(A)) - #define AXIS_DIR_REV(A) !TERN(FT_MOTION, ftMotion, stepper).motor_direction(A) - #if HAS_X_AXIS if (AXIS_IS_MOVING(X)) { const AxisEnum x_head = TERN0(FT_MOTION, ftMotion.cfg.active) ? X_AXIS : X_AXIS_HEAD; diff --git a/Marlin/src/module/ft_motion.cpp b/Marlin/src/module/ft_motion.cpp index 69b2116bba..0164abc862 100644 --- a/Marlin/src/module/ft_motion.cpp +++ b/Marlin/src/module/ft_motion.cpp @@ -53,8 +53,8 @@ FTMotion ftMotion; ft_config_t FTMotion::cfg; bool FTMotion::busy; // = false -XYZEval FTMotion::axis_move_end_ti = { 0 }; -AxisBits FTMotion::axis_move_dir; +AxisBits FTMotion::moving_axis_flags, // These axes are moving in the planner block being processed + FTMotion::axis_move_dir; // ...in these directions // Private variables. @@ -157,7 +157,10 @@ void FTMotion::loop() { fill_stepper_plan_buffer(); // Set busy status for use by planner.busy() + const bool oldBusy = busy; busy = stepping.bresenham_iterations_pending > 0 || !stepper_plan_is_empty(); + if (oldBusy && !busy) moving_axis_flags.reset(); + } #if HAS_FTM_SHAPING @@ -211,7 +214,7 @@ void FTMotion::reset() { TERN_(HAS_EXTRUDERS, prev_traj_e = 0.0f); // Reset linear advance variables. TERN_(DISTINCT_E_FACTORS, block_extruder_axis = E_AXIS); - axis_move_end_ti.reset(); + moving_axis_flags.reset(); if (did_suspend) stepper.wake_up(); } @@ -348,21 +351,20 @@ bool FTMotion::plan_next_block() { TERN_(FTM_HAS_LIN_ADVANCE, use_advance_lead = current_block->use_advance_lead); - // Watch endstops until the move ends - const millis_t move_end_ti = millis() + \ - stepper_plan_count() * FTM_TS + // Time to empty stepper command buffer - SEC_TO_MS(currentGenerator->getTotalDuration()) + // Time to finish this block - SEC_TO_MS((FTM_TS) * calc_runout_samples()); // Time for a rounout block - #define _SET_MOVE_END(A) do{ \ if (moveDist.A) { \ - axis_move_end_ti.A = move_end_ti; \ + moving_axis_flags.A = true; \ axis_move_dir.A = moveDist.A > 0; \ } \ }while(0); LOGICAL_AXIS_MAP(_SET_MOVE_END); + // If the endstop is already pressed, endstop interrupts won't invoke + // endstop_triggered and the move will grind. So check here for a + // triggered endstop, which marks the block for discard on the next ISR. + endstops.update(); + return true; } } diff --git a/Marlin/src/module/ft_motion.h b/Marlin/src/module/ft_motion.h index 55798adc6c..a06f71cab2 100644 --- a/Marlin/src/module/ft_motion.h +++ b/Marlin/src/module/ft_motion.h @@ -135,8 +135,8 @@ class FTMotion { reset(); } - static XYZEval axis_move_end_ti; - static AxisBits axis_move_dir; + static AxisBits moving_axis_flags, // These axes are moving in the planner block being processed + axis_move_dir; // ...in these directions // Public methods static void init(); @@ -169,7 +169,7 @@ class FTMotion { static TrajectoryType getTrajectoryType() { return trajectoryType; } FORCE_INLINE static bool axis_is_moving(const AxisEnum axis) { - return cfg.active ? PENDING(millis(), axis_move_end_ti[axis]) : stepper.axis_is_moving(axis); + return cfg.active ? moving_axis_flags[axis] : stepper.axis_is_moving(axis); } FORCE_INLINE static bool motor_direction(const AxisEnum axis) { return cfg.active ? axis_move_dir[axis] : stepper.last_direction_bits[axis]; diff --git a/Marlin/src/module/probe.cpp b/Marlin/src/module/probe.cpp index 91a3268739..937b8ebeeb 100644 --- a/Marlin/src/module/probe.cpp +++ b/Marlin/src/module/probe.cpp @@ -595,6 +595,7 @@ bool Probe::set_deployed(const bool deploy, const bool no_return/*=false*/) { if (!no_return) do_blocking_move_to(old_xy); // Return to the original location unless handled externally endstops.enable_z_probe(deploy); + return false; } diff --git a/Marlin/src/module/probe.h b/Marlin/src/module/probe.h index 76957eb1d4..74904d35c5 100644 --- a/Marlin/src/module/probe.h +++ b/Marlin/src/module/probe.h @@ -46,7 +46,8 @@ #endif #if ENABLED(BD_SENSOR) - #define PROBE_READ() bdp_state + #include "endstops.h" + #define PROBE_READ() endstops.bdp_state #elif USE_Z_MIN_PROBE #define PROBE_READ() READ(Z_MIN_PROBE_PIN) #else diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index 8a44a40b8b..184f039608 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -3337,14 +3337,17 @@ void Stepper::init() { * derive the current XYZE position later on. */ void Stepper::_set_position(const abce_long_t &spos) { - #if ENABLED(INPUT_SHAPING_X) - const int32_t x_shaping_delta = count_position.x - shaping_x.last_block_end_pos; - #endif - #if ENABLED(INPUT_SHAPING_Y) - const int32_t y_shaping_delta = count_position.y - shaping_y.last_block_end_pos; - #endif - #if ENABLED(INPUT_SHAPING_Z) - const int32_t z_shaping_delta = count_position.z - shaping_z.last_block_end_pos; + #if HAS_ZV_SHAPING + const bool ftMotionActive = TERN0(FT_MOTION, ftMotion.cfg.active); + #if ENABLED(INPUT_SHAPING_X) + const int32_t x_shaping_delta = ftMotionActive ? 0 : count_position.x - shaping_x.last_block_end_pos; + #endif + #if ENABLED(INPUT_SHAPING_Y) + const int32_t y_shaping_delta = ftMotionActive ? 0 : count_position.y - shaping_y.last_block_end_pos; + #endif + #if ENABLED(INPUT_SHAPING_Z) + const int32_t z_shaping_delta = ftMotionActive ? 0 : count_position.z - shaping_z.last_block_end_pos; + #endif #endif #if ANY(IS_CORE, MARKFORGED_XY, MARKFORGED_YX) @@ -3541,13 +3544,11 @@ void Stepper::report_positions() { #if ENABLED(FT_MOTION) /** - * Run stepping from the Stepper ISR at regular short intervals. + * Run stepping for FT Motion from the Stepper ISR at regular short intervals. * - * - Set ftMotion.sts_stepperBusy state to reflect whether there are any commands in the circular buffer. - * - If there are no commands in the buffer, return. - * - Get the next command from the circular buffer ftMotion.stepperCmdBuff[]. - * - If the block is being aborted, return without processing the command. - * - Apply STEP/DIR along with any delays required. A command may be empty, with no STEP/DIR. + * - If there are no STEP commands in the buffer, return. + * - Update the last_direction_bits for all stepping axes. + * - Apply STEP/DIR along with any delays required. */ void Stepper::ftMotion_stepper() { AxisBits &step_bits = ftMotion.stepping.step_bits; // Aliases for prettier code diff --git a/buildroot/tests/mega2560 b/buildroot/tests/mega2560 index d7a149063c..befb17e1f7 100755 --- a/buildroot/tests/mega2560 +++ b/buildroot/tests/mega2560 @@ -65,7 +65,7 @@ opt_set MOTHERBOARD BOARD_AZTEEG_X3_PRO NUM_SERVOS 1 \ FIL_RUNOUT3_STATE HIGH FILAMENT_RUNOUT_SCRIPT '"M600 T%c"' opt_enable VIKI2 BOOT_MARLIN_LOGO_ANIMATED SDSUPPORT AUTO_REPORT_SD_STATUS \ Z_PROBE_SERVO_NR Z_SERVO_ANGLES Z_SERVO_MEASURE_ANGLE DEACTIVATE_SERVOS_AFTER_MOVE Z_SERVO_DEACTIVATE_AFTER_STOW \ - AUTO_BED_LEVELING_3POINT DEBUG_LEVELING_FEATURE PROBE_PT_1 PROBE_PT_2 PROBE_PT_3 \ + AUTO_BED_LEVELING_3POINT DEBUG_LEVELING_FEATURE PROBE_PT_1 PROBE_PT_2 PROBE_PT_3 PROBE_WAKEUP_TIME_MS \ EEPROM_SETTINGS EEPROM_CHITCHAT M114_DETAIL AUTO_REPORT_POSITION \ NO_VOLUMETRICS EXTENDED_CAPABILITIES_REPORT AUTO_REPORT_TEMPERATURES AUTOTEMP G38_PROBE_TARGET JOYSTICK \ DIRECT_STEPPING DETECT_BROKEN_ENDSTOP \ From 61cc3cdf091df4db972c9e8068b10eb3605497de Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 2 Nov 2025 15:47:02 -0600 Subject: [PATCH 18/99] =?UTF-8?q?=F0=9F=A9=B9=20Followup=20fix=20SD=20Quic?= =?UTF-8?q?ksort,=20FT=20Motion,=20Simulator?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/NATIVE_SIM/fastio.h | 2 ++ Marlin/src/inc/Warnings.cpp | 4 ++-- Marlin/src/sd/cardreader.cpp | 7 +++++++ 3 files changed, 11 insertions(+), 2 deletions(-) diff --git a/Marlin/src/HAL/NATIVE_SIM/fastio.h b/Marlin/src/HAL/NATIVE_SIM/fastio.h index f501afdbaa..e0b7af09f9 100644 --- a/Marlin/src/HAL/NATIVE_SIM/fastio.h +++ b/Marlin/src/HAL/NATIVE_SIM/fastio.h @@ -28,6 +28,8 @@ #include "../shared/Marduino.h" #include +#define NO_COMPILE_TIME_PWM + #define SET_DIR_INPUT(IO) Gpio::setDir(IO, 1) #define SET_DIR_OUTPUT(IO) Gpio::setDir(IO, 0) diff --git a/Marlin/src/inc/Warnings.cpp b/Marlin/src/inc/Warnings.cpp index ac5aab6efc..be617aa2e8 100644 --- a/Marlin/src/inc/Warnings.cpp +++ b/Marlin/src/inc/Warnings.cpp @@ -944,8 +944,8 @@ #if ANY(BIQU_MICROPROBE_V1, BIQU_MICROPROBE_V2) #warning "Let us know if you experience any issues with BIQU Microprobe and FT_MOTION." #endif - #if DELAY_BEFORE_PROBING <= 25 - #warning "A DELAY_BEFORE_PROBING over 25 ms is recommended with FT_MOTION." + #if PROBE_WAKEUP_TIME_MS < 30 + #warning "A PROBE_WAKEUP_TIME_MS over 30 ms is recommended with FT_MOTION." #endif #endif diff --git a/Marlin/src/sd/cardreader.cpp b/Marlin/src/sd/cardreader.cpp index 24ee80a2cc..a2c0da933c 100644 --- a/Marlin/src/sd/cardreader.cpp +++ b/Marlin/src/sd/cardreader.cpp @@ -1378,6 +1378,13 @@ void CardReader::cdroot() { #endif #endif + #else // !SDSORT_USES_RAM + + // By default re-read the names from SD for every compare + // retaining only two filenames at a time. This is very + // slow but is safest and uses minimal RAM. + char name1[LONG_FILENAME_LENGTH]; + #endif // SDSORT_USES_RAM if (fileCnt > 1) { From 150425e480e50c53360855ee9c14cf60a6e7d4ca Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 2 Nov 2025 16:25:26 -0600 Subject: [PATCH 19/99] =?UTF-8?q?=F0=9F=94=A8=20Update=20MarlinSimUI=20com?= =?UTF-8?q?mit=20ID?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- ini/native.ini | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/ini/native.ini b/ini/native.ini index 06d41d2ce4..9f241efb2b 100644 --- a/ini/native.ini +++ b/ini/native.ini @@ -58,7 +58,7 @@ debug_build_flags = -fstack-protector-strong -g -g3 -ggdb lib_compat_mode = off build_src_filter = ${common.default_src_filter} + lib_deps = ${common.lib_deps} - MarlinSimUI=https://github.com/p3p/MarlinSimUI/archive/2e71215018.zip + MarlinSimUI=https://github.com/p3p/MarlinSimUI/archive/29c11d4f63.zip Adafruit NeoPixel=https://github.com/p3p/Adafruit_NeoPixel/archive/c6b319f447.zip LiquidCrystal=https://github.com/p3p/LiquidCrystal/archive/322fb5fc23.zip extra_scripts = ${common.extra_scripts} From 79bd65be35b43937335e1ccc094b12a2f5ad984c Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Mon, 3 Nov 2025 00:34:02 +0000 Subject: [PATCH 20/99] [cron] Bump distribution date (2025-11-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 87c8749906..a6f3898c00 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 "2025-11-02" +//#define STRING_DISTRIBUTION_DATE "2025-11-03" /** * The protocol for communication to the host. Protocol indicates communication diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index e87409f70f..c1b2af6868 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 "2025-11-02" + #define STRING_DISTRIBUTION_DATE "2025-11-03" #endif /** From 0c4beea9beafef7bd571555ea400cbd8a0af10d9 Mon Sep 17 00:00:00 2001 From: narno2202 <130909513+narno2202@users.noreply.github.com> Date: Mon, 3 Nov 2025 04:16:44 +0100 Subject: [PATCH 21/99] =?UTF-8?q?=F0=9F=A9=B9=20Fix=20FT=5FMOTION=20+=20DI?= =?UTF-8?q?STINCT=5FE=5FFACTORS=20(#28106)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Fixes #28105 --- Marlin/src/module/ft_motion.cpp | 5 ++++- Marlin/src/module/ft_motion.h | 5 ++++- buildroot/tests/LPC1768 | 6 +++--- 3 files changed, 11 insertions(+), 5 deletions(-) diff --git a/Marlin/src/module/ft_motion.cpp b/Marlin/src/module/ft_motion.cpp index 0164abc862..029c620500 100644 --- a/Marlin/src/module/ft_motion.cpp +++ b/Marlin/src/module/ft_motion.cpp @@ -78,11 +78,14 @@ XYZEval FTMotion::curr_steps_q32_32 = {0}; uint32_t FTMotion::stepper_plan_tail = 0, // The index to consume from FTMotion::stepper_plan_head = 0; // The index to produce into +#if FTM_HAS_LIN_ADVANCE + bool FTMotion::use_advance_lead; +#endif + #if ENABLED(DISTINCT_E_FACTORS) uint8_t FTMotion::block_extruder_axis; // Cached E Axis from last-fetched block #elif HAS_EXTRUDERS constexpr uint8_t FTMotion::block_extruder_axis; - bool FTMotion::use_advance_lead; #endif // Shaping variables. diff --git a/Marlin/src/module/ft_motion.h b/Marlin/src/module/ft_motion.h index a06f71cab2..94a8f61a3e 100644 --- a/Marlin/src/module/ft_motion.h +++ b/Marlin/src/module/ft_motion.h @@ -215,11 +215,14 @@ class FTMotion { static TrajectoryGenerator* currentGenerator; static TrajectoryType trajectoryType; + #if FTM_HAS_LIN_ADVANCE + static bool use_advance_lead; + #endif + #if ENABLED(DISTINCT_E_FACTORS) static uint8_t block_extruder_axis; // Cached extruder axis index #elif HAS_EXTRUDERS static constexpr uint8_t block_extruder_axis = E_AXIS; - static bool use_advance_lead; #endif #if HAS_FTM_SHAPING diff --git a/buildroot/tests/LPC1768 b/buildroot/tests/LPC1768 index f00efb8341..386a146d0b 100755 --- a/buildroot/tests/LPC1768 +++ b/buildroot/tests/LPC1768 @@ -30,9 +30,9 @@ restore_configs opt_set MOTHERBOARD BOARD_MKS_SBASE \ EXTRUDERS 2 TEMP_SENSOR_1 1 \ NUM_SERVOS 2 SERVO_DELAY '{ 300, 300 }' SWITCHING_NOZZLE_SERVO_ANGLES '{ { 0, 90 }, { 90, 0 } }' -opt_enable SWITCHING_NOZZLE SWITCHING_NOZZLE_E1_SERVO_NR SWITCHING_NOZZLE_LIFT_TO_PROBE EDITABLE_SERVO_ANGLES SERVO_DETACH_GCODE \ - ULTIMAKERCONTROLLER REALTIME_REPORTING_COMMANDS FULL_REPORT_TO_HOST_FEATURE -exec_test $1 $2 "MKS SBASE with SWITCHING_NOZZLE, Grbl Realtime Report" "$3" +opt_enable DISTINCT_E_FACTORS SWITCHING_NOZZLE SWITCHING_NOZZLE_E1_SERVO_NR SWITCHING_NOZZLE_LIFT_TO_PROBE EDITABLE_SERVO_ANGLES SERVO_DETACH_GCODE \ + ULTIMAKERCONTROLLER REALTIME_REPORTING_COMMANDS FULL_REPORT_TO_HOST_FEATURE FT_MOTION FTM_SMOOTHING FTM_HOME_AND_PROBE +exec_test $1 $2 "MKS SBASE with SWITCHING_NOZZLE, FT Motion, Grbl Realtime Report" "$3" restore_configs opt_set MOTHERBOARD BOARD_RAMPS_14_RE_ARM_EEB \ From 29ad078fda7042a54710c7523a8255df49f291be Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 2 Nov 2025 21:48:24 -0600 Subject: [PATCH 22/99] =?UTF-8?q?=F0=9F=9A=B8=F0=9F=8C=A1=EF=B8=8F=20Refac?= =?UTF-8?q?tor=20AUTOTEMP,=20apply=20to=20LCD=20temp=20change=20(#28155)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Fixes #28154 --- Marlin/src/core/language.h | 1 + Marlin/src/gcode/gcode.h | 3 ++ Marlin/src/gcode/temp/M104_M109.cpp | 20 +++++++- Marlin/src/lcd/menu/menu_advanced.cpp | 6 +-- Marlin/src/lcd/menu/menu_temperature.cpp | 2 +- Marlin/src/lcd/menu/menu_tune.cpp | 9 ++-- Marlin/src/lcd/tft/touch.cpp | 5 +- Marlin/src/module/planner.cpp | 60 ++--------------------- Marlin/src/module/planner.h | 29 +++-------- Marlin/src/module/settings.cpp | 25 +++++----- Marlin/src/module/temperature.cpp | 62 ++++++++++++++++++++++-- Marlin/src/module/temperature.h | 53 +++++++++++++++++++- Marlin/src/module/tool_change.cpp | 2 +- buildroot/tests/mega2560 | 2 +- 14 files changed, 170 insertions(+), 109 deletions(-) diff --git a/Marlin/src/core/language.h b/Marlin/src/core/language.h index f2860ae7d4..e0a31db9ab 100644 --- a/Marlin/src/core/language.h +++ b/Marlin/src/core/language.h @@ -296,6 +296,7 @@ #define STR_TOOL_CHANGING "Tool-changing" #define STR_HOTEND_OFFSETS "Hotend offsets" #define STR_SERVO_ANGLES "Servo Angles" +#define STR_AUTOTEMP "Auto Temp Control" #define STR_HOTEND_PID "Hotend PID" #define STR_BED_PID "Bed PID" #define STR_CHAMBER_PID "Chamber PID" diff --git a/Marlin/src/gcode/gcode.h b/Marlin/src/gcode/gcode.h index effbd85449..a08ae769fe 100644 --- a/Marlin/src/gcode/gcode.h +++ b/Marlin/src/gcode/gcode.h @@ -766,6 +766,9 @@ private: static void M104_M109(const bool isM109); FORCE_INLINE static void M104() { M104_M109(false); } FORCE_INLINE static void M109() { M104_M109(true); } + #if ENABLED(AUTOTEMP) + static void M104_report(const bool forReplay=true); + #endif #endif static void M105(); diff --git a/Marlin/src/gcode/temp/M104_M109.cpp b/Marlin/src/gcode/temp/M104_M109.cpp index 4df86edc55..fa6cc948c0 100644 --- a/Marlin/src/gcode/temp/M104_M109.cpp +++ b/Marlin/src/gcode/temp/M104_M109.cpp @@ -70,6 +70,9 @@ * (used by printingIsActive, etc.) and turning off heaters will stop the timer. */ void GcodeSuite::M104_M109(const bool isM109) { + #if ENABLED(AUTOTEMP) + if (!isM109 && !parser.seen_any()) return M104_report(); + #endif if (DEBUGGING(DRYRUN)) return; @@ -125,10 +128,25 @@ void GcodeSuite::M104_M109(const bool isM109) { thermalManager.set_heating_message(target_extruder, !isM109 && got_temp); } - TERN_(AUTOTEMP, planner.autotemp_M104_M109()); + TERN_(AUTOTEMP, thermalManager.autotemp_M104_M109()); if (isM109 && got_temp) (void)thermalManager.wait_for_hotend(target_extruder, no_wait_for_cooling); } +#if ENABLED(AUTOTEMP) + // + // Report AUTOTEMP settings saved to EEPROM + // + void GcodeSuite::M104_report(const bool forReplay/*=true*/) { + TERN_(MARLIN_SMALL_BUILD, return); + report_heading_etc(forReplay, F(STR_AUTOTEMP)); + SERIAL_ECHOLNPGM(" M104" + " S", thermalManager.autotemp.cfg.min, + " B", thermalManager.autotemp.cfg.max, + " F", thermalManager.autotemp.cfg.factor + ); + } +#endif + #endif // HAS_HOTEND diff --git a/Marlin/src/lcd/menu/menu_advanced.cpp b/Marlin/src/lcd/menu/menu_advanced.cpp index fbd07cc549..07516205ff 100644 --- a/Marlin/src/lcd/menu/menu_advanced.cpp +++ b/Marlin/src/lcd/menu/menu_advanced.cpp @@ -325,9 +325,9 @@ void menu_backlash(); // Autotemp, Min, Max, Fact // #if ALL(AUTOTEMP, HAS_TEMP_HOTEND) - EDIT_ITEM(int3, MSG_MIN, &planner.autotemp.min, 0, thermalManager.hotend_max_target(0)); - EDIT_ITEM(int3, MSG_MAX, &planner.autotemp.max, 0, thermalManager.hotend_max_target(0)); - EDIT_ITEM(float42_52, MSG_FACTOR, &planner.autotemp.factor, 0, 10); + EDIT_ITEM(int3, MSG_MIN, &thermalManager.autotemp.cfg.min, 0, thermalManager.hotend_max_target(0)); + EDIT_ITEM(int3, MSG_MAX, &thermalManager.autotemp.cfg.max, 0, thermalManager.hotend_max_target(0)); + EDIT_ITEM(float42_52, MSG_FACTOR, &thermalManager.autotemp.cfg.factor, 0, 10); #endif // diff --git a/Marlin/src/lcd/menu/menu_temperature.cpp b/Marlin/src/lcd/menu/menu_temperature.cpp index 14824ca6b4..14845f5253 100644 --- a/Marlin/src/lcd/menu/menu_temperature.cpp +++ b/Marlin/src/lcd/menu/menu_temperature.cpp @@ -154,7 +154,7 @@ void menu_temperature() { EDIT_ITEM_FAST(int3, MSG_NOZZLE, &editable.celsius, 0, thermalManager.hotend_max_target(0), []{ thermalManager.setTargetHotend(editable.celsius, 0); }); #elif HAS_MULTI_HOTEND HOTEND_LOOP() { - editable.celsius = thermalManager.temp_hotend[e].target; + editable.celsius = thermalManager.degTargetHotend(e); EDIT_ITEM_FAST_N(int3, e, MSG_NOZZLE_N, &editable.celsius, 0, thermalManager.hotend_max_target(e), []{ thermalManager.setTargetHotend(editable.celsius, MenuItemBase::itemIndex); }); } #endif diff --git a/Marlin/src/lcd/menu/menu_tune.cpp b/Marlin/src/lcd/menu/menu_tune.cpp index 18d52bb640..8b34b01612 100644 --- a/Marlin/src/lcd/menu/menu_tune.cpp +++ b/Marlin/src/lcd/menu/menu_tune.cpp @@ -125,10 +125,13 @@ void menu_tune() { // Nozzle [1-4]: // #if HOTENDS == 1 - EDIT_ITEM_FAST(int3, MSG_NOZZLE, &thermalManager.temp_hotend[0].target, 0, thermalManager.hotend_max_target(0), []{ thermalManager.start_watching_hotend(0); }); + editable.celsius = thermalManager.degTargetHotend(0); + EDIT_ITEM_FAST(int3, MSG_NOZZLE, &editable.celsius, 0, thermalManager.hotend_max_target(0), []{ thermalManager.setTargetHotend(editable.celsius, 0); }); #elif HAS_MULTI_HOTEND - HOTEND_LOOP() - EDIT_ITEM_FAST_N(int3, e, MSG_NOZZLE_N, &thermalManager.temp_hotend[e].target, 0, thermalManager.hotend_max_target(e), []{ thermalManager.start_watching_hotend(MenuItemBase::itemIndex); }); + HOTEND_LOOP() { + editable.celsius = thermalManager.degTargetHotend(e); + EDIT_ITEM_FAST_N(int3, e, MSG_NOZZLE_N, &editable.celsius, 0, thermalManager.hotend_max_target(e), []{ thermalManager.setTargetHotend(editable.celsius, MenuItemBase::itemIndex); }); + } #endif #if ENABLED(SINGLENOZZLE_STANDBY_TEMP) diff --git a/Marlin/src/lcd/tft/touch.cpp b/Marlin/src/lcd/tft/touch.cpp index eb62caa273..cefd7cb779 100644 --- a/Marlin/src/lcd/tft/touch.cpp +++ b/Marlin/src/lcd/tft/touch.cpp @@ -236,9 +236,10 @@ void Touch::touch(touch_control_t * const control) { #if HAS_HOTEND #define HOTEND_HEATER(N) TERN0(HAS_MULTI_HOTEND, N) TERN_(HAS_MULTI_HOTEND, MenuItemBase::itemIndex = heater); + editable.celsius = thermalManager.degTargetHotend(HOTEND_HEATER(heater)); MenuItem_int3::action(GET_TEXT_F(TERN(HAS_MULTI_HOTEND, MSG_NOZZLE_N, MSG_NOZZLE)), - &thermalManager.temp_hotend[HOTEND_HEATER(heater)].target, 0, thermalManager.hotend_max_target(HOTEND_HEATER(heater)), - []{ thermalManager.start_watching_hotend(HOTEND_HEATER(MenuItemBase::itemIndex)); } + &editable.celsius, 0, thermalManager.hotend_max_target(HOTEND_HEATER(heater)), + []{ thermalManager.setTargetHotend(editable.celsius, HOTEND_HEATER(MenuItemBase::itemIndex)); } ); #endif break; diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index b4c53fab6b..6534425262 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -211,10 +211,6 @@ uint32_t Planner::max_acceleration_steps_per_s2[DISTINCT_AXES]; // (steps/s^2) D skew_factor_t Planner::skew_factor; // Initialized by settings.load #endif -#if ENABLED(AUTOTEMP) - autotemp_t Planner::autotemp = { AUTOTEMP_MIN, AUTOTEMP_MAX, AUTOTEMP_FACTOR, false }; -#endif - // private: xyze_long_t Planner::position{0}; @@ -1339,7 +1335,8 @@ void Planner::check_axes_activity() { // TERN_(HAS_TAIL_FAN_SPEED, if (fans_need_update) sync_fan_speeds(tail_fan_speed)); - TERN_(AUTOTEMP, autotemp_task()); + // Update hotend temperature based on extruder speed + TERN_(AUTOTEMP, thermalManager.autotemp_task()); #if ENABLED(BARICUDA) TERN_(HAS_HEATER_1, hal.set_pwm_duty(pin_t(HEATER_1_PIN), tail_valve_pressure)); @@ -1349,51 +1346,7 @@ void Planner::check_axes_activity() { #if ENABLED(AUTOTEMP) - #if ENABLED(AUTOTEMP_PROPORTIONAL) - void Planner::_autotemp_update_from_hotend() { - const celsius_t target = thermalManager.degTargetHotend(active_extruder); - autotemp.min = target + AUTOTEMP_MIN_P; - autotemp.max = target + AUTOTEMP_MAX_P; - } - #endif - - /** - * Called after changing tools to: - * - Reset or re-apply the default proportional autotemp factor. - * - Enable autotemp if the factor is non-zero. - */ - void Planner::autotemp_update() { - _autotemp_update_from_hotend(); - autotemp.factor = TERN0(AUTOTEMP_PROPORTIONAL, AUTOTEMP_FACTOR_P); - autotemp.enabled = autotemp.factor != 0; - } - - /** - * Called by the M104/M109 commands after setting Hotend Temperature - */ - void Planner::autotemp_M104_M109() { - _autotemp_update_from_hotend(); - - if (parser.seenval('S')) autotemp.min = parser.value_celsius(); - if (parser.seenval('B')) autotemp.max = parser.value_celsius(); - - // When AUTOTEMP_PROPORTIONAL is enabled, F0 disables autotemp. - // Normally, leaving off F also disables autotemp. - autotemp.factor = parser.seen('F') ? parser.value_float() : TERN0(AUTOTEMP_PROPORTIONAL, AUTOTEMP_FACTOR_P); - autotemp.enabled = autotemp.factor != 0; - } - - /** - * Called every so often to adjust the hotend target temperature - * based on the extrusion speed, which is calculated from the blocks - * currently in the planner. - */ - void Planner::autotemp_task() { - static float oldt = 0.0f; - - if (!autotemp.enabled) return; - if (thermalManager.degTargetHotend(active_extruder) < autotemp.min - 2) return; // Below the min? - + float Planner::get_high_e_speed() { float high = 0.0f; for (uint8_t b = block_buffer_tail; b != block_buffer_head; b = next_block_index(b)) { const block_t * const block = &block_buffer[b]; @@ -1402,12 +1355,7 @@ void Planner::check_axes_activity() { NOLESS(high, se); } } - - float t = autotemp.min + high * autotemp.factor; - LIMIT(t, autotemp.min, autotemp.max); - if (t < oldt) t = t * (1.0f - (AUTOTEMP_OLDWEIGHT)) + oldt * (AUTOTEMP_OLDWEIGHT); - oldt = t; - thermalManager.setTargetHotend(t, active_extruder); + return high; } #endif // AUTOTEMP diff --git a/Marlin/src/module/planner.h b/Marlin/src/module/planner.h index c001dadd66..14c83b0559 100644 --- a/Marlin/src/module/planner.h +++ b/Marlin/src/module/planner.h @@ -32,6 +32,8 @@ #include "../MarlinCore.h" +#include "temperature.h" + #if ENABLED(JD_HANDLE_SMALL_SEGMENTS) // Enable this option for perfect accuracy but maximum // computation. Should be fine on ARM processors. @@ -165,14 +167,6 @@ typedef struct { } block_flags_t; -#if ENABLED(AUTOTEMP) - typedef struct { - celsius_t min, max; - float factor; - bool enabled; - } autotemp_t; -#endif - #if ENABLED(LASER_FEATURE) typedef struct { @@ -679,6 +673,10 @@ class Planner { // Manage fans, paste pressure, etc. static void check_axes_activity(); + #if ENABLED(AUTOTEMP) + static float get_high_e_speed(); + #endif + // Apply fan speeds #if HAS_FAN static void sync_fan_speeds(uint8_t (&fan_speed)[FAN_COUNT]); @@ -1104,13 +1102,6 @@ class Planner { static void clear_block_buffer_runtime(); #endif - #if ENABLED(AUTOTEMP) - static autotemp_t autotemp; - static void autotemp_update(); - static void autotemp_M104_M109(); - static void autotemp_task(); - #endif - #if HAS_LINEAR_E_JERK FORCE_INLINE static void recalculate_max_e_jerk() { const float prop = junction_deviation_mm * SQRT(0.5) / (1.0f - SQRT(0.5)); @@ -1121,14 +1112,6 @@ class Planner { private: - #if ENABLED(AUTOTEMP) - #if ENABLED(AUTOTEMP_PROPORTIONAL) - static void _autotemp_update_from_hotend(); - #else - static void _autotemp_update_from_hotend() {} - #endif - #endif - /** * Get the index of the next / previous block in the ring buffer */ diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index 3414d322da..523a3767df 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -271,8 +271,7 @@ typedef struct SettingsDataStruct { // AUTOTEMP // #if ENABLED(AUTOTEMP) - celsius_t planner_autotemp_max, planner_autotemp_min; - float planner_autotemp_factor; + autotemp_cfg_t planner_autotemp_cfg; // M104 S B F #endif // @@ -1012,10 +1011,8 @@ void MarlinSettings::postprocess() { // AUTOTEMP // #if ENABLED(AUTOTEMP) - _FIELD_TEST(planner_autotemp_max); - EEPROM_WRITE(planner.autotemp.max); - EEPROM_WRITE(planner.autotemp.min); - EEPROM_WRITE(planner.autotemp.factor); + _FIELD_TEST(planner_autotemp_cfg); + EEPROM_WRITE(thermalManager.autotemp.cfg); #endif // @@ -2066,9 +2063,8 @@ void MarlinSettings::postprocess() { // AUTOTEMP // #if ENABLED(AUTOTEMP) - EEPROM_READ(planner.autotemp.max); - EEPROM_READ(planner.autotemp.min); - EEPROM_READ(planner.autotemp.factor); + _FIELD_TEST(planner_autotemp_cfg); + EEPROM_READ(thermalManager.autotemp.cfg); #endif // @@ -3450,11 +3446,7 @@ void MarlinSettings::reset() { // // AUTOTEMP // - #if ENABLED(AUTOTEMP) - planner.autotemp.max = AUTOTEMP_MAX; - planner.autotemp.min = AUTOTEMP_MIN; - planner.autotemp.factor = AUTOTEMP_FACTOR; - #endif + TERN_(AUTOTEMP, thermalManager.autotemp.reset()); // // X Axis Twist Compensation @@ -3853,6 +3845,11 @@ void MarlinSettings::reset() { #endif gcode.say_units(); // " (in/mm)" + // + // M104 settings for AUTOTEMP + // + TERN_(AUTOTEMP, gcode.M104_report()); + // // M149 Temperature units // diff --git a/Marlin/src/module/temperature.cpp b/Marlin/src/module/temperature.cpp index fa84cec25d..5d5ccd3e4d 100644 --- a/Marlin/src/module/temperature.cpp +++ b/Marlin/src/module/temperature.cpp @@ -389,6 +389,10 @@ PGMSTR(str_t_heating_failed, STR_T_HEATING_FAILED); #endif // HAS_HOTEND +#if ENABLED(AUTOTEMP) + autotemp_t Temperature::autotemp; // Initialized by settings.load +#endif + #if HAS_TEMP_REDUNDANT redundant_info_t Temperature::temp_redundant; #endif @@ -3552,7 +3556,7 @@ void Temperature::init() { void Temperature::disable_all_heaters() { // Disable autotemp, unpause and reset everything - TERN_(AUTOTEMP, planner.autotemp.enabled = false); + TERN_(AUTOTEMP, autotemp.enabled = false); TERN_(PROBING_HEATERS_OFF, pause_heaters(false)); #if HAS_HOTEND @@ -3637,7 +3641,7 @@ void Temperature::disable_all_heaters() { singlenozzle_temp[old_tool] = temp_hotend[0].target; if (singlenozzle_temp[new_tool] && singlenozzle_temp[new_tool] != singlenozzle_temp[old_tool]) { setTargetHotend(singlenozzle_temp[new_tool], 0); - TERN_(AUTOTEMP, planner.autotemp_update()); + TERN_(AUTOTEMP, autotemp_update()); set_heating_message(0); (void)wait_for_hotend(0, false); // Wait for heating or cooling } @@ -4778,7 +4782,7 @@ void Temperature::isr() { OPTARG(G26_CLICK_CAN_CANCEL, const bool click_to_cancel/*=false*/) ) { #if ENABLED(AUTOTEMP) - REMEMBER(1, planner.autotemp.enabled, false); + REMEMBER(1, autotemp.enabled, false); #endif #if TEMP_RESIDENCY_TIME > 0 @@ -4911,6 +4915,58 @@ void Temperature::isr() { #endif // HAS_TEMP_HOTEND + #if ENABLED(AUTOTEMP) + + void Temperature::_autotemp_update_from_hotend() { + TERN_(AUTOTEMP_PROPORTIONAL, autotemp.update(degTargetHotend(active_extruder))); + } + + /** + * Called after changing tools to: + * - Reset or re-apply the default proportional autotemp factor. + * - Enable autotemp if the factor is non-zero. + */ + void Temperature::autotemp_update() { + _autotemp_update_from_hotend(); + autotemp.cfg.factor = TERN0(AUTOTEMP_PROPORTIONAL, AUTOTEMP_FACTOR_P); + autotemp.enabled = autotemp.cfg.factor != 0; + } + + /** + * Called by the M104/M109 commands after setting Hotend Temperature + */ + void Temperature::autotemp_M104_M109() { + _autotemp_update_from_hotend(); + + if (parser.seenval('S')) autotemp.cfg.min = parser.value_celsius(); + if (parser.seenval('B')) autotemp.cfg.max = parser.value_celsius(); + + // When AUTOTEMP_PROPORTIONAL is enabled, F0 disables autotemp. + // Normally, leaving off F also disables autotemp. + autotemp.cfg.factor = parser.seen('F') ? parser.value_float() : TERN0(AUTOTEMP_PROPORTIONAL, AUTOTEMP_FACTOR_P); + autotemp.enabled = autotemp.cfg.factor != 0; + } + + /** + * Called every so often to adjust the hotend target temperature + * based on the extrusion speed, which is calculated from the blocks + * currently in the planner. + */ + void Temperature::autotemp_task() { + if (!autotemp.enabled) return; + if (degTargetHotend(active_extruder) < autotemp.cfg.min - 2) return; // Below the min? + + // Get a highest target proportion greater than zero + float high = planner.get_high_e_speed(); + + // Calculate a new target, with weighted correction for a drop + float t = autotemp.calculate(high); + + _setTargetHotend(t, active_extruder); + } + + #endif // AUTOTEMP + #if HAS_HEATED_BED #ifndef MIN_COOLING_SLOPE_DEG_BED diff --git a/Marlin/src/module/temperature.h b/Marlin/src/module/temperature.h index 92fae44deb..884a72646e 100644 --- a/Marlin/src/module/temperature.h +++ b/Marlin/src/module/temperature.h @@ -603,6 +603,41 @@ typedef struct { raw_adc_t raw_min, raw_max; celsius_t mintemp, maxtemp; } temp_ #define HAS_FAN_LOGIC 1 #endif +#if ENABLED(AUTOTEMP) + + typedef struct { + celsius_t min, max; + float factor; + } autotemp_cfg_t; + + typedef struct { + autotemp_cfg_t cfg; + bool enabled; + + void reset() { + cfg.min = AUTOTEMP_MIN; + cfg.max = AUTOTEMP_MAX; + cfg.factor = AUTOTEMP_FACTOR; + enabled = false; + } + #if ENABLED(AUTOTEMP_PROPORTIONAL) + void update(const celsius_t t) { + cfg.min = t + AUTOTEMP_MIN_P; + cfg.max = t + AUTOTEMP_MAX_P; + } + #endif + float calculate(const celsius_t high) { + static float oldt = 0; + float t = cfg.min + high * cfg.factor; + NOMORE(t, cfg.max); + if (t < oldt) t = t * (1.0f - (AUTOTEMP_OLDWEIGHT)) + oldt * (AUTOTEMP_OLDWEIGHT); + oldt = t; + return t; + } + } autotemp_t; + +#endif // AUTOTEMP + class Temperature { public: @@ -1001,6 +1036,10 @@ class Temperature { #if HAS_HOTEND + static void _setTargetHotend(const celsius_t celsius, const uint8_t E_NAME) { + temp_hotend[HOTEND_INDEX].target = _MIN(celsius, hotend_max_target(HOTEND_INDEX)); + } + static void setTargetHotend(const celsius_t celsius, const uint8_t E_NAME) { const uint8_t ee = HOTEND_INDEX; #if PREHEAT_TIME_HOTEND_MS > 0 @@ -1010,7 +1049,8 @@ class Temperature { start_hotend_preheat_time(ee); #endif TERN_(AUTO_POWER_CONTROL, if (celsius) powerManager.power_on()); - temp_hotend[ee].target = _MIN(celsius, hotend_max_target(ee)); + _setTargetHotend(celsius, ee); + TERN_(AUTOTEMP, autotemp.enabled = false); start_watching_hotend(ee); } @@ -1052,6 +1092,13 @@ class Temperature { #endif // HAS_HOTEND + #if ENABLED(AUTOTEMP) + static autotemp_t autotemp; + static void autotemp_update(); + static void autotemp_M104_M109(); + static void autotemp_task(); + #endif + #if HAS_HEATED_BED #if ENABLED(SHOW_TEMP_ADC_VALUES) @@ -1349,6 +1396,10 @@ class Temperature { return true; } + #if ENABLED(AUTOTEMP) + static void _autotemp_update_from_hotend(); + #endif + // 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(2) + TEMP_SENSOR_IS_MAX_TC(REDUNDANT) diff --git a/Marlin/src/module/tool_change.cpp b/Marlin/src/module/tool_change.cpp index baf4ad813e..85254ea598 100644 --- a/Marlin/src/module/tool_change.cpp +++ b/Marlin/src/module/tool_change.cpp @@ -1581,7 +1581,7 @@ void tool_change(const uint8_t new_tool, bool no_move/*=false*/) { // Migrate the temperature to the new hotend #if HAS_MULTI_HOTEND thermalManager.setTargetHotend(thermalManager.degTargetHotend(active_extruder), migration_extruder); - TERN_(AUTOTEMP, planner.autotemp_update()); + TERN_(AUTOTEMP, thermalManager.autotemp_update()); thermalManager.set_heating_message(0); thermalManager.wait_for_hotend(active_extruder); #endif diff --git a/buildroot/tests/mega2560 b/buildroot/tests/mega2560 index befb17e1f7..f323602954 100755 --- a/buildroot/tests/mega2560 +++ b/buildroot/tests/mega2560 @@ -82,7 +82,7 @@ opt_set DEFAULT_AXIS_STEPS_PER_UNIT '{ 4000 }' \ MANUAL_FEEDRATE '{ 4*60 }' \ AXIS_RELATIVE_MODES '{ false }' \ HOMING_BUMP_MM '{}' HOMING_BUMP_DIVISOR '{}' HOMING_FEEDRATE_MM_M '{}' -opt_enable REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER +opt_enable REPRAP_DISCOUNT_FULL_GRAPHIC_SMART_CONTROLLER AUTOTEMP AUTOTEMP_PROPORTIONAL opt_disable X_DRIVER_TYPE Y_DRIVER_TYPE Z_DRIVER_TYPE exec_test $1 $2 "E Axis Only | DOGM MarlinUI" "$3" From e9810691ec6d5786a1e28abba875cc769d287469 Mon Sep 17 00:00:00 2001 From: zzcatvs <145735142+zzcatvs@users.noreply.github.com> Date: Tue, 4 Nov 2025 04:09:08 +0800 Subject: [PATCH 23/99] =?UTF-8?q?=E2=9C=A8=20FYSETC=20Spider=20King=20V1.1?= =?UTF-8?q?=20(STM32H723ZG)=20(#27125)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/core/boards.h | 157 +++++++++--------- Marlin/src/pins/pins.h | 46 +++-- .../pins/stm32f4/pins_FYSETC_SPIDER_KING_V1.h | 28 ++++ .../stm32f4/pins_FYSETC_SPIDER_KING_V1_1.h | 28 ++++ ...407.h => pins_FYSETC_SPIDER_KING_common.h} | 86 +++++++--- .../pins_FYSETC_SPIDER_KING_V1_1_H723.h | 29 ++++ .../stm32h7/pins_FYSETC_SPIDER_KING_V1_H723.h | 29 ++++ ini/renamed.ini | 3 + ini/stm32f4.ini | 4 +- ini/stm32h7.ini | 15 +- 10 files changed, 302 insertions(+), 123 deletions(-) create mode 100644 Marlin/src/pins/stm32f4/pins_FYSETC_SPIDER_KING_V1.h create mode 100644 Marlin/src/pins/stm32f4/pins_FYSETC_SPIDER_KING_V1_1.h rename Marlin/src/pins/stm32f4/{pins_FYSETC_SPIDER_KING407.h => pins_FYSETC_SPIDER_KING_common.h} (83%) create mode 100644 Marlin/src/pins/stm32h7/pins_FYSETC_SPIDER_KING_V1_1_H723.h create mode 100644 Marlin/src/pins/stm32h7/pins_FYSETC_SPIDER_KING_V1_H723.h diff --git a/Marlin/src/core/boards.h b/Marlin/src/core/boards.h index 7cc9760e49..6fb8c5ac66 100644 --- a/Marlin/src/core/boards.h +++ b/Marlin/src/core/boards.h @@ -431,67 +431,68 @@ // STM32 ARM Cortex-M4F // -#define BOARD_ARMED 5200 // Arm'ed STM32F4-based controller -#define BOARD_RUMBA32_V1_0 5201 // RUMBA32 STM32F446VE based controller from Aus3D -#define BOARD_RUMBA32_V1_1 5202 // RUMBA32 STM32F446VE based controller from Aus3D -#define BOARD_RUMBA32_MKS 5203 // RUMBA32 STM32F446VE based controller from Makerbase -#define BOARD_RUMBA32_BTT 5204 // RUMBA32 STM32F446VE based controller from BIGTREETECH -#define BOARD_BLACK_STM32F407VE 5205 // Black STM32F407VE development board -#define BOARD_BLACK_STM32F407ZE 5206 // Black STM32F407ZE development board -#define BOARD_BTT_SKR_MINI_E3_V3_0_1 5207 // BigTreeTech SKR Mini E3 V3.0.1 (STM32F401RC) -#define BOARD_BTT_SKR_PRO_V1_1 5208 // BigTreeTech SKR Pro v1.1 (STM32F407ZG) -#define BOARD_BTT_SKR_PRO_V1_2 5209 // BigTreeTech SKR Pro v1.2 (STM32F407ZG) -#define BOARD_BTT_BTT002_V1_0 5210 // BigTreeTech BTT002 v1.0 (STM32F407VG) -#define BOARD_BTT_E3_RRF 5211 // BigTreeTech E3 RRF (STM32F407VG) -#define BOARD_BTT_SKR_V2_0_REV_A 5212 // BigTreeTech SKR v2.0 Rev A (STM32F407VG) -#define BOARD_BTT_SKR_V2_0_REV_B 5213 // BigTreeTech SKR v2.0 Rev B (STM32F407VG/STM32F429VG) -#define BOARD_BTT_GTR_V1_0 5214 // BigTreeTech GTR v1.0 (STM32F407IGT) -#define BOARD_BTT_OCTOPUS_V1_0 5215 // BigTreeTech Octopus v1.0 (STM32F446ZE) -#define BOARD_BTT_OCTOPUS_V1_1 5216 // BigTreeTech Octopus v1.1 (STM32F446ZE) -#define BOARD_BTT_OCTOPUS_PRO_V1_0 5217 // BigTreeTech Octopus Pro v1.0 (STM32F446ZE / STM32F429ZG) -#define BOARD_LERDGE_K 5218 // Lerdge K (STM32F407ZG) -#define BOARD_LERDGE_S 5219 // Lerdge S (STM32F407VE) -#define BOARD_LERDGE_X 5220 // Lerdge X (STM32F407VE) -#define BOARD_FYSETC_S6 5221 // FYSETC S6 (STM32F446VE) -#define BOARD_FYSETC_S6_V2_0 5222 // FYSETC S6 v2.0 (STM32F446VE) -#define BOARD_FYSETC_SPIDER 5223 // FYSETC Spider (STM32F446VE) -#define BOARD_FYSETC_SPIDER_V2_2 5224 // FYSETC Spider V2.2 (STM32F446VE) -#define BOARD_FLYF407ZG 5225 // FLYmaker FLYF407ZG (STM32F407ZG) -#define BOARD_MKS_ROBIN2 5226 // MKS Robin2 V1.0 (STM32F407ZE) -#define BOARD_MKS_ROBIN_PRO_V2 5227 // MKS Robin Pro V2 (STM32F407VE) -#define BOARD_MKS_ROBIN_NANO_V3 5228 // MKS Robin Nano V3 (STM32F407VG) -#define BOARD_MKS_ROBIN_NANO_V3_1 5229 // MKS Robin Nano V3.1 (STM32F407VE) -#define BOARD_MKS_MONSTER8_V1 5230 // MKS Monster8 V1 (STM32F407VE) -#define BOARD_MKS_MONSTER8_V2 5231 // MKS Monster8 V2 (STM32F407VE) -#define BOARD_ANET_ET4 5232 // ANET ET4 V1.x (STM32F407VG) -#define BOARD_ANET_ET4P 5233 // ANET ET4P V1.x (STM32F407VG) -#define BOARD_FYSETC_CHEETAH_V20 5234 // FYSETC Cheetah V2.0 (STM32F401RC) -#define BOARD_FYSETC_CHEETAH_V30 5235 // FYSETC Cheetah V3.0 (STM32F446RC) -#define BOARD_TH3D_EZBOARD_V2 5236 // TH3D EZBoard v2.0 (STM32F405RG) -#define BOARD_OPULO_LUMEN_REV3 5237 // Opulo Lumen PnP Controller REV3 (STM32F407VE / STM32F407VG) -#define BOARD_OPULO_LUMEN_REV4 5238 // Opulo Lumen PnP Controller REV4 (STM32F407VE / STM32F407VG) -#define BOARD_MKS_ROBIN_NANO_V1_3_F4 5239 // MKS Robin Nano V1.3 and MKS Robin Nano-S V1.3 (STM32F407VE) -#define BOARD_MKS_EAGLE 5240 // MKS Eagle (STM32F407VE) -#define BOARD_ARTILLERY_RUBY 5241 // Artillery Ruby (STM32F401RC) -#define BOARD_CREALITY_V24S1_301F4 5242 // Creality v2.4.S1_301F4 (STM32F401RC) as found in the Ender-3 S1 F4 -#define BOARD_CREALITY_CR4NTXXC10 5243 // Creality E3 Free-runs Silent Motherboard (STM32F401RET6) -#define BOARD_FYSETC_SPIDER_KING407 5244 // FYSETC Spider King407 (STM32F407ZG) -#define BOARD_MKS_SKIPR_V1 5245 // MKS SKIPR v1.0 all-in-one board (STM32F407VE) -#define BOARD_TRONXY_CXY_446_V10 5246 // TRONXY CXY-446-V10-220413/CXY-V6-191121 (STM32F446ZE) -#define BOARD_CREALITY_F401RE 5247 // Creality CR4NS200141C13 (STM32F401RE) as found in the Ender-5 S1 -#define BOARD_BLACKPILL_CUSTOM 5248 // Custom board based on STM32F401CDU6. -#define BOARD_I3DBEEZ9_V1 5249 // I3DBEEZ9 V1 (STM32F407ZG) -#define BOARD_MELLOW_FLY_E3_V2 5250 // Mellow Fly E3 V2 (STM32F407VG) -#define BOARD_BLACKBEEZMINI_V1 5251 // BlackBeezMini V1 (STM32F401CCU6) -#define BOARD_XTLW_CLIMBER_8TH 5252 // XTLW Climber-8th (STM32F407VGT6) -#define BOARD_FLY_RRF_E3_V1 5253 // Fly RRF E3 V1.0 (STM32F407VG) -#define BOARD_FLY_SUPER8 5254 // Fly SUPER8 (STM32F407ZGT6) -#define BOARD_FLY_D8 5255 // FLY D8 (STM32F407VG) -#define BOARD_FLY_CDY_V3 5256 // FLY CDY V3 (STM32F407VGT6) -#define BOARD_ZNP_ROBIN_NANO 5257 // Elegoo Neptune 2 v1.2 board -#define BOARD_ZNP_ROBIN_NANO_V1_3 5258 // Elegoo Neptune 2 v1.3 board -#define BOARD_MKS_NEPTUNE_X 5259 // Elegoo Neptune X -#define BOARD_MKS_NEPTUNE_3 5260 // Elegoo Neptune 3 +#define BOARD_ARMED 5200 // Arm'ed STM32F4-based controller +#define BOARD_RUMBA32_V1_0 5201 // RUMBA32 STM32F446VE based controller from Aus3D +#define BOARD_RUMBA32_V1_1 5202 // RUMBA32 STM32F446VE based controller from Aus3D +#define BOARD_RUMBA32_MKS 5203 // RUMBA32 STM32F446VE based controller from Makerbase +#define BOARD_RUMBA32_BTT 5204 // RUMBA32 STM32F446VE based controller from BIGTREETECH +#define BOARD_BLACK_STM32F407VE 5205 // Black STM32F407VE development board +#define BOARD_BLACK_STM32F407ZE 5206 // Black STM32F407ZE development board +#define BOARD_BTT_SKR_MINI_E3_V3_0_1 5207 // BigTreeTech SKR Mini E3 V3.0.1 (STM32F401RC) +#define BOARD_BTT_SKR_PRO_V1_1 5208 // BigTreeTech SKR Pro v1.1 (STM32F407ZG) +#define BOARD_BTT_SKR_PRO_V1_2 5209 // BigTreeTech SKR Pro v1.2 (STM32F407ZG) +#define BOARD_BTT_BTT002_V1_0 5210 // BigTreeTech BTT002 v1.0 (STM32F407VG) +#define BOARD_BTT_E3_RRF 5211 // BigTreeTech E3 RRF (STM32F407VG) +#define BOARD_BTT_SKR_V2_0_REV_A 5212 // BigTreeTech SKR v2.0 Rev A (STM32F407VG) +#define BOARD_BTT_SKR_V2_0_REV_B 5213 // BigTreeTech SKR v2.0 Rev B (STM32F407VG/STM32F429VG) +#define BOARD_BTT_GTR_V1_0 5214 // BigTreeTech GTR v1.0 (STM32F407IGT) +#define BOARD_BTT_OCTOPUS_V1_0 5215 // BigTreeTech Octopus v1.0 (STM32F446ZE) +#define BOARD_BTT_OCTOPUS_V1_1 5216 // BigTreeTech Octopus v1.1 (STM32F446ZE) +#define BOARD_BTT_OCTOPUS_PRO_V1_0 5217 // BigTreeTech Octopus Pro v1.0 (STM32F446ZE / STM32F429ZG) +#define BOARD_LERDGE_K 5218 // Lerdge K (STM32F407ZG) +#define BOARD_LERDGE_S 5219 // Lerdge S (STM32F407VE) +#define BOARD_LERDGE_X 5220 // Lerdge X (STM32F407VE) +#define BOARD_FYSETC_S6 5221 // FYSETC S6 (STM32F446VE) +#define BOARD_FYSETC_S6_V2_0 5222 // FYSETC S6 v2.0 (STM32F446VE) +#define BOARD_FYSETC_SPIDER 5223 // FYSETC Spider (STM32F446VE) +#define BOARD_FYSETC_SPIDER_V2_2 5224 // FYSETC Spider V2.2 (STM32F446VE) +#define BOARD_FLYF407ZG 5225 // FLYmaker FLYF407ZG (STM32F407ZG) +#define BOARD_MKS_ROBIN2 5226 // MKS Robin2 V1.0 (STM32F407ZE) +#define BOARD_MKS_ROBIN_PRO_V2 5227 // MKS Robin Pro V2 (STM32F407VE) +#define BOARD_MKS_ROBIN_NANO_V3 5228 // MKS Robin Nano V3 (STM32F407VG) +#define BOARD_MKS_ROBIN_NANO_V3_1 5229 // MKS Robin Nano V3.1 (STM32F407VE) +#define BOARD_MKS_MONSTER8_V1 5230 // MKS Monster8 V1 (STM32F407VE) +#define BOARD_MKS_MONSTER8_V2 5231 // MKS Monster8 V2 (STM32F407VE) +#define BOARD_ANET_ET4 5232 // ANET ET4 V1.x (STM32F407VG) +#define BOARD_ANET_ET4P 5233 // ANET ET4P V1.x (STM32F407VG) +#define BOARD_FYSETC_CHEETAH_V20 5234 // FYSETC Cheetah V2.0 (STM32F401RC) +#define BOARD_FYSETC_CHEETAH_V30 5235 // FYSETC Cheetah V3.0 (STM32F446RC) +#define BOARD_TH3D_EZBOARD_V2 5236 // TH3D EZBoard v2.0 (STM32F405RG) +#define BOARD_OPULO_LUMEN_REV3 5237 // Opulo Lumen PnP Controller REV3 (STM32F407VE / STM32F407VG) +#define BOARD_OPULO_LUMEN_REV4 5238 // Opulo Lumen PnP Controller REV4 (STM32F407VE / STM32F407VG) +#define BOARD_MKS_ROBIN_NANO_V1_3_F4 5239 // MKS Robin Nano V1.3 and MKS Robin Nano-S V1.3 (STM32F407VE) +#define BOARD_MKS_EAGLE 5240 // MKS Eagle (STM32F407VE) +#define BOARD_ARTILLERY_RUBY 5241 // Artillery Ruby (STM32F401RC) +#define BOARD_CREALITY_V24S1_301F4 5242 // Creality v2.4.S1_301F4 (STM32F401RC) as found in the Ender-3 S1 F4 +#define BOARD_CREALITY_CR4NTXXC10 5243 // Creality E3 Free-runs Silent Motherboard (STM32F401RET6) +#define BOARD_FYSETC_SPIDER_KING_V1_F407 5244 // FYSETC Spider King v1 (STM32F407ZG) +#define BOARD_FYSETC_SPIDER_KING_V1_1_F407 5245 // FYSETC Spider King v1.1 (STM32F407ZG) +#define BOARD_MKS_SKIPR_V1 5246 // MKS SKIPR v1.0 all-in-one board (STM32F407VE) +#define BOARD_TRONXY_CXY_446_V10 5247 // TRONXY CXY-446-V10-220413/CXY-V6-191121 (STM32F446ZE) +#define BOARD_CREALITY_F401RE 5248 // Creality CR4NS200141C13 (STM32F401RE) as found in the Ender-5 S1 +#define BOARD_BLACKPILL_CUSTOM 5249 // Custom board based on STM32F401CDU6. +#define BOARD_I3DBEEZ9_V1 5250 // I3DBEEZ9 V1 (STM32F407ZG) +#define BOARD_MELLOW_FLY_E3_V2 5251 // Mellow Fly E3 V2 (STM32F407VG) +#define BOARD_BLACKBEEZMINI_V1 5252 // BlackBeezMini V1 (STM32F401CCU6) +#define BOARD_XTLW_CLIMBER_8TH 5253 // XTLW Climber-8th (STM32F407VGT6) +#define BOARD_FLY_RRF_E3_V1 5254 // Fly RRF E3 V1.0 (STM32F407VG) +#define BOARD_FLY_SUPER8 5255 // Fly SUPER8 (STM32F407ZGT6) +#define BOARD_FLY_D8 5256 // FLY D8 (STM32F407VG) +#define BOARD_FLY_CDY_V3 5257 // FLY CDY V3 (STM32F407VGT6) +#define BOARD_ZNP_ROBIN_NANO 5258 // Elegoo Neptune 2 v1.2 board +#define BOARD_ZNP_ROBIN_NANO_V1_3 5259 // Elegoo Neptune 2 v1.3 board +#define BOARD_MKS_NEPTUNE_X 5260 // Elegoo Neptune X +#define BOARD_MKS_NEPTUNE_3 5261 // Elegoo Neptune 3 // // Other ARM Cortex-M4 @@ -502,22 +503,24 @@ // ARM Cortex-M7 // -#define BOARD_REMRAM_V1 6000 // RemRam v1 -#define BOARD_NUCLEO_F767ZI 6001 // ST NUCLEO-F767ZI Dev Board -#define BOARD_BTT_SKR_SE_BX_V2 6002 // BigTreeTech SKR SE BX V2.0 (STM32H743II) -#define BOARD_BTT_SKR_SE_BX_V3 6003 // BigTreeTech SKR SE BX V3.0 (STM32H743II) -#define BOARD_BTT_SKR_V3_0 6004 // BigTreeTech SKR V3.0 (STM32H743VI / STM32H723VG) -#define BOARD_BTT_SKR_V3_0_EZ 6005 // BigTreeTech SKR V3.0 EZ (STM32H743VI / STM32H723VG) -#define BOARD_BTT_OCTOPUS_MAX_EZ_V1_0 6006 // BigTreeTech Octopus Max EZ V1.0 (STM32H723ZE) -#define BOARD_BTT_OCTOPUS_PRO_V1_0_1 6007 // BigTreeTech Octopus Pro v1.0.1 (STM32H723ZE) -#define BOARD_BTT_OCTOPUS_PRO_V1_1 6008 // BigTreeTech Octopus Pro v1.1 (STM32H723ZE) -#define BOARD_BTT_MANTA_M8P_V2_0 6009 // BigTreeTech Manta M8P V2.0 (STM32H723ZE) -#define BOARD_BTT_KRAKEN_V1_0 6010 // BigTreeTech Kraken v1.0 (STM32H723ZG) -#define BOARD_TEENSY40 6011 // Teensy 4.0 -#define BOARD_TEENSY41 6012 // Teensy 4.1 -#define BOARD_T41U5XBB 6013 // T41U5XBB Teensy 4.1 breakout board -#define BOARD_FLY_D8_PRO 6014 // FLY_D8_PRO (STM32H723VG) -#define BOARD_FLY_SUPER8_PRO 6015 // FLY SUPER8 PRO (STM32H723ZG) +#define BOARD_REMRAM_V1 6000 // RemRam v1 +#define BOARD_NUCLEO_F767ZI 6001 // ST NUCLEO-F767ZI Dev Board +#define BOARD_BTT_SKR_SE_BX_V2 6002 // BigTreeTech SKR SE BX V2.0 (STM32H743II) +#define BOARD_BTT_SKR_SE_BX_V3 6003 // BigTreeTech SKR SE BX V3.0 (STM32H743II) +#define BOARD_BTT_SKR_V3_0 6004 // BigTreeTech SKR V3.0 (STM32H743VI / STM32H723VG) +#define BOARD_BTT_SKR_V3_0_EZ 6005 // BigTreeTech SKR V3.0 EZ (STM32H743VI / STM32H723VG) +#define BOARD_BTT_OCTOPUS_MAX_EZ_V1_0 6006 // BigTreeTech Octopus Max EZ V1.0 (STM32H723ZE) +#define BOARD_BTT_OCTOPUS_PRO_V1_0_1 6007 // BigTreeTech Octopus Pro v1.0.1 (STM32H723ZE) +#define BOARD_BTT_OCTOPUS_PRO_V1_1 6008 // BigTreeTech Octopus Pro v1.1 (STM32H723ZE) +#define BOARD_BTT_MANTA_M8P_V2_0 6009 // BigTreeTech Manta M8P V2.0 (STM32H723ZE) +#define BOARD_BTT_KRAKEN_V1_0 6010 // BigTreeTech Kraken v1.0 (STM32H723ZG) +#define BOARD_TEENSY40 6011 // Teensy 4.0 +#define BOARD_TEENSY41 6012 // Teensy 4.1 +#define BOARD_T41U5XBB 6013 // T41U5XBB Teensy 4.1 breakout board +#define BOARD_FLY_D8_PRO 6014 // FLY_D8_PRO (STM32H723VG) +#define BOARD_FLY_SUPER8_PRO 6015 // FLY SUPER8 PRO (STM32H723ZG) +#define BOARD_FYSETC_SPIDER_KING_V1_H723 6016 // FYSETC Spider King v1 (STM32H723ZG) +#define BOARD_FYSETC_SPIDER_KING_V1_1_H723 6017 // FYSETC Spider King v1.1 (STM32H723ZG) // // Espressif ESP32 WiFi diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index abe4673407..6f14e8b67a 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -786,8 +786,10 @@ #include "stm32f4/pins_CREALITY_V24S1_301F4.h" // STM32F4 env:STM32F401RC_creality env:STM32F401RC_creality_nobootloader env:STM32F401RC_creality_jlink env:STM32F401RC_creality_stlink #elif MB(CREALITY_CR4NTXXC10) #include "stm32f4/pins_CREALITY_CR4NTXXC10.h" // STM32F4 env:STM32F401RE_freeruns env:STM32F401RE_freeruns_jlink env:STM32F401RE_freeruns_stlink -#elif MB(FYSETC_SPIDER_KING407) - #include "stm32f4/pins_FYSETC_SPIDER_KING407.h" // STM32F4 env:FYSETC_SPIDER_KING407 +#elif MB(FYSETC_SPIDER_KING_V1_F407) + #include "stm32f4/pins_FYSETC_SPIDER_KING_V1.h" // STM32F4 env:STM32F407ZG_fysetc +#elif MB(FYSETC_SPIDER_KING_V1_1_F407) + #include "stm32f4/pins_FYSETC_SPIDER_KING_V1_1.h" // STM32F4 env:STM32F407ZG_fysetc #elif MB(MKS_SKIPR_V1) #include "stm32f4/pins_MKS_SKIPR_V1_0.h" // STM32F4 env:mks_skipr_v1 env:mks_skipr_v1_nobootloader #elif MB(TRONXY_CXY_446_V10) @@ -833,37 +835,41 @@ // #elif MB(REMRAM_V1) - #include "stm32f7/pins_REMRAM_V1.h" // STM32F7 env:REMRAM_V1 + #include "stm32f7/pins_REMRAM_V1.h" // STM32F7 env:REMRAM_V1 #elif MB(NUCLEO_F767ZI) - #include "stm32f7/pins_NUCLEO_F767ZI.h" // STM32F7 env:NUCLEO_F767ZI + #include "stm32f7/pins_NUCLEO_F767ZI.h" // STM32F7 env:NUCLEO_F767ZI #elif MB(BTT_SKR_SE_BX_V2) - #include "stm32h7/pins_BTT_SKR_SE_BX_V2.h" // STM32H7 env:BTT_SKR_SE_BX + #include "stm32h7/pins_BTT_SKR_SE_BX_V2.h" // STM32H7 env:BTT_SKR_SE_BX #elif MB(BTT_SKR_SE_BX_V3) - #include "stm32h7/pins_BTT_SKR_SE_BX_V3.h" // STM32H7 env:BTT_SKR_SE_BX + #include "stm32h7/pins_BTT_SKR_SE_BX_V3.h" // STM32H7 env:BTT_SKR_SE_BX #elif MB(BTT_SKR_V3_0) - #include "stm32h7/pins_BTT_SKR_V3_0.h" // STM32H7 env:STM32H743VI_btt env:STM32H723VG_btt + #include "stm32h7/pins_BTT_SKR_V3_0.h" // STM32H7 env:STM32H743VI_btt env:STM32H723VG_btt #elif MB(BTT_SKR_V3_0_EZ) - #include "stm32h7/pins_BTT_SKR_V3_0_EZ.h" // STM32H7 env:STM32H743VI_btt env:STM32H723VG_btt + #include "stm32h7/pins_BTT_SKR_V3_0_EZ.h" // STM32H7 env:STM32H743VI_btt env:STM32H723VG_btt #elif MB(BTT_OCTOPUS_MAX_EZ_V1_0) - #include "stm32h7/pins_BTT_OCTOPUS_MAX_EZ.h" // STM32H7 env:STM32H723ZE_btt + #include "stm32h7/pins_BTT_OCTOPUS_MAX_EZ.h" // STM32H7 env:STM32H723ZE_btt #elif MB(BTT_OCTOPUS_PRO_V1_0_1) - #include "stm32h7/pins_BTT_OCTOPUS_PRO_V1_0_1.h" // STM32H7 env:STM32H723ZE_btt + #include "stm32h7/pins_BTT_OCTOPUS_PRO_V1_0_1.h" // STM32H7 env:STM32H723ZE_btt #elif MB(BTT_OCTOPUS_PRO_V1_1) - #include "stm32h7/pins_BTT_OCTOPUS_PRO_V1_1.h" // STM32H7 env:STM32H723ZE_btt + #include "stm32h7/pins_BTT_OCTOPUS_PRO_V1_1.h" // STM32H7 env:STM32H723ZE_btt #elif MB(BTT_MANTA_M8P_V2_0) - #include "stm32h7/pins_BTT_MANTA_M8P_V2_0.h" // STM32H7 env:STM32H723ZE_btt + #include "stm32h7/pins_BTT_MANTA_M8P_V2_0.h" // STM32H7 env:STM32H723ZE_btt #elif MB(BTT_KRAKEN_V1_0) - #include "stm32h7/pins_BTT_KRAKEN_V1_0.h" // STM32H7 env:STM32H723ZG_btt + #include "stm32h7/pins_BTT_KRAKEN_V1_0.h" // STM32H7 env:STM32H723ZG_btt #elif MB(TEENSY40) - #include "teensy4/pins_TEENSY40.h" // Teensy-4.0 env:teensy40 + #include "teensy4/pins_TEENSY40.h" // Teensy-4.0 env:teensy40 #elif MB(TEENSY41) - #include "teensy4/pins_TEENSY41.h" // Teensy-4.1 env:teensy41 + #include "teensy4/pins_TEENSY41.h" // Teensy-4.1 env:teensy41 #elif MB(T41U5XBB) - #include "teensy4/pins_T41U5XBB.h" // Teensy-4.x env:teensy41 + #include "teensy4/pins_T41U5XBB.h" // Teensy-4.x env:teensy41 #elif MB(FLY_D8_PRO) - #include "stm32h7/pins_FLY_D8_PRO.h" // STM32H7 env:FLY_D8_PRO + #include "stm32h7/pins_FLY_D8_PRO.h" // STM32H7 env:FLY_D8_PRO #elif MB(FLY_SUPER8_PRO) - #include "stm32h7/pins_FLY_SUPER8_PRO.h" // STM32H7 env:FLY_SUPER8_PRO + #include "stm32h7/pins_FLY_SUPER8_PRO.h" // STM32H7 env:FLY_SUPER8_PRO +#elif MB(FYSETC_SPIDER_KING_V1_H723) + #include "stm32h7/pins_FYSETC_SPIDER_KING_V1_H723.h" // STM32H7 env:STM32H723ZG_fysetc +#elif MB(FYSETC_SPIDER_KING_V1_1_H723) + #include "stm32h7/pins_FYSETC_SPIDER_KING_V1_1_H723.h" // STM32H7 env:STM32H723ZG_fysetc // // Espressif ESP32 @@ -997,6 +1003,7 @@ #define BOARD_BTT_MANTA_M4P_V1_0 99927 #define BOARD_VAKE403D 99928 #define BOARD_TRONXY_V10 99929 + #define BOARD_FYSETC_SPIDER_KING407 99930 #if MB(MKS_13) #error "BOARD_MKS_13 is now BOARD_MKS_GEN_13. Please update your configuration." @@ -1058,6 +1065,8 @@ #error "BOARD_TRONXY_V10 is now BOARD_TRONXY_CXY_446_V10. Please update your configuration." #elif MB(VAKE403D) #error "BOARD_VAKE403D is no longer supported in Marlin." + #elif MB(FYSETC_SPIDER_KING407) + #error "BOARD_FYSETC_SPIDER_KING407 is now BOARD_FYSETC_SPIDER_KING_V1_F407 or BOARD_FYSETC_SPIDER_KING_V1_1_F407. Please update your configuration." #elif MB(ERROR) #warning "Most likely missing / misplaced Configuration files." #elif defined(MOTHERBOARD) @@ -1097,6 +1106,7 @@ #undef BOARD_BTT_MANTA_M4P_V1_0 #undef BOARD_VAKE403D #undef BOARD_TRONXY_V10 + #undef BOARD_FYSETC_SPIDER_KING407 #endif diff --git a/Marlin/src/pins/stm32f4/pins_FYSETC_SPIDER_KING_V1.h b/Marlin/src/pins/stm32f4/pins_FYSETC_SPIDER_KING_V1.h new file mode 100644 index 0000000000..014112dfcd --- /dev/null +++ b/Marlin/src/pins/stm32f4/pins_FYSETC_SPIDER_KING_V1.h @@ -0,0 +1,28 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2025 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_INFO_NAME + #define BOARD_INFO_NAME "Spider King V1.0" +#endif + +#include "pins_FYSETC_SPIDER_KING_common.h" diff --git a/Marlin/src/pins/stm32f4/pins_FYSETC_SPIDER_KING_V1_1.h b/Marlin/src/pins/stm32f4/pins_FYSETC_SPIDER_KING_V1_1.h new file mode 100644 index 0000000000..ac9ff0da1b --- /dev/null +++ b/Marlin/src/pins/stm32f4/pins_FYSETC_SPIDER_KING_V1_1.h @@ -0,0 +1,28 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2025 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_INFO_NAME + #define BOARD_INFO_NAME "Spider King V1.1" +#endif + +#include "pins_FYSETC_SPIDER_KING_common.h" diff --git a/Marlin/src/pins/stm32f4/pins_FYSETC_SPIDER_KING407.h b/Marlin/src/pins/stm32f4/pins_FYSETC_SPIDER_KING_common.h similarity index 83% rename from Marlin/src/pins/stm32f4/pins_FYSETC_SPIDER_KING407.h rename to Marlin/src/pins/stm32f4/pins_FYSETC_SPIDER_KING_common.h index e243f6cfcd..d6c2f8b2fc 100644 --- a/Marlin/src/pins/stm32f4/pins_FYSETC_SPIDER_KING407.h +++ b/Marlin/src/pins/stm32f4/pins_FYSETC_SPIDER_KING_common.h @@ -21,34 +21,51 @@ */ #pragma once -#include "env_validate.h" +// The FYSETC Spider King has shipped with both STM32F4 and STM32H7 MCUs. +// Ensure the correct env_validate.h file is included based on the build environment used. +#if NOT_TARGET(STM32H7) + #include "env_validate.h" +#else + #include "../stm32h7/env_validate.h" +#endif #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 +// EEPROM // -#if NO_EEPROM_SELECTED - #undef NO_EEPROM_SELECTED - //#define FLASH_EEPROM_EMULATION - //#define SRAM_EEPROM_EMULATION - #define I2C_EEPROM -#endif +#if NOT_TARGET(STM32H7) + // I2C EEPROM for STM32F4. Does not work on Spider King with STM32H7 MCU. + #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 0x1000U // 4KB + #if ENABLED(I2C_EEPROM) + #define I2C_EEPROM + #define I2C_SCL_PIN PF1 + #define I2C_SDA_PIN PF0 + #define MARLIN_EEPROM_SIZE 0x1000 // 4KB + #endif +#else + // Emulated EEPROM for STM32H7 + #if ANY(NO_EEPROM_SELECTED, FLASH_EEPROM_EMULATION) + #undef NO_EEPROM_SELECTED + #ifndef FLASH_EEPROM_EMULATION + #define FLASH_EEPROM_EMULATION + #endif + #define EEPROM_PAGE_SIZE (0x800UL) // 2K + #define EEPROM_START_ADDRESS (0x8000000UL + (STM32_FLASH_SIZE) * 1024UL - (EEPROM_PAGE_SIZE) * 2UL) + #define MARLIN_EEPROM_SIZE EEPROM_PAGE_SIZE + #endif #endif // @@ -57,7 +74,14 @@ #define SERVO0_PIN PA1 // -// Software SPI pins for TMC2130 stepper drivers +// Probe enable +// +#if ENABLED(PROBE_ENABLE_DISABLE) && !defined(PROBE_ENABLE_PIN) + #define PROBE_ENABLE_PIN SERVO0_PIN +#endif + +// +// Software SPI pins for TMC stepper drivers // #define TMC_USE_SW_SPI #if ENABLED(TMC_USE_SW_SPI) @@ -337,9 +361,19 @@ #define BOARD_ST7920_DELAY_3 640 #endif -// -// Wifi module -// +/** + * ------- + * GND | 9 8 | 3.3V + * (ESP-CS) PB12 | 10 7 | PB15 (ESP-MOSI) + * 3.3V | 11 6 | PB14 (ESP-MISO) + * (ESP-IO0) PD7 | 12 5 | PB13 (ESP-CLK) + * (ESP-IO4) PD10 | 13 4 | -- + * -- | 14 3 | PE15 (ESP-EN) + * (ESP-RX) PD8 | 15 2 | -- + * (ESP-TX) PD9 | 16 1 | PE14 (ESP-RST) + * ------- + * WIFI + */ #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 @@ -349,7 +383,15 @@ // // NeoPixel LED +// FYSETC_242_OLED_12864 & FYSETC_MINI_12864_2_1 uses one of the EXP pins for NeoPixels // -#ifndef NEOPIXEL_PIN - #define NEOPIXEL_PIN PD3 +#if ANY(FYSETC_242_OLED_12864, FYSETC_MINI_12864_2_1) + // Allow dedicated RGB (NeoPixel) pin to be used for a NeoPixel strip + #ifndef NEOPIXEL2_PIN + #define NEOPIXEL2_PIN PD3 // Neo-pixel + #endif +#else + #ifndef NEOPIXEL_PIN + #define NEOPIXEL_PIN PD3 // Neo-pixel + #endif #endif diff --git a/Marlin/src/pins/stm32h7/pins_FYSETC_SPIDER_KING_V1_1_H723.h b/Marlin/src/pins/stm32h7/pins_FYSETC_SPIDER_KING_V1_1_H723.h new file mode 100644 index 0000000000..44f54bb122 --- /dev/null +++ b/Marlin/src/pins/stm32h7/pins_FYSETC_SPIDER_KING_V1_1_H723.h @@ -0,0 +1,29 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2025 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_INFO_NAME + #define BOARD_INFO_NAME "Spider King V1.1" +#endif + +#include "../stm32f4/pins_FYSETC_SPIDER_KING_common.h" diff --git a/Marlin/src/pins/stm32h7/pins_FYSETC_SPIDER_KING_V1_H723.h b/Marlin/src/pins/stm32h7/pins_FYSETC_SPIDER_KING_V1_H723.h new file mode 100644 index 0000000000..551d367e28 --- /dev/null +++ b/Marlin/src/pins/stm32h7/pins_FYSETC_SPIDER_KING_V1_H723.h @@ -0,0 +1,29 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2025 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_INFO_NAME + #define BOARD_INFO_NAME "Spider King V1.0" +#endif + +#include "../stm32f4/pins_FYSETC_SPIDER_KING_common.h" diff --git a/ini/renamed.ini b/ini/renamed.ini index 4f9ce0793d..93f8afa43f 100644 --- a/ini/renamed.ini +++ b/ini/renamed.ini @@ -146,3 +146,6 @@ extends = renamed [env:FYSETC_S6_8000] ;=> STM32F446VE_fysetc_32k_bootloader extends = renamed + +[env:FYSETC_SPIDER_KING407] ;=> STM32F407ZG_fysetc +extends = renamed diff --git a/ini/stm32f4.ini b/ini/stm32f4.ini index b736cbd0f4..722e73b396 100644 --- a/ini/stm32f4.ini +++ b/ini/stm32f4.ini @@ -126,9 +126,9 @@ board_upload.offset_address = 0x08008000 upload_command = dfu-util -a 0 -s 0x08008000:leave -D "$SOURCE" # -# FYSETC SPIDER KING407 (STM32F407ZGT6 ARM Cortex-M4) +# FYSETC Spider King v1.x (STM32F407ZGT6 ARM Cortex-M4) # -[env:FYSETC_SPIDER_KING407] +[env:STM32F407ZG_fysetc] extends = stm32_variant platform_packages = platformio/tool-dfuutil@~1.11.0 board = marlin_STM32F407ZGT6 diff --git a/ini/stm32h7.ini b/ini/stm32h7.ini index 0bc35352cf..8ddb37590e 100644 --- a/ini/stm32h7.ini +++ b/ini/stm32h7.ini @@ -100,9 +100,9 @@ extends = STM32H723Vx_btt board = marlin_STM32H723VG # -# BigTreeTech STM32H723Zx ARM Cortex-M7 Common +# STM32H723Zx ARM Cortex-M7 Common # -[STM32H723Zx_btt] +[STM32H723Zx_common] extends = stm32_variant platform = ststm32@15.4.1 platform_packages = framework-arduinoststm32@~4.20200.220530 @@ -128,14 +128,14 @@ debug_tool = cmsis-dap # BigTreeTech Octopus Pro V1.0.1/1.1 / Octopus Max EZ V1.0 / Manta M8P V2.0 (STM32H723ZET6 ARM Cortex-M7) # [env:STM32H723ZE_btt] -extends = STM32H723Zx_btt +extends = STM32H723Zx_common board = marlin_STM32H723ZE # # BigTreeTech Kraken V1.0 (STM32H723ZGT6 ARM Cortex-M7) # [env:STM32H723ZG_btt] -extends = STM32H723Zx_btt +extends = STM32H723Zx_common board = marlin_STM32H723ZG # @@ -172,3 +172,10 @@ build_flags = ${stm32_variant.build_flags} -DUSE_USB_HS -DUSE_USB_HS_IN_FS -DD_CACHE_DISABLED upload_protocol = dfu + +# +# FYSETC Spider King v1.x (STM32H723ZGT6 ARM Cortex-M7) +# +[env:STM32H723ZG_fysetc] +extends = STM32H723Zx_common +board = marlin_STM32H723ZG From 1774dbd53997ca4113cb97b6ff4a2d3aab765586 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 3 Nov 2025 17:51:55 -0600 Subject: [PATCH 24/99] =?UTF-8?q?=F0=9F=A9=B9=20Fix=20'interval'=20type=20?= =?UTF-8?q?warning?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Resolves #28156 --- Marlin/src/module/stepper.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index 184f039608..d44060e815 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -1586,7 +1586,7 @@ void Stepper::isr() { #endif // Get the interval to the next ISR call - interval = uint32_t(STEPPER_TIMER_RATE * 0.030); // Max wait of 30ms regardless of stepper timer frequency + interval = hal_timer_t(STEPPER_TIMER_RATE * 0.03); // Max wait of 30ms regardless of stepper timer frequency NOMORE(interval, nextMainISR); // Time until the next Pulse / Block phase TERN_(INPUT_SHAPING_X, NOMORE(interval, ShapingQueue::peek_x())); // Time until next input shaping echo for X TERN_(INPUT_SHAPING_Y, NOMORE(interval, ShapingQueue::peek_y())); // Time until next input shaping echo for Y From 6b14b948a912d38a9d748b8629738c2e83506662 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Tue, 4 Nov 2025 00:31:21 +0000 Subject: [PATCH 25/99] [cron] Bump distribution date (2025-11-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 a6f3898c00..6b7a73b667 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 "2025-11-03" +//#define STRING_DISTRIBUTION_DATE "2025-11-04" /** * The protocol for communication to the host. Protocol indicates communication diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index c1b2af6868..2e3caedf75 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 "2025-11-03" + #define STRING_DISTRIBUTION_DATE "2025-11-04" #endif /** From ac5836a2a2937728e453ff62f7bfb72f571bae93 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 4 Nov 2025 01:16:23 -0600 Subject: [PATCH 26/99] =?UTF-8?q?=F0=9F=94=A8=20Bring=20Makefile=20up=20to?= =?UTF-8?q?=20date?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Makefile | 122 +++++++++++++++++++++------------------ Marlin/src/core/boards.h | 10 ++-- 2 files changed, 70 insertions(+), 62 deletions(-) diff --git a/Marlin/Makefile b/Marlin/Makefile index fb1786b6b0..aed2506ac8 100644 --- a/Marlin/Makefile +++ b/Marlin/Makefile @@ -188,15 +188,15 @@ else ifeq ($(HARDWARE_MOTHERBOARD),1033) else ifeq ($(HARDWARE_MOTHERBOARD),1034) # RAMPS 1.6+ (Power outputs: Hotend, Fan, Bed) -else ifeq ($(HARDWARE_MOTHERBOARD),1035) +else ifeq ($(HARDWARE_MOTHERBOARD),1040) # RAMPS 1.6+ (Power outputs: Hotend0, Hotend1, Bed) -else ifeq ($(HARDWARE_MOTHERBOARD),1036) +else ifeq ($(HARDWARE_MOTHERBOARD),1041) # RAMPS 1.6+ (Power outputs: Hotend, Fan0, Fan1) -else ifeq ($(HARDWARE_MOTHERBOARD),1037) +else ifeq ($(HARDWARE_MOTHERBOARD),1042) # RAMPS 1.6+ (Power outputs: Hotend0, Hotend1, Fan) -else ifeq ($(HARDWARE_MOTHERBOARD),1038) +else ifeq ($(HARDWARE_MOTHERBOARD),1043) # RAMPS 1.6+ (Power outputs: Spindle, Controller Fan) -else ifeq ($(HARDWARE_MOTHERBOARD),1039) +else ifeq ($(HARDWARE_MOTHERBOARD),1044) # # RAMPS Derivatives - ATmega1280, ATmega2560 @@ -286,60 +286,62 @@ else ifeq ($(HARDWARE_MOTHERBOARD),1138) else ifeq ($(HARDWARE_MOTHERBOARD),1139) # Creality: CR10S, CR20, CR-X else ifeq ($(HARDWARE_MOTHERBOARD),1140) -# Dagoma F5 +# Creality CR-10 V2, CR-10 V3 else ifeq ($(HARDWARE_MOTHERBOARD),1141) -# Dagoma D6 (as found in the Dagoma DiscoUltimate V2 TMC) +# Dagoma F5 else ifeq ($(HARDWARE_MOTHERBOARD),1142) -# FYSETC F6 1.3 +# Dagoma D6 (as found in the Dagoma DiscoUltimate V2 TMC) else ifeq ($(HARDWARE_MOTHERBOARD),1143) -# FYSETC F6 1.4 +# FYSETC F6 1.3 else ifeq ($(HARDWARE_MOTHERBOARD),1144) -# Wanhao Duplicator i3 Plus +# FYSETC F6 1.4 else ifeq ($(HARDWARE_MOTHERBOARD),1145) -# VORON Design +# Wanhao Duplicator i3 Plus else ifeq ($(HARDWARE_MOTHERBOARD),1146) -# Tronxy TRONXY-V3-1.0 +# VORON Design else ifeq ($(HARDWARE_MOTHERBOARD),1147) -# Z-Bolt X Series +# Tronxy TRONXY-V3-1.0 else ifeq ($(HARDWARE_MOTHERBOARD),1148) -# TT OSCAR +# Z-Bolt X Series else ifeq ($(HARDWARE_MOTHERBOARD),1149) -# BIQU Tango V1 +# TT OSCAR else ifeq ($(HARDWARE_MOTHERBOARD),1150) -# MKS GEN L V2 +# BIQU Tango V1 else ifeq ($(HARDWARE_MOTHERBOARD),1151) -# MKS GEN L V2.1 +# MKS GEN L V2 else ifeq ($(HARDWARE_MOTHERBOARD),1152) -# Copymaster 3D +# MKS GEN L V2.1 else ifeq ($(HARDWARE_MOTHERBOARD),1153) -# Ortur 4 +# Copymaster 3D else ifeq ($(HARDWARE_MOTHERBOARD),1154) -# Tenlog D3 Hero IDEX printer +# Ortur 4 else ifeq ($(HARDWARE_MOTHERBOARD),1155) -# Tenlog D3, D5, D6 IDEX Printer +# Tenlog D3 Hero IDEX printer else ifeq ($(HARDWARE_MOTHERBOARD),1156) -# Ramps S 1.2 by Sakul.cz (Power outputs: Hotend0, Hotend1, Fan, Bed) +# Tenlog D3, D5, D6 IDEX Printer else ifeq ($(HARDWARE_MOTHERBOARD),1157) -# Ramps S 1.2 by Sakul.cz (Power outputs: Hotend0, Hotend1, Hotend2, Bed) +# Ramps S 1.2 by Sakul.cz (Power outputs: Hotend0, Hotend1, Fan, Bed) else ifeq ($(HARDWARE_MOTHERBOARD),1158) -# Ramps S 1.2 by Sakul.cz (Power outputs: Hotend, Fan0, Fan1, Bed) +# Ramps S 1.2 by Sakul.cz (Power outputs: Hotend0, Hotend1, Hotend2, Bed) else ifeq ($(HARDWARE_MOTHERBOARD),1159) -# Longer LK1 PRO / Alfawise U20 Pro (PRO version) +# Ramps S 1.2 by Sakul.cz (Power outputs: Hotend, Fan0, Fan1, Bed) else ifeq ($(HARDWARE_MOTHERBOARD),1160) -# Longer LKx PRO / Alfawise Uxx Pro (PRO version) +# Longer LK1 PRO / Alfawise U20 Pro (PRO version) else ifeq ($(HARDWARE_MOTHERBOARD),1161) -# Pxmalion Core I3 +# Longer LKx PRO / Alfawise Uxx Pro (PRO version) else ifeq ($(HARDWARE_MOTHERBOARD),1162) -# Panowin Cutlass (as found in the Panowin F1) +# Pxmalion Core I3 else ifeq ($(HARDWARE_MOTHERBOARD),1163) -# Kodama Bardo V1.x (as found in the Kodama Trinus) +# Panowin Cutlass (as found in the Panowin F1) else ifeq ($(HARDWARE_MOTHERBOARD),1164) -# XTLW MFF V1.0 +# Kodama Bardo V1.x (as found in the Kodama Trinus) else ifeq ($(HARDWARE_MOTHERBOARD),1165) -# XTLW MFF V2.0 +# XTLW MFF V1.0 else ifeq ($(HARDWARE_MOTHERBOARD),1166) -# E3D Rumba BigBox +# XTLW MFF V2.0 else ifeq ($(HARDWARE_MOTHERBOARD),1167) +# E3D Rumba BigBox +else ifeq ($(HARDWARE_MOTHERBOARD),1168) # # RAMBo and derivatives @@ -408,32 +410,34 @@ else ifeq ($(HARDWARE_MOTHERBOARD),1319) else ifeq ($(HARDWARE_MOTHERBOARD),1320) # Geeetech GT2560 Rev B for A20(M/T/D) else ifeq ($(HARDWARE_MOTHERBOARD),1321) -# Einstart retrofit -else ifeq ($(HARDWARE_MOTHERBOARD),1322) -# Wanhao 0ne+ i3 Mini -else ifeq ($(HARDWARE_MOTHERBOARD),1323) -# Overlord/Overlord Pro -else ifeq ($(HARDWARE_MOTHERBOARD),1324) -# ADIMLab Gantry v1 -else ifeq ($(HARDWARE_MOTHERBOARD),1325) -# ADIMLab Gantry v2 -else ifeq ($(HARDWARE_MOTHERBOARD),1326) -# Leapfrog Xeed 2015 -else ifeq ($(HARDWARE_MOTHERBOARD),1327) -# PICA Shield (original version) -else ifeq ($(HARDWARE_MOTHERBOARD),1328) -# PICA Shield (rev C or later) -else ifeq ($(HARDWARE_MOTHERBOARD),1329) -# Intamsys 4.0 (Funmat HT) -else ifeq ($(HARDWARE_MOTHERBOARD),1330) -# Malyan M180 Mainboard Version 2 (no display function, direct G-code only) -else ifeq ($(HARDWARE_MOTHERBOARD),1331) -# Mega controller & Protoneer CNC Shield V3.00 -else ifeq ($(HARDWARE_MOTHERBOARD),1332) -# WEEDO 62A board (TINA2, Monoprice Cadet, etc.) -else ifeq ($(HARDWARE_MOTHERBOARD),1333) # Geeetech GT2560 V4.1B for A10(M/T/D) +else ifeq ($(HARDWARE_MOTHERBOARD),1322) +# Einstart retrofit +else ifeq ($(HARDWARE_MOTHERBOARD),1323) +# Wanhao 0ne+ i3 Mini +else ifeq ($(HARDWARE_MOTHERBOARD),1324) +# Wanhao D9 MK2 +else ifeq ($(HARDWARE_MOTHERBOARD),1325) +# Overlord/Overlord Pro +else ifeq ($(HARDWARE_MOTHERBOARD),1326) +# ADIMLab Gantry v1 +else ifeq ($(HARDWARE_MOTHERBOARD),1327) +# ADIMLab Gantry v2 +else ifeq ($(HARDWARE_MOTHERBOARD),1328) +# Leapfrog Xeed 2015 +else ifeq ($(HARDWARE_MOTHERBOARD),1329) +# PICA Shield (original version) +else ifeq ($(HARDWARE_MOTHERBOARD),1330) +# PICA Shield (rev C or later) +else ifeq ($(HARDWARE_MOTHERBOARD),1331) +# Intamsys 4.0 (Funmat HT) +else ifeq ($(HARDWARE_MOTHERBOARD),1332) +# Malyan M180 Mainboard Version 2 +else ifeq ($(HARDWARE_MOTHERBOARD),1333) +# Mega controller & Protoneer CNC Shield V3.00 else ifeq ($(HARDWARE_MOTHERBOARD),1334) +# WEEDO 62A board (TINA2, Monoprice Cadet, etc.) +else ifeq ($(HARDWARE_MOTHERBOARD),1335) # # ATmega1281, ATmega2561 @@ -513,7 +517,7 @@ else ifeq ($(HARDWARE_MOTHERBOARD),1511) MCU ?= atmega1284p PROG_MCU ?= m1284p # ZoneStar ZMIB V2 -else ifeq ($(HARDWARE_MOTHERBOARD),1511) +else ifeq ($(HARDWARE_MOTHERBOARD),1512) HARDWARE_VARIANT ?= Sanguino MCU ?= atmega1284p PROG_MCU ?= m1284p @@ -627,6 +631,10 @@ else ifeq ($(HARDWARE_MOTHERBOARD),1707) MCU ?= at90usb1286 PROG_MCU ?= usb1286 +# +# SAM3X8E ARM Cortex-M3 +# + # UltiMachine Archim1 (with DRV8825 drivers) else ifeq ($(HARDWARE_MOTHERBOARD),3023) HARDWARE_VARIANT ?= archim diff --git a/Marlin/src/core/boards.h b/Marlin/src/core/boards.h index 6fb8c5ac66..f22c9fd1f1 100644 --- a/Marlin/src/core/boards.h +++ b/Marlin/src/core/boards.h @@ -55,11 +55,11 @@ #define BOARD_RAMPS_PLUS_EEF 1033 // RAMPS Plus 3DYMY (Power outputs: Hotend0, Hotend1, Fan) #define BOARD_RAMPS_PLUS_SF 1034 // RAMPS Plus 3DYMY (Power outputs: Spindle, Controller Fan) -#define BOARD_RAMPS_BTT_16_PLUS_EFB 1035 // RAMPS 1.6+ (Power outputs: Hotend, Fan, Bed) -#define BOARD_RAMPS_BTT_16_PLUS_EEB 1036 // RAMPS 1.6+ (Power outputs: Hotend0, Hotend1, Bed) -#define BOARD_RAMPS_BTT_16_PLUS_EFF 1037 // RAMPS 1.6+ (Power outputs: Hotend, Fan0, Fan1) -#define BOARD_RAMPS_BTT_16_PLUS_EEF 1038 // RAMPS 1.6+ (Power outputs: Hotend0, Hotend1, Fan) -#define BOARD_RAMPS_BTT_16_PLUS_SF 1039 // RAMPS 1.6+ (Power outputs: Spindle, Controller Fan) +#define BOARD_RAMPS_BTT_16_PLUS_EFB 1040 // RAMPS 1.6+ (Power outputs: Hotend, Fan, Bed) +#define BOARD_RAMPS_BTT_16_PLUS_EEB 1041 // RAMPS 1.6+ (Power outputs: Hotend0, Hotend1, Bed) +#define BOARD_RAMPS_BTT_16_PLUS_EFF 1042 // RAMPS 1.6+ (Power outputs: Hotend, Fan0, Fan1) +#define BOARD_RAMPS_BTT_16_PLUS_EEF 1043 // RAMPS 1.6+ (Power outputs: Hotend0, Hotend1, Fan) +#define BOARD_RAMPS_BTT_16_PLUS_SF 1044 // RAMPS 1.6+ (Power outputs: Spindle, Controller Fan) // // RAMPS Derivatives - ATmega1280, ATmega2560 From 8547f4f5b921cfafe56fbdf73ef764b801f40f2b Mon Sep 17 00:00:00 2001 From: ellensp <530024+ellensp@users.noreply.github.com> Date: Tue, 4 Nov 2025 20:31:57 +1300 Subject: [PATCH 27/99] =?UTF-8?q?=F0=9F=94=A8=F0=9F=90=9B=20Don't=20use=20?= =?UTF-8?q?broken=20'board=20=3D=20fysetc=5Ff6=5F13'=20(#28159)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .github/workflows/ci-build-tests.yml | 2 +- Marlin/src/pins/pins.h | 4 ++-- buildroot/tests/{FYSETC_F6 => mega2560ext} | 2 +- ini/avr.ini | 7 ------- ini/renamed.ini | 3 +++ 5 files changed, 7 insertions(+), 11 deletions(-) rename buildroot/tests/{FYSETC_F6 => mega2560ext} (98%) diff --git a/.github/workflows/ci-build-tests.yml b/.github/workflows/ci-build-tests.yml index b3b0c94243..5d53536a27 100644 --- a/.github/workflows/ci-build-tests.yml +++ b/.github/workflows/ci-build-tests.yml @@ -58,7 +58,7 @@ jobs: - at90usb1286_dfu # AVR Extended - - FYSETC_F6 + - mega2560ext - melzi_optiboot - rambo - sanguino1284p diff --git a/Marlin/src/pins/pins.h b/Marlin/src/pins/pins.h index 6f14e8b67a..e73a00ae81 100644 --- a/Marlin/src/pins/pins.h +++ b/Marlin/src/pins/pins.h @@ -184,9 +184,9 @@ #elif MB(DAGOMA_D6) #include "ramps/pins_DAGOMA_D6.h" // ATmega2560 env:mega2560ext #elif MB(FYSETC_F6_13) - #include "ramps/pins_FYSETC_F6_13.h" // ATmega2560 env:FYSETC_F6 + #include "ramps/pins_FYSETC_F6_13.h" // ATmega2560 env:mega2560ext #elif MB(FYSETC_F6_14) - #include "ramps/pins_FYSETC_F6_14.h" // ATmega2560 env:FYSETC_F6 + #include "ramps/pins_FYSETC_F6_14.h" // ATmega2560 env:mega2560ext #elif MB(DUPLICATOR_I3_PLUS) #include "ramps/pins_DUPLICATOR_I3_PLUS.h" // ATmega2560 env:mega2560 #elif MB(VORON) diff --git a/buildroot/tests/FYSETC_F6 b/buildroot/tests/mega2560ext similarity index 98% rename from buildroot/tests/FYSETC_F6 rename to buildroot/tests/mega2560ext index 6337fab5fc..b1bd97b433 100755 --- a/buildroot/tests/FYSETC_F6 +++ b/buildroot/tests/mega2560ext @@ -1,6 +1,6 @@ #!/usr/bin/env bash # -# Build tests for AVR ATmega FYSETC F6 1.3 +# Build tests for mega2560ext - AVR ATmega (extended) # # exit on first failure diff --git a/ini/avr.ini b/ini/avr.ini index 5e7861037d..6d2b46525e 100644 --- a/ini/avr.ini +++ b/ini/avr.ini @@ -87,13 +87,6 @@ board = megaatmega2560 extends = common_avr8 board = reprap_rambo -# -# FYSETC F6 V1.3 / V1.4 -# -[env:FYSETC_F6] -extends = common_avr8 -board = fysetc_f6_13 - # # Sanguinololu (ATmega644p) # diff --git a/ini/renamed.ini b/ini/renamed.ini index 93f8afa43f..121518b202 100644 --- a/ini/renamed.ini +++ b/ini/renamed.ini @@ -149,3 +149,6 @@ extends = renamed [env:FYSETC_SPIDER_KING407] ;=> STM32F407ZG_fysetc extends = renamed + +[env:FYSETC_F6] ;=> mega2560ext +extends = renamed From e0f0a9491df801441308054f686caaf7b3a93bdd Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Wed, 5 Nov 2025 00:32:26 +0000 Subject: [PATCH 28/99] [cron] Bump distribution date (2025-11-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 6b7a73b667..a520d3f4a2 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 "2025-11-04" +//#define STRING_DISTRIBUTION_DATE "2025-11-05" /** * The protocol for communication to the host. Protocol indicates communication diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 2e3caedf75..bb17221017 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 "2025-11-04" + #define STRING_DISTRIBUTION_DATE "2025-11-05" #endif /** From 924c2ca0fefe08d146709f9a60944b5e6182875d Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 5 Nov 2025 19:16:43 -0600 Subject: [PATCH 29/99] =?UTF-8?q?=F0=9F=8E=A8=20Fix=20style=20snafus?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../cocoa_press/status_screen.cpp | 2 +- Marlin/src/module/ft_motion.cpp | 16 ++++++++-------- Marlin/src/module/stepper.cpp | 6 +++--- 3 files changed, 12 insertions(+), 12 deletions(-) diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/status_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/status_screen.cpp index 65ac4551b9..d1e2d52916 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/status_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/cocoa_press/status_screen.cpp @@ -111,7 +111,7 @@ void StatusScreen::send_buffer(CommandProcessor &cmd, const void *data, uint16_t const char *ptr = (const char*) data; constexpr uint16_t block_size = 512; char block[block_size]; - for (;len > 0;) { + while (len > 0) { const uint16_t nBytes = min(len, block_size); memcpy_P(block, ptr, nBytes); cmd.write((const void*)block, nBytes); diff --git a/Marlin/src/module/ft_motion.cpp b/Marlin/src/module/ft_motion.cpp index 029c620500..6f79f566fc 100644 --- a/Marlin/src/module/ft_motion.cpp +++ b/Marlin/src/module/ft_motion.cpp @@ -75,8 +75,8 @@ TrajectoryType FTMotion::trajectoryType = TrajectoryType::FTM_TRAJECTORY_TYPE; stepper_plan_t FTMotion::stepper_plan_buff[FTM_BUFFER_SIZE]; XYZEval FTMotion::curr_steps_q32_32 = {0}; -uint32_t FTMotion::stepper_plan_tail = 0, // The index to consume from - FTMotion::stepper_plan_head = 0; // The index to produce into +uint32_t FTMotion::stepper_plan_tail = 0, // The index to consume from + FTMotion::stepper_plan_head = 0; // The index to produce into #if FTM_HAS_LIN_ADVANCE bool FTMotion::use_advance_lead; @@ -240,16 +240,16 @@ void FTMotion::discard_planner_block_protected() { uint32_t FTMotion::calc_runout_samples() { xyze_long_t delay = {0}; #if ENABLED(FTM_SMOOTHING) - #define _ADD(A) delay.A += smoothing.A.delay_samples; - LOGICAL_AXIS_MAP(_ADD) - #undef _ADD + #define _DELAY_ADD(A) delay.A += smoothing.A.delay_samples; + LOGICAL_AXIS_MAP(_DELAY_ADD) + #undef _DELAY_ADD #endif #if HAS_FTM_SHAPING // Ni[max_i] is the delay of the last pulse, but it is relative to Ni[0] (the negative delay centroid) - #define _ADD(A) if(shaping.A.ena) delay.A += shaping.A.Ni[shaping.A.max_i] - shaping.A.Ni[0]; - SHAPED_MAP(_ADD) - #undef _ADD + #define _DELAY_ADD(A) if (shaping.A.ena) delay.A += shaping.A.Ni[shaping.A.max_i] - shaping.A.Ni[0]; + SHAPED_MAP(_DELAY_ADD) + #undef _DELAY_ADD #endif return delay.large(); } diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index d44060e815..be8cb766e6 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -2474,7 +2474,7 @@ hal_timer_t Stepper::block_phase_isr() { else cutter.apply_power(0); } #endif - TERN_(SMOOTH_LIN_ADVANCE, curr_step_rate = acc_step_rate;) + TERN_(SMOOTH_LIN_ADVANCE, curr_step_rate = acc_step_rate); } // Are we in Deceleration phase ? else if (step_events_completed >= decelerate_start) { @@ -2548,7 +2548,7 @@ hal_timer_t Stepper::block_phase_isr() { } } #endif - TERN_(SMOOTH_LIN_ADVANCE, curr_step_rate = step_rate;) + TERN_(SMOOTH_LIN_ADVANCE, curr_step_rate = step_rate); } else { // Must be in cruise phase otherwise @@ -2558,7 +2558,7 @@ hal_timer_t Stepper::block_phase_isr() { ticks_nominal = calc_multistep_timer_interval(current_block->nominal_rate << oversampling_factor); // Prepare for deceleration IF_DISABLED(S_CURVE_ACCELERATION, acc_step_rate = current_block->nominal_rate); - TERN_(SMOOTH_LIN_ADVANCE, curr_step_rate = current_block->nominal_rate;) + TERN_(SMOOTH_LIN_ADVANCE, curr_step_rate = current_block->nominal_rate); deceleration_time = ticks_nominal / 2; // Apply Nonlinear Extrusion, if enabled From ce7edc6223ff1a212cb4fb0ba9dc1d0b5053a3b3 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 5 Nov 2025 19:18:23 -0600 Subject: [PATCH 30/99] =?UTF-8?q?=F0=9F=A7=91=E2=80=8D=F0=9F=92=BB=20Save?= =?UTF-8?q?=20some=20string=20space?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp | 10 +++++----- Marlin/src/gcode/feature/ft_motion/M493.cpp | 12 ++++++------ Marlin/src/gcode/feature/ft_motion/M494.cpp | 6 +++--- Marlin/src/module/settings.cpp | 2 +- 4 files changed, 15 insertions(+), 15 deletions(-) diff --git a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp index 1f43508ead..5ba817ea3e 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp @@ -397,7 +397,7 @@ void unified_bed_leveling::G29() { if (parser.seen('Q')) { const int16_t test_pattern = parser.has_value() ? parser.value_int() : -99; if (!WITHIN(test_pattern, TERN0(UBL_DEVEL_DEBUGGING, -1), 2)) { - SERIAL_ECHOLNPGM("?Invalid (Q) test pattern. (" TERN(UBL_DEVEL_DEBUGGING, "-1", "0") " to 2)\n"); + SERIAL_ECHOLN(F("?Invalid "), F("(Q) test pattern. (" TERN(UBL_DEVEL_DEBUGGING, "-1", "0") " to 2)\n")); return; } SERIAL_ECHOLNPGM("Applying test pattern.\n"); @@ -648,7 +648,7 @@ void unified_bed_leveling::G29() { } if (!WITHIN(param.KLS_storage_slot, 0, a - 1)) { - SERIAL_ECHOLNPGM("?Invalid storage slot.\n?Use 0 to ", a - 1); + SERIAL_ECHOLN(F("?Invalid "), F("storage slot.\n?Use 0 to "), a - 1); return; } @@ -676,7 +676,7 @@ void unified_bed_leveling::G29() { } if (!WITHIN(param.KLS_storage_slot, 0, a - 1)) { - SERIAL_ECHOLNPGM("?Invalid storage slot.\n?Use 0 to ", a - 1); + SERIAL_ECHOLN(F("?Invalid "), F("storage slot.\n?Use 0 to "), a - 1); goto LEAVE; } @@ -1182,7 +1182,7 @@ bool unified_bed_leveling::G29_parse_parameters() { #if HAS_BED_PROBE param.J_grid_size = parser.value_byte(); if (param.J_grid_size && !WITHIN(param.J_grid_size, 2, 9)) { - SERIAL_ECHOLNPGM("?Invalid grid size (J) specified (2-9).\n"); + SERIAL_ECHOLN(F("?Invalid "), F("grid size (J) specified (2-9).\n")); err_flag = true; } #else @@ -1851,7 +1851,7 @@ void unified_bed_leveling::smart_fill_mesh() { } if (!parser.has_value() || !WITHIN(parser.value_int(), 0, a - 1)) { - SERIAL_ECHOLNPGM("?Invalid storage slot.\n?Use 0 to ", a - 1); + SERIAL_ECHOLN(F("?Invalid "), F("storage slot.\n?Use 0 to "), a - 1); return; } diff --git a/Marlin/src/gcode/feature/ft_motion/M493.cpp b/Marlin/src/gcode/feature/ft_motion/M493.cpp index 6f021c1a0f..6696ae64af 100644 --- a/Marlin/src/gcode/feature/ft_motion/M493.cpp +++ b/Marlin/src/gcode/feature/ft_motion/M493.cpp @@ -224,7 +224,7 @@ void GcodeSuite::M493() { const ftMotionShaper_t shaperVal = seenC ? (ftMotionShaper_t)parser.value_byte() : ftMotionShaper_NONE; const bool goodShaper = WITHIN(shaperVal, ftMotionShaper_NONE, ftMotionShaper_MZV); if (seenC && !goodShaper) { - SERIAL_ECHOLNPGM("?Invalid (C)ompensator value. (0-", int(ftMotionShaper_MZV)); + SERIAL_ECHOLN(F("?Invalid "), F("(C)ompensator value. (0-"), int(ftMotionShaper_MZV)); return; } auto set_shaper = [&](const AxisEnum axis, ftMotionShaper_t newsh) { @@ -267,12 +267,12 @@ void GcodeSuite::M493() { flag.report = true; break; default: - SERIAL_ECHOLNPGM("?Invalid (D)ynamic Frequency Mode value."); + SERIAL_ECHOLN(F("?Invalid "), F("(D)ynamic Frequency Mode value.")); break; } } else { - SERIAL_ECHOLNPGM("?Wrong shaper for (D)ynamic Frequency mode ", ftMotion.cfg.dynFreqMode, "."); + SERIAL_ECHOLNPGM("?Wrong shaper for (D)ynamic Frequency Mode ", ftMotion.cfg.dynFreqMode, "."); } } @@ -288,7 +288,7 @@ void GcodeSuite::M493() { const float baseFreqVal = seenA ? parser.value_float() : 0.0f; const bool goodBaseFreq = seenA && WITHIN(baseFreqVal, FTM_MIN_SHAPE_FREQ, (FTM_FS) / 2); if (seenA && !goodBaseFreq) - SERIAL_ECHOLN(F("?Invalid (A) Base Frequency value. ("), int(FTM_MIN_SHAPE_FREQ), C('-'), int((FTM_FS) / 2), C(')')); + SERIAL_ECHOLN(F("?Invalid "), F("(A) Base Frequency value. ("), int(FTM_MIN_SHAPE_FREQ), C('-'), int((FTM_FS) / 2), C(')')); #if HAS_DYNAMIC_FREQ // Dynamic Frequency parameter @@ -303,14 +303,14 @@ void GcodeSuite::M493() { const float zetaVal = seenI ? parser.value_float() : 0.0f; const bool goodZeta = seenI && WITHIN(zetaVal, 0.01f, 1.0f); if (seenI && !goodZeta) - SERIAL_ECHOLNPGM("?Invalid (I) Zeta value. (0.01-1.0)"); // Zeta out of range + SERIAL_ECHOLN(F("?Invalid "), F("(I) Zeta value. (0.01-1.0)")); // Zeta out of range // Vibration Tolerance parameter const bool seenQ = parser.seenval('Q'); const float vtolVal = seenQ ? parser.value_float() : 0.0f; const bool goodVtol = seenQ && WITHIN(vtolVal, 0.00f, 1.0f); if (seenQ && !goodVtol) - SERIAL_ECHOLNPGM("?Invalid (Q) Vibration Tolerance value. (0.0-1.0)"); // VTol out of range + SERIAL_ECHOLN(F("?Invalid "), F("(Q) Vibration Tolerance value. (0.0-1.0)")); // VTol out of range const bool apply_xy = !parser.seen("XYZE"); diff --git a/Marlin/src/gcode/feature/ft_motion/M494.cpp b/Marlin/src/gcode/feature/ft_motion/M494.cpp index 10856be280..840333f896 100644 --- a/Marlin/src/gcode/feature/ft_motion/M494.cpp +++ b/Marlin/src/gcode/feature/ft_motion/M494.cpp @@ -97,7 +97,7 @@ void GcodeSuite::M494() { report = true; } else - SERIAL_ECHOLNPGM("?Invalid trajectory type [T] value. Use 0=TRAPEZOIDAL, 1=POLY5, 2=POLY6"); + SERIAL_ECHOLN(F("?Invalid "), F("trajectory type [T] value. Use 0=TRAPEZOIDAL, 1=POLY5, 2=POLY6")); } // Parse overshoot parameter. @@ -108,7 +108,7 @@ void GcodeSuite::M494() { report = true; } else - SERIAL_ECHOLNPGM("?Invalid overshoot [O] value. Range 1.25-1.875"); + SERIAL_ECHOLN(F("?Invalid "), F("overshoot [O] value. Range 1.25-1.875")); } #if ENABLED(FTM_SMOOTHING) @@ -121,7 +121,7 @@ void GcodeSuite::M494() { report = true; \ } \ else \ - SERIAL_ECHOLNPGM("?Invalid ", C(N), " smoothing time [", C(CHARIFY(A)), "] value."); \ + SERIAL_ECHOLN("?Invalid ", C(N), " smoothing time [", C(CHARIFY(A)), "] value."); \ } CARTES_GANG( diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index 523a3767df..51f27966c4 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -3126,7 +3126,7 @@ void MarlinSettings::postprocess() { #if ENABLED(AUTO_BED_LEVELING_UBL) inline void ubl_invalid_slot(const int s) { - DEBUG_ECHOLNPGM("?Invalid slot.\n", s, " mesh slots available."); + DEBUG_ECHOLN(F("?Invalid "), F("slot.\n"), s, F(" mesh slots available.")); UNUSED(s); } From 8e9e0396726c5b0d2a1b34e71e4383fcfaa72241 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 5 Nov 2025 19:18:59 -0600 Subject: [PATCH 31/99] =?UTF-8?q?=F0=9F=A7=91=E2=80=8D=F0=9F=92=BB=20Renam?= =?UTF-8?q?e=20Trajectory=20Gen?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/module/ft_motion.cpp | 6 +++--- Marlin/src/module/ft_motion.h | 7 +++---- .../{poly5_trajectory_generator.h => trajectory_poly5.h} | 0 ...poly6_trajectory_generator.cpp => trajectory_poly6.cpp} | 2 +- .../{poly6_trajectory_generator.h => trajectory_poly6.h} | 0 ...dal_trajectory_generator.h => trajectory_trapezoidal.h} | 0 6 files changed, 7 insertions(+), 8 deletions(-) rename Marlin/src/module/ft_motion/{poly5_trajectory_generator.h => trajectory_poly5.h} (100%) rename Marlin/src/module/ft_motion/{poly6_trajectory_generator.cpp => trajectory_poly6.cpp} (99%) rename Marlin/src/module/ft_motion/{poly6_trajectory_generator.h => trajectory_poly6.h} (100%) rename Marlin/src/module/ft_motion/{trapezoidal_trajectory_generator.h => trajectory_trapezoidal.h} (100%) diff --git a/Marlin/src/module/ft_motion.cpp b/Marlin/src/module/ft_motion.cpp index 6f79f566fc..238c6737df 100644 --- a/Marlin/src/module/ft_motion.cpp +++ b/Marlin/src/module/ft_motion.cpp @@ -32,9 +32,9 @@ #if ENABLED(FT_MOTION) #include "ft_motion.h" -#include "ft_motion/trapezoidal_trajectory_generator.h" -#include "ft_motion/poly5_trajectory_generator.h" -#include "ft_motion/poly6_trajectory_generator.h" +#include "ft_motion/trajectory_trapezoidal.h" +#include "ft_motion/trajectory_poly5.h" +#include "ft_motion/trajectory_poly6.h" #include "stepper.h" // Access stepper block queue function and abort status. #include "endstops.h" diff --git a/Marlin/src/module/ft_motion.h b/Marlin/src/module/ft_motion.h index 94a8f61a3e..420b0fb2aa 100644 --- a/Marlin/src/module/ft_motion.h +++ b/Marlin/src/module/ft_motion.h @@ -25,10 +25,9 @@ #include "planner.h" // Access block type from planner. #include "stepper.h" // For stepper motion and direction -#include "ft_motion/trajectory_generator.h" -#include "ft_motion/trapezoidal_trajectory_generator.h" -#include "ft_motion/poly5_trajectory_generator.h" -#include "ft_motion/poly6_trajectory_generator.h" +#include "ft_motion/trajectory_trapezoidal.h" +#include "ft_motion/trajectory_poly5.h" +#include "ft_motion/trajectory_poly6.h" #if HAS_FTM_SHAPING #include "ft_motion/shaping.h" diff --git a/Marlin/src/module/ft_motion/poly5_trajectory_generator.h b/Marlin/src/module/ft_motion/trajectory_poly5.h similarity index 100% rename from Marlin/src/module/ft_motion/poly5_trajectory_generator.h rename to Marlin/src/module/ft_motion/trajectory_poly5.h diff --git a/Marlin/src/module/ft_motion/poly6_trajectory_generator.cpp b/Marlin/src/module/ft_motion/trajectory_poly6.cpp similarity index 99% rename from Marlin/src/module/ft_motion/poly6_trajectory_generator.cpp rename to Marlin/src/module/ft_motion/trajectory_poly6.cpp index 6d01eb96bb..a16f344217 100644 --- a/Marlin/src/module/ft_motion/poly6_trajectory_generator.cpp +++ b/Marlin/src/module/ft_motion/trajectory_poly6.cpp @@ -24,7 +24,7 @@ #if ENABLED(FT_MOTION) -#include "poly6_trajectory_generator.h" +#include "trajectory_poly6.h" #include #include "../ft_motion.h" diff --git a/Marlin/src/module/ft_motion/poly6_trajectory_generator.h b/Marlin/src/module/ft_motion/trajectory_poly6.h similarity index 100% rename from Marlin/src/module/ft_motion/poly6_trajectory_generator.h rename to Marlin/src/module/ft_motion/trajectory_poly6.h diff --git a/Marlin/src/module/ft_motion/trapezoidal_trajectory_generator.h b/Marlin/src/module/ft_motion/trajectory_trapezoidal.h similarity index 100% rename from Marlin/src/module/ft_motion/trapezoidal_trajectory_generator.h rename to Marlin/src/module/ft_motion/trajectory_trapezoidal.h From e9c5b99722804ab1a8044018438822d54a8b5f3e Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Thu, 6 Nov 2025 06:10:44 +0000 Subject: [PATCH 32/99] [cron] Bump distribution date (2025-11-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 a520d3f4a2..f1a270ebb9 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 "2025-11-05" +//#define STRING_DISTRIBUTION_DATE "2025-11-06" /** * The protocol for communication to the host. Protocol indicates communication diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index bb17221017..3ec5edd79f 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 "2025-11-05" + #define STRING_DISTRIBUTION_DATE "2025-11-06" #endif /** From 39697628e724278cf932342881961ba654360ccb Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 6 Nov 2025 16:36:45 -0600 Subject: [PATCH 33/99] =?UTF-8?q?=E2=9C=85=20FT=20Motion=20test=20EXTRUDER?= =?UTF-8?q?S=20>=201?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- buildroot/tests/I3DBEEZ9_V1 | 5 +++-- 1 file changed, 3 insertions(+), 2 deletions(-) diff --git a/buildroot/tests/I3DBEEZ9_V1 b/buildroot/tests/I3DBEEZ9_V1 index 8100932827..06507f56f6 100755 --- a/buildroot/tests/I3DBEEZ9_V1 +++ b/buildroot/tests/I3DBEEZ9_V1 @@ -1,6 +1,6 @@ #!/usr/bin/env bash # -# Build tests for STM32F407ZG I3DBEEZ9 Board +# Build tests for I3DBEEZ9_V1 (STM32F407ZG) Board # # exit on first failure @@ -18,7 +18,8 @@ opt_set MOTHERBOARD BOARD_I3DBEEZ9_V1 SERIAL_PORT -1 \ EXTRUDERS 3 TEMP_SENSOR_1 1 TEMP_SENSOR_2 1 \ E0_AUTO_FAN_PIN PC10 E1_AUTO_FAN_PIN PC11 E2_AUTO_FAN_PIN PC12 \ X_DRIVER_TYPE TMC2209 Y_DRIVER_TYPE TMC2130 -opt_enable BLTOUCH EEPROM_SETTINGS AUTO_BED_LEVELING_3POINT Z_SAFE_HOMING PINS_DEBUGGING +opt_enable FT_MOTION FTM_SMOOTHING FTM_HOME_AND_PROBE FT_MOTION_MENU FTM_RESONANCE_TEST \ + BLTOUCH EEPROM_SETTINGS AUTO_BED_LEVELING_3POINT Z_SAFE_HOMING PINS_DEBUGGING exec_test $1 $2 "I3DBEE Z9 Board | 3 Extruders | Auto-Fan | BLTOUCH | Mixed TMC" "$3" restore_configs From f6dbb5974883f1d7d2465dfba16fb657b15ddef3 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Fri, 7 Nov 2025 00:31:58 +0000 Subject: [PATCH 34/99] [cron] Bump distribution date (2025-11-07) --- 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 f1a270ebb9..1727bdbe3c 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 "2025-11-06" +//#define STRING_DISTRIBUTION_DATE "2025-11-07" /** * The protocol for communication to the host. Protocol indicates communication diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 3ec5edd79f..5b13c65108 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 "2025-11-06" + #define STRING_DISTRIBUTION_DATE "2025-11-07" #endif /** From e176df1e6d03cb82a46954e2e2064a9dd4c176e7 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 6 Nov 2025 23:01:07 -0600 Subject: [PATCH 35/99] =?UTF-8?q?=F0=9F=8E=A8=20FT=20Motion=20comments,=20?= =?UTF-8?q?style?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Resolves #28151 --- Marlin/src/module/ft_motion.cpp | 21 ++++++++++++++++----- Marlin/src/module/ft_motion/stepping.cpp | 12 ++++++------ Marlin/src/module/stepper.cpp | 18 +++++++++--------- Marlin/src/module/stepper.h | 2 +- Marlin/src/module/stepper/cycles.h | 4 ++-- 5 files changed, 34 insertions(+), 23 deletions(-) diff --git a/Marlin/src/module/ft_motion.cpp b/Marlin/src/module/ft_motion.cpp index 238c6737df..0a2c9f6c3a 100644 --- a/Marlin/src/module/ft_motion.cpp +++ b/Marlin/src/module/ft_motion.cpp @@ -484,7 +484,7 @@ xyze_float_t FTMotion::calc_traj_point(const float dist) { stepper_plan_t FTMotion::calc_stepper_plan(xyze_float_t traj_coords) { // 1) Convert trajectory to step delta - #define _TOSTEPS_q32(A, B) int64_t(traj_coords.A * planner.settings.axis_steps_per_mm[B] * (1ull << 32)) + #define _TOSTEPS_q32(A, B) int64_t(traj_coords.A * planner.settings.axis_steps_per_mm[B] * (1ULL << 32)) XYZEval next_steps_q32_32 = LOGICAL_AXIS_ARRAY( _TOSTEPS_q32(e, block_extruder_axis), _TOSTEPS_q32(x, X_AXIS), _TOSTEPS_q32(y, Y_AXIS), _TOSTEPS_q32(z, Z_AXIS), @@ -493,7 +493,7 @@ stepper_plan_t FTMotion::calc_stepper_plan(xyze_float_t traj_coords) { ); #undef _TOSTEPS_q32 - constexpr uint32_t ITERATIONS_PER_TRAJ_INV_uq0_32 = (1ull << 32) / ITERATIONS_PER_TRAJ; + constexpr uint32_t ITERATIONS_PER_TRAJ_INV_uq0_32 = (1ULL << 32) / ITERATIONS_PER_TRAJ; stepper_plan_t stepper_plan; #define _RUN_AXIS(A) do{ \ @@ -525,10 +525,21 @@ stepper_plan_t FTMotion::calc_stepper_plan(xyze_float_t traj_coords) { */ void FTMotion::fill_stepper_plan_buffer() { while (!stepper_plan_is_full()) { - float total_duration = currentGenerator->getTotalDuration(); // if the current plan is empty, it will have zero duration. + float total_duration = currentGenerator->getTotalDuration(); // If the current plan is empty, it will have zero duration. while (tau + FTM_TS > total_duration) { - // Previous block plan consumed, try to get the next one. - tau -= total_duration; // The exact end of the last block may be in-between trajectory points, so the next one may start anywhere of (-FTM_TS, 0]. + /** + * We’ve reached the end of the current block. + * + * `tau` is the time that has elapsed inside this block. After a block is finished, the next one may + * start at any point between *just before* the last sampled time (one step earlier, i.e. `-FTM_TS`) + * and *exactly at* the last sampled time (0). IOW the real start of the next block could be anywhere + * in the interval (-FTM_TS, 0]. + * + * To account for that uncertainty we simply subtract the duration of the finished block from `tau`. + * This brings us back to a time value that is valid for the next block, while still allowing the next + * block’s start to be offset by up to one time step into the past. + */ + tau -= total_duration; const bool plan_available = plan_next_block(); if (!plan_available) return; total_duration = currentGenerator->getTotalDuration(); diff --git a/Marlin/src/module/ft_motion/stepping.cpp b/Marlin/src/module/ft_motion/stepping.cpp index 96ef4466d8..f44087a7d4 100644 --- a/Marlin/src/module/ft_motion/stepping.cpp +++ b/Marlin/src/module/ft_motion/stepping.cpp @@ -29,20 +29,20 @@ void Stepping::reset() { stepper_plan.reset(); - delta_error_q32.set(LOGICAL_AXIS_ARRAY_1(_BV32(31))); // start as 0.5 in q32 so steps are rounded + delta_error_q32.set(LOGICAL_AXIS_LIST_1(1 << 31)); // Start as 0.5 in q32 so steps are rounded step_bits = 0; bresenham_iterations_pending = 0; } uint32_t Stepping::advance_until_step() { xyze_ulong_t space_q32 = -delta_error_q32 + UINT32_MAX; // How much accumulation until a step in any axis is ALMOST due - // scalar in the right hand because types.h is missing scalar on left cases + // TODO: Add operators to types.h for scalar destination. xyze_ulong_t advance_q32 = stepper_plan.advance_dividend_q0_32; uint32_t iterations = bresenham_iterations_pending; // Per-axis lower-bound approx of floor(space_q32/adv), min across axes (lower bound because this fast division underestimates result by up to 1) - // #define RUN_AXIS(A) if(advance_q32.A > 0) NOMORE(iterations, space_q32.A/advance_q32.A); - #define RUN_AXIS(A) if(advance_q32.A > 0) NOMORE(iterations, uint32_t((uint64_t(space_q32.A) * advance_dividend_reciprocal.A) >> 32)); + //#define RUN_AXIS(A) if (advance_q32.A > 0) NOMORE(iterations, space_q32.A / advance_q32.A); + #define RUN_AXIS(A) if (advance_q32.A > 0) NOMORE(iterations, uint32_t((uint64_t(space_q32.A) * advance_dividend_reciprocal.A) >> 32)); LOGICAL_AXIS_MAP(RUN_AXIS); #undef RUN_AXIS @@ -72,7 +72,7 @@ uint32_t Stepping::plan() { if (bresenham_iterations_pending > 0) { intervals = advance_until_step(); if (bool(step_bits)) return intervals; // steps to make => return the wait time so it gets done in due time - // Else all bresenham iterations were advanced without steps => this is just the frame end, so plan the next one directly and accumulate the wait + // Else all Bresenham iterations were advanced without steps => this is just the frame end, so plan the next one directly and accumulate the wait } if (ftMotion.stepper_plan_is_empty()) { @@ -97,7 +97,7 @@ uint32_t Stepping::plan() { return INTERVAL_PER_TRAJ_POINT; } - // This vector division is unavoidable, but it saves a division per step during bresenham + // This vector division is unavoidable, but it saves a division per step during Bresenham // The reciprocal is actually 2^32/dividend, but that requires dividing a uint64_t, which quite expensive // Since even the real reciprocal may underestimate the quotient by 1 anyway already, this optimisation doesn't // make things worse. This underestimation is compensated for in advance_until_step. diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index be8cb766e6..873d1383d0 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -272,7 +272,7 @@ uint32_t Stepper::advance_divisor = 0, hal_timer_t Stepper::ticks_nominal = 0; #if DISABLED(S_CURVE_ACCELERATION) - uint32_t Stepper::acc_step_rate; // needed for deceleration start point + uint32_t Stepper::acc_step_rate; // Needed for deceleration start point #endif xyz_long_t Stepper::endstops_trigsteps; @@ -1989,7 +1989,7 @@ void Stepper::pulse_phase_isr() { #if HAS_ROUGH_LIN_ADVANCE if (la_active && step_needed.e) { - // don't actually step here, but do subtract movements steps + // Don't actually step here, but do subtract movements steps // from the linear advance step count step_needed.e = false; la_advance_steps--; @@ -2000,14 +2000,14 @@ void Stepper::pulse_phase_isr() { #endif #if HAS_ZV_SHAPING - // record an echo if a step is needed in the primary bresenham + // Record an echo if a step is needed in the primary Bresenham const bool x_step = TERN0(INPUT_SHAPING_X, step_needed.x && shaping_x.enabled), y_step = TERN0(INPUT_SHAPING_Y, step_needed.y && shaping_y.enabled), z_step = TERN0(INPUT_SHAPING_Z, step_needed.z && shaping_z.enabled); if (x_step || y_step || z_step) ShapingQueue::enqueue(x_step, TERN0(INPUT_SHAPING_X, shaping_x.forward), y_step, TERN0(INPUT_SHAPING_Y, shaping_y.forward), z_step, TERN0(INPUT_SHAPING_Z, shaping_z.forward)); - // do the first part of the secondary bresenham + // Do the first part of the secondary Bresenham #if ENABLED(INPUT_SHAPING_X) if (x_step) PULSE_PREP_SHAPING(X, shaping_x.delta_error, shaping_x.forward ? shaping_x.factor1 : -shaping_x.factor1); @@ -2195,7 +2195,7 @@ hal_timer_t Stepper::calc_timer_interval(uint32_t step_rate) { #else - if (step_rate >= 0x0800) { // higher step rate + if (step_rate >= 0x0800) { // Higher step rate // AVR is able to keep up at around 65kHz Stepping ISR rate at most. // So values for step_rate > 65535 might as well be truncated. // Handle it as quickly as possible. i.e., assume highest byte is zero @@ -2208,7 +2208,7 @@ hal_timer_t Stepper::calc_timer_interval(uint32_t step_rate) { const uint8_t gain = uint8_t(pgm_read_byte(table_address + 2)); return base - MultiU8X8toH8(uint8_t(step_rate & 0x00FF), gain); } - else if (step_rate > minimal_step_rate) { // lower step rates + else if (step_rate > minimal_step_rate) { // Lower step rates step_rate -= minimal_step_rate; // Correct for minimal speed const uintptr_t table_address = uintptr_t(&speed_lookuptable_slow[uint8_t(step_rate >> 3)]); return uint16_t(pgm_read_word(table_address)) @@ -2388,7 +2388,7 @@ hal_timer_t Stepper::block_phase_isr() { ticks_nominal = 0; } #endif - time_spent_in_isr = -time_spent; // unsigned but guaranteed to be +ve when needed + time_spent_in_isr = -time_spent; // Unsigned but guaranteed to be +ve when needed time_spent_out_isr = 0; #endif @@ -3295,7 +3295,7 @@ void Stepper::init() { } void Stepper::set_shaping_frequency(const AxisEnum axis, const float freq) { - // enabling or disabling shaping whilst moving can result in lost steps + // Enabling or disabling shaping whilst moving can result in lost steps planner.synchronize(); const bool was_on = hal.isr_state(); @@ -3373,7 +3373,7 @@ void Stepper::_set_position(const abce_long_t &spos) { ); TERN_(HAS_EXTRUDERS, count_position.e = spos.e); #else - // default non-h-bot planning + // Default non-h-bot planning count_position = spos; #endif diff --git a/Marlin/src/module/stepper.h b/Marlin/src/module/stepper.h index 5d5c000577..dfca23715e 100644 --- a/Marlin/src/module/stepper.h +++ b/Marlin/src/module/stepper.h @@ -275,7 +275,7 @@ constexpr ena_mask_t enable_overlap[] = { float zeta; bool enabled : 1; bool forward : 1; - int16_t delta_error = 0; // delta_error for seconday bresenham mod 128 + int16_t delta_error = 0; // delta_error for secondary Bresenham mod 128 uint8_t factor1; uint8_t factor2; int32_t last_block_end_pos = 0; diff --git a/Marlin/src/module/stepper/cycles.h b/Marlin/src/module/stepper/cycles.h index fa76f60127..2f04342538 100644 --- a/Marlin/src/module/stepper/cycles.h +++ b/Marlin/src/module/stepper/cycles.h @@ -115,7 +115,7 @@ constexpr uint32_t min_isr_loop_cycles = isr_mixing_stepper_cycles + LOGICAL_AXE // Calculate the minimum MPU cycles needed per pulse to enforce constexpr uint32_t min_stepper_pulse_cycles = _min_pulse_high_ns * CYCLES_PER_MICROSECOND / 1000; -// The loop takes the base time plus the time for all the bresenham logic for 1 << R pulses plus the time +// The loop takes the base time plus the time for all the Bresenham logic for 1 << R pulses plus the time // between pulses for ((1 << R) - 1) pulses. But the user could be enforcing a minimum time so the loop time is: constexpr uint32_t isr_loop_cycles(const int R) { return ((isr_loop_base_cycles + min_isr_loop_cycles + min_stepper_pulse_cycles) * ((1UL << R) - 1) + _MAX(min_isr_loop_cycles, min_stepper_pulse_cycles)); } @@ -140,7 +140,7 @@ constexpr uint32_t isr_shaping_loop_cycles(const int R) { // HELP ME: What is what? // Directions are set up for MIXING_STEPPERS - like before. // Finding the right stepper may last up to MIXING_STEPPERS loops in get_next_stepper(). - // These loops are a bit faster than advancing a bresenham counter. + // These loops are a bit faster than advancing a Bresenham counter. // Always only one E stepper is stepped. * TERN1(MIXING_EXTRUDER, (MIXING_STEPPERS)) ); From 2073b67e455827804e32c4a2ddf3a0f679c663de Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 7 Nov 2025 00:21:09 -0600 Subject: [PATCH 36/99] =?UTF-8?q?=E2=9C=85=20FT=20Motion=20test=20EXTRUDER?= =?UTF-8?q?S=20>=201=20(2)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- buildroot/tests/I3DBEEZ9_V1 | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/buildroot/tests/I3DBEEZ9_V1 b/buildroot/tests/I3DBEEZ9_V1 index 06507f56f6..8cc91901c1 100755 --- a/buildroot/tests/I3DBEEZ9_V1 +++ b/buildroot/tests/I3DBEEZ9_V1 @@ -18,7 +18,7 @@ opt_set MOTHERBOARD BOARD_I3DBEEZ9_V1 SERIAL_PORT -1 \ EXTRUDERS 3 TEMP_SENSOR_1 1 TEMP_SENSOR_2 1 \ E0_AUTO_FAN_PIN PC10 E1_AUTO_FAN_PIN PC11 E2_AUTO_FAN_PIN PC12 \ X_DRIVER_TYPE TMC2209 Y_DRIVER_TYPE TMC2130 -opt_enable FT_MOTION FTM_SMOOTHING FTM_HOME_AND_PROBE FT_MOTION_MENU FTM_RESONANCE_TEST \ +opt_enable FT_MOTION FTM_SMOOTHING FTM_HOME_AND_PROBE FT_MOTION_MENU FTM_RESONANCE_TEST EMERGENCY_PARSER \ BLTOUCH EEPROM_SETTINGS AUTO_BED_LEVELING_3POINT Z_SAFE_HOMING PINS_DEBUGGING exec_test $1 $2 "I3DBEE Z9 Board | 3 Extruders | Auto-Fan | BLTOUCH | Mixed TMC" "$3" From d1f2b2d27baeabdbd8f584b65d739b22fc939c22 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 7 Nov 2025 01:43:22 -0600 Subject: [PATCH 37/99] =?UTF-8?q?=F0=9F=A9=B9=20Quieter=20FTM=20build?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp | 2 +- Marlin/src/gcode/bedlevel/mbl/G29.cpp | 2 +- Marlin/src/gcode/calibrate/G28.cpp | 4 ++-- Marlin/src/gcode/probe/G30.cpp | 2 +- Marlin/src/module/ft_motion.h | 10 ++++++---- Marlin/src/module/ft_motion/stepping.cpp | 2 +- 6 files changed, 12 insertions(+), 10 deletions(-) diff --git a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp index 5ba817ea3e..24a1638731 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp @@ -314,7 +314,7 @@ void unified_bed_leveling::G29() { const bool may_move = p_val == 1 || p_val == 2 || p_val == 4 || parser.seen_test('J'); // Potentially disable Fixed-Time Motion for probing - TERN_(FT_MOTION, FTMotionDisableInScope FT_Disabler); + TERN_(FT_MOTION, FTM_DISABLE_IN_SCOPE()); // Check for commands that require the printer to be homed if (may_move) { diff --git a/Marlin/src/gcode/bedlevel/mbl/G29.cpp b/Marlin/src/gcode/bedlevel/mbl/G29.cpp index 7b826acba7..0e48ec1449 100644 --- a/Marlin/src/gcode/bedlevel/mbl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/mbl/G29.cpp @@ -68,7 +68,7 @@ inline void echo_not_entered(const char c) { SERIAL_CHAR(c); SERIAL_ECHOLNPGM(" void GcodeSuite::G29() { // Potentially disable Fixed-Time Motion for probing - TERN_(FT_MOTION, FTMotionDisableInScope FT_Disabler); + TERN_(FT_MOTION, FTM_DISABLE_IN_SCOPE()); DEBUG_SECTION(log_G29, "G29", true); diff --git a/Marlin/src/gcode/calibrate/G28.cpp b/Marlin/src/gcode/calibrate/G28.cpp index 92f05b1fba..20b50cd7f1 100644 --- a/Marlin/src/gcode/calibrate/G28.cpp +++ b/Marlin/src/gcode/calibrate/G28.cpp @@ -131,7 +131,7 @@ inline void home_z_safely() { // Potentially disable Fixed-Time Motion for homing - TERN_(FT_MOTION, FTMotionDisableInScope FT_Disabler); + TERN_(FT_MOTION, FTM_DISABLE_IN_SCOPE()); DEBUG_SECTION(log_G28, "home_z_safely", DEBUGGING(LEVELING)); @@ -290,7 +290,7 @@ void GcodeSuite::G28() { #endif // Potentially disable Fixed-Time Motion for homing - TERN_(FT_MOTION, FTMotionDisableInScope FT_Disabler); + TERN_(FT_MOTION, FTM_DISABLE_IN_SCOPE()); // Always home with tool 0 active #if HAS_MULTI_HOTEND diff --git a/Marlin/src/gcode/probe/G30.cpp b/Marlin/src/gcode/probe/G30.cpp index c4f45e785f..463a4cd836 100644 --- a/Marlin/src/gcode/probe/G30.cpp +++ b/Marlin/src/gcode/probe/G30.cpp @@ -81,7 +81,7 @@ void GcodeSuite::G30() { TERN_(HAS_PTC, ptc.set_enabled(parser.boolval('C', true))); // Potentially disable Fixed-Time Motion for probing - TERN_(FT_MOTION, FTMotionDisableInScope FT_Disabler); + TERN_(FT_MOTION, FTM_DISABLE_IN_SCOPE()); // Probe the bed, optionally raise, and return the measured height const float measured_z = probe.probe_at_point(probepos, raise_after); diff --git a/Marlin/src/module/ft_motion.h b/Marlin/src/module/ft_motion.h index 420b0fb2aa..bec65f2abf 100644 --- a/Marlin/src/module/ft_motion.h +++ b/Marlin/src/module/ft_motion.h @@ -258,8 +258,8 @@ extern FTMotion ftMotion; // Use ftMotion.thing, not FTMotion::thing. * Optional behavior to turn FT Motion off for homing/probing. * Applies when FTM_HOME_AND_PROBE is disabled. */ -typedef struct FTMotionDisableInScope { - #if DISABLED(FTM_HOME_AND_PROBE) +#if DISABLED(FTM_HOME_AND_PROBE) + typedef struct FTMotionDisableInScope { bool isactive; FTMotionDisableInScope() { isactive = ftMotion.cfg.active; @@ -269,5 +269,7 @@ typedef struct FTMotionDisableInScope { ftMotion.cfg.active = isactive; if (isactive) ftMotion.init(); } - #endif -} FTMotionDisableInScope_t; + } FTMotionDisableInScope_t; +#endif + +#define FTM_DISABLE_IN_SCOPE() TERN(FTM_HOME_AND_PROBE, NOOP, FTMotionDisableInScope FT_Disabler) diff --git a/Marlin/src/module/ft_motion/stepping.cpp b/Marlin/src/module/ft_motion/stepping.cpp index f44087a7d4..fec5d05555 100644 --- a/Marlin/src/module/ft_motion/stepping.cpp +++ b/Marlin/src/module/ft_motion/stepping.cpp @@ -29,7 +29,7 @@ void Stepping::reset() { stepper_plan.reset(); - delta_error_q32.set(LOGICAL_AXIS_LIST_1(1 << 31)); // Start as 0.5 in q32 so steps are rounded + delta_error_q32.set(LOGICAL_AXIS_LIST_1(1UL << 31)); // Start as 0.5 in q32 so steps are rounded step_bits = 0; bresenham_iterations_pending = 0; } From dd3c3d09f2d89be09cec0a05d61f3eb046792350 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 7 Nov 2025 12:43:38 -0600 Subject: [PATCH 38/99] =?UTF-8?q?=F0=9F=A9=B9=20Quieter=20FTM=20build=20(2?= =?UTF-8?q?)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/bedlevel/abl/G29.cpp | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Marlin/src/gcode/bedlevel/abl/G29.cpp b/Marlin/src/gcode/bedlevel/abl/G29.cpp index ea578e5710..c306274aec 100644 --- a/Marlin/src/gcode/bedlevel/abl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/abl/G29.cpp @@ -275,9 +275,9 @@ G29_TYPE GcodeSuite::G29() { // Set and report "probing" state to host TERN_(FULL_REPORT_TO_HOST_FEATURE, set_and_report_grblstate(M_PROBE, false)); - #if DISABLED(PROBE_MANUALLY) && ENABLED(FT_MOTION) + #if DISABLED(PROBE_MANUALLY) // Potentially disable Fixed-Time Motion for probing - FTMotionDisableInScope FT_Disabler; + TERN_(FT_MOTION, FTM_DISABLE_IN_SCOPE()); #endif /** From f48aa53d7cf689e9ec70f29f4dccb9884e5e1e64 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sat, 8 Nov 2025 00:30:09 +0000 Subject: [PATCH 39/99] [cron] Bump distribution date (2025-11-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 1727bdbe3c..edf9a292d9 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 "2025-11-07" +//#define STRING_DISTRIBUTION_DATE "2025-11-08" /** * The protocol for communication to the host. Protocol indicates communication diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 5b13c65108..5f4b7b8320 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 "2025-11-07" + #define STRING_DISTRIBUTION_DATE "2025-11-08" #endif /** From 667aa15b87a5c64a5e3954a983824c24bf0779a1 Mon Sep 17 00:00:00 2001 From: narno2202 <130909513+narno2202@users.noreply.github.com> Date: Sat, 8 Nov 2025 22:16:06 +0100 Subject: [PATCH 40/99] =?UTF-8?q?=E2=9C=A8=20FTM=5FRESONANCE=5FTEST=20(#28?= =?UTF-8?q?158)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration_adv.h | 1 + Marlin/src/core/types.h | 2 +- Marlin/src/feature/e_parser.cpp | 21 +- Marlin/src/feature/e_parser.h | 7 + .../src/gcode/feature/ft_motion/M495_M496.cpp | 186 ++++++++++++++++++ Marlin/src/gcode/gcode.cpp | 4 + Marlin/src/gcode/gcode.h | 7 + Marlin/src/inc/SanityCheck.h | 3 + Marlin/src/lcd/language/language_en.h | 10 + Marlin/src/lcd/menu/menu_motion.cpp | 36 ++++ Marlin/src/module/ft_motion.cpp | 61 +++++- Marlin/src/module/ft_motion.h | 11 ++ .../module/ft_motion/resonance_generator.cpp | 88 +++++++++ .../module/ft_motion/resonance_generator.h | 73 +++++++ Marlin/src/module/ft_motion/stepping.h | 1 - .../module/ft_motion/trajectory_generator.h | 7 +- .../src/module/ft_motion/trajectory_poly6.cpp | 2 +- buildroot/tests/STM32F103RC_btt | 5 +- ini/features.ini | 3 +- 19 files changed, 512 insertions(+), 16 deletions(-) create mode 100644 Marlin/src/gcode/feature/ft_motion/M495_M496.cpp create mode 100644 Marlin/src/module/ft_motion/resonance_generator.cpp create mode 100644 Marlin/src/module/ft_motion/resonance_generator.h diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 830db40333..de1c841f1c 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1177,6 +1177,7 @@ #define FTM_SHAPING_ZETA_E 0.03f // Zeta used by input shapers for E axis #define FTM_SHAPING_V_TOL_E 0.05f // Vibration tolerance used by EI input shapers for E axis + //#define FTM_RESONANCE_TEST // Sine sweep motion for resonance study //#define FTM_SMOOTHING // Smoothing can reduce artifacts and make steppers quieter // on sharp corners, but too much will round corners. #if ENABLED(FTM_SMOOTHING) diff --git a/Marlin/src/core/types.h b/Marlin/src/core/types.h index 23d83c4b9e..486f78fde8 100644 --- a/Marlin/src/core/types.h +++ b/Marlin/src/core/types.h @@ -867,7 +867,7 @@ struct XYZEval { FI void set(const XYZval &pxyz, const T pe) { set(pxyz); e = pe; } FI void set(LOGICAL_AXIS_ARGS_LC(const T)) { LOGICAL_AXIS_CODE(_e = e, a = x, b = y, c = z, _i = i, _j = j, _k = k, _u = u, _v = v, _w = w); } #if DISTINCT_AXES > LOGICAL_AXES - FI void set(const T (&arr)[DISTINCT_AXES]) { LOGICAL_AXIS_CODE(e = arr[LOGICAL_AXES-1], x = arr[0], y = arr[1], z = arr[2], i = arr[3], j = arr[4], k = arr[5], u = arr[6], v = arr[7], w = arr[8]); } + FI void set(const T (&arr)[DISTINCT_AXES], const uint8_t eindex) { LOGICAL_AXIS_CODE(e = arr[LOGICAL_AXES-1 + eindex], x = arr[0], y = arr[1], z = arr[2], i = arr[3], j = arr[4], k = arr[5], u = arr[6], v = arr[7], w = arr[8]); } #endif #endif diff --git a/Marlin/src/feature/e_parser.cpp b/Marlin/src/feature/e_parser.cpp index e249d81969..9e974f2e83 100644 --- a/Marlin/src/feature/e_parser.cpp +++ b/Marlin/src/feature/e_parser.cpp @@ -33,6 +33,9 @@ // Static data members bool EmergencyParser::killed_by_M112, // = false EmergencyParser::quickstop_by_M410, + #if ENABLED(FTM_RESONANCE_TEST) + EmergencyParser::rt_stop_by_M496, // = false + #endif #if HAS_MEDIA EmergencyParser::sd_abort_by_M524, #endif @@ -147,9 +150,22 @@ void EmergencyParser::update(EmergencyParser::State &state, const uint8_t c) { case EP_M10: state = (c == '8') ? EP_M108 : EP_IGNORE; break; case EP_M11: state = (c == '2') ? EP_M112 : EP_IGNORE; break; - case EP_M4: state = (c == '1') ? EP_M41 : EP_IGNORE; break; + case EP_M4: + switch (c) { + case '1' :state = EP_M41; break; + #if ENABLED(FT_MOTION_RESONANCE_TEST) + case '9': state = EP_M49; break; + #endif + default: state = EP_IGNORE; + } + break; + case EP_M41: state = (c == '0') ? EP_M410 : EP_IGNORE; break; + #if ENABLED(FTM_RESONANCE_TEST) + case EP_M49: state = (c == '6') ? EP_M496 : EP_IGNORE; break; + #endif + #if HAS_MEDIA case EP_M5: state = (c == '2') ? EP_M52 : EP_IGNORE; break; case EP_M52: state = (c == '4') ? EP_M524 : EP_IGNORE; break; @@ -195,6 +211,9 @@ void EmergencyParser::update(EmergencyParser::State &state, const uint8_t c) { case EP_M108: wait_for_user = wait_for_heatup = false; break; case EP_M112: killed_by_M112 = true; break; case EP_M410: quickstop_by_M410 = true; break; + #if ENABLED(FTM_RESONANCE_TEST) + case EP_M496: rt_stop_by_M496 = true; break; + #endif #if ENABLED(EP_BABYSTEPPING) case EP_M293: babystep.ep_babysteps++; break; case EP_M294: babystep.ep_babysteps--; break; diff --git a/Marlin/src/feature/e_parser.h b/Marlin/src/feature/e_parser.h index 8dacb0581c..17e85a331d 100644 --- a/Marlin/src/feature/e_parser.h +++ b/Marlin/src/feature/e_parser.h @@ -43,6 +43,9 @@ public: #if HAS_MEDIA EP_M5, EP_M52, EP_M524, #endif + #if ENABLED(FTM_RESONANCE_TEST) + EP_M49, EP_M496, + #endif #if ENABLED(EP_BABYSTEPPING) EP_M2, EP_M29, EP_M293, EP_M294, #endif @@ -64,6 +67,10 @@ public: static bool killed_by_M112; static bool quickstop_by_M410; + #if ENABLED(FTM_RESONANCE_TEST) + static bool rt_stop_by_M496; + #endif + #if HAS_MEDIA static bool sd_abort_by_M524; #endif diff --git a/Marlin/src/gcode/feature/ft_motion/M495_M496.cpp b/Marlin/src/gcode/feature/ft_motion/M495_M496.cpp new file mode 100644 index 0000000000..15e1a1fe0f --- /dev/null +++ b/Marlin/src/gcode/feature/ft_motion/M495_M496.cpp @@ -0,0 +1,186 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2025 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/MarlinConfig.h" + +#if ENABLED(FTM_RESONANCE_TEST) + +#include "../../gcode.h" +#include "../../../module/ft_motion.h" +#include "../../../module/ft_motion/resonance_generator.h" + +void say_resonance_test() { + const ftm_resonance_test_params_t &p = ftMotion.rtg.rt_params; + SERIAL_ECHO_START(); + SERIAL_ECHOLN(F("M495 "), F("Resonance Test")); + SERIAL_ECHOLNPGM(" Axis: ", p.axis == NO_AXIS_ENUM ? C('-') : C(AXIS_CHAR(p.axis))); + SERIAL_ECHOLNPGM(" Freq Range (F..T): ", p.min_freq, " .. ", p.max_freq, " Hz"); + SERIAL_ECHOLNPGM(" Octave Duration (O): ", p.octave_duration, " s"); + SERIAL_ECHOLNPGM(" Accel/Hz (A): ", p.accel_per_hz); +} + +/** + * M495: Configure and run the resonance test. + * With no parameters report the current settings. + * + * Parameters: + * A Accel per Hz. (Default 60) + * F Start frequency. (Default 5.0) + * S Start the test. + * T End frequency. (Default 100.0f) + * O Octave duration for logarithmic progression + * C Amplitude correction factor. (Default 5) + * X Flag to select the X axis. + * Y Flag to select the Y axis. + * Z Flag to select the Z axis. + * H Get the Resonance Frequency from Timeline value. (Default 0) + * + * Examples: + * M495 S : Start the test with default or last-used parameters + * M495 X S : Start the test on the X axis with default or last-used parameters + * M495 H : Get Resonance Frequency from Timeline value + * + */ +void GcodeSuite::M495() { + if (!parser.seen_any()) return say_resonance_test(); + + ftm_resonance_test_params_t &p = ftMotion.rtg.rt_params; + + const bool seenX = parser.seen_test('X'), seenY = parser.seen_test('Y'), seenZ = parser.seen_test('Z'); + + if (seenX + seenY + seenZ == 1) { + const AxisEnum a = seenX ? X_AXIS : seenY ? Y_AXIS : Z_AXIS; + p.axis = a; + SERIAL_ECHOLN(C(AXIS_CHAR(a)), F("-axis selected"), F(" for "), F("Resonance Test")); + } + else if (seenX + seenY + seenZ > 1) { + SERIAL_ECHOLN(F("?Specify X, Y, or Z axis"), F(" for "), F("Resonance Test")); + return; + } + + if (parser.seenval('A')) { + const float val = parser.value_float(); + if (p.axis == Z_AXIS && val > 15.0f) { + p.accel_per_hz = 15.0f; + SERIAL_ECHOLNPGM("Accel/Hz set to max 15 mm/s for Z Axis"); + } + else { + p.accel_per_hz = val; + SERIAL_ECHOLNPGM("Accel/Hz set to ", p.accel_per_hz); + } + } + + if (parser.seenval('F')) { + const float val = parser.value_float(); + if (val >= 5.0f) { + p.min_freq = val; + SERIAL_ECHOLNPGM("Start Frequency set to ", p.min_freq, " Hz"); + } + else { + SERIAL_ECHOLN(F("?Invalid "), F("Start [F]requency. (minimum 5.0 Hz)")); + } + } + + if (parser.seenval('T')) { + const float val = parser.value_float(); + if (val > p.min_freq && val <= 200.0f) { + p.max_freq = val; + SERIAL_ECHOLNPGM("End Frequency set to ", p.max_freq, " Hz"); + } + else { + SERIAL_ECHOLN(F("?Invalid "), F("End Frequency [T]. (StartFreq .. 200 Hz)")); + } + } + + if (parser.seenval('O')) { + const float val = parser.value_float(); + if (WITHIN(val, 20, 60)) { + p.octave_duration = val; + SERIAL_ECHOLNPGM("Octave Duration set to ",p.octave_duration, " s"); + } + else { + SERIAL_ECHOLN(F("?Invalid "), F("octave duration [O]. (20..60 s)")); + } + } + + if (parser.seenval('C')) { + const int val = parser.value_int(); + if (WITHIN(val, 1, 8)) { + p.amplitude_correction = val; + SERIAL_ECHOLNPGM("Amplitude Correction Factor set to ", p.amplitude_correction); + } + else { + SERIAL_ECHOLN(F("?Invalid "), F("Amplitude [C]orrection Factor. (1..8)")); + } + } + + if (parser.seenval('G')) { + const float val = parser.value_float(); + if (WITHIN(val, 0, 100)) { + ftMotion.rtg.timeline = val; + SERIAL_ECHOLNPGM("Resonance Frequency set to ", ftMotion.rtg.getFrequencyFromTimeline(), " Hz"); + } + else { + SERIAL_ECHOLN(F("?Invalid "), F("Timeline value (0..100 s)")); + } + } + + if (parser.seen_test('S')) { + if (ftMotion.cfg.active) { + if (p.axis != NO_AXIS_ENUM) { + if (p.max_freq > p.min_freq) { + SERIAL_ECHOLN(F("Starting "), F("Resonance Test")); + ftMotion.start_resonance_test(); + // The function returns immediately, the test runs in the background. + } + else { + SERIAL_ECHOLNPGM("?End Frequency must be greater than Start Frequency"); + } + } + else { + SERIAL_ECHOLN(F("?Specify X, Y, or Z axis"), F(" first")); + } + } + else { + SERIAL_ECHOLN(F("?Activate FT Motion to run the "), F("Resonance Test")); + } + } +} + +/** + * M496: Abort the resonance test (via Emergency Parser) + */ +void GcodeSuite::M496() { + if (ftMotion.rtg.isActive()) { + ftMotion.rtg.abort(); + EmergencyParser::rt_stop_by_M496 = false; + #if DISABLED(MARLIN_SMALL_BUILD) + SERIAL_ECHOLN(F("Resonance Test"), F(" aborted.")); + #endif + return; + } + #if DISABLED(MARLIN_SMALL_BUILD) + SERIAL_ECHOLN(F("No active "), F("Resonance Test"), F(" to abort.")); + #endif +} + +#endif // FTM_RESONANCE_TEST diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index 20b268256e..f7ecbbd1d3 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -926,6 +926,10 @@ void GcodeSuite::process_parsed_command(bool no_ok/*=false*/) { #if ENABLED(FTM_SMOOTHING) case 494: M494(); break; // M494: Fixed-Time Motion extras #endif + #if ENABLED(FTM_RESONANCE_TEST) + case 495: M495(); break; // M495: Resonance test for Input Shaping + case 496: M496(); break; // M496: Abort resonance test + #endif #endif case 500: M500(); break; // M500: Store settings in EEPROM diff --git a/Marlin/src/gcode/gcode.h b/Marlin/src/gcode/gcode.h index a08ae769fe..e288b9bd99 100644 --- a/Marlin/src/gcode/gcode.h +++ b/Marlin/src/gcode/gcode.h @@ -252,6 +252,8 @@ * M485 - Send RS485 packets (Requires RS485_SERIAL_PORT) * M486 - Identify and cancel objects. (Requires CANCEL_OBJECTS) * M493 - Set / Report input FT Motion/Shaping parameters. (Requires FT_MOTION) + * M495 - Set / Start resonance test. (Requires FTM_RESONANCE_TEST) + * M496 - Abort resonance test. (Requires FTM_RESONANCE_TEST) * M500 - Store parameters in EEPROM. (Requires EEPROM_SETTINGS) * M501 - Restore parameters from EEPROM. (Requires EEPROM_SETTINGS) * M502 - Revert to the default "factory settings". ** Does not write them to EEPROM! ** @@ -1115,6 +1117,11 @@ private: static void M493_report(const bool forReplay=true); static void M494(); static void M494_report(const bool forReplay=true); + #if ENABLED(FTM_RESONANCE_TEST) + static void M495(); + static void M495_report(const bool forReplay=true); + static void M496(); + #endif #endif static void M500(); diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index cd77bd24ba..4bc63660a2 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -4510,6 +4510,9 @@ static_assert(_PLUS_TEST(3), "DEFAULT_MAX_ACCELERATION values must be positive." static_assert(FTM_SMOOTHING_TIME_Z <= FTM_MAX_SMOOTHING_TIME, "FTM_SMOOTHING_TIME_Z must be <= FTM_MAX_SMOOTHING_TIME."); static_assert(FTM_SMOOTHING_TIME_E <= FTM_MAX_SMOOTHING_TIME, "FTM_SMOOTHING_TIME_E must be <= FTM_MAX_SMOOTHING_TIME."); #endif + #if ENABLED(FTM_RESONANCE_TEST) && DISABLED(EMERGENCY_PARSER) + #error "EMERGENCY_PARSER is required with FTM_RESONANCE_TEST (to cancel the test)." + #endif #endif // Multi-Stepping Limit diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index 05c5fd43dd..a1ba59bcca 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -951,6 +951,14 @@ namespace LanguageNarrow_en { LSTR MSG_FTM_SMOOTH_TIME_N = _UxGT("@ Smoothing Time"); LSTR MSG_FTM_POLY6_OVERSHOOT = _UxGT("@ Poly6 Overshoot"); + LSTR MSG_FTM_RESONANCE_TEST = _UxGT("Resonance Test"); + LSTR MSG_FTM_RT_RUNNING = _UxGT("Res. Test Running..."); + LSTR MSG_FTM_RT_START_N = _UxGT("Start @ Axis Test"); + LSTR MSG_FTM_RT_STOP = _UxGT("Abort Test"); + LSTR MSG_FTM_RETRIEVE_FREQ = _UxGT("Calc. Res. Freq."); + LSTR MSG_FTM_RESONANCE_FREQ = _UxGT("Resonance Freq."); + LSTR MSG_FTM_TIMELINE_FREQ = _UxGT("Timeline (s)"); + LSTR MSG_LEVEL_X_AXIS = _UxGT("Level X Axis"); LSTR MSG_AUTO_CALIBRATE = _UxGT("Auto Calibrate"); LSTR MSG_FTDI_HEATER_TIMEOUT = _UxGT("Idle timeout, temperature decreased. Press Okay to reheat and again to resume."); @@ -1158,6 +1166,8 @@ namespace LanguageWide_en { LSTR MSG_EEPROM_INITIALIZED = _UxGT("Default Settings Restored"); LSTR MSG_PREHEAT_M_CHAMBER = _UxGT("Preheat $ Chamber"); LSTR MSG_PREHEAT_M_SETTINGS = _UxGT("Preheat $ Config"); + LSTR MSG_FTM_RT_RUNNING = _UxGT("Resonance Test Running..."); + LSTR MSG_FTM_RESONANCE_FREQ = _UxGT("Resonance frequency"); #endif } diff --git a/Marlin/src/lcd/menu/menu_motion.cpp b/Marlin/src/lcd/menu/menu_motion.cpp index 0d23484f3f..dd75cc5c29 100644 --- a/Marlin/src/lcd/menu/menu_motion.cpp +++ b/Marlin/src/lcd/menu/menu_motion.cpp @@ -382,6 +382,38 @@ void menu_move() { END_MENU(); } + #if ENABLED(FTM_RESONANCE_TEST) + + void menu_ftm_resonance_freq() { + START_MENU(); + BACK_ITEM(MSG_FTM_RESONANCE_TEST); + + STATIC_ITEM(MSG_FTM_RETRIEVE_FREQ); + EDIT_ITEM(float62, MSG_FTM_TIMELINE_FREQ, &ftMotion.rtg.timeline, 0.0f, 600.0f); + PSTRING_ITEM(MSG_FTM_RESONANCE_FREQ, ftostr53_63(ftMotion.rtg.getFrequencyFromTimeline()), SS_FULL); + + END_MENU(); + } + + void menu_ftm_resonance_test() { + START_MENU(); + BACK_ITEM(MSG_FIXED_TIME_MOTION); + + if (ftMotion.rtg.isActive() && !ftMotion.rtg.isDone()) { + STATIC_ITEM(MSG_FTM_RT_RUNNING); + ACTION_ITEM(MSG_FTM_RT_STOP, []{ ftMotion.rtg.abort(); ui.go_back(); }); + } + else { + GCODES_ITEM_N(X_AXIS, MSG_FTM_RT_START_N, F("M495 X S")); + GCODES_ITEM_N(Y_AXIS, MSG_FTM_RT_START_N, F("M495 Y S")); + GCODES_ITEM_N(Z_AXIS, MSG_FTM_RT_START_N, F("M495 Z S")); + SUBMENU(MSG_FTM_RETRIEVE_FREQ, menu_ftm_resonance_freq); + } + END_MENU(); + } + + #endif // FTM_RESONANCE_TEST + #if HAS_DYNAMIC_FREQ void menu_ftm_dyn_mode() { @@ -504,6 +536,10 @@ void menu_move() { #if ENABLED(FTM_SMOOTHING) CARTES_MAP(_SMOO_MENU_ITEM); #endif + + #if ENABLED(FTM_RESONANCE_TEST) + SUBMENU(MSG_FTM_RESONANCE_TEST, menu_ftm_resonance_test); + #endif } END_MENU(); } // menu_ft_motion diff --git a/Marlin/src/module/ft_motion.cpp b/Marlin/src/module/ft_motion.cpp index 0a2c9f6c3a..74ef6e79ef 100644 --- a/Marlin/src/module/ft_motion.cpp +++ b/Marlin/src/module/ft_motion.cpp @@ -35,6 +35,11 @@ #include "ft_motion/trajectory_trapezoidal.h" #include "ft_motion/trajectory_poly5.h" #include "ft_motion/trajectory_poly6.h" +#if ENABLED(FTM_RESONANCE_TEST) + #include "ft_motion/resonance_generator.h" + #include "../gcode/gcode.h" // for home_all_axes +#endif + #include "stepper.h" // Access stepper block queue function and abort status. #include "endstops.h" @@ -71,6 +76,9 @@ Poly6TrajectoryGenerator FTMotion::poly6Generator; TrajectoryGenerator* FTMotion::currentGenerator = &FTMotion::trapezoidalGenerator; TrajectoryType FTMotion::trajectoryType = TrajectoryType::FTM_TRAJECTORY_TYPE; +// Resonance Test +TERN_(FTM_RESONANCE_TEST,ResonanceGenerator FTMotion::rtg;) // Resonance trajectory generator instance + // Compact plan buffer stepper_plan_t FTMotion::stepper_plan_buff[FTM_BUFFER_SIZE]; XYZEval FTMotion::curr_steps_q32_32 = {0}; @@ -150,14 +158,32 @@ void FTMotion::loop() { * 3. Reset all the states / memory. * 4. Signal ready for new block. */ - if (stepper.abort_current_block) { - discard_planner_block_protected(); - reset(); - currentGenerator->planRunout(0.0f); // Reset generator state - stepper.abort_current_block = false; // Abort finished. - } - fill_stepper_plan_buffer(); + const bool using_resonance = TERN(FTM_RESONANCE_TEST, rtg.isActive(), false); + + #if ENABLED(FTM_RESONANCE_TEST) + if (using_resonance) { + // Resonance Test has priority over normal ft_motion operation. + // Process resonance test if active. When it's done, generate the last data points for a clean ending. + if (rtg.isActive()) { + if (rtg.isDone()) { + rtg.abort(); + return; + } + rtg.fill_stepper_plan_buffer(); + } + } + #endif + + if (!using_resonance) { + if (stepper.abort_current_block) { + discard_planner_block_protected(); + reset(); + currentGenerator->planRunout(0.0f); // Reset generator state + stepper.abort_current_block = false; // Abort finished. + } + fill_stepper_plan_buffer(); + } // Set busy status for use by planner.busy() const bool oldBusy = busy; @@ -557,4 +583,25 @@ void FTMotion::fill_stepper_plan_buffer() { } } +#if ENABLED(FTM_RESONANCE_TEST) + + // Start Resonance Testing + void FTMotion::start_resonance_test() { + home_if_needed(); // Ensure known axes first + + ftm_resonance_test_params_t &p = rtg.rt_params; + + // Safe Acceleration per Hz for Z axis + if (p.axis == Z_AXIS && p.accel_per_hz > 15.0f) + p.accel_per_hz = 15.0f; + + // Always move to the center of the bed + do_blocking_move_to_xy(X_CENTER, Y_CENTER, Z_CLEARANCE_FOR_HOMING); + + // Start test at the current position with the configured time-step + rtg.start(current_position, FTM_TS); + } + +#endif // FTM_RESONANCE_TEST + #endif // FT_MOTION diff --git a/Marlin/src/module/ft_motion.h b/Marlin/src/module/ft_motion.h index bec65f2abf..6e5b36cbe4 100644 --- a/Marlin/src/module/ft_motion.h +++ b/Marlin/src/module/ft_motion.h @@ -28,6 +28,9 @@ #include "ft_motion/trajectory_trapezoidal.h" #include "ft_motion/trajectory_poly5.h" #include "ft_motion/trajectory_poly6.h" +#if ENABLED(FTM_RESONANCE_TEST) + #include "ft_motion/resonance_generator.h" +#endif #if HAS_FTM_SHAPING #include "ft_motion/shaping.h" @@ -88,6 +91,10 @@ typedef struct FTConfig { */ class FTMotion { + #if ENABLED(FTM_RESONANCE_TEST) + friend void ResonanceGenerator::fill_stepper_plan_buffer(); + #endif + public: // Public variables @@ -140,6 +147,10 @@ class FTMotion { // Public methods static void init(); static void loop(); // Controller main, to be invoked from non-isr task. + #if ENABLED(FTM_RESONANCE_TEST) + static void start_resonance_test(); // Start a resonance test with given parameters + static ResonanceGenerator rtg; // Resonance trajectory generator instance + #endif #if HAS_FTM_SHAPING // Refresh gains and indices used by shaping functions. diff --git a/Marlin/src/module/ft_motion/resonance_generator.cpp b/Marlin/src/module/ft_motion/resonance_generator.cpp new file mode 100644 index 0000000000..f1b14ab72a --- /dev/null +++ b/Marlin/src/module/ft_motion/resonance_generator.cpp @@ -0,0 +1,88 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2025 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" + +#if ENABLED(FTM_RESONANCE_TEST) + +#include "../ft_motion.h" +#include "resonance_generator.h" + +#include + +ftm_resonance_test_params_t ResonanceGenerator::rt_params; // Resonance test parameters + +bool ResonanceGenerator::active = false; // Resonance test active +bool ResonanceGenerator::done = false; // Resonance test done +float ResonanceGenerator::rt_time = FTM_TS; // Resonance test timer +float ResonanceGenerator::timeline = 0.0f; + +ResonanceGenerator::ResonanceGenerator() {} + +void ResonanceGenerator::abort() { + reset(); + ftMotion.reset(); +} + +void ResonanceGenerator::reset() { + rt_params = ftm_resonance_test_params_t(); + rt_time = FTM_TS; + active = false; + done = false; +} + +void ResonanceGenerator::fill_stepper_plan_buffer() { + xyze_float_t traj_coords = {}; + + while (!ftMotion.stepper_plan_is_full()) { + // Calculate current frequency + // Logarithmic approach with duration per octave + const float freq = rt_params.min_freq * powf(2.0f, rt_time / rt_params.octave_duration); + if (freq > rt_params.max_freq) { + done = true; + return; + } + + // Amplitude based on a sinusoidal wave : A = accel / (4 * PI^2 * f^2) + //const float accel_magnitude = rt_params.accel_per_hz * freq; + //const float amplitude = rt_params.amplitude_correction * accel_magnitude / (4.0f * sq(M_PI) * sq(freq)); + const float amplitude = rt_params.amplitude_correction * rt_params.accel_per_hz * 0.25f / (sq(M_PI) * freq); + + // Phase in radians + const float phase = 2.0f * M_PI * freq * rt_time; + + // Position Offset : between -A and +A + const float pos_offset = amplitude * sinf(phase); + + // Set base position and apply offset to the test axis in one step for all axes + #define _SET_TRAJ(A) traj_coords.A = rt_params.start_pos.A + (rt_params.axis == A##_AXIS ? pos_offset : 0.0f); + LOGICAL_AXIS_MAP(_SET_TRAJ); + + stepper_plan_t plan = ftMotion.calc_stepper_plan(traj_coords); + // Store in buffer + ftMotion.enqueue_stepper_plan(plan); + // Increment time for the next point + rt_time += FTM_TS; + } +} + +#endif // FTM_RESONANCE_TEST diff --git a/Marlin/src/module/ft_motion/resonance_generator.h b/Marlin/src/module/ft_motion/resonance_generator.h new file mode 100644 index 0000000000..16156693dd --- /dev/null +++ b/Marlin/src/module/ft_motion/resonance_generator.h @@ -0,0 +1,73 @@ +/** + * Marlin 3D Printer Firmware + * Copyright (c) 2025 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 "../../inc/MarlinConfigPre.h" + +#include + +typedef struct FTMResonanceTestParams { + AxisEnum axis = NO_AXIS_ENUM; // Axis to test + float min_freq = 5.0f; // Minimum frequency [Hz] + float max_freq = 100.0f; // Maximum frequency [Hz] + float octave_duration = 40.0f; // Octave duration for logarithmic progression + float accel_per_hz = 60.0f; // Acceleration per Hz [mm/sec/Hz] or [g/Hz] + int16_t amplitude_correction = 5; // Amplitude correction factor + xyze_pos_t start_pos; // Initial stepper position +} ftm_resonance_test_params_t; + +class ResonanceGenerator { + public: + static ftm_resonance_test_params_t rt_params; // Resonance test parameters + static float timeline; // Timeline Value to calculate resonance frequency + + ResonanceGenerator(); + + void planRunout(const float duration); + + void reset(); + + void start(const xyze_pos_t &spos, const float t) { + rt_params.start_pos = spos; + rt_time = t; + active = true; + done = false; + } + + float getFrequencyFromTimeline() { + return (rt_params.min_freq * powf(2.0f, timeline / rt_params.octave_duration)); // Return frequency based on timeline + } + + void fill_stepper_plan_buffer(); // Fill stepper plan buffer with trajectory points + + bool isActive() const { return active; } + bool isDone() const { return done; } + void setActive(bool state) { active = state; } + void setDone(bool state) { done = state; } + + void abort(); // Abort resonance test + + private: + static float rt_time; // Test timer + static bool active; // Resonance test active + static bool done; // Resonance test done +}; diff --git a/Marlin/src/module/ft_motion/stepping.h b/Marlin/src/module/ft_motion/stepping.h index 6d0f3d31a5..2b9ad3a21a 100644 --- a/Marlin/src/module/ft_motion/stepping.h +++ b/Marlin/src/module/ft_motion/stepping.h @@ -29,7 +29,6 @@ typedef struct stepper_plan { void reset() { advance_dividend_q0_32.reset(); } } stepper_plan_t; - // Stepping plan handles steps for a while frame (trajectory point delta) typedef struct Stepping { stepper_plan_t stepper_plan; diff --git a/Marlin/src/module/ft_motion/trajectory_generator.h b/Marlin/src/module/ft_motion/trajectory_generator.h index 934394940a..677249af0d 100644 --- a/Marlin/src/module/ft_motion/trajectory_generator.h +++ b/Marlin/src/module/ft_motion/trajectory_generator.h @@ -21,7 +21,7 @@ */ #pragma once -#include +#include "../../inc/MarlinConfigPre.h" /** * Base class for trajectory generators. @@ -72,4 +72,7 @@ protected: /** * Trajectory generator types for runtime selection */ -enum class TrajectoryType : uint8_t { TRAPEZOIDAL, POLY5, POLY6 }; +enum class TrajectoryType : uint8_t { + TRAPEZOIDAL, POLY5, POLY6 + OPTARG(FTM_RESONANCE_TEST, RESONANCE) +}; diff --git a/Marlin/src/module/ft_motion/trajectory_poly6.cpp b/Marlin/src/module/ft_motion/trajectory_poly6.cpp index a16f344217..338c7b0d5d 100644 --- a/Marlin/src/module/ft_motion/trajectory_poly6.cpp +++ b/Marlin/src/module/ft_motion/trajectory_poly6.cpp @@ -25,8 +25,8 @@ #if ENABLED(FT_MOTION) #include "trajectory_poly6.h" -#include #include "../ft_motion.h" +#include Poly6TrajectoryGenerator::Poly6TrajectoryGenerator() {} diff --git a/buildroot/tests/STM32F103RC_btt b/buildroot/tests/STM32F103RC_btt index 97339d7750..369fa80978 100755 --- a/buildroot/tests/STM32F103RC_btt +++ b/buildroot/tests/STM32F103RC_btt @@ -14,6 +14,7 @@ opt_set MOTHERBOARD BOARD_BTT_SKR_MINI_E3_V1_0 SERIAL_PORT 1 SERIAL_PORT_2 -1 \ X_DRIVER_TYPE TMC2209 Y_DRIVER_TYPE TMC2209 Z_DRIVER_TYPE TMC2209 E0_DRIVER_TYPE TMC2209 \ X_CURRENT_HOME X_CURRENT/2 Y_CURRENT_HOME Y_CURRENT/2 Z_CURRENT_HOME Y_CURRENT/2 opt_enable CR10_STOCKDISPLAY PINS_DEBUGGING Z_IDLE_HEIGHT EDITABLE_HOMING_CURRENT \ - FT_MOTION FT_MOTION_MENU BIQU_MICROPROBE_V1 PROBE_ENABLE_DISABLE Z_SAFE_HOMING AUTO_BED_LEVELING_BILINEAR \ - ADAPTIVE_STEP_SMOOTHING LIN_ADVANCE SMOOTH_LIN_ADVANCE NONLINEAR_EXTRUSION INPUT_SHAPING_X INPUT_SHAPING_Y + INPUT_SHAPING_X INPUT_SHAPING_Y FT_MOTION FT_MOTION_MENU FTM_RESONANCE_TEST EMERGENCY_PARSER \ + BIQU_MICROPROBE_V1 PROBE_ENABLE_DISABLE Z_SAFE_HOMING AUTO_BED_LEVELING_BILINEAR \ + ADAPTIVE_STEP_SMOOTHING LIN_ADVANCE SMOOTH_LIN_ADVANCE NONLINEAR_EXTRUSION exec_test $1 $2 "BigTreeTech SKR Mini E3 1.0 - TMC2209 HW Serial, FT_MOTION" "$3" diff --git a/ini/features.ini b/ini/features.ini index f727f00f16..1c10302fb0 100644 --- a/ini/features.ini +++ b/ini/features.ini @@ -311,8 +311,9 @@ HAS_DUPLICATION_MODE = build_src_filter=+ PLATFORM_M997_SUPPORT = build_src_filter=+ HAS_TOOLCHANGE = build_src_filter=+ -FT_MOTION = build_src_filter=+ + - + +FT_MOTION = build_src_filter=+ + - + - FTM_SMOOTHING = build_src_filter=+ +FTM_RESONANCE_TEST = build_src_filter=+ HAS_LIN_ADVANCE_K = build_src_filter=+ PHOTO_GCODE = build_src_filter=+ CONTROLLER_FAN_EDITABLE = build_src_filter=+ From 5b34686dda296cbb670d9cb80639c3ad13750f3d Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 8 Nov 2025 16:04:40 -0600 Subject: [PATCH 41/99] =?UTF-8?q?=E2=9C=A8=20FTM=5FRESONANCE=5FTEST=20(2)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration_adv.h | 1 + 1 file changed, 1 insertion(+) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index de1c841f1c..ae4acaa56b 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1178,6 +1178,7 @@ #define FTM_SHAPING_V_TOL_E 0.05f // Vibration tolerance used by EI input shapers for E axis //#define FTM_RESONANCE_TEST // Sine sweep motion for resonance study + //#define FTM_SMOOTHING // Smoothing can reduce artifacts and make steppers quieter // on sharp corners, but too much will round corners. #if ENABLED(FTM_SMOOTHING) From 07630e65593779b88ff08551266b4b237c7b36b0 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 8 Nov 2025 16:15:20 -0600 Subject: [PATCH 42/99] =?UTF-8?q?=F0=9F=8E=A8=20per=20=3D>=20pct?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/HD44780/marlinui_HD44780.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp b/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp index a7507bd1e8..fe4b0e5aa7 100644 --- a/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp +++ b/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp @@ -1124,7 +1124,7 @@ void MarlinUI::draw_status_screen() { rotate_progress(); #else char c; - uint16_t per; + uint16_t pct; #if HAS_FAN0 if (true #if ALL(HAS_EXTRUDERS, ADAPTIVE_FAN_SLOWING) @@ -1136,18 +1136,18 @@ void MarlinUI::draw_status_screen() { #if ENABLED(ADAPTIVE_FAN_SLOWING) else { c = '*'; spd = thermalManager.scaledFanSpeed(0, spd); } #endif - per = thermalManager.pwmToPercent(spd); + pct = thermalManager.pwmToPercent(spd); } else #endif { #if HAS_EXTRUDERS c = 'E'; - per = planner.flow_percentage[0]; + pct = planner.flow_percentage[0]; #endif } lcd_put_lchar(c); - lcd_put_u8str(i16tostr3rj(per)); + lcd_put_u8str(i16tostr3rj(pct)); lcd_put_u8str(F("%")); #endif #endif From 90363cefd02b97a1e1e550388b74e2e4913fa717 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sat, 8 Nov 2025 16:38:24 -0600 Subject: [PATCH 43/99] =?UTF-8?q?=F0=9F=8E=A8=20Conditional=20HAS=5FVOLUME?= =?UTF-8?q?TRIC=5FEXTRUSION?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/feature/fwretract.cpp | 5 ++--- Marlin/src/feature/powerloss.cpp | 8 ++++---- Marlin/src/feature/powerloss.h | 4 ++-- Marlin/src/gcode/bedlevel/G26.cpp | 4 ++-- Marlin/src/gcode/config/M200-M205.cpp | 4 ++-- Marlin/src/gcode/gcode.cpp | 2 +- Marlin/src/gcode/gcode.h | 2 +- Marlin/src/gcode/host/M115.cpp | 2 +- Marlin/src/gcode/host/M360.cpp | 2 +- Marlin/src/inc/Conditionals-4-adv.h | 4 ++++ Marlin/src/lcd/menu/menu_advanced.cpp | 8 ++++---- Marlin/src/module/planner.cpp | 8 ++++---- Marlin/src/module/planner.h | 17 +++++++---------- Marlin/src/module/settings.cpp | 12 ++++++------ 14 files changed, 41 insertions(+), 41 deletions(-) diff --git a/Marlin/src/feature/fwretract.cpp b/Marlin/src/feature/fwretract.cpp index 8944d2bd35..5ea20401ea 100644 --- a/Marlin/src/feature/fwretract.cpp +++ b/Marlin/src/feature/fwretract.cpp @@ -164,9 +164,8 @@ void FWRetract::retract(const bool retracting E_OPTARG(bool swapping/*=false*/)) current_retract[active_extruder] = 0; // Recover E, set_current_to_destination - prepare_internal_move_to_destination( - MUL_TERN(RETRACT_SYNC_MIXING, swapping ? settings.swap_retract_recover_feedrate_mm_s : settings.retract_recover_feedrate_mm_s, MIXING_STEPPERS) - ); + const feedRate_t fr_mm_s = swapping ? settings.swap_retract_recover_feedrate_mm_s : settings.retract_recover_feedrate_mm_s; + prepare_internal_move_to_destination(MUL_TERN(RETRACT_SYNC_MIXING, fr_mm_s, MIXING_STEPPERS)); } TERN_(RETRACT_SYNC_MIXING, mixer.T(old_mixing_tool)); // Restore original mixing tool diff --git a/Marlin/src/feature/powerloss.cpp b/Marlin/src/feature/powerloss.cpp index 01a4d3bc02..385ca6b72d 100644 --- a/Marlin/src/feature/powerloss.cpp +++ b/Marlin/src/feature/powerloss.cpp @@ -221,7 +221,7 @@ void PrintJobRecovery::save(const bool force/*=false*/, const float zraise/*=POW TERN_(HAS_WORKSPACE_OFFSET, info.workspace_offset = workspace_offset); E_TERN_(info.active_extruder = active_extruder); - #if DISABLED(NO_VOLUMETRICS) + #if HAS_VOLUMETRIC_EXTRUSION info.flag.volumetric_enabled = parser.volumetric_enabled; #if HAS_MULTI_EXTRUDER COPY(info.filament_size, planner.filament_size); @@ -496,7 +496,7 @@ void PrintJobRecovery::resume() { #endif // Recover volumetric extrusion state - #if DISABLED(NO_VOLUMETRICS) + #if HAS_VOLUMETRIC_EXTRUSION #if HAS_MULTI_EXTRUDER EXTRUDER_LOOP() PROCESS_SUBCOMMANDS_NOW(TS(F("M200T"), e, F("D"), p_float_t(info.filament_size[e], 3))); @@ -659,7 +659,7 @@ void PrintJobRecovery::resume() { DEBUG_ECHOLNPGM("active_extruder: ", info.active_extruder); #endif - #if DISABLED(NO_VOLUMETRICS) + #if HAS_VOLUMETRIC_EXTRUSION DEBUG_ECHOPGM("filament_size:"); EXTRUDER_LOOP() DEBUG_ECHOLNPGM(" ", info.filament_size[e]); DEBUG_EOL(); @@ -725,7 +725,7 @@ void PrintJobRecovery::resume() { DEBUG_ECHOLNPGM("flag.dryrun: ", AS_DIGIT(info.flag.dryrun)); DEBUG_ECHOLNPGM("flag.allow_cold_extrusion: ", AS_DIGIT(info.flag.allow_cold_extrusion)); - #if DISABLED(NO_VOLUMETRICS) + #if HAS_VOLUMETRIC_EXTRUSION DEBUG_ECHOLNPGM("flag.volumetric_enabled: ", AS_DIGIT(info.flag.volumetric_enabled)); #endif } diff --git a/Marlin/src/feature/powerloss.h b/Marlin/src/feature/powerloss.h index 187e804aa8..eceb862779 100644 --- a/Marlin/src/feature/powerloss.h +++ b/Marlin/src/feature/powerloss.h @@ -88,7 +88,7 @@ typedef struct { uint8_t active_extruder; #endif - #if DISABLED(NO_VOLUMETRICS) + #if HAS_VOLUMETRIC_EXTRUSION float filament_size[EXTRUDERS]; #endif @@ -140,7 +140,7 @@ typedef struct { #if HAS_LEVELING bool leveling:1; // M420 S #endif - #if DISABLED(NO_VOLUMETRICS) + #if HAS_VOLUMETRIC_EXTRUSION bool volumetric_enabled:1; // M200 S D #endif } flag; diff --git a/Marlin/src/gcode/bedlevel/G26.cpp b/Marlin/src/gcode/bedlevel/G26.cpp index b655c3026f..ba4647e6f5 100644 --- a/Marlin/src/gcode/bedlevel/G26.cpp +++ b/Marlin/src/gcode/bedlevel/G26.cpp @@ -663,7 +663,7 @@ void GcodeSuite::G26() { do_z_clearance(Z_CLEARANCE_BETWEEN_PROBES); - #if DISABLED(NO_VOLUMETRICS) + #if HAS_VOLUMETRIC_EXTRUSION bool volumetric_was_enabled = parser.volumetric_enabled; parser.volumetric_enabled = false; planner.calculate_volumetric_multipliers(); @@ -856,7 +856,7 @@ void GcodeSuite::G26() { destination.z = Z_CLEARANCE_BETWEEN_PROBES; move_to(destination, 0); // Raise the nozzle - #if DISABLED(NO_VOLUMETRICS) + #if HAS_VOLUMETRIC_EXTRUSION parser.volumetric_enabled = volumetric_was_enabled; planner.calculate_volumetric_multipliers(); #endif diff --git a/Marlin/src/gcode/config/M200-M205.cpp b/Marlin/src/gcode/config/M200-M205.cpp index dd4eada06f..53d0b4b4a8 100644 --- a/Marlin/src/gcode/config/M200-M205.cpp +++ b/Marlin/src/gcode/config/M200-M205.cpp @@ -24,7 +24,7 @@ #include "../../MarlinCore.h" #include "../../module/planner.h" -#if DISABLED(NO_VOLUMETRICS) +#if HAS_VOLUMETRIC_EXTRUSION /** * M200: Set filament diameter and set E axis units to cubic units @@ -107,7 +107,7 @@ #endif } -#endif // !NO_VOLUMETRICS +#endif // HAS_VOLUMETRIC_EXTRUSION /** * M201: Set max acceleration in units/s^2 for print moves. diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index f7ecbbd1d3..373cc16a53 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -717,7 +717,7 @@ void GcodeSuite::process_parsed_command(bool no_ok/*=false*/) { #endif #endif - #if DISABLED(NO_VOLUMETRICS) + #if HAS_VOLUMETRIC_EXTRUSION case 200: M200(); break; // M200: Set filament diameter, E to cubic units #endif diff --git a/Marlin/src/gcode/gcode.h b/Marlin/src/gcode/gcode.h index e288b9bd99..a0f3f68f6f 100644 --- a/Marlin/src/gcode/gcode.h +++ b/Marlin/src/gcode/gcode.h @@ -883,7 +883,7 @@ private: #endif #endif - #if DISABLED(NO_VOLUMETRICS) + #if HAS_VOLUMETRIC_EXTRUSION static void M200(); static void M200_report(const bool forReplay=true); #endif diff --git a/Marlin/src/gcode/host/M115.cpp b/Marlin/src/gcode/host/M115.cpp index 92193108f0..5ed52dbba1 100644 --- a/Marlin/src/gcode/host/M115.cpp +++ b/Marlin/src/gcode/host/M115.cpp @@ -139,7 +139,7 @@ void GcodeSuite::M115() { cap_line(F("EEPROM"), ENABLED(EEPROM_SETTINGS)); // Volumetric Extrusion (M200) - cap_line(F("VOLUMETRIC"), DISABLED(NO_VOLUMETRICS)); + cap_line(F("VOLUMETRIC"), ENABLED(HAS_VOLUMETRIC_EXTRUSION)); // AUTOREPORT_POS (M154) cap_line(F("AUTOREPORT_POS"), ENABLED(AUTO_REPORT_POSITION)); diff --git a/Marlin/src/gcode/host/M360.cpp b/Marlin/src/gcode/host/M360.cpp index 56ab7ad8b9..d5f54a81a1 100644 --- a/Marlin/src/gcode/host/M360.cpp +++ b/Marlin/src/gcode/host/M360.cpp @@ -242,7 +242,7 @@ void GcodeSuite::M360() { #endif config_line_e(e, F("Acceleration"), planner.settings.max_acceleration_mm_per_s2[E_AXIS_N(e)]); config_line_e(e, F("MaxSpeed"), planner.settings.max_feedrate_mm_s[E_AXIS_N(e)]); - config_line_e(e, F("Diameter"), TERN(NO_VOLUMETRICS, DEFAULT_NOMINAL_FILAMENT_DIA, planner.filament_size[e])); + config_line_e(e, F("Diameter"), TERN(HAS_VOLUMETRIC_EXTRUSION, planner.filament_size[e], DEFAULT_NOMINAL_FILAMENT_DIA)); config_line_e(e, F("MaxTemp"), thermalManager.hotend_maxtemp[e]); } #endif diff --git a/Marlin/src/inc/Conditionals-4-adv.h b/Marlin/src/inc/Conditionals-4-adv.h index df2327254d..8770f6bf9b 100644 --- a/Marlin/src/inc/Conditionals-4-adv.h +++ b/Marlin/src/inc/Conditionals-4-adv.h @@ -245,6 +245,10 @@ #undef STEALTHCHOP_E #endif +#if DISABLED(NO_VOLUMETRICS) + #define HAS_VOLUMETRIC_EXTRUSION 1 +#endif + #if !TEMP_SENSOR_CHAMBER #undef CHAMBER_CHECK_INTERVAL #undef CHAMBER_AUTO_FAN_PIN diff --git a/Marlin/src/lcd/menu/menu_advanced.cpp b/Marlin/src/lcd/menu/menu_advanced.cpp index 07516205ff..a8d792dbca 100644 --- a/Marlin/src/lcd/menu/menu_advanced.cpp +++ b/Marlin/src/lcd/menu/menu_advanced.cpp @@ -33,7 +33,7 @@ #include "../../module/planner.h" #include "../../module/stepper.h" -#if DISABLED(NO_VOLUMETRICS) +#if HAS_VOLUMETRIC_EXTRUSION #include "../../gcode/parser.h" #endif @@ -103,7 +103,7 @@ void menu_backlash(); #endif -#if DISABLED(NO_VOLUMETRICS) || ENABLED(ADVANCED_PAUSE_FEATURE) +#if ANY(HAS_VOLUMETRIC_EXTRUSION, ADVANCED_PAUSE_FEATURE) #define HAS_ADV_FILAMENT_MENU 1 #endif @@ -142,7 +142,7 @@ void menu_backlash(); EDIT_ITEM(bool, MSG_NLE_ON, &stepper.ne.settings.enabled); #endif - #if DISABLED(NO_VOLUMETRICS) + #if HAS_VOLUMETRIC_EXTRUSION EDIT_ITEM(bool, MSG_VOLUMETRIC_ENABLED, &parser.volumetric_enabled, planner.calculate_volumetric_multipliers); #if ENABLED(VOLUMETRIC_EXTRUDER_LIMIT) @@ -160,7 +160,7 @@ void menu_backlash(); EDIT_ITEM_FAST_N(float43, e, MSG_FILAMENT_DIAM_E, &planner.filament_size[e], 1.5f, 3.25f, planner.calculate_volumetric_multipliers); #endif } - #endif // !NO_VOLUMETRICS + #endif // HAS_VOLUMETRIC_EXTRUSION #if ENABLED(CONFIGURE_FILAMENT_CHANGE) constexpr float extrude_maxlength = TERN(PREVENT_LENGTHY_EXTRUDE, EXTRUDE_MAXLENGTH, 999); diff --git a/Marlin/src/module/planner.cpp b/Marlin/src/module/planner.cpp index 6534425262..7bb078be16 100644 --- a/Marlin/src/module/planner.cpp +++ b/Marlin/src/module/planner.cpp @@ -178,7 +178,7 @@ uint32_t Planner::max_acceleration_steps_per_s2[DISTINCT_AXES]; // (steps/s^2) D float Planner::e_factor[EXTRUDERS] = ARRAY_BY_EXTRUDERS1(1.0f); // The flow percentage and volumetric multiplier combine to scale E movement #endif -#if DISABLED(NO_VOLUMETRICS) +#if HAS_VOLUMETRIC_EXTRUSION float Planner::volumetric_area_nominal = CIRCLE_AREA(float(DEFAULT_NOMINAL_FILAMENT_DIA) * 0.5f); // Nominal cross-sectional area float Planner::filament_size[EXTRUDERS], // diameter of filament (in millimeters), typically around 1.75 or 2.85, 0 disables the volumetric calculations for the extruder Planner::volumetric_multiplier[EXTRUDERS]; // Reciprocal of cross-sectional area of filament (in mm^2). Pre-calculated to reduce computation in the planner @@ -1214,7 +1214,7 @@ void Planner::recalculate(const float safe_exit_speed_sqr) { if (fan_speed[f] > FAN_OFF_PWM) { const bool first_kick = fan_kick_end[f] == 0 && TERN1(FAN_KICKSTART_LINEAR, fan_speed[f] > set_fan_speed[f]); if (first_kick) - fan_kick_end[f] = ms + (FAN_KICKSTART_TIME) TERN_(FAN_KICKSTART_LINEAR, * (fan_speed[f] - set_fan_speed[f]) / 255); + fan_kick_end[f] = ms + MUL_TERN(FAN_KICKSTART_LINEAR, FAN_KICKSTART_TIME, (fan_speed[f] - set_fan_speed[f]) / 255); if (first_kick || PENDING(ms, fan_kick_end[f])) { fan_speed[f] = FAN_KICKSTART_POWER; return; @@ -1360,7 +1360,7 @@ void Planner::check_axes_activity() { #endif // AUTOTEMP -#if DISABLED(NO_VOLUMETRICS) +#if HAS_VOLUMETRIC_EXTRUSION /** * Get a volumetric multiplier from a filament diameter. @@ -1385,7 +1385,7 @@ void Planner::check_axes_activity() { #endif } -#endif // !NO_VOLUMETRICS +#endif // HAS_VOLUMETRIC_EXTRUSION #if ENABLED(VOLUMETRIC_EXTRUDER_LIMIT) diff --git a/Marlin/src/module/planner.h b/Marlin/src/module/planner.h index 14c83b0559..d8d0e053e7 100644 --- a/Marlin/src/module/planner.h +++ b/Marlin/src/module/planner.h @@ -474,7 +474,7 @@ class Planner { static float e_factor[EXTRUDERS]; // The flow percentage and volumetric multiplier combine to scale E movement #endif - #if DISABLED(NO_VOLUMETRICS) + #if HAS_VOLUMETRIC_EXTRUSION static float volumetric_area_nominal; // (mm^3) Nominal cross-sectional area static float filament_size[EXTRUDERS], // (mm) Diameter of filament, typically around 1.75 or 2.85, 0 disables the volumetric calculations for the extruder volumetric_multiplier[EXTRUDERS]; // (1/mm^2) Reciprocal of cross-sectional area of filament. Pre-calculated to reduce computation in the planner @@ -660,7 +660,7 @@ class Planner { #if HAS_EXTRUDERS FORCE_INLINE static void refresh_e_factor(const uint8_t e) { - e_factor[e] = flow_percentage[e] * 0.01f IF_DISABLED(NO_VOLUMETRICS, * volumetric_multiplier[e]); + e_factor[e] = MUL_TERN(HAS_VOLUMETRIC_EXTRUSION, flow_percentage[e] * 0.01f, volumetric_multiplier[e]); } static void set_flow(const uint8_t e, const int16_t flow) { @@ -702,7 +702,7 @@ class Planner { void enable_stall_prevention(const bool onoff); #endif - #if DISABLED(NO_VOLUMETRICS) + #if HAS_VOLUMETRIC_EXTRUSION // Update multipliers based on new diameter measurements static void calculate_volumetric_multipliers(); @@ -711,6 +711,10 @@ class Planner { // Update pre calculated extruder feedrate limits based on volumetric values static void calculate_volumetric_extruder_limit(const uint8_t e); static void calculate_volumetric_extruder_limits(); + FORCE_INLINE static void set_volumetric_extruder_limit(const uint8_t e, const float v) { + volumetric_extruder_limit[e] = v; + calculate_volumetric_extruder_limit(e); + } #endif FORCE_INLINE static void set_filament_size(const uint8_t e, const float v) { @@ -723,13 +727,6 @@ class Planner { #endif - #if ENABLED(VOLUMETRIC_EXTRUDER_LIMIT) - FORCE_INLINE static void set_volumetric_extruder_limit(const uint8_t e, const float v) { - volumetric_extruder_limit[e] = v; - calculate_volumetric_extruder_limit(e); - } - #endif - #if ENABLED(ENABLE_LEVELING_FADE_HEIGHT) /** diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index 51f27966c4..7ebcb63eb1 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -480,7 +480,7 @@ typedef struct SettingsDataStruct { #endif // - // !NO_VOLUMETRIC + // HAS_VOLUMETRIC_EXTRUSION // bool parser_volumetric_enabled; // M200 S parser.volumetric_enabled float planner_filament_size[EXTRUDERS]; // M200 T D planner.filament_size[] @@ -733,7 +733,7 @@ void MarlinSettings::postprocess() { TERN_(PIDTEMP, thermalManager.updatePID()); - #if DISABLED(NO_VOLUMETRICS) + #if HAS_VOLUMETRIC_EXTRUSION planner.calculate_volumetric_multipliers(); #elif EXTRUDERS for (uint8_t i = COUNT(planner.e_factor); i--;) @@ -1399,7 +1399,7 @@ void MarlinSettings::postprocess() { { _FIELD_TEST(parser_volumetric_enabled); - #if DISABLED(NO_VOLUMETRICS) + #if HAS_VOLUMETRIC_EXTRUSION EEPROM_WRITE(parser.volumetric_enabled); EEPROM_WRITE(planner.filament_size); @@ -2488,7 +2488,7 @@ void MarlinSettings::postprocess() { _FIELD_TEST(parser_volumetric_enabled); EEPROM_READ(storage); - #if DISABLED(NO_VOLUMETRICS) + #if HAS_VOLUMETRIC_EXTRUSION if (!validating) { parser.volumetric_enabled = storage.volumetric_enabled; COPY(planner.filament_size, storage.filament_size); @@ -3597,7 +3597,7 @@ void MarlinSettings::reset() { // // Volumetric & Filament Size // - #if DISABLED(NO_VOLUMETRICS) + #if HAS_VOLUMETRIC_EXTRUSION parser.volumetric_enabled = ENABLED(VOLUMETRIC_DEFAULT_ON); for (uint8_t q = 0; q < COUNT(planner.filament_size); ++q) planner.filament_size[q] = DEFAULT_NOMINAL_FILAMENT_DIA; @@ -3863,7 +3863,7 @@ void MarlinSettings::reset() { // // M200 Volumetric Extrusion // - IF_DISABLED(NO_VOLUMETRICS, gcode.M200_report(forReplay)); + TERN_(HAS_VOLUMETRIC_EXTRUSION, gcode.M200_report(forReplay)); // // M92 Steps per Unit From f946b60670d987f3617337712c273a3935c7f953 Mon Sep 17 00:00:00 2001 From: Mihai <299015+mh-dm@users.noreply.github.com> Date: Sun, 9 Nov 2025 00:48:09 +0200 Subject: [PATCH 44/99] =?UTF-8?q?=E2=9C=A8=20S=5FCURVE=5FFACTOR=20(#27101)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration.h | 5 +++ Marlin/src/inc/SanityCheck.h | 10 +++++ Marlin/src/module/stepper.cpp | 79 ++++++++++++++++++++++++----------- Marlin/src/module/stepper.h | 2 +- 4 files changed, 71 insertions(+), 25 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 00f8ce2088..e51d16d565 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -1395,6 +1395,11 @@ * See https://github.com/synthetos/TinyG/wiki/Jerk-Controlled-Motion-Explained */ //#define S_CURVE_ACCELERATION +#if ENABLED(S_CURVE_ACCELERATION) + // Define to use 4th instead of 6th order motion curve + //#define S_CURVE_FACTOR 0.25 // Initial and final acceleration factor, ideally 0.1 to 0.4. + // Shouldn't generally require tuning. +#endif //=========================================================================== //============================= Z Probe Options ============================= diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 4bc63660a2..e0a42cdf37 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -866,6 +866,16 @@ static_assert(COUNT(arm) == LOGICAL_AXES, "AXIS_RELATIVE_MODES must contain " _L #endif #endif // LIN_ADVANCE +/** + * S_CURVE_ACCELERATION + */ +#if ENABLED(S_CURVE_ACCELERATION) && defined(S_CURVE_FACTOR) + #ifdef __AVR__ + #error "S_CURVE_FACTOR is not yet implemented for AVR. Disable it to continue." + #endif + static_assert(WITHIN(S_CURVE_FACTOR, 0, 1), "S_CURVE_FACTOR must be between 0.0 and 1.0."); +#endif + /** * Linear Advance and FT Motion - Check K value range */ diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index 873d1383d0..a875289f3c 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -661,7 +661,7 @@ void Stepper::apply_directions() { * a "linear pop" velocity curve; with pop being the sixth derivative of position: * velocity - 1st, acceleration - 2nd, jerk - 3rd, snap - 4th, crackle - 5th, pop - 6th * - * The Bézier curve takes the form: + * The 6th order Bézier curve takes the form: * * V(t) = P_0 * B_0(t) + P_1 * B_1(t) + P_2 * B_2(t) + P_3 * B_3(t) + P_4 * B_4(t) + P_5 * B_5(t) * @@ -681,7 +681,10 @@ void Stepper::apply_directions() { * Unfortunately, we cannot use forward-differencing to calculate each position through * the curve, as Marlin uses variable timer periods. So, we require a formula of the form: * + * 6th order: * V_f(t) = A*t^5 + B*t^4 + C*t^3 + D*t^2 + E*t + F + * 4th order: + * V_f(t) = A*t^3 + B*t^2 + C*t + F * * Looking at the above B_0(t) through B_5(t) expanded forms, if we take the coefficients of t^5 * through t of the Bézier form of V(t), we can determine that: @@ -704,15 +707,27 @@ void Stepper::apply_directions() { * E = 0 * F = P_i * + * For 4th order we want the initial and final acceleration to be a fixed S_CURVE_FACTOR fraction + * and solving gives us: + * + * A = 2*(1 - S_CURVE_FACTOR)*(P_i - P_t) + * B = 3*(1 - S_CURVE_FACTOR)*(P_t - P_i) + * C = S_CURVE_FACTOR*(P_t - P_i) + * F = P_i + * * As the t is evaluated in non uniform steps here, there is no other way rather than evaluating * the Bézier curve at each point: * + * 6th order: * V_f(t) = A*t^5 + B*t^4 + C*t^3 + F [0 <= t <= 1] + * 4th order: + * V_f(t) = A*t^3 + B*t^2 + C*t + F [0 <= t <= 1] * * Floating point arithmetic execution time cost is prohibitive, so we will transform the math to - * use fixed point values to be able to evaluate it in realtime. Assuming a maximum of 250000 steps - * per second (driver pulses should at least be 2µS hi/2µS lo), and allocating 2 bits to avoid - * overflows on the evaluation of the Bézier curve, means we can use + * use fixed point values to be able to evaluate it in realtime. + * + * 6th order: Assumes a maximum of 250000 steps/s (driver pulses down to 2µS hi/2µS lo), + * and allocates 2 bits to avoid overflows on the evaluation of the Bézier curve: * * t: unsigned Q0.32 (0 <= t < 1) |range 0 to 0xFFFFFFFF unsigned * A: signed Q24.7 , |range = +/- 250000 * 6 * 128 = +/- 192000000 = 0x0B71B000 | 28 bits + sign @@ -720,6 +735,8 @@ void Stepper::apply_directions() { * C: signed Q24.7 , |range = +/- 250000 *10 * 128 = +/- 320000000 = 0x1312D000 | 29 bits + sign * F: signed Q24.7 , |range = +/- 250000 * 128 = 32000000 = 0x01E84800 | 25 bits + sign * + * 4th order: With B coefficient at least 5x smaller the maximum will be ~1250000 steps/s. + * * The trapezoid generator state contains the following information, that we will use to create and evaluate * the Bézier curve: * @@ -734,9 +751,15 @@ void Stepper::apply_directions() { * * At the start of each trapezoid, calculate the coefficients A,B,C,F and Advance [AV], as follows: * + * 6th order: * A = 6*128*(VF - VI) = 768*(VF - VI) * B = 15*128*(VI - VF) = 1920*(VI - VF) * C = 10*128*(VF - VI) = 1280*(VF - VI) + * 4th order: + * A = 2*(1-S_CURVE_FACTOR)*128*(VI - VF) + * B = 3*(1-S_CURVE_FACTOR)*128*(VF - VI) + * C = S_CURVE_FACTOR*128*(VF - VI) + * both: * F = 128*VI = 128*VI * AV = (1<<32)/TS ~= 0xFFFFFFFF / TS (To use ARM UDIV, that is 32 bits) (this is computed at the planner, to offload expensive calculations from the ISR) * @@ -1385,9 +1408,17 @@ void Stepper::apply_directions() { // For all the other 32bit CPUs FORCE_INLINE void Stepper::_calc_bezier_curve_coeffs(const int32_t v0, const int32_t v1, const uint32_t av) { // Calculate the Bézier coefficients - bezier_A = 768 * (v1 - v0); - bezier_B = 1920 * (v0 - v1); - bezier_C = 1280 * (v1 - v0); + #ifndef S_CURVE_FACTOR + bezier_A = 768 * (v1 - v0); + bezier_B = 1920 * (v0 - v1); + bezier_C = 1280 * (v1 - v0); + #else + // Must convert from S_CURVE_FACTOR to int only once. + constexpr int FACTOR128 = S_CURVE_FACTOR * 128; + bezier_A = (2 * (128 - FACTOR128)) * (v0 - v1); + bezier_B = (3 * (128 - FACTOR128)) * (v1 - v0); + bezier_C = FACTOR128 * (v1 - v0); + #endif bezier_F = 128 * v0; bezier_AV = av; } @@ -1409,8 +1440,10 @@ void Stepper::apply_directions() { ".syntax unified" "\n\t" // is to prevent CM0,CM1 non-unified syntax A("lsrs %[ahi],%[alo],#1") // a = F << 31 1 cycles A("lsls %[alo],%[alo],#31") // 1 cycles - A("umull %[flo],%[fhi],%[fhi],%[t]") // f *= t 5 cycles [fhi:flo=64bits] - A("umull %[flo],%[fhi],%[fhi],%[t]") // f>>=32; f*=t 5 cycles [fhi:flo=64bits] + #ifndef S_CURVE_FACTOR + A("umull %[flo],%[fhi],%[fhi],%[t]") // f *= t 5 cycles [fhi:flo=64bits] + A("umull %[flo],%[fhi],%[fhi],%[t]") // f>>=32; f*=t 5 cycles [fhi:flo=64bits] + #endif A("lsrs %[flo],%[fhi],#1") // 1 cycles [31bits] A("smlal %[alo],%[ahi],%[flo],%[C]") // a+=(f>>33)*C; 5 cycles A("umull %[flo],%[fhi],%[fhi],%[t]") // f>>=32; f*=t 5 cycles [fhi:flo=64bits] @@ -1438,21 +1471,19 @@ void Stepper::apply_directions() { // For non ARM targets, we provide a fallback implementation. Really doubt it // will be useful, unless the processor is fast and 32bit - uint32_t t = bezier_AV * curr_step; // t: Range 0 - 1^32 = 32 bits - uint64_t f = t; - f *= t; // Range 32*2 = 64 bits (unsigned) - f >>= 32; // Range 32 bits (unsigned) - f *= t; // Range 32*2 = 64 bits (unsigned) - f >>= 32; // Range 32 bits : f = t^3 (unsigned) - int64_t acc = (int64_t) bezier_F << 31; // Range 63 bits (signed) - acc += ((uint32_t) f >> 1) * (int64_t) bezier_C; // Range 29bits + 31 = 60bits (plus sign) - f *= t; // Range 32*2 = 64 bits - f >>= 32; // Range 32 bits : f = t^3 (unsigned) - acc += ((uint32_t) f >> 1) * (int64_t) bezier_B; // Range 29bits + 31 = 60bits (plus sign) - f *= t; // Range 32*2 = 64 bits - f >>= 32; // Range 32 bits : f = t^3 (unsigned) - acc += ((uint32_t) f >> 1) * (int64_t) bezier_A; // Range 28bits + 31 = 59bits (plus sign) - acc >>= (31 + 7); // Range 24bits (plus sign) + uint32_t t = bezier_AV * curr_step; // t: Range 32 bits + uint64_t f = t; // f: Range 64 bits + #ifndef S_CURVE_FACTOR + f *= t; f >>= 32; // f = t^2 (unsigned) + f *= t; f >>= 32; // f = t^3 (unsigned) + #endif + int64_t acc = int64_t(bezier_F) << 31; // Range 63 bits (signed) + acc += uint32_t(f >> 1) * int64_t(bezier_C); // Range 29bits + 31 = 60bits (plus sign) + f *= t; f >>= 32; // f = t^2 or t^4 (unsigned) + acc += uint32_t(f >> 1) * int64_t(bezier_B); // Range 29bits + 31 = 60bits (plus sign) + f *= t; f >>= 32; // f = t^3 or t^5 (unsigned) + acc += uint32_t(f >> 1) * int64_t(bezier_A); // Range 28bits + 31 = 59bits (plus sign) + acc >>= (31 + 7); // Range 24bits (plus sign) return (int32_t) acc; #endif diff --git a/Marlin/src/module/stepper.h b/Marlin/src/module/stepper.h index dfca23715e..d1132face6 100644 --- a/Marlin/src/module/stepper.h +++ b/Marlin/src/module/stepper.h @@ -459,7 +459,7 @@ class Stepper { static int32_t bezier_A, // A coefficient in Bézier speed curve bezier_B, // B coefficient in Bézier speed curve bezier_C; // C coefficient in Bézier speed curve - static uint32_t bezier_F, // F coefficient in Bézier speed curve + static uint32_t bezier_F, // F/free coefficient in Bézier speed curve bezier_AV; // AV coefficient in Bézier speed curve #ifdef __AVR__ static bool A_negative; // If A coefficient was negative From 412513be436309d3641504008aaa89927088ad66 Mon Sep 17 00:00:00 2001 From: narno2202 <130909513+narno2202@users.noreply.github.com> Date: Sun, 9 Nov 2025 00:01:05 +0100 Subject: [PATCH 45/99] =?UTF-8?q?=E2=9C=A8=20FTM=5FRESONANCE=5FTEST=20(3)?= =?UTF-8?q?=20(#28164)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/menu/menu_motion.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/lcd/menu/menu_motion.cpp b/Marlin/src/lcd/menu/menu_motion.cpp index dd75cc5c29..ef082fe89f 100644 --- a/Marlin/src/lcd/menu/menu_motion.cpp +++ b/Marlin/src/lcd/menu/menu_motion.cpp @@ -401,7 +401,7 @@ void menu_move() { if (ftMotion.rtg.isActive() && !ftMotion.rtg.isDone()) { STATIC_ITEM(MSG_FTM_RT_RUNNING); - ACTION_ITEM(MSG_FTM_RT_STOP, []{ ftMotion.rtg.abort(); ui.go_back(); }); + ACTION_ITEM(MSG_FTM_RT_STOP, []{ ftMotion.rtg.abort(); ui.refresh(); }); } else { GCODES_ITEM_N(X_AXIS, MSG_FTM_RT_START_N, F("M495 X S")); From e53f2a3d827f120b2375d6de68775dbbaba5964a Mon Sep 17 00:00:00 2001 From: ellensp <530024+ellensp@users.noreply.github.com> Date: Sun, 9 Nov 2025 12:03:05 +1300 Subject: [PATCH 46/99] =?UTF-8?q?=F0=9F=A9=B9=20Fix=20=5F=5FARM=5FARCH=20c?= =?UTF-8?q?heck=20to=20omit=20M0+=20(#28162)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/module/stepper.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index a875289f3c..18d6ae8906 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -1424,7 +1424,7 @@ void Stepper::apply_directions() { } FORCE_INLINE int32_t Stepper::_eval_bezier_curve(const uint32_t curr_step) { - #if (defined(__arm__) || defined(__thumb__)) && __ARM_ARCH >= 6 && !defined(STM32G0B1xx) // TODO: Test define STM32G0xx versus STM32G0B1xx + #if (defined(__arm__) || defined(__thumb__)) && __ARM_ARCH >= 7 && !defined(STM32G0B1xx) // TODO: Test define STM32G0xx versus STM32G0B1xx // For ARM Cortex M3/M4 CPUs, we have the optimized assembler version, that takes 43 cycles to execute uint32_t flo = 0; From 59cee1cb87903f0c7d12f733c00acd42c7d88661 Mon Sep 17 00:00:00 2001 From: ellensp <530024+ellensp@users.noreply.github.com> Date: Sun, 9 Nov 2025 12:20:58 +1300 Subject: [PATCH 47/99] =?UTF-8?q?=F0=9F=94=A7=20Custom=20boot=20screen=20f?= =?UTF-8?q?or=20Graphical=20TFT=20(#28160)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration_adv.h | 2 +- Marlin/src/inc/SanityCheck.h | 4 +- Marlin/src/lcd/tft/canvas.cpp | 11 +++++ Marlin/src/lcd/tft/tft_image.cpp | 69 +++++++++++++++--------------- Marlin/src/lcd/tft/tft_image.h | 11 ++++- Marlin/src/lcd/tft/ui_color_ui.cpp | 14 ++++++ Marlin/src/lcd/tft/ui_common.h | 29 +++++++++++-- 7 files changed, 99 insertions(+), 41 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index ae4acaa56b..ffcecc3533 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -1628,7 +1628,7 @@ #if HAS_MARLINUI_U8GLIB //#define BOOT_MARLIN_LOGO_ANIMATED // Animated Marlin logo. Costs ~3260 (or ~940) bytes of flash. #endif - #if ANY(HAS_MARLINUI_U8GLIB, TOUCH_UI_FTDI_EVE, HAS_MARLINUI_HD44780) + #if ANY(HAS_MARLINUI_U8GLIB, TOUCH_UI_FTDI_EVE, HAS_MARLINUI_HD44780, HAS_GRAPHICAL_TFT) //#define SHOW_CUSTOM_BOOTSCREEN // Show the bitmap in Marlin/_Bootscreen.h on startup. #endif #endif diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index e0a42cdf37..f5c593fccd 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -399,8 +399,8 @@ static_assert(COUNT(arm) == LOGICAL_AXES, "AXIS_RELATIVE_MODES must contain " _L /** * Custom Boot and Status screens */ -#if ENABLED(SHOW_CUSTOM_BOOTSCREEN) && NONE(HAS_MARLINUI_HD44780, HAS_MARLINUI_U8GLIB, TOUCH_UI_FTDI_EVE, IS_DWIN_MARLINUI) - #error "SHOW_CUSTOM_BOOTSCREEN requires Character LCD, Graphical LCD, or TOUCH_UI_FTDI_EVE." +#if ENABLED(SHOW_CUSTOM_BOOTSCREEN) && NONE(TFT_COLOR_UI, HAS_MARLINUI_HD44780, HAS_MARLINUI_U8GLIB, TOUCH_UI_FTDI_EVE, IS_DWIN_MARLINUI) + #error "SHOW_CUSTOM_BOOTSCREEN requires Character LCD, Graphical LCD, TOUCH_UI_FTDI_EVE, or TFT_COLOR_UI." #elif ENABLED(SHOW_CUSTOM_BOOTSCREEN) && DISABLED(SHOW_BOOTSCREEN) #error "SHOW_CUSTOM_BOOTSCREEN requires SHOW_BOOTSCREEN." #elif ENABLED(CUSTOM_STATUS_SCREEN_IMAGE) && !HAS_MARLINUI_U8GLIB diff --git a/Marlin/src/lcd/tft/canvas.cpp b/Marlin/src/lcd/tft/canvas.cpp index 0f77149a5a..a237bb8434 100644 --- a/Marlin/src/lcd/tft/canvas.cpp +++ b/Marlin/src/lcd/tft/canvas.cpp @@ -134,11 +134,22 @@ void Canvas::addImage(int16_t x, int16_t y, MarlinImage image, uint16_t *colors) uint32_t rle_offset; } rle_state; + #if ENABLED(SHOW_CUSTOM_BOOTSCREEN) + static MarlinImage last_image = noImage; + #endif + // RLE16 HIGHCOLOR - 16 bits per pixel if (color_mode == RLE16) { uint8_t *bytedata = (uint8_t *)images[image].data; if (!bytedata) return; + #if ENABLED(SHOW_CUSTOM_BOOTSCREEN) // Reset RLE state if a different image + if (image != last_image) { + rle_state.has_rle_state = false; + last_image = image; + } + #endif + // Loop through the image data advancing the row and column as needed int16_t srcy = 0, srcx = 0, // Image data line / column index dsty = y, dstx = x; // Destination line / column index diff --git a/Marlin/src/lcd/tft/tft_image.cpp b/Marlin/src/lcd/tft/tft_image.cpp index 1d287f4ba6..25fefbf8c5 100644 --- a/Marlin/src/lcd/tft/tft_image.cpp +++ b/Marlin/src/lcd/tft/tft_image.cpp @@ -30,40 +30,41 @@ const tImage NoLogo = { nullptr, 0, 0, NOCOLORS }; const tImage images[imgCount] = { - TERN(SHOW_BOOTSCREEN, BOOTSCREEN_LOGO, NoLogo), // imgBootScreen - HotEnd_64x64x4, // imgHotEnd - Bed_64x64x4, // imgBed - Bed_Heated_64x64x4, // imgBedHeated - Chamber_64x64x4, // imgChamber - Chamber_Heated_64x64x4, // imgChamberHeated - Fan0_64x64x4, // imgFanIdle - Fan_Slow0_64x64x4, // imgFanSlow0 - Fan_Slow1_64x64x4, // imgFanSlow1 - Fan_Fast0_64x64x4, // imgFanFast0 - Fan_Fast1_64x64x4, // imgFanFast1 - Feedrate_32x32x4, // imgFeedRate - Flowrate_32x32x4, // imgFlowRate - SD_64x64x4, // imgSD - Menu_64x64x4, // imgMenu - Settings_64x64x4, // imgSettings - Directory_32x32x4, // imgDirectory - Confirm_64x64x4, // imgConfirm - Cancel_64x64x4, // imgCancel - Increase_64x64x4, // imgIncrease - Decrease_64x64x4, // imgDecrease - Back_32x32x4, // imgBack - Up_32x32x4, // imgUp - Down_32x32x4, // imgDown - Left_32x32x4, // imgLeft - Right_32x32x4, // imgRight - Refresh_32x32x4, // imgRefresh - Leveling_32x32x4, // imgLeveling - Slider8x16x4, // imgSlider - Home_64x64x4, // imgHome - BtnRounded_64x52x4, // imgBtn52Rounded - BtnRounded_42x39x4, // imgBtn39Rounded - Time_Elapsed_32x32x4, // imgTimeElapsed - Time_Remaining_32x32x4, // imgTimeRemaining + TERN(SHOW_CUSTOM_BOOTSCREEN, CUSTOM_BOOTSCREEN, NoLogo), // imgCustomBoot + TERN(SHOW_BOOTSCREEN, BOOTSCREEN_LOGO, NoLogo), // imgBootScreen + HotEnd_64x64x4, // imgHotEnd + Bed_64x64x4, // imgBed + Bed_Heated_64x64x4, // imgBedHeated + Chamber_64x64x4, // imgChamber + Chamber_Heated_64x64x4, // imgChamberHeated + Fan0_64x64x4, // imgFanIdle + Fan_Slow0_64x64x4, // imgFanSlow0 + Fan_Slow1_64x64x4, // imgFanSlow1 + Fan_Fast0_64x64x4, // imgFanFast0 + Fan_Fast1_64x64x4, // imgFanFast1 + Feedrate_32x32x4, // imgFeedRate + Flowrate_32x32x4, // imgFlowRate + SD_64x64x4, // imgSD + Menu_64x64x4, // imgMenu + Settings_64x64x4, // imgSettings + Directory_32x32x4, // imgDirectory + Confirm_64x64x4, // imgConfirm + Cancel_64x64x4, // imgCancel + Increase_64x64x4, // imgIncrease + Decrease_64x64x4, // imgDecrease + Back_32x32x4, // imgBack + Up_32x32x4, // imgUp + Down_32x32x4, // imgDown + Left_32x32x4, // imgLeft + Right_32x32x4, // imgRight + Refresh_32x32x4, // imgRefresh + Leveling_32x32x4, // imgLeveling + Slider8x16x4, // imgSlider + Home_64x64x4, // imgHome + BtnRounded_64x52x4, // imgBtn52Rounded + BtnRounded_42x39x4, // imgBtn39Rounded + Time_Elapsed_32x32x4, // imgTimeElapsed + Time_Remaining_32x32x4, // imgTimeRemaining }; #endif // HAS_GRAPHICAL_TFT diff --git a/Marlin/src/lcd/tft/tft_image.h b/Marlin/src/lcd/tft/tft_image.h index 8abca6f330..e1f078a90b 100644 --- a/Marlin/src/lcd/tft/tft_image.h +++ b/Marlin/src/lcd/tft/tft_image.h @@ -25,12 +25,21 @@ #if ENABLED(COMPACT_MARLIN_BOOT_LOGO) #define MARLIN_LOGO_CHOSEN(W,H) { (void *)marlin_logo_##W##x##H##x16_rle16, W, H, RLE16 } + #if ENABLED(SHOW_CUSTOM_BOOTSCREEN) + #define _CUSTOM_BOOTSCREEN_CHOSEN(W,H) { (void *)custom_bootscreen_##W##x##H##x16_rle16, W, H, RLE16 } + #define CUSTOM_BOOTSCREEN_CHOSEN(W,H) _CUSTOM_BOOTSCREEN_CHOSEN(W,H) + #endif #else #define MARLIN_LOGO_CHOSEN(W,H) { (void *)marlin_logo_##W##x##H##x16, W, H, HIGHCOLOR } + #if ENABLED(SHOW_CUSTOM_BOOTSCREEN) + #define _CUSTOM_BOOTSCREEN_CHOSEN(W,H){ (void *)custom_bootscreen_##W##x##H##x16, W, H, HIGHCOLOR } + #define CUSTOM_BOOTSCREEN_CHOSEN(W,H) _CUSTOM_BOOTSCREEN_CHOSEN(W,H) + #endif #endif enum MarlinImage : uint8_t { - imgBootScreen = 0x00, // BOOTSCREEN_LOGO / NoLogo + imgCustomBoot = 0x00, // CUSTOM_BOOTSCREEN + imgBootScreen, // BOOTSCREEN_LOGO / NoLogo imgHotEnd, // HotEnd_64x64x4 imgBed, // Bed_64x64x4 imgBedHeated, // Bed_Heated_64x64x4 diff --git a/Marlin/src/lcd/tft/ui_color_ui.cpp b/Marlin/src/lcd/tft/ui_color_ui.cpp index 6c90cb6c36..3287285f69 100644 --- a/Marlin/src/lcd/tft/ui_color_ui.cpp +++ b/Marlin/src/lcd/tft/ui_color_ui.cpp @@ -64,6 +64,20 @@ void MarlinUI::tft_idle() { #if ENABLED(SHOW_BOOTSCREEN) void MarlinUI::show_bootscreen() { + #if ENABLED(SHOW_CUSTOM_BOOTSCREEN) + tft.queue.reset(); + tft.canvas(CUSTOM_BOOTSCREEN_X, CUSTOM_BOOTSCREEN_Y, CUSTOM_BOOTSCREEN_WIDTH, CUSTOM_BOOTSCREEN_HEIGHT); + tft.set_background(COLOR_BACKGROUND); + tft.add_image(0, 0, imgCustomBoot); + tft.queue.sync(); + #ifndef CUSTOM_BOOTSCREEN_TIMEOUT + #define CUSTOM_BOOTSCREEN_TIMEOUT 2500 + #endif + #if CUSTOM_BOOTSCREEN_TIMEOUT + safe_delay(CUSTOM_BOOTSCREEN_TIMEOUT); + #endif + #endif + tft.queue.reset(); tft.canvas(0, 0, TFT_WIDTH, TFT_HEIGHT); diff --git a/Marlin/src/lcd/tft/ui_common.h b/Marlin/src/lcd/tft/ui_common.h index ef26d6745f..f43dc95fb2 100644 --- a/Marlin/src/lcd/tft/ui_common.h +++ b/Marlin/src/lcd/tft/ui_common.h @@ -30,14 +30,37 @@ #include "tft.h" #include "tft_image.h" +#if ENABLED(SHOW_CUSTOM_BOOTSCREEN) + + #include "../../../_Bootscreen.h" + + #ifndef CUSTOM_BOOTSCREEN + #define CUSTOM_BOOTSCREEN CustomBootscreen + #endif + #ifndef CUSTOM_BOOTSCREEN_WIDTH + #define CUSTOM_BOOTSCREEN_WIDTH TFT_WIDTH + #endif + #ifndef CUSTOM_BOOTSCREEN_HEIGHT + #define CUSTOM_BOOTSCREEN_HEIGHT TFT_HEIGHT + #endif + + #ifndef CUSTOM_BOOTSCREEN_X + #define CUSTOM_BOOTSCREEN_X ((TFT_WIDTH - (CUSTOM_BOOTSCREEN_WIDTH)) / 2) + #endif + #ifndef CUSTOM_BOOTSCREEN_Y + #define CUSTOM_BOOTSCREEN_Y ((TFT_HEIGHT - (CUSTOM_BOOTSCREEN_HEIGHT)) / 2) + #endif + + const tImage CustomBootscreen = CUSTOM_BOOTSCREEN_CHOSEN(CUSTOM_BOOTSCREEN_WIDTH, CUSTOM_BOOTSCREEN_HEIGHT); + +#endif // SHOW_CUSTOM_BOOTSCREEN + #if ENABLED(TOUCH_SCREEN) #include "touch.h" extern bool draw_menu_navigation; #else // add_control() function is used to display encoder-controlled elements - enum TouchControlType : uint16_t { - NONE = 0x0000, - }; + enum TouchControlType : uint16_t { NONE = 0x0000 }; #endif #define UI_INCL_(W, H) STRINGIFY_(ui_##W##x##H.h) From cf9f20503080bc9f048f04fc539f673afe7bbe17 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sun, 9 Nov 2025 01:43:06 +0000 Subject: [PATCH 48/99] [cron] Bump distribution date (2025-11-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 edf9a292d9..c0c9196ea9 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 "2025-11-08" +//#define STRING_DISTRIBUTION_DATE "2025-11-09" /** * The protocol for communication to the host. Protocol indicates communication diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 5f4b7b8320..b74c79d301 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 "2025-11-08" + #define STRING_DISTRIBUTION_DATE "2025-11-09" #endif /** From 6e01ba3ce8593f6fb75e76b2e69b9c1c5142544e Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 9 Nov 2025 17:33:29 -0600 Subject: [PATCH 49/99] =?UTF-8?q?=F0=9F=A7=91=E2=80=8D=F0=9F=92=BB=20Probe?= =?UTF-8?q?=20code=20refinements?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration.h | 3 +- Marlin/src/gcode/calibrate/G33.cpp | 6 +-- Marlin/src/inc/Conditionals-5-post.h | 3 ++ Marlin/src/inc/SanityCheck.h | 78 +++++++++++----------------- Marlin/src/module/motion.cpp | 4 +- Marlin/src/module/probe.cpp | 16 +++--- Marlin/src/module/probe.h | 34 +++++++----- 7 files changed, 71 insertions(+), 73 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index e51d16d565..a327c406ef 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -1053,7 +1053,8 @@ // Delta radius and diagonal rod adjustments //#define DELTA_RADIUS_TRIM_TOWER { 0.0, 0.0, 0.0 } // (mm) //#define DELTA_DIAGONAL_ROD_TRIM_TOWER { 0.0, 0.0, 0.0 } // (mm) -#endif + +#endif // DELTA // @section scara diff --git a/Marlin/src/gcode/calibrate/G33.cpp b/Marlin/src/gcode/calibrate/G33.cpp index 1eabb30ffa..0a8dd459ca 100644 --- a/Marlin/src/gcode/calibrate/G33.cpp +++ b/Marlin/src/gcode/calibrate/G33.cpp @@ -380,9 +380,9 @@ static float auto_tune_a(const float dcr) { * With HAS_DELTA_SENSORLESS_PROBING: * Use these flags to calibrate stall sensitivity: * Example: G33 P1 Y Z - to calibrate X only - * X Don't activate stallguard on X - * Y Don't activate stallguard on Y - * Z Don't activate stallguard on Z + * X Don't activate StallGuard on X + * Y Don't activate StallGuard on Y + * Z Don't activate StallGuard on Z * S Save offset_sensorless_adj */ void GcodeSuite::G33() { diff --git a/Marlin/src/inc/Conditionals-5-post.h b/Marlin/src/inc/Conditionals-5-post.h index 4bed697726..77982c2c0b 100644 --- a/Marlin/src/inc/Conditionals-5-post.h +++ b/Marlin/src/inc/Conditionals-5-post.h @@ -3303,6 +3303,9 @@ #if ANY(ADVANCED_PAUSE_FEATURE, PROBING_HEATERS_OFF) #define HEATER_IDLE_HANDLER 1 #endif +#if ENABLED(DELTA) + #undef PROBING_STEPPERS_OFF +#endif #if HAS_BED_PROBE && (ANY(PROBING_HEATERS_OFF, PROBING_STEPPERS_OFF, PROBING_ESTEPPERS_OFF, PROBING_FANS_OFF) || DELAY_BEFORE_PROBING > 0) #define HAS_QUIET_PROBING 1 #endif diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index f5c593fccd..c13c0ded82 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -1277,53 +1277,22 @@ static_assert(NUM_SERVOS <= NUM_SERVO_PLUGS, "NUM_SERVOS (or some servo index) i + (DISABLED(BLTOUCH) && HAS_Z_SERVO_PROBE) \ + COUNT_ENABLED(PROBE_MANUALLY, BLTOUCH, BD_SENSOR, FIX_MOUNTED_PROBE, NOZZLE_AS_PROBE, TOUCH_MI_PROBE, SOLENOID_PROBE, Z_PROBE_ALLEN_KEY, Z_PROBE_SLED, RACK_AND_PINION_PROBE, SENSORLESS_PROBING, MAGLEV4, MAG_MOUNTED_PROBE, BIQU_MICROPROBE_V1, BIQU_MICROPROBE_V2) #error "Please enable only one probe option. See the following errors:" - #if ENABLED(BLTOUCH) - #error "(BLTOUCH is enabled.)" - #elif HAS_Z_SERVO_PROBE - #error "(Z_SERVO_PROBE is enabled.)" - #endif - #if ENABLED(PROBE_MANUALLY) - #error "(PROBE_MANUALLY is enabled.)" - #endif - #if ENABLED(BD_SENSOR) - #error "(BD_SENSOR is enabled.)" - #endif - #if ENABLED(FIX_MOUNTED_PROBE) - #error "(FIX_MOUNTED_PROBE is enabled.)" - #endif - #if ENABLED(NOZZLE_AS_PROBE) - #error "(NOZZLE_AS_PROBE is enabled.)" - #endif - #if ENABLED(TOUCH_MI_PROBE) - #error "(TOUCH_MI_PROBE is enabled.)" - #endif - #if ENABLED(SOLENOID_PROBE) - #error "(SOLENOID_PROBE is enabled.)" - #endif - #if ENABLED(Z_PROBE_ALLEN_KEY) - #error "(Z_PROBE_ALLEN_KEY is enabled.)" - #endif - #if ENABLED(Z_PROBE_SLED) - #error "(Z_PROBE_SLED is enabled.)" - #endif - #if ENABLED(RACK_AND_PINION_PROBE) - #error "(RACK_AND_PINION_PROBE is enabled.)" - #endif - #if ENABLED(SENSORLESS_PROBING) - #error "(SENSORLESS_PROBING is enabled.)" - #endif - #if ENABLED(MAGLEV4) - #error "(MAGLEV4 is enabled.)" - #endif - #if ENABLED(MAG_MOUNTED_PROBE) - #error "(MAG_MOUNTED_PROBE is enabled.)" - #endif - #if ENABLED(BIQU_MICROPROBE_V1) - #error "(BIQU_MICROPROBE_V1 is enabled.)" - #endif - #if ENABLED(BIQU_MICROPROBE_V2) - #error "(BIQU_MICROPROBE_V2 is enabled.)" - #endif + static_assert(DISABLED(BLTOUCH), "(BLTOUCH is enabled.)"); + static_assert(ENABLED(BLTOUCH) || DISABLED(HAS_Z_SERVO_PROBE), "(Z_SERVO_PROBE is enabled.)"); + static_assert(DISABLED(PROBE_MANUALLY), "(PROBE_MANUALLY is enabled.)"); + static_assert(DISABLED(BD_SENSOR), "(BD_SENSOR is enabled.)"); + static_assert(DISABLED(FIX_MOUNTED_PROBE), "(FIX_MOUNTED_PROBE is enabled.)"); + static_assert(DISABLED(NOZZLE_AS_PROBE), "(NOZZLE_AS_PROBE is enabled.)"); + static_assert(DISABLED(TOUCH_MI_PROBE), "(TOUCH_MI_PROBE is enabled.)"); + static_assert(DISABLED(SOLENOID_PROBE), "(SOLENOID_PROBE is enabled.)"); + static_assert(DISABLED(Z_PROBE_ALLEN_KEY), "(Z_PROBE_ALLEN_KEY is enabled.)"); + static_assert(DISABLED(Z_PROBE_SLED), "(Z_PROBE_SLED is enabled.)"); + static_assert(DISABLED(RACK_AND_PINION_PROBE), "(RACK_AND_PINION_PROBE is enabled.)"); + static_assert(DISABLED(SENSORLESS_PROBING), "(SENSORLESS_PROBING is enabled.)"); + static_assert(DISABLED(MAGLEV4), "(MAGLEV4 is enabled.)"); + static_assert(DISABLED(MAG_MOUNTED_PROBE), "(MAG_MOUNTED_PROBE is enabled.)"); + static_assert(DISABLED(BIQU_MICROPROBE_V1), "(BIQU_MICROPROBE_V1 is enabled.)"); + static_assert(DISABLED(BIQU_MICROPROBE_V2), "(BIQU_MICROPROBE_V2 is enabled.)"); #endif #if HAS_BED_PROBE @@ -1500,7 +1469,6 @@ static_assert(NUM_SERVOS <= NUM_SERVO_PLUGS, "NUM_SERVOS (or some servo index) i #elif !PIN_EXISTS(PROBE_ENABLE) #error "BIQU MicroProbe requires a PROBE_ENABLE_PIN." #endif - #if ENABLED(BIQU_MICROPROBE_V1) #if ENABLED(INVERTED_PROBE_STATE) #if Z_MIN_PROBE_ENDSTOP_HIT_STATE != LOW @@ -1518,6 +1486,13 @@ static_assert(NUM_SERVOS <= NUM_SERVO_PLUGS, "NUM_SERVOS (or some servo index) i #error "BIQU_MICROPROBE_V1 requires Z_MIN_ENDSTOP_HIT_STATE HIGH." #endif #endif + #if NONE(ONBOARD_ENDSTOPPULLUPS, ENDSTOPPULLUPS, ENDSTOPPULLUP_ZMIN, ENDSTOPPULLUP_ZMIN_PROBE) + #if USE_Z_MIN_PROBE + #error "BIQU_MICROPROBE_V1 on Z_MIN_PROBE_PIN requires ENDSTOPPULLUP_ZMIN_PROBE, or ENDSTOPPULLUPS." + #else + #error "BIQU_MICROPROBE_V1 on Z_MIN_PIN requires ENDSTOPPULLUP_ZMIN, or ENDSTOPPULLUPS." + #endif + #endif #elif ENABLED(BIQU_MICROPROBE_V2) #if ENABLED(INVERTED_PROBE_STATE) #if Z_MIN_PROBE_ENDSTOP_HIT_STATE != HIGH @@ -1536,6 +1511,13 @@ static_assert(NUM_SERVOS <= NUM_SERVO_PLUGS, "NUM_SERVOS (or some servo index) i #endif #endif #endif + #if NONE(ONBOARD_ENDSTOPPULLUPS, ENDSTOPPULLUPS, ENDSTOPPULLUP_ZMIN, ENDSTOPPULLUP_ZMIN_PROBE) + #if USE_Z_MIN_PROBE + #error "BIQU_MICROPROBE_V2 on Z_MIN_PROBE_PIN requires ENDSTOPPULLUP_ZMIN_PROBE, or ENDSTOPPULLUPS." + #else + #error "BIQU_MICROPROBE_V2 on Z_MIN_PIN requires ENDSTOPPULLUP_ZMIN, or ENDSTOPPULLUPS." + #endif + #endif #endif // BIQU_MICROPROBE_V1 || BIQU_MICROPROBE_V2 /** diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index cb99000451..cf524cbdb9 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -2207,7 +2207,7 @@ void prepare_line_to_destination() { thermalManager.wait_for_hotend_heating(active_extruder); #endif - TERN_(HAS_QUIET_PROBING, if (final_approach) probe.set_probing_paused(true)); + TERN_(HAS_QUIET_PROBING, if (final_approach) probe.set_devices_paused_for_probing(true)); } // Disable stealthChop if used. Enable diag1 pin on driver. @@ -2246,7 +2246,7 @@ void prepare_line_to_destination() { if (is_home_dir) { #if HOMING_Z_WITH_PROBE && HAS_QUIET_PROBING - if (axis == Z_AXIS && final_approach) probe.set_probing_paused(false); + if (axis == Z_AXIS && final_approach) probe.set_devices_paused_for_probing(false); #endif endstops.validate_homing_move(); diff --git a/Marlin/src/module/probe.cpp b/Marlin/src/module/probe.cpp index 937b8ebeeb..ae688a864e 100644 --- a/Marlin/src/module/probe.cpp +++ b/Marlin/src/module/probe.cpp @@ -347,12 +347,16 @@ xyz_pos_t Probe::offset; // Initialized by settings.load #define DELAY_BEFORE_PROBING 25 #endif - void Probe::set_probing_paused(const bool dopause) { + /** + * Optionally turn off noisy components so we get a cleaner probe signal. + * Pause for at least 25ms when preparing to probe (dopause == true). + */ + void Probe::set_devices_paused_for_probing(const bool dopause) { TERN_(PROBING_HEATERS_OFF, thermalManager.pause_heaters(dopause)); TERN_(PROBING_FANS_OFF, thermalManager.set_fans_paused(dopause)); TERN_(PROBING_ESTEPPERS_OFF, if (dopause) stepper.disable_e_steppers()); - #if ENABLED(PROBING_STEPPERS_OFF) && DISABLED(DELTA) - static uint8_t old_trusted; + #if ENABLED(PROBING_STEPPERS_OFF) + static main_axes_bits_t old_trusted; if (dopause) { old_trusted = axes_trusted; stepper.disable_axis(X_AXIS); @@ -660,7 +664,7 @@ bool Probe::probe_down_to_z(const float z, const feedRate_t fr_mm_s) { endstops.enable(true); #endif // SENSORLESS_PROBING - TERN_(HAS_QUIET_PROBING, set_probing_paused(true)); + TERN_(HAS_QUIET_PROBING, set_devices_paused_for_probing(true)); // Move down until the probe is triggered do_blocking_move_to_z(z, fr_mm_s); @@ -668,7 +672,7 @@ bool Probe::probe_down_to_z(const float z, const feedRate_t fr_mm_s) { // Check to see if the probe was triggered const bool probe_triggered = ( #if HAS_DELTA_SENSORLESS_PROBING - endstops.trigger_state() & (_BV(X_MAX) | _BV(Y_MAX) | _BV(Z_MAX)) + PROBE_TRIGGERED() #else TEST(endstops.trigger_state(), Z_MIN_PROBE) #endif @@ -679,7 +683,7 @@ bool Probe::probe_down_to_z(const float z, const feedRate_t fr_mm_s) { if (probe_triggered) refresh_largest_sensorless_adj(); #endif - TERN_(HAS_QUIET_PROBING, set_probing_paused(false)); + TERN_(HAS_QUIET_PROBING, set_devices_paused_for_probing(false)); // Re-enable stealthChop if used. Disable diag1 pin on driver. #if ENABLED(SENSORLESS_PROBING) diff --git a/Marlin/src/module/probe.h b/Marlin/src/module/probe.h index 74904d35c5..d0f0ada34c 100644 --- a/Marlin/src/module/probe.h +++ b/Marlin/src/module/probe.h @@ -33,6 +33,10 @@ #include "../feature/bltouch.h" #endif +#if ANY(BD_SENSOR, HAS_DELTA_SENSORLESS_PROBING) + #include "endstops.h" +#endif + #define DEBUG_OUT ENABLED(DEBUG_LEVELING_FEATURE) #include "../core/debug_out.h" @@ -45,20 +49,24 @@ }; #endif -#if ENABLED(BD_SENSOR) - #include "endstops.h" - #define PROBE_READ() endstops.bdp_state -#elif USE_Z_MIN_PROBE - #define PROBE_READ() READ(Z_MIN_PROBE_PIN) +#if HAS_DELTA_SENSORLESS_PROBING + #define PROBE_READ() (endstops.trigger_state() & (_BV(X_MAX) | _BV(Y_MAX) | _BV(Z_MAX))) + #define PROBE_TRIGGERED() (PROBE_READ() != 0) #else - #define PROBE_READ() READ(Z_MIN_PIN) + #if ENABLED(BD_SENSOR) + #define PROBE_READ() endstops.bdp_state + #elif USE_Z_MIN_PROBE + #define PROBE_READ() READ(Z_MIN_PROBE_PIN) + #else + #define PROBE_READ() READ(Z_MIN_PIN) + #endif + #if USE_Z_MIN_PROBE + #define PROBE_HIT_STATE Z_MIN_PROBE_ENDSTOP_HIT_STATE + #else + #define PROBE_HIT_STATE Z_MIN_ENDSTOP_HIT_STATE + #endif + #define PROBE_TRIGGERED() (PROBE_READ() == PROBE_HIT_STATE) #endif -#if USE_Z_MIN_PROBE - #define PROBE_HIT_STATE Z_MIN_PROBE_ENDSTOP_HIT_STATE -#else - #define PROBE_HIT_STATE Z_MIN_ENDSTOP_HIT_STATE -#endif -#define PROBE_TRIGGERED() (PROBE_READ() == PROBE_HIT_STATE) // In BLTOUCH HS mode, the probe travels in a deployed state. #define Z_TWEEN_SAFE_CLEARANCE SUM_TERN(BLTOUCH, Z_CLEARANCE_BETWEEN_PROBES, bltouch.z_extra_clearance()) @@ -347,7 +355,7 @@ public: #endif #if HAS_QUIET_PROBING - static void set_probing_paused(const bool p); + static void set_devices_paused_for_probing(const bool p); #endif #if ENABLED(PROBE_TARE) From cf609152c275b95f7b1c6ec1409dd9dfb286a4e9 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Mon, 10 Nov 2025 00:34:05 +0000 Subject: [PATCH 50/99] [cron] Bump distribution date (2025-11-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 c0c9196ea9..da42afd480 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 "2025-11-09" +//#define STRING_DISTRIBUTION_DATE "2025-11-10" /** * The protocol for communication to the host. Protocol indicates communication diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index b74c79d301..7a198943a2 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 "2025-11-09" + #define STRING_DISTRIBUTION_DATE "2025-11-10" #endif /** From 27dcfe0ea82b22ac3b5cf1cc72ebd7e55449c3a3 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 9 Nov 2025 18:37:18 -0600 Subject: [PATCH 51/99] =?UTF-8?q?=E2=9C=85=20New=20rule=20in=20use=5Fexamp?= =?UTF-8?q?le=5Fconfigs?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- buildroot/bin/use_example_configs | 2 ++ 1 file changed, 2 insertions(+) diff --git a/buildroot/bin/use_example_configs b/buildroot/bin/use_example_configs index 401e15da61..72930d8c45 100755 --- a/buildroot/bin/use_example_configs +++ b/buildroot/bin/use_example_configs @@ -101,6 +101,8 @@ def main(): if branch.startswith("bugfix-2."): branch = branch + elif branch.endswith("bugfix-2.1.x"): + branch = "bugfix-2.1.x" elif branch.endswith("-2.1.x") or branch == "2.1.x": branch = "latest-2.1.x" elif branch.endswith("-2.0.x") or branch == "2.0.x": From 88a4e559451f631a62882e3cd6fa4df42f32d056 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 9 Nov 2025 21:25:25 -0600 Subject: [PATCH 52/99] =?UTF-8?q?=F0=9F=A9=B9=20Fix=20SMOOTH=5FSET?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Followup to ce7edc6223 --- Marlin/src/gcode/feature/ft_motion/M494.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/gcode/feature/ft_motion/M494.cpp b/Marlin/src/gcode/feature/ft_motion/M494.cpp index 840333f896..f3a4e61123 100644 --- a/Marlin/src/gcode/feature/ft_motion/M494.cpp +++ b/Marlin/src/gcode/feature/ft_motion/M494.cpp @@ -121,7 +121,7 @@ void GcodeSuite::M494() { report = true; \ } \ else \ - SERIAL_ECHOLN("?Invalid ", C(N), " smoothing time [", C(CHARIFY(A)), "] value."); \ + SERIAL_ECHOLNPGM("?Invalid ", C(N), " smoothing time [", C(CHARIFY(A)), "] value."); \ } CARTES_GANG( From a420e3c15585286f6faedb18fae7c2c1fafb7664 Mon Sep 17 00:00:00 2001 From: David Buezas Date: Mon, 10 Nov 2025 06:43:37 +0100 Subject: [PATCH 53/99] =?UTF-8?q?=F0=9F=94=A7=20PROBE=5FWAKEUP=5FTIME=5FMS?= =?UTF-8?q?=2030=20for=20BIQU=20probes=20(#28153)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/inc/Conditionals-5-post.h | 6 ++++++ Marlin/src/inc/Warnings.cpp | 13 +++++++++---- 2 files changed, 15 insertions(+), 4 deletions(-) diff --git a/Marlin/src/inc/Conditionals-5-post.h b/Marlin/src/inc/Conditionals-5-post.h index 77982c2c0b..9eb5031055 100644 --- a/Marlin/src/inc/Conditionals-5-post.h +++ b/Marlin/src/inc/Conditionals-5-post.h @@ -3687,4 +3687,10 @@ #define FTM_BUFFER_SIZE 128 #endif #define FTM_BUFFER_MASK (FTM_BUFFER_SIZE - 1u) + #if ANY(BIQU_MICROPROBE_V1, BIQU_MICROPROBE_V2) + #ifndef PROBE_WAKEUP_TIME_MS + #define PROBE_WAKEUP_TIME_MS 30 + #define PROBE_WAKEUP_TIME_WARNING 1 + #endif + #endif #endif diff --git a/Marlin/src/inc/Warnings.cpp b/Marlin/src/inc/Warnings.cpp index be617aa2e8..6da36d832f 100644 --- a/Marlin/src/inc/Warnings.cpp +++ b/Marlin/src/inc/Warnings.cpp @@ -724,6 +724,10 @@ #warning "BIQU MicroProbe V2 detect signal requires a strong pull-up. Some processors have weak internal pull-up capabilities, so we recommended connecting MicroProbe SIGNAL / GND to Z-MIN / Z-STOP instead of the dedicated PROBE port. (Define NO_MICROPROBE_WARNING to suppress this warning.)" #endif +#if PROBE_WAKEUP_TIME_WARNING + #warning "PROBE_WAKEUP_TIME_MS has been set to the default 30ms." +#endif + // // Warn users of potential endstop/DIAG pin conflicts to prevent homing issues when not using sensorless homing // @@ -943,6 +947,9 @@ #if ENABLED(FTM_HOME_AND_PROBE) #if ANY(BIQU_MICROPROBE_V1, BIQU_MICROPROBE_V2) #warning "Let us know if you experience any issues with BIQU Microprobe and FT_MOTION." + #if PROBE_WAKEUP_TIME_MS <= 25 + #warning "A PROBE_WAKEUP_TIME_MS over 25 ms is recommended with FT_MOTION and BIQU_MICROPROBE_V1 or BIQU_MICROPROBE_V2." + #endif #endif #if PROBE_WAKEUP_TIME_MS < 30 #warning "A PROBE_WAKEUP_TIME_MS over 30 ms is recommended with FT_MOTION." @@ -973,8 +980,6 @@ /** * Smooth Linear Advance with Mixing Extruder, S-Curve Acceleration */ -#if ENABLED(SMOOTH_LIN_ADVANCE) - #if ENABLED(MIXING_EXTRUDER) - #warning "SMOOTH_LIN_ADVANCE with MIXING_EXTRUDER is untested. Use with caution." - #endif +#if ALL(SMOOTH_LIN_ADVANCE, MIXING_EXTRUDER) + #warning "SMOOTH_LIN_ADVANCE with MIXING_EXTRUDER is untested. Use with caution." #endif From cda684b6fdd7ec7ab5762fac77687ffc6c4de557 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 10 Nov 2025 00:18:11 -0600 Subject: [PATCH 54/99] =?UTF-8?q?=F0=9F=8E=A8=20LCD=20cosmetic,=20babystep?= =?UTF-8?q?=20size?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/e3v2/proui/dwin.cpp | 18 +++++++++--------- .../src/lcd/extui/anycubic_vyper/dgus_tft.cpp | 8 ++++---- Marlin/src/lcd/extui/ui_api.h | 2 +- 3 files changed, 14 insertions(+), 14 deletions(-) diff --git a/Marlin/src/lcd/e3v2/proui/dwin.cpp b/Marlin/src/lcd/e3v2/proui/dwin.cpp index 8ff1fe6412..974a0a8866 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin.cpp @@ -200,7 +200,7 @@ typedef struct { select_t select_page{0}, select_print{0}; #if ENABLED(LCD_BED_TRAMMING) - constexpr float bed_tramming_inset_lfbr[] = BED_TRAMMING_INSET_LFRB; + constexpr float bed_tramming_inset_lfrb[] = BED_TRAMMING_INSET_LFRB; #endif bool hash_changed = true; // Flag to know if message status was changed @@ -2435,23 +2435,23 @@ void setFlow() { setPIntOnClick(FLOW_EDIT_MIN, FLOW_EDIT_MAX, []{ planner.refres switch (point) { case 0: LCD_MESSAGE(MSG_TRAM_FL); - x = bed_tramming_inset_lfbr[0]; - y = bed_tramming_inset_lfbr[1]; + x = bed_tramming_inset_lfrb[0]; + y = bed_tramming_inset_lfrb[1]; break; case 1: LCD_MESSAGE(MSG_TRAM_FR); - x = X_BED_SIZE - bed_tramming_inset_lfbr[2]; - y = bed_tramming_inset_lfbr[1]; + x = X_BED_SIZE - bed_tramming_inset_lfrb[2]; + y = bed_tramming_inset_lfrb[1]; break; case 2: LCD_MESSAGE(MSG_TRAM_BR); - x = X_BED_SIZE - bed_tramming_inset_lfbr[2]; - y = Y_BED_SIZE - bed_tramming_inset_lfbr[3]; + x = X_BED_SIZE - bed_tramming_inset_lfrb[2]; + y = Y_BED_SIZE - bed_tramming_inset_lfrb[3]; break; case 3: LCD_MESSAGE(MSG_TRAM_BL); - x = bed_tramming_inset_lfbr[0]; - y = Y_BED_SIZE - bed_tramming_inset_lfbr[3]; + x = bed_tramming_inset_lfrb[0]; + y = Y_BED_SIZE - bed_tramming_inset_lfrb[3]; break; #if ENABLED(BED_TRAMMING_INCLUDE_CENTER) case 4: diff --git a/Marlin/src/lcd/extui/anycubic_vyper/dgus_tft.cpp b/Marlin/src/lcd/extui/anycubic_vyper/dgus_tft.cpp index af5e20d3a1..5678cb3d3f 100644 --- a/Marlin/src/lcd/extui/anycubic_vyper/dgus_tft.cpp +++ b/Marlin/src/lcd/extui/anycubic_vyper/dgus_tft.cpp @@ -1967,14 +1967,14 @@ namespace Anycubic { setSoftEndstopState(false); - z_off = getZOffset_mm() - 0.01f; + z_off = getZOffset_mm() - BABYSTEP_SIZE_Z; setZOffset_mm(z_off); sendTxtToTFT(ftostr52sprj(getZOffset_mm()) + 2, TXT_LEVEL_OFFSET); if (isAxisPositionKnown(Z)) { const float currZpos = getAxisPosition_mm(Z); - setAxisPosition_mm(currZpos - 0.01f, Z); + setAxisPosition_mm(currZpos - BABYSTEP_SIZE_Z, Z); } setSoftEndstopState(true); @@ -1985,14 +1985,14 @@ namespace Anycubic { setSoftEndstopState(false); - z_off = getZOffset_mm() + 0.01f; + z_off = getZOffset_mm() + BABYSTEP_SIZE_Z; setZOffset_mm(z_off); sendTxtToTFT(ftostr52sprj(getZOffset_mm()) + 2, TXT_LEVEL_OFFSET); if (isAxisPositionKnown(Z)) { // Move Z axis const float currZpos = getAxisPosition_mm(Z); - setAxisPosition_mm(currZpos + 0.01f, Z); + setAxisPosition_mm(currZpos + BABYSTEP_SIZE_Z, Z); } setSoftEndstopState(true); diff --git a/Marlin/src/lcd/extui/ui_api.h b/Marlin/src/lcd/extui/ui_api.h index a4b514d3ce..88145621e5 100644 --- a/Marlin/src/lcd/extui/ui_api.h +++ b/Marlin/src/lcd/extui/ui_api.h @@ -74,7 +74,7 @@ namespace ExtUI { #if ENABLED(MPC_AUTOTUNE) enum mpcresult_t : uint8_t { MPC_STARTED, MPC_TEMP_ERROR, MPC_INTERRUPTED, MPC_DONE }; #endif - struct probe_limits_t { float xmin, ymin, xmax, ymax; }; + typedef struct { float xmin, ymin, xmax, ymax; } probe_limits_t; constexpr uint8_t extruderCount = EXTRUDERS; constexpr uint8_t hotendCount = HOTENDS; From 9393c1ed1b22e8100692540a071d89a85511936c Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 10 Nov 2025 11:59:46 -0600 Subject: [PATCH 55/99] =?UTF-8?q?=F0=9F=A9=B9=20Fix=20MBL=20+=20FT=20Motio?= =?UTF-8?q?n=20build?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/bedlevel/mbl/G29.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Marlin/src/gcode/bedlevel/mbl/G29.cpp b/Marlin/src/gcode/bedlevel/mbl/G29.cpp index 0e48ec1449..1cdeba103e 100644 --- a/Marlin/src/gcode/bedlevel/mbl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/mbl/G29.cpp @@ -46,7 +46,7 @@ #include "../../../core/debug_out.h" #if ENABLED(FT_MOTION) - #include "../../module/ft_motion.h" + #include "../../../module/ft_motion.h" #endif // Save 130 bytes with non-duplication of PSTR From 689c7b83e1d769fb9d26af985a67f0e50fcfff32 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 10 Nov 2025 12:01:45 -0600 Subject: [PATCH 56/99] =?UTF-8?q?=F0=9F=8E=A8=20Move=20bubblesort=20string?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/sd/cardreader.cpp | 13 ++++++------- 1 file changed, 6 insertions(+), 7 deletions(-) diff --git a/Marlin/src/sd/cardreader.cpp b/Marlin/src/sd/cardreader.cpp index a2c0da933c..7153b2fb1f 100644 --- a/Marlin/src/sd/cardreader.cpp +++ b/Marlin/src/sd/cardreader.cpp @@ -1378,13 +1378,6 @@ void CardReader::cdroot() { #endif #endif - #else // !SDSORT_USES_RAM - - // By default re-read the names from SD for every compare - // retaining only two filenames at a time. This is very - // slow but is safest and uses minimal RAM. - char name1[LONG_FILENAME_LENGTH]; - #endif // SDSORT_USES_RAM if (fileCnt > 1) { @@ -1496,6 +1489,12 @@ void CardReader::cdroot() { } #else { + #if DISABLED(SDSORT_USES_RAM) + // By default re-read the names from SD for every compare, retaining two + // filenames at a time. This is very slow but is safest and uses minimal RAM. + char name1[LONG_FILENAME_LENGTH]; + #endif + // Bubble Sort for (int16_t i = fileCnt; --i;) { bool didSwap = false; From 10009b018d566ff91bdbe5c2655adb77d5795c9a Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Tue, 11 Nov 2025 00:32:37 +0000 Subject: [PATCH 57/99] [cron] Bump distribution date (2025-11-11) --- 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 da42afd480..d1d2b563cc 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 "2025-11-10" +//#define STRING_DISTRIBUTION_DATE "2025-11-11" /** * The protocol for communication to the host. Protocol indicates communication diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 7a198943a2..0bbdfd8de2 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 "2025-11-10" + #define STRING_DISTRIBUTION_DATE "2025-11-11" #endif /** From 579545177dabc5d17fd35a80f1e9968e4414900f Mon Sep 17 00:00:00 2001 From: ellensp <530024+ellensp@users.noreply.github.com> Date: Wed, 12 Nov 2025 14:51:22 +1300 Subject: [PATCH 58/99] =?UTF-8?q?=E2=9C=A8=20GCODE=5FMACROS=5FIN=5FEEPROM?= =?UTF-8?q?=20(#28114)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration_adv.h | 8 +++-- Marlin/src/gcode/feature/macro/M810-M819.cpp | 12 +++++--- Marlin/src/gcode/feature/macro/M820.cpp | 9 +++--- Marlin/src/gcode/gcode.cpp | 4 +++ Marlin/src/gcode/gcode.h | 8 ++++- Marlin/src/module/settings.cpp | 32 ++++++++++++++++++++ buildroot/tests/DUE | 2 +- 7 files changed, 61 insertions(+), 14 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index ffcecc3533..2e0f7f14fb 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -4091,13 +4091,17 @@ /** * G-code Macros * - * Add G-codes M810-M819 to define and run G-code macros. - * Macros are not saved to EEPROM. + * Add G-codes M810-M819 to define and run G-code macros + * and M820 to report the current set of macros. + * Macros are not saved to EEPROM unless enabled below. */ //#define GCODE_MACROS #if ENABLED(GCODE_MACROS) #define GCODE_MACROS_SLOTS 5 // Up to 10 may be used #define GCODE_MACROS_SLOT_SIZE 50 // Maximum length of a single macro + #if ENABLED(EEPROM_SETTINGS) + //#define GCODE_MACROS_IN_EEPROM // Include macros in EEPROM + #endif #endif /** diff --git a/Marlin/src/gcode/feature/macro/M810-M819.cpp b/Marlin/src/gcode/feature/macro/M810-M819.cpp index 7b9e1a13f1..29f6a11d14 100644 --- a/Marlin/src/gcode/feature/macro/M810-M819.cpp +++ b/Marlin/src/gcode/feature/macro/M810-M819.cpp @@ -28,10 +28,8 @@ #include "../../queue.h" #include "../../parser.h" -char gcode_macros[GCODE_MACROS_SLOTS][GCODE_MACROS_SLOT_SIZE + 1] = {{ 0 }}; - /** - * M810_819: Set/execute a G-code macro. + * M810 - M819: Set/execute a G-code macro. * * Usage: * M810 |... Set Macro 0 to the given commands, separated by the pipe character @@ -48,7 +46,7 @@ void GcodeSuite::M810_819() { if (len > GCODE_MACROS_SLOT_SIZE) SERIAL_ERROR_MSG("Macro too long."); else { - char c, *s = parser.string_arg, *d = gcode_macros[index]; + char c, *s = parser.string_arg, *d = gcode.macros[index]; do { c = *s++; *d++ = c == '|' ? '\n' : c; @@ -57,9 +55,13 @@ void GcodeSuite::M810_819() { } else { // Execute a macro - char * const cmd = gcode_macros[index]; + char * const cmd = gcode.macros[index]; if (strlen(cmd)) process_subcommands_now(cmd); } } +void GcodeSuite::M810_819_report(const bool forReplay/*=true*/) { + M820(forReplay); +} + #endif // GCODE_MACROS diff --git a/Marlin/src/gcode/feature/macro/M820.cpp b/Marlin/src/gcode/feature/macro/M820.cpp index 9759f482ec..5c6176d2aa 100644 --- a/Marlin/src/gcode/feature/macro/M820.cpp +++ b/Marlin/src/gcode/feature/macro/M820.cpp @@ -28,17 +28,16 @@ #include "../../queue.h" #include "../../parser.h" -extern char gcode_macros[GCODE_MACROS_SLOTS][GCODE_MACROS_SLOT_SIZE + 1]; - /** * M820: List defined M810 - M819 macros */ -void GcodeSuite::M820() { - SERIAL_ECHOLNPGM(STR_STORED_MACROS); +void GcodeSuite::M820(const bool withoutEcho/*=true*/) { + report_heading(withoutEcho, F(STR_STORED_MACROS)); bool some = false; for (uint8_t i = 0; i < GCODE_MACROS_SLOTS; ++i) { - const char *cmd = gcode_macros[i]; + const char *cmd = gcode.macros[i]; if (*cmd) { + report_echo_start(withoutEcho); SERIAL_ECHO(F("M81"), i, C(' ')); char c; while ((c = *cmd++)) SERIAL_CHAR(c == '\n' ? '|' : c); diff --git a/Marlin/src/gcode/gcode.cpp b/Marlin/src/gcode/gcode.cpp index 373cc16a53..aa629f4a71 100644 --- a/Marlin/src/gcode/gcode.cpp +++ b/Marlin/src/gcode/gcode.cpp @@ -104,6 +104,10 @@ relative_t GcodeSuite::axis_relative; // Init in constructor xyz_pos_t GcodeSuite::coordinate_system[MAX_COORDINATE_SYSTEMS]; #endif +#if ENABLED(GCODE_MACROS) + char GcodeSuite::macros[GCODE_MACROS_SLOTS][GCODE_MACROS_SLOT_SIZE + 1] = {{ 0 }}; +#endif + void GcodeSuite::report_echo_start(const bool forReplay) { if (!forReplay) SERIAL_ECHO_START(); } void GcodeSuite::report_heading(const bool forReplay, FSTR_P const fstr, const bool eol/*=true*/) { if (forReplay) return; diff --git a/Marlin/src/gcode/gcode.h b/Marlin/src/gcode/gcode.h index a0f3f68f6f..9b48813732 100644 --- a/Marlin/src/gcode/gcode.h +++ b/Marlin/src/gcode/gcode.h @@ -510,6 +510,11 @@ public: static void dwell(const millis_t time); + #if ENABLED(GCODE_MACROS) + static char macros[GCODE_MACROS_SLOTS][GCODE_MACROS_SLOT_SIZE + 1]; + static void reset_macros() { for (uint8_t i = 0; i < GCODE_MACROS_SLOTS; ++i) macros[i][0] = '\0'; } + #endif + private: friend class MarlinSettings; @@ -1229,7 +1234,8 @@ private: #if ENABLED(GCODE_MACROS) static void M810_819(); - static void M820(); + static void M810_819_report(const bool forReplay=true); + static void M820(const bool withoutEcho=true); #endif #if HAS_BED_PROBE diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index 7ebcb63eb1..caddd8129c 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -705,6 +705,13 @@ typedef struct SettingsDataStruct { // uint32_t material_changes #endif + // + // GCODE_MACROS + // + #if ENABLED(GCODE_MACROS_EEPROM) + char gcode_macros[GCODE_MACROS_SLOTS][GCODE_MACROS_SLOT_SIZE + 1]; + #endif + } SettingsData; //static_assert(sizeof(SettingsData) <= MARLIN_EEPROM_SIZE, "EEPROM too small to contain SettingsData!"); @@ -1823,6 +1830,14 @@ void MarlinSettings::postprocess() { EEPROM_WRITE(mmu3.mmu_hw_enabled); // EEPROM_MMU_ENABLED #endif + // + // GCODE_MACROS + // + #if ENABLED(GCODE_MACROS_EEPROM) + _FIELD_TEST(gcode_macros); + EEPROM_WRITE(gcode.macros); + #endif + // // Report final CRC and Data Size // @@ -2981,6 +2996,13 @@ void MarlinSettings::postprocess() { EEPROM_READ(mmu3.mmu_hw_enabled); // EEPROM_MMU_ENABLED #endif + // + // GCODE_MACROS + // + #if ENABLED(GCODE_MACROS_EEPROM) + EEPROM_READ(gcode.macros); + #endif + // // Validate Final Size and CRC // @@ -3800,6 +3822,11 @@ void MarlinSettings::reset() { mmu3.mmu_hw_enabled = true; #endif + // + // G-code Macros + // + TERN_(GCODE_MACROS_EEPROM, gcode.reset_macros()); + // // Hotend Idle Timeout // @@ -4035,6 +4062,11 @@ void MarlinSettings::reset() { // TERN_(EDITABLE_HOMING_FEEDRATE, gcode.M210_report(forReplay)); + // + // G-Code Macros + // + TERN_(GCODE_MACROS, gcode.M810_819_report(forReplay)); + // // Probe Offset // diff --git a/buildroot/tests/DUE b/buildroot/tests/DUE index 448da6f9d4..d5fcf2e4cb 100755 --- a/buildroot/tests/DUE +++ b/buildroot/tests/DUE @@ -15,7 +15,7 @@ opt_set MOTHERBOARD BOARD_RAMPS4DUE_EFB \ TEMP_SENSOR_CHAMBER 3 TEMP_CHAMBER_PIN 6 HEATER_CHAMBER_PIN 45 \ BACKLASH_MEASUREMENT_FEEDRATE 600 \ TRAMMING_POINT_XY '{{20,20},{20,20},{20,20},{20,20},{20,20}}' TRAMMING_POINT_NAME_5 '"Point 5"' -opt_enable S_CURVE_ACCELERATION EEPROM_SETTINGS GCODE_MACROS \ +opt_enable S_CURVE_ACCELERATION EEPROM_SETTINGS GCODE_MACROS GCODE_MACROS_IN_EEPROM \ FIX_MOUNTED_PROBE Z_SAFE_HOMING CODEPENDENT_XY_HOMING \ ASSISTED_TRAMMING REPORT_TRAMMING_MM ASSISTED_TRAMMING_WAIT_POSITION \ EEPROM_SETTINGS SDSUPPORT BINARY_FILE_TRANSFER \ From ba8b685ede00a05390b80947ee7a802b481a68aa Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 11 Nov 2025 17:51:51 -0600 Subject: [PATCH 59/99] =?UTF-8?q?=F0=9F=A7=91=E2=80=8D=F0=9F=92=BB=20Old?= =?UTF-8?q?=20macros=20cleanup?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/core/macros.h | 6 ------ Marlin/src/core/types.h | 2 +- Marlin/src/gcode/control/M350_M351.cpp | 2 +- Marlin/src/gcode/host/M114.cpp | 2 +- Marlin/src/inc/SanityCheck.h | 4 ++-- Marlin/src/module/delta.cpp | 2 +- Marlin/src/module/delta.h | 2 +- Marlin/src/module/motion.cpp | 4 ++-- 8 files changed, 9 insertions(+), 15 deletions(-) diff --git a/Marlin/src/core/macros.h b/Marlin/src/core/macros.h index d66450f758..29a625dbc3 100644 --- a/Marlin/src/core/macros.h +++ b/Marlin/src/core/macros.h @@ -25,12 +25,6 @@ #define __has_include(...) 1 #endif -#define ABCE 4 -#define XYZE 4 -#define ABC 3 -#define XYZ 3 -#define XY 2 - #define _AXIS(A) (A##_AXIS) #define _FORCE_INLINE_ __attribute__((__always_inline__)) __inline__ diff --git a/Marlin/src/core/types.h b/Marlin/src/core/types.h index 486f78fde8..520e876315 100644 --- a/Marlin/src/core/types.h +++ b/Marlin/src/core/types.h @@ -541,7 +541,7 @@ struct XYval { #endif #if HAS_Y_AXIS FI void set(const T px, const T py) { x = px; y = py; } - FI void set(const T (&arr)[XY]) { x = arr[0]; y = arr[1]; } + FI void set(const T (&arr)[2]) { x = arr[0]; y = arr[1]; } #endif #if NUM_AXES > XY FI void set(const T (&arr)[NUM_AXES]) { x = arr[0]; y = arr[1]; } diff --git a/Marlin/src/gcode/control/M350_M351.cpp b/Marlin/src/gcode/control/M350_M351.cpp index 425abad529..76753b2ea9 100644 --- a/Marlin/src/gcode/control/M350_M351.cpp +++ b/Marlin/src/gcode/control/M350_M351.cpp @@ -27,7 +27,7 @@ #include "../gcode.h" #include "../../module/stepper.h" -#if NUM_AXES == XYZ && EXTRUDERS >= 1 +#if NUM_AXES == 3 && EXTRUDERS >= 1 #define HAS_M350_B_PARAM 1 // "5th axis" (after E0) for an original XYZEB setup. #endif diff --git a/Marlin/src/gcode/host/M114.cpp b/Marlin/src/gcode/host/M114.cpp index 6ec6c2f3ca..35e618e6f2 100644 --- a/Marlin/src/gcode/host/M114.cpp +++ b/Marlin/src/gcode/host/M114.cpp @@ -36,7 +36,7 @@ } SERIAL_EOL(); } - inline void report_linear_axis_pos(const xyze_pos_t &pos) { report_all_axis_pos(pos, XYZ); } + inline void report_linear_axis_pos(const xyze_pos_t &pos) { report_all_axis_pos(pos, 3); } void report_linear_axis_pos(const xyz_pos_t &pos, const uint8_t precision=3) { LOOP_NUM_AXES(a) SERIAL_ECHO(FPSTR(pgm_read_ptr(&SP_AXIS_LBL[a])), p_float_t(pos[a], precision)); diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index c13c0ded82..b8b4a42f40 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -600,7 +600,7 @@ static_assert(COUNT(arm) == LOGICAL_AXES, "AXIS_RELATIVE_MODES must contain " _L #if ENABLED(NOZZLE_PARK_FEATURE) constexpr float npp[] = NOZZLE_PARK_POINT; - static_assert(COUNT(npp) == _MIN(NUM_AXES, XYZ), "NOZZLE_PARK_POINT requires coordinates for enabled axes, but only up to X,Y,Z."); + static_assert(COUNT(npp) == _MIN(NUM_AXES, 3), "NOZZLE_PARK_POINT requires coordinates for enabled axes, but only up to X,Y,Z."); constexpr xyz_pos_t npp_xyz = NOZZLE_PARK_POINT; static_assert(WITHIN(npp_xyz.x, X_MIN_POS, X_MAX_POS), "NOZZLE_PARK_POINT.X is out of bounds (X_MIN_POS, X_MAX_POS)."); static_assert(TERN1(HAS_Y_AXIS, WITHIN(npp_xyz.y, Y_MIN_POS, Y_MAX_POS)), "NOZZLE_PARK_POINT.Y is out of bounds (Y_MIN_POS, Y_MAX_POS)."); @@ -1122,7 +1122,7 @@ static_assert(NUM_SERVOS <= NUM_SERVO_PLUGS, "NUM_SERVOS (or some servo index) i #error "Leveling in Marlin requires three or more axes, with Z as the vertical axis." #elif ENABLED(CNC_WORKSPACE_PLANES) && !HAS_Z_AXIS #error "CNC_WORKSPACE_PLANES currently requires a Z axis" -#elif ENABLED(DIRECT_STEPPING) && NUM_AXES > XYZ +#elif ENABLED(DIRECT_STEPPING) && NUM_AXES > 3 #error "DIRECT_STEPPING does not currently support more than 3 axes (i.e., XYZ)." #elif ENABLED(FOAMCUTTER_XYUV) && !(HAS_I_AXIS && HAS_J_AXIS) #error "FOAMCUTTER_XYUV requires I and J steppers to be enabled." diff --git a/Marlin/src/module/delta.cpp b/Marlin/src/module/delta.cpp index 2f0415babc..5c913cb5c4 100644 --- a/Marlin/src/module/delta.cpp +++ b/Marlin/src/module/delta.cpp @@ -56,7 +56,7 @@ float delta_radius, delta_diagonal_rod, segments_per_second; abc_float_t delta_tower_angle_trim; -xy_float_t delta_tower[ABC]; +xy_float_t delta_tower[3]; abc_float_t delta_diagonal_rod_2_tower; float delta_clip_start_height = Z_MAX_POS; abc_float_t delta_diagonal_rod_trim; diff --git a/Marlin/src/module/delta.h b/Marlin/src/module/delta.h index a82f068615..92e647d6d9 100644 --- a/Marlin/src/module/delta.h +++ b/Marlin/src/module/delta.h @@ -34,7 +34,7 @@ extern float delta_radius, delta_diagonal_rod, segments_per_second; extern abc_float_t delta_tower_angle_trim; -extern xy_float_t delta_tower[ABC]; +extern xy_float_t delta_tower[3]; extern abc_float_t delta_diagonal_rod_2_tower; extern float delta_clip_start_height; extern abc_float_t delta_diagonal_rod_trim; diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index cf524cbdb9..34f516c60a 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -120,12 +120,12 @@ xyze_pos_t destination; // {0} #if HAS_HOTEND_OFFSET xyz_pos_t hotend_offset[HOTENDS]; // Initialized by settings.load void reset_hotend_offsets() { - constexpr float tmp[XYZ][HOTENDS] = { HOTEND_OFFSET_X, HOTEND_OFFSET_Y, HOTEND_OFFSET_Z }; + constexpr float tmp[3][HOTENDS] = { HOTEND_OFFSET_X, HOTEND_OFFSET_Y, HOTEND_OFFSET_Z }; static_assert( !tmp[X_AXIS][0] && !tmp[Y_AXIS][0] && !tmp[Z_AXIS][0], "Offsets for the first hotend must be 0.0." ); - // Transpose from [XYZ][HOTENDS] to [HOTENDS][XYZ] + // Transpose from [3][HOTENDS] to [HOTENDS][3] HOTEND_LOOP() LOOP_ABC(a) hotend_offset[e][a] = tmp[a][e]; TERN_(DUAL_X_CARRIAGE, hotend_offset[1].x = _MAX(X2_HOME_POS, X2_MAX_POS)); } From b0f6155d990ef0ceda865b18837b3a119d0c545b Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 11 Nov 2025 19:50:22 -0600 Subject: [PATCH 60/99] =?UTF-8?q?=F0=9F=A7=91=E2=80=8D=F0=9F=92=BB=20FTM?= =?UTF-8?q?=20trajectory=20code=20tweaks?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../module/ft_motion/trajectory_generator.h | 2 +- .../src/module/ft_motion/trajectory_poly5.h | 40 ++++++++++--------- .../src/module/ft_motion/trajectory_poly6.cpp | 25 ++++++------ .../module/ft_motion/trajectory_trapezoidal.h | 18 +++++---- 4 files changed, 45 insertions(+), 40 deletions(-) diff --git a/Marlin/src/module/ft_motion/trajectory_generator.h b/Marlin/src/module/ft_motion/trajectory_generator.h index 677249af0d..f0d07f932e 100644 --- a/Marlin/src/module/ft_motion/trajectory_generator.h +++ b/Marlin/src/module/ft_motion/trajectory_generator.h @@ -37,7 +37,7 @@ public: * @param nominal_speed Peak feedrate [mm/s] * @param distance Total distance to travel [mm] */ - virtual void plan(const float initial_speed, const float final_speed, const float acceleration, const float nominal_speed, const float distance) = 0; + virtual void plan(const float initial_speed, const float final_speed, const float acceleration, float nominal_speed, const float distance) = 0; /** * Plan a zero-motion trajectory for a specific duration. diff --git a/Marlin/src/module/ft_motion/trajectory_poly5.h b/Marlin/src/module/ft_motion/trajectory_poly5.h index 91ee23b094..e59c8a79fd 100644 --- a/Marlin/src/module/ft_motion/trajectory_poly5.h +++ b/Marlin/src/module/ft_motion/trajectory_poly5.h @@ -34,51 +34,52 @@ class Poly5TrajectoryGenerator : public TrajectoryGenerator { public: Poly5TrajectoryGenerator() = default; - void plan(const float initial_speed, const float final_speed, const float acceleration, const float nominal_speed, const float distance) override { + void plan(const float initial_speed, const float final_speed, const float acceleration, float nominal_speed, const float distance) override { this->initial_speed = initial_speed; - this->nominal_speed = nominal_speed; // Calculate timing phases using the same logic as trapezoidal generator const float one_over_acc = 1.0f / acceleration; - const float ldiff = distance + 0.5f * one_over_acc * (sq(this->initial_speed) + sq(final_speed)); + const float ldiff = distance + 0.5f * one_over_acc * (sq(initial_speed) + sq(final_speed)); - T2 = ldiff / this->nominal_speed - one_over_acc * this->nominal_speed; + T2 = ldiff / nominal_speed - one_over_acc * nominal_speed; if (T2 < 0.0f) { T2 = 0.0f; - this->nominal_speed = sqrtf(ldiff * acceleration); + nominal_speed = SQRT(ldiff * acceleration); } - T1 = (this->nominal_speed - this->initial_speed) * one_over_acc; - T3 = (this->nominal_speed - final_speed) * one_over_acc; + this->nominal_speed = nominal_speed; - const float d1 = (this->initial_speed + this->nominal_speed) * T1 * 0.5f; + T1 = (nominal_speed - initial_speed) * one_over_acc; + T3 = (nominal_speed - final_speed) * one_over_acc; + + const float d1 = (initial_speed + nominal_speed) * T1 * 0.5f; const float T1_2 = sq(T1); const float T1_3 = T1_2 * T1; const float T1_4 = T1_3 * T1; const float T1_5 = T1_4 * T1; // acc_c0 = 0.0f; // initial position is zero - acc_c1 = this->initial_speed; + acc_c1 = initial_speed; // acc_c2 = 0.0f; // initial acceleration is zero - acc_c3 = (10.0f * d1 - (6.0f * this->initial_speed + 4.0f * this->nominal_speed) * T1) / T1_3; - acc_c4 = (15.0f * d1 - (8.0f * this->initial_speed + 7.0f * this->nominal_speed) * T1) / -T1_4; - acc_c5 = (6.0f * d1 - 3.0f * (this->initial_speed + this->nominal_speed) * T1) / T1_5; + acc_c3 = (10.0f * d1 - (6.0f * initial_speed + 4.0f * nominal_speed) * T1) / T1_3; + acc_c4 = (15.0f * d1 - (8.0f * initial_speed + 7.0f * nominal_speed) * T1) / -T1_4; + acc_c5 = (6.0f * d1 - 3.0f * (initial_speed + nominal_speed) * T1) / T1_5; pos_before_coast = d1; // Coast phase - pos_after_coast = pos_before_coast + this->nominal_speed * T2; + pos_after_coast = pos_before_coast + nominal_speed * T2; // Deceration phase - const float d3 = (this->nominal_speed + final_speed) * T3 * 0.5f; + const float d3 = (nominal_speed + final_speed) * T3 * 0.5f; const float T3_2 = sq(T3); const float T3_3 = T3_2 * T3; const float T3_4 = T3_3 * T3; const float T3_5 = T3_4 * T3; // dec_c0 = 0.0f; // initial position is zero - dec_c1 = this->nominal_speed; + dec_c1 = nominal_speed; // dec_c2 = 0.0f; // initial acceleration is zero - dec_c3 = (10.0f * d3 - (6.0f * this->nominal_speed + 4.0f * final_speed) * T3) / T3_3; - dec_c4 = (15.0f * d3 - (8.0f * this->nominal_speed + 7.0f * final_speed) * T3) / -T3_4; - dec_c5 = (6.0f * d3 - 3.0f * (this->nominal_speed + final_speed) * T3) / T3_5; + dec_c3 = (10.0f * d3 - (6.0f * nominal_speed + 4.0f * final_speed) * T3) / T3_3; + dec_c4 = (15.0f * d3 - (8.0f * nominal_speed + 7.0f * final_speed) * T3) / -T3_4; + dec_c5 = (6.0f * d3 - 3.0f * (nominal_speed + final_speed) * T3) / T3_5; } void planRunout(const float duration) override { @@ -90,7 +91,8 @@ public: if (t < T1) { // Acceration phase return t * (acc_c1 + sq(t) * (acc_c3 + t * (acc_c4 + t * acc_c5))); - } else if (t <= (T1 + T2)) { + } + else if (t <= (T1 + T2)) { // Coasting phase return pos_before_coast + this->nominal_speed * (t - T1); } diff --git a/Marlin/src/module/ft_motion/trajectory_poly6.cpp b/Marlin/src/module/ft_motion/trajectory_poly6.cpp index 338c7b0d5d..45dff71084 100644 --- a/Marlin/src/module/ft_motion/trajectory_poly6.cpp +++ b/Marlin/src/module/ft_motion/trajectory_poly6.cpp @@ -32,24 +32,25 @@ Poly6TrajectoryGenerator::Poly6TrajectoryGenerator() {} void Poly6TrajectoryGenerator::plan(const float initial_speed, const float final_speed, const float acceleration, float nominal_speed, const float distance) { this->initial_speed = initial_speed; - this->nominal_speed = nominal_speed; // --- Trapezoid timings (unchanged) --- const float invA = 1.0f / acceleration; - const float ldiff = distance + 0.5f * invA * (sq(this->initial_speed) + sq(final_speed)); + const float ldiff = distance + 0.5f * invA * (sq(initial_speed) + sq(final_speed)); - T2 = ldiff / this->nominal_speed - invA * this->nominal_speed; + T2 = ldiff / nominal_speed - invA * nominal_speed; if (T2 < 0.0f) { T2 = 0.0f; - this->nominal_speed = sqrtf(ldiff * acceleration); + nominal_speed = SQRT(ldiff * acceleration); } - T1 = (this->nominal_speed - this->initial_speed) * invA; - T3 = (this->nominal_speed - final_speed) * invA; + this->nominal_speed = nominal_speed; + + T1 = (nominal_speed - initial_speed) * invA; + T3 = (nominal_speed - final_speed) * invA; // Distances at phase boundaries (trapezoid areas) - pos_before_coast = 0.5f * (this->initial_speed + this->nominal_speed) * T1; - pos_after_coast = pos_before_coast + this->nominal_speed * T2; + pos_before_coast = 0.5f * (initial_speed + nominal_speed) * T1; + pos_after_coast = pos_before_coast + nominal_speed * T2; // --- Build sextic (in position) for each phase --- // We start from a quintic-in-position s5(u) that meets endpoints with a(0)=a(1)=0, @@ -63,9 +64,9 @@ void Poly6TrajectoryGenerator::plan(const float initial_speed, const float final { const float Ts = T1; const float s0 = 0.0f; - const float v0 = this->initial_speed; + const float v0 = initial_speed; const float s1 = pos_before_coast; - const float v1 = this->nominal_speed; + const float v1 = nominal_speed; const float delta_p = s1 - s0 - v0 * Ts; const float delta_v = (v1 - v0) * Ts; @@ -86,8 +87,8 @@ void Poly6TrajectoryGenerator::plan(const float initial_speed, const float final { const float Ts = T3; const float s0 = pos_after_coast; - const float v0 = this->nominal_speed; - const float s1 = pos_after_coast + 0.5f * (this->nominal_speed + final_speed) * T3; + const float v0 = nominal_speed; + const float s1 = pos_after_coast + 0.5f * (nominal_speed + final_speed) * T3; const float v1 = final_speed; const float delta_p = s1 - s0 - v0 * Ts; diff --git a/Marlin/src/module/ft_motion/trajectory_trapezoidal.h b/Marlin/src/module/ft_motion/trajectory_trapezoidal.h index 1c96618f50..2bfe1dc5ed 100644 --- a/Marlin/src/module/ft_motion/trajectory_trapezoidal.h +++ b/Marlin/src/module/ft_motion/trajectory_trapezoidal.h @@ -33,9 +33,8 @@ class TrapezoidalTrajectoryGenerator : public TrajectoryGenerator { public: TrapezoidalTrajectoryGenerator() = default; - void plan(const float initial_speed, const float final_speed, const float acceleration, const float nominal_speed, const float distance) override { + void plan(const float initial_speed, const float final_speed, const float acceleration, float nominal_speed, const float distance) override { this->initial_speed = initial_speed; - this->nominal_speed = nominal_speed; this->acceleration = acceleration; const float one_over_accel = 1.0f / acceleration; @@ -44,26 +43,29 @@ public: T2 = ldiff / nominal_speed - one_over_accel * nominal_speed; if (T2 < 0.0f) { T2 = 0.0f; - this->nominal_speed = sqrtf(ldiff * acceleration); + nominal_speed = SQRT(ldiff * acceleration); } - T1 = (this->nominal_speed - initial_speed) * one_over_accel; - T3 = (this->nominal_speed - final_speed) * one_over_accel; + this->nominal_speed = nominal_speed; + + T1 = (nominal_speed - initial_speed) * one_over_accel; + T3 = (nominal_speed - final_speed) * one_over_accel; // Calculate the distance traveled during the accel phase pos_before_coast = initial_speed * T1 + 0.5f * acceleration * sq(T1); // Calculate the distance traveled during the coast phase - pos_after_coast = pos_before_coast + this->nominal_speed * T2; + pos_after_coast = pos_before_coast + nominal_speed * T2; } float getDistanceAtTime(const float t) const override { if (t < T1) { // Acceleration phase return (this->initial_speed * t) + (0.5f * this->acceleration * sq(t)); - } else if (t <= (T1 + T2)) { + } + else if (t <= (T1 + T2)) { // Coasting phase - return pos_before_coast + this->nominal_speed * (t - T1); + return pos_before_coast + nominal_speed * (t - T1); } // Deceleration phase const float tau_decel = t - (T1 + T2); From 54fe84ea32313250dfa8bc04c05b801f9d25463b Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 11 Nov 2025 21:59:31 -0600 Subject: [PATCH 61/99] =?UTF-8?q?=F0=9F=A7=91=E2=80=8D=F0=9F=92=BB=20Misse?= =?UTF-8?q?d=20some?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Followup to ba8b685ede --- Marlin/src/core/types.h | 4 ++-- Marlin/src/gcode/host/M115.cpp | 2 +- Marlin/src/inc/Conditionals-1-axes.h | 2 +- 3 files changed, 4 insertions(+), 4 deletions(-) diff --git a/Marlin/src/core/types.h b/Marlin/src/core/types.h index 520e876315..c48e0ffe68 100644 --- a/Marlin/src/core/types.h +++ b/Marlin/src/core/types.h @@ -543,7 +543,7 @@ struct XYval { FI void set(const T px, const T py) { x = px; y = py; } FI void set(const T (&arr)[2]) { x = arr[0]; y = arr[1]; } #endif - #if NUM_AXES > XY + #if NUM_AXES > 2 FI void set(const T (&arr)[NUM_AXES]) { x = arr[0]; y = arr[1]; } #endif #if LOGICAL_AXES > NUM_AXES @@ -1334,7 +1334,7 @@ public: // Axis names for G-code parsing, reports, etc. constexpr xyze_char_t axis_codes LOGICAL_AXIS_ARRAY('E', 'X', 'Y', 'Z', AXIS4_NAME, AXIS5_NAME, AXIS6_NAME, AXIS7_NAME, AXIS8_NAME, AXIS9_NAME); -#if NUM_AXES <= XYZ && !HAS_EXTRUDERS +#if NUM_AXES <= 3 && !HAS_EXTRUDERS #define AXIS_CHAR(A) ((char)('X' + A)) #define IAXIS_CHAR AXIS_CHAR #else diff --git a/Marlin/src/gcode/host/M115.cpp b/Marlin/src/gcode/host/M115.cpp index 5ed52dbba1..19d0ae9b63 100644 --- a/Marlin/src/gcode/host/M115.cpp +++ b/Marlin/src/gcode/host/M115.cpp @@ -85,7 +85,7 @@ void GcodeSuite::M115() { " MACHINE_TYPE:" MACHINE_NAME " KINEMATICS:" MACHINE_KINEMATICS " EXTRUDER_COUNT:" STRINGIFY(EXTRUDERS) - #if NUM_AXES != XYZ + #if NUM_AXES != 3 " AXIS_COUNT:" STRINGIFY(NUM_AXES) #endif #if defined(MACHINE_UUID) || ENABLED(HAS_STM32_UID) diff --git a/Marlin/src/inc/Conditionals-1-axes.h b/Marlin/src/inc/Conditionals-1-axes.h index 8744547153..1ad256b3b8 100644 --- a/Marlin/src/inc/Conditionals-1-axes.h +++ b/Marlin/src/inc/Conditionals-1-axes.h @@ -258,7 +258,7 @@ #if NUM_AXES >= XY #define HAS_Y_AXIS 1 #define HAS_B_AXIS 1 - #if NUM_AXES >= XYZ + #if NUM_AXES >= 3 #define HAS_Z_AXIS 1 #define HAS_C_AXIS 1 #if NUM_AXES >= 4 From ebf9aa5c82bf2c7dc21d867d5a4e3454bba90036 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Wed, 12 Nov 2025 06:11:20 +0000 Subject: [PATCH 62/99] [cron] Bump distribution date (2025-11-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 d1d2b563cc..0e726abbe9 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 "2025-11-11" +//#define STRING_DISTRIBUTION_DATE "2025-11-12" /** * The protocol for communication to the host. Protocol indicates communication diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 0bbdfd8de2..d11738b8b6 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 "2025-11-11" + #define STRING_DISTRIBUTION_DATE "2025-11-12" #endif /** From 3293b2780ec89357173256620562d7afc6a7dab2 Mon Sep 17 00:00:00 2001 From: narno2202 <130909513+narno2202@users.noreply.github.com> Date: Wed, 12 Nov 2025 23:06:36 +0100 Subject: [PATCH 63/99] =?UTF-8?q?=F0=9F=A9=B9=20Prevent=20=C3=B7=200=20in?= =?UTF-8?q?=20FT=20Motion=20(#28150)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/module/ft_motion/stepping.cpp | 11 +++++++---- 1 file changed, 7 insertions(+), 4 deletions(-) diff --git a/Marlin/src/module/ft_motion/stepping.cpp b/Marlin/src/module/ft_motion/stepping.cpp index fec5d05555..f86d07cf7c 100644 --- a/Marlin/src/module/ft_motion/stepping.cpp +++ b/Marlin/src/module/ft_motion/stepping.cpp @@ -42,7 +42,7 @@ uint32_t Stepping::advance_until_step() { uint32_t iterations = bresenham_iterations_pending; // Per-axis lower-bound approx of floor(space_q32/adv), min across axes (lower bound because this fast division underestimates result by up to 1) //#define RUN_AXIS(A) if (advance_q32.A > 0) NOMORE(iterations, space_q32.A / advance_q32.A); - #define RUN_AXIS(A) if (advance_q32.A > 0) NOMORE(iterations, uint32_t((uint64_t(space_q32.A) * advance_dividend_reciprocal.A) >> 32)); + #define RUN_AXIS(A) NOMORE(iterations, uint32_t((uint64_t(space_q32.A) * advance_dividend_reciprocal.A) >> 32)); LOGICAL_AXIS_MAP(RUN_AXIS); #undef RUN_AXIS @@ -90,8 +90,8 @@ uint32_t Stepping::plan() { #undef _HANDLE_DIR_CHANGES } - if (!(bool)stepper_plan.advance_dividend_q0_32) { - // don't waste time in zero motion traj points + if (stepper_plan.advance_dividend_q0_32 == 0) { + // Don't waste time in zero motion traj points bresenham_iterations_pending = 0; step_bits = 0; return INTERVAL_PER_TRAJ_POINT; @@ -101,7 +101,10 @@ uint32_t Stepping::plan() { // The reciprocal is actually 2^32/dividend, but that requires dividing a uint64_t, which quite expensive // Since even the real reciprocal may underestimate the quotient by 1 anyway already, this optimisation doesn't // make things worse. This underestimation is compensated for in advance_until_step. - #define _DIVIDEND_RECIP(A) advance_dividend_reciprocal.A = UINT32_MAX / stepper_plan.advance_dividend_q0_32.A; + #define _DIVIDEND_RECIP(A) do{ \ + const uint32_t d = stepper_plan.advance_dividend_q0_32.A; \ + advance_dividend_reciprocal.A = d ? UINT32_MAX / d : UINT32_MAX; \ + }while(0); LOGICAL_AXIS_MAP(_DIVIDEND_RECIP); #undef _DIVIDEND_RECIP From e3fa27ac9fd52842f4796f169857d08137e65d4d Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Thu, 13 Nov 2025 00:31:59 +0000 Subject: [PATCH 64/99] [cron] Bump distribution date (2025-11-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 0e726abbe9..96608675e4 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 "2025-11-12" +//#define STRING_DISTRIBUTION_DATE "2025-11-13" /** * The protocol for communication to the host. Protocol indicates communication diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index d11738b8b6..f4656ed16c 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 "2025-11-12" + #define STRING_DISTRIBUTION_DATE "2025-11-13" #endif /** From 8342a5a83e0bee0d5fd0ca8ca919272d471bd249 Mon Sep 17 00:00:00 2001 From: =?UTF-8?q?Axel=20Sep=C3=BAlveda?= Date: Thu, 13 Nov 2025 23:14:57 -0300 Subject: [PATCH 65/99] =?UTF-8?q?=F0=9F=90=9B=20Fix=20TPARA=20kinematics?= =?UTF-8?q?=20(#28068)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration.h | 32 ++++- Marlin/src/inc/Conditionals-5-post.h | 26 +++- Marlin/src/inc/SanityCheck.h | 7 + Marlin/src/module/motion.cpp | 73 +++++++--- Marlin/src/module/motion.h | 2 +- Marlin/src/module/scara.cpp | 206 ++++++++++++++++++++------- Marlin/src/sd/cardreader.cpp | 4 +- buildroot/tests/mega2560 | 12 +- 8 files changed, 274 insertions(+), 88 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index a327c406ef..219cfe42c7 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -1110,17 +1110,37 @@ #define TPARA_LINKAGE_1 120 // (mm) #define TPARA_LINKAGE_2 120 // (mm) - // TPARA tower offset (position of Tower relative to bed zero position) + // Height of the Shoulder axis (pivot) relative to the tower floor + #define TPARA_SHOULDER_AXIS_HEIGHT 135.0 // (mm) + + // The position of the last linkage relative to the robot arm origin + // (intersection of the base axis and floor) when at the home position + #define TPARA_ARM_X_HOME_POS 28.75 // (mm) Measured from shoulder axis to tool holder axis in home position + #define TPARA_ARM_Y_HOME_POS 0 // (mm) + #define TPARA_ARM_Z_HOME_POS 250.00 // (mm) Measured from tool holder axis to the floor + + // TPARA Workspace offset relative to the tower (position of workspace origin relative to robot Tower origin ) // This needs to be reasonably accurate as it defines the printbed position in the TPARA space. - #define TPARA_OFFSET_X 0 // (mm) - #define TPARA_OFFSET_Y 0 // (mm) - #define TPARA_OFFSET_Z 0 // (mm) + #define TPARA_OFFSET_X 127.0 // (mm) to coincide with minimum radius MIDDLE_DEAD_ZONE_R, and W(0,0,0) is reachable + #define TPARA_OFFSET_Y 0.0 // (mm) + #define TPARA_OFFSET_Z 0.0 // (mm) + + // TPARA tool connection point offset, relative to the tool moving frame origin which is in the last linkage axis, + // (TCP: tool center/connection point) of the robot, + // the plane of measured offset must be alligned with home position plane + #define TPARA_TCP_OFFSET_X 27.0 // (mm) Tool flange: 27 (distance from pivot to bolt holes), extruder tool: 50.0, + #define TPARA_TCP_OFFSET_Y 0.0 // (mm) + #define TPARA_TCP_OFFSET_Z -65.0 // (mm) Tool flange (bottom): -6 (caution as Z 0 posiion will crash second linkage to the floor, -35 is safe for testing with no tool), extruder tool (depends on extruder): -65.0 #define FEEDRATE_SCALING // Convert XY feedrate from mm/s to degrees/s on the fly // Radius around the center where the arm cannot reach - #define MIDDLE_DEAD_ZONE_R 0 // (mm) -#endif + // For now use a hardcoded uniform limit, although it should be calculated, or fix a limit for each axis angle + #define MIDDLE_DEAD_ZONE_R 100 // (mm) + + // Max angle between L1 and L2 + #define TPARA_MAX_L1L2_ANGLE 140.0f // (degrees) +#endif // AXEL_TPARA // @section polar diff --git a/Marlin/src/inc/Conditionals-5-post.h b/Marlin/src/inc/Conditionals-5-post.h index 9eb5031055..f2b3e361c6 100644 --- a/Marlin/src/inc/Conditionals-5-post.h +++ b/Marlin/src/inc/Conditionals-5-post.h @@ -313,10 +313,24 @@ /** * SCARA cannot use SLOWDOWN and requires QUICKHOME * Printable radius assumes joints can fully extend + * + * TPARA cannot use SLOWDOWN nor QUICKHOME + * Printable radius assumes joints can't fully extend + * AXEL_TPARA is assigned a default Home Position unless overridden */ #if IS_SCARA #if ENABLED(AXEL_TPARA) - #define PRINTABLE_RADIUS (TPARA_LINKAGE_1 + TPARA_LINKAGE_2) + #define PRINTABLE_RADIUS_2 HYPOT2(TPARA_LINKAGE_1, TPARA_LINKAGE_2) - 2 * (TPARA_LINKAGE_1) * (TPARA_LINKAGE_2) * cosf(TPARA_MAX_L1L2_ANGLE) + #define PRINTABLE_RADIUS SQRT(PRINTABLE_RADIUS_2) + #ifndef MANUAL_X_HOME_POS + #define MANUAL_X_HOME_POS (TPARA_ARM_X_HOME_POS + TPARA_TCP_OFFSET_X - TPARA_OFFSET_X) + #endif + #ifndef MANUAL_Y_HOME_POS + #define MANUAL_Y_HOME_POS (TPARA_ARM_Y_HOME_POS + TPARA_TCP_OFFSET_Y - TPARA_OFFSET_Y) + #endif + #ifndef MANUAL_Z_HOME_POS + #define MANUAL_Z_HOME_POS (TPARA_ARM_Z_HOME_POS + TPARA_TCP_OFFSET_Z - TPARA_OFFSET_Z) + #endif #else #define QUICK_HOME #define PRINTABLE_RADIUS (SCARA_LINKAGE_1 + SCARA_LINKAGE_2) @@ -352,10 +366,12 @@ #endif #endif -#ifdef MANUAL_Z_HOME_POS - #define Z_HOME_POS MANUAL_Z_HOME_POS -#else - #define Z_HOME_POS TERN(Z_HOME_TO_MIN, Z_MIN_POS, Z_MAX_POS) +#if HAS_Z_AXIS + #ifdef MANUAL_Z_HOME_POS + #define Z_HOME_POS MANUAL_Z_HOME_POS + #else + #define Z_HOME_POS TERN(Z_HOME_TO_MIN, Z_MIN_POS, Z_MAX_POS) + #endif #endif #if HAS_I_AXIS diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index b8b4a42f40..fc31f9901b 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -1252,6 +1252,13 @@ static_assert(NUM_SERVOS <= NUM_SERVO_PLUGS, "NUM_SERVOS (or some servo index) i #endif #endif +/** + * Axel TPARA requirements + */ +#if ENABLED(AXEL_TPARA) && !ALL(HOME_Z_FIRST, HOME_Y_BEFORE_X) + #error "AXEL_TPARA requires both HOME_Z_FIRST and HOME_Y_BEFORE_X to be enabled." +#endif + /** * Junction deviation is incompatible with kinematic systems. */ diff --git a/Marlin/src/module/motion.cpp b/Marlin/src/module/motion.cpp index 34f516c60a..42d673db93 100644 --- a/Marlin/src/module/motion.cpp +++ b/Marlin/src/module/motion.cpp @@ -85,19 +85,34 @@ bool relative_mode; // = false bool z_min_trusted; // = false #endif +// Warn for unexpected TPARA home position +#if ENABLED(AXEL_TPARA) + static_assert( + ABS(X_HOME_POS - (TPARA_ARM_X_HOME_POS + TPARA_TCP_OFFSET_X - TPARA_OFFSET_X)) < 0.01f, + "X_HOME_POS should be equal to (TPARA_ARM_X_HOME_POS + TPARA_TCP_OFFSET_X - TPARA_OFFSET_X)"); + static_assert( + ABS(Y_HOME_POS - (TPARA_ARM_Y_HOME_POS + TPARA_TCP_OFFSET_Y - TPARA_OFFSET_Y)) < 0.01f, + "Y_HOME_POS should be equal to (TPARA_ARM_Y_HOME_POS + TPARA_TCP_OFFSET_Y - TPARA_OFFSET_Y)."); + static_assert( + ABS(Z_HOME_POS - (TPARA_ARM_Z_HOME_POS + TPARA_TCP_OFFSET_Z - TPARA_OFFSET_Z)) < 0.01f, + "Z_HOME_POS should be equal to (TPARA_ARM_Z_HOME_POS + TPARA_TCP_OFFSET_Z - TPARA_OFFSET_Z)."); +#endif + /** * Cartesian Current Position * Used to track the native machine position as moves are queued. * Used by 'line_to_current_position' to do a move after changing it. * Used by 'sync_plan_position' to update 'planner.position'. */ -#ifdef Z_IDLE_HEIGHT - #define Z_INIT_POS Z_IDLE_HEIGHT -#else - #define Z_INIT_POS Z_HOME_POS -#endif - -xyze_pos_t current_position = LOGICAL_AXIS_ARRAY(0, X_HOME_POS, Y_HOME_POS, Z_INIT_POS, I_HOME_POS, J_HOME_POS, K_HOME_POS, U_HOME_POS, V_HOME_POS, W_HOME_POS); +xyze_pos_t current_position = LOGICAL_AXIS_ARRAY(0, + X_HOME_POS, Y_HOME_POS, + #ifdef Z_IDLE_HEIGHT + Z_IDLE_HEIGHT + #else + Z_HOME_POS + #endif + , I_HOME_POS, J_HOME_POS, K_HOME_POS, U_HOME_POS, V_HOME_POS, W_HOME_POS +); /** * Cartesian Destination @@ -154,18 +169,18 @@ xyz_pos_t cartes; #if HAS_SCARA_OFFSET abc_pos_t scara_home_offset; #endif - + // If it does not have software endstops, use the printable radius #if HAS_SOFTWARE_ENDSTOPS float delta_max_radius, delta_max_radius_2; #elif IS_SCARA constexpr float delta_max_radius = PRINTABLE_RADIUS, - delta_max_radius_2 = sq(PRINTABLE_RADIUS); + delta_max_radius_2 = sq(float(PRINTABLE_RADIUS)); #elif ENABLED(POLAR) constexpr float delta_max_radius = PRINTABLE_RADIUS, - delta_max_radius_2 = sq(PRINTABLE_RADIUS); + delta_max_radius_2 = sq(float(PRINTABLE_RADIUS)); #else // DELTA constexpr float delta_max_radius = PRINTABLE_RADIUS, - delta_max_radius_2 = sq(PRINTABLE_RADIUS); + delta_max_radius_2 = sq(float(PRINTABLE_RADIUS)); #endif #endif @@ -179,6 +194,7 @@ xyz_pos_t cartes; // Set by M206, M428, or menu item. Saved to EEPROM. xyz_pos_t home_offset{0}; #endif + #if HAS_WORKSPACE_OFFSET // The above two are combined to save on computes xyz_pos_t workspace_offset{0}; @@ -633,12 +649,14 @@ void report_current_position_projected() { can_reach = HYPOT2(rx, ry) <= sq(PRINTABLE_RADIUS - inset + fslop); #elif ENABLED(AXEL_TPARA) - - const float R2 = HYPOT2(rx - TPARA_OFFSET_X, ry - TPARA_OFFSET_Y); + // TODO: A custom check, as reach depends also on Z destination. + // During printing assume destination Z is the current Z. + // For now use the max reach of the arm. + const float R2 = HYPOT2(rx + TPARA_OFFSET_X, ry + TPARA_OFFSET_Y); can_reach = ( - R2 <= sq(L1 + L2) - inset + R2 <= PRINTABLE_RADIUS_2 - inset #if MIDDLE_DEAD_ZONE_R > 0 - && R2 >= FLOAT_SQ(MIDDLE_DEAD_ZONE_R) + && R2 >= FLOAT_SQ(MIDDLE_DEAD_ZONE_R + TPARA_TCP_OFFSET_X) #endif ); @@ -726,6 +744,8 @@ void quickstop_stepper() { void sync_plan_position() { if (DEBUGGING(LEVELING)) DEBUG_POS("sync_plan_position", current_position); planner.set_position_mm(current_position); + //SERIAL_ECHOLNPGM("Sync_plan_position: ", current_position.x, ", ", current_position.y, ", ", current_position.z); + //SERIAL_EOL(); } #if HAS_EXTRUDERS @@ -818,6 +838,9 @@ void line_to_current_position(const feedRate_t fr_mm_s/*=feedrate_mm_s*/) { void prepare_fast_move_to_destination(const feedRate_t scaled_fr_mm_s/*=MMS_SCALED(feedrate_mm_s)*/) { if (DEBUGGING(LEVELING)) DEBUG_POS("prepare_fast_move_to_destination", destination); + //SERIAL_ECHOLNPGM("Prepare fast move to destination: ", destination.x , ",", destination.y, ",", destination.z, "," , destination.e); + //SERIAL_EOL(); + #if UBL_SEGMENTED // UBL segmented line will do Z-only moves in single segment bedlevel.line_to_destination_segmented(scaled_fr_mm_s); @@ -1260,6 +1283,8 @@ void restore_feedrate_and_scaling() { * radius within the set software endstops. */ void apply_motion_limits(xyz_pos_t &target) { + //SERIAL_ECHOLNPGM("Motion limits in: ", target.x, ", ", target.y, ", ", target.z); + //SERIAL_EOL(); if (!soft_endstop._enabled) return; @@ -1287,6 +1312,8 @@ void restore_feedrate_and_scaling() { #else if (TERN1(IS_SCARA, axis_was_homed(X_AXIS) && axis_was_homed(Y_AXIS))) { const float dist_2 = HYPOT2(target.x - offs.x, target.y - offs.y); + //SERIAL_ECHOLNPGM("Motion limits data: dist_2:", dist_2, " delta_max_radius_2: ", delta_max_radius_2); + //SERIAL_EOL(); if (dist_2 > delta_max_radius_2) target *= float(delta_max_radius / SQRT(dist_2)); // 200 / 300 = 0.66 } @@ -1538,8 +1565,13 @@ float get_move_distance(const xyze_pos_t &diff OPTARG(HAS_ROTATIONAL_AXES, bool const xyze_float_t diff = destination - current_position; - // If the move is only in Z/E don't split up the move - if (!diff.x && !diff.y) { + //SERIAL_ECHOLNPGM("Destination: ", destination.x, " , ", destination.y, " , ", destination.z, " , ", destination.e); + //SERIAL_ECHOLNPGM("Current pos: ", current_position.x, " , ", current_position.y, " , ", current_position.z, " , ", current_position.e); + //SERIAL_ECHOLNPGM("Difference : ", diff.x, " , ", diff.y, " , ", diff.z, " , ", diff.e); + + // For TPARA always split up the move, then skip next code + // For DELTA/SCARA if the move is only in Z/E don't split up the move + if (TERN0(AXEL_TPARA, !diff.x && !diff.y)) { planner.buffer_line(destination, scaled_fr_mm_s); return false; // caller will update current_position } @@ -1872,6 +1904,9 @@ float get_move_distance(const xyze_pos_t &diff OPTARG(HAS_ROTATIONAL_AXES, bool void prepare_line_to_destination() { apply_motion_limits(destination); + //SERIAL_ECHOLNPGM(">TPARA Prepare line to destination: ", destination.x , " , ", destination.y, " , ", destination.z, " , " , destination.e); + //SERIAL_EOL(); + #if ANY(PREVENT_COLD_EXTRUSION, PREVENT_LENGTHY_EXTRUDE) if (!DEBUGGING(DRYRUN) && destination.e != current_position.e) { @@ -2782,6 +2817,10 @@ void prepare_line_to_destination() { * current_position to home, because neither X nor Y is at home until * both are at home. Z can however be homed individually. * + * TPARA should wait until all YZ homing is done before setting the YZ + * current_position to home, because neither Y nor Z is at home until + * both are at home. X can however be homed individually. + * * Callers must sync the planner position after calling this! */ void set_axis_is_at_home(const AxisEnum axis) { diff --git a/Marlin/src/module/motion.h b/Marlin/src/module/motion.h index 7cafb2f019..0ebd1b5748 100644 --- a/Marlin/src/module/motion.h +++ b/Marlin/src/module/motion.h @@ -137,7 +137,7 @@ inline int8_t pgm_read_any(const int8_t *p) { return TERN(__IMXRT1062__, *p, pgm #define XYZ_DEFS(T, NAME, OPT) \ inline T NAME(const AxisEnum axis) { \ - static const XYZval NAME##_P DEFS_PROGMEM = NUM_AXIS_ARRAY(X_##OPT, Y_##OPT, Z_##OPT, I_##OPT, J_##OPT, K_##OPT, U_##OPT, V_##OPT, W_##OPT); \ + static constexpr XYZval NAME##_P DEFS_PROGMEM = NUM_AXIS_ARRAY(X_##OPT, Y_##OPT, Z_##OPT, I_##OPT, J_##OPT, K_##OPT, U_##OPT, V_##OPT, W_##OPT); \ return pgm_read_any(&NAME##_P[axis]); \ } XYZ_DEFS(float, base_min_pos, MIN_POS); // base_min_pos(axis) diff --git a/Marlin/src/module/scara.cpp b/Marlin/src/module/scara.cpp index d6016d77a1..8274335862 100644 --- a/Marlin/src/module/scara.cpp +++ b/Marlin/src/module/scara.cpp @@ -41,7 +41,7 @@ float segments_per_second = DEFAULT_SEGMENTS_PER_SECOND; #if ANY(MORGAN_SCARA, MP_SCARA) - static constexpr xy_pos_t scara_offset = { SCARA_OFFSET_X, SCARA_OFFSET_Y }; + constexpr xy_pos_t scara_offset = { SCARA_OFFSET_X, SCARA_OFFSET_Y }; /** * Morgan SCARA Forward Kinematics. Results in 'cartes'. @@ -178,22 +178,97 @@ float segments_per_second = DEFAULT_SEGMENTS_PER_SECOND; #elif ENABLED(AXEL_TPARA) - static constexpr xyz_pos_t robot_offset = { TPARA_OFFSET_X, TPARA_OFFSET_Y, TPARA_OFFSET_Z }; + // TPARA offset relative to the origin of the robot + constexpr xyz_pos_t robot_shoulder_offset = { 0, 0, TPARA_SHOULDER_AXIS_HEIGHT }; + // Workspace offset relative to the origin of the robot + constexpr xyz_pos_t robot_workspace_offset = { TPARA_OFFSET_X, TPARA_OFFSET_Y, TPARA_OFFSET_Z }; + // Tool offset relative to the tool center point of the robot + constexpr xyz_pos_t tool_offset = { TPARA_TCP_OFFSET_X, TPARA_TCP_OFFSET_Y, TPARA_TCP_OFFSET_Z }; + // Tool offset in cylindrical coordinates (r, phi, z) + constexpr xyz_pos_t tool_offset_cyl = { SQRT(sq(TPARA_TCP_OFFSET_X) + sq(TPARA_TCP_OFFSET_Y)) , ATAN2(TPARA_TCP_OFFSET_Y, TPARA_TCP_OFFSET_X), TPARA_TCP_OFFSET_Z }; - void scara_set_axis_is_at_home(const AxisEnum axis) { - if (axis == Z_AXIS) - current_position.z = Z_HOME_POS; - else { - xyz_pos_t homeposition = { X_HOME_POS, Y_HOME_POS, Z_HOME_POS }; - //DEBUG_ECHOLNPGM_P(PSTR("homeposition X"), homeposition.x, SP_Y_LBL, homeposition.y, SP_Z_LBL, homeposition.z); + //xyz_pos_t home_t_w_offset = tool_offset - robot_workspace_offset; - inverse_kinematics(homeposition); - forward_kinematics(delta.a, delta.b, delta.c); - current_position[axis] = cartes[axis]; + // Remove offset for calculation with trigonometric + // Tool offset coordinates are recalculated for each angle + xyz_pos_t remove_W_T_offset(const xyz_pos_t &raw) { + // Remove workspace offset first, so we can use trigonometrics relative to robot reference + // frame (otherwise a negative raw position would "mirror/invert" the tool offset) + xyz_pos_t toolhead_absolute = raw + robot_workspace_offset; - //DEBUG_ECHOLNPGM_P(PSTR("Cartesian X"), current_position.x, SP_Y_LBL, current_position.y); - update_software_endstops(axis); + // We should apply a rotation matrix, but is too costly to calculate sin and cos + const float r2 = HYPOT2(toolhead_absolute.x, toolhead_absolute.y); + xyz_pos_t tool_offset_rotated; + if (UNEAR_ZERO(r2)) { + // avoid zero div + tool_offset_rotated.x = tool_offset_cyl.x; + tool_offset_rotated.y = 0.0f; + tool_offset_rotated.z = tool_offset_cyl.z; } + else { + const float inv_r = RSQRT(r2); + tool_offset_rotated.x = tool_offset_cyl.x * toolhead_absolute.x * inv_r; // Equivalent to tool_offset_cyl.x * cos(atan2(toolhead_absolute.y, toolhead_absolute.x)) + tool_offset_rotated.y = tool_offset_cyl.x * toolhead_absolute.y * inv_r; // Equivalent to tool_offset_cyl.x * sin(atan2(toolhead_absolute.y, toolhead_absolute.x)) + tool_offset_rotated.z = tool_offset_cyl.z; + } + + return toolhead_absolute - tool_offset_rotated; // Returns the real robot position without tool or workspace offset + } + + // Apply tool and workspace offset to robot flange position, accounting for the rotated tool offset + constexpr xyz_pos_t apply_T_W_offset(const xyz_pos_t &rpos) { + // We should apply a rotation matrix, but it's too costly + const float r2 = rpos.x * rpos.x + rpos.y * rpos.y; + if (UNEAR_ZERO(r2)) { + // avoid zero div + xyz_pos_t tool_offset_rotated = { tool_offset_cyl.x, 0.0f, tool_offset_cyl.z }; + return rpos + tool_offset_rotated - robot_workspace_offset; + } + else { + const float inv_r = RSQRT(r2); + xyz_pos_t tool_offset_rotated = { + tool_offset_cyl.x * rpos.x * inv_r, + tool_offset_cyl.x * rpos.y * inv_r, + tool_offset_cyl.z + }; + //SERIAL_ECHOLNPGM(" Tool_offset_rotated(x,y,z) ", tool_offset_rotated.x, ",", tool_offset_rotated.y, ",", tool_offset_rotated.z ); + return rpos + tool_offset_rotated - robot_workspace_offset; + } + } + + /** + * Set an axis' current position to its home position (after homing). + * + * TPARA must wait for YZ homing before setting current_position.Y/Z to home. + * Neither Y nor Z is home until both are at home. + */ + void scara_set_axis_is_at_home(const AxisEnum axis) { + // Home position should be arm end position -+ offsets (+ tool offset - workspace offset), measured at home robot position + xyz_pos_t homeposition = { X_HOME_POS , Y_HOME_POS , Z_HOME_POS }; + + //SERIAL_ECHOLNPGM("TPARA Set axis is at home: ", C(iaxis_codes[axis])); + //SERIAL_XYZ("Home: ", homeposition); + //SERIAL_XYZ("Pos before IK: ", current_position); + //SERIAL_ECHOLNPGM("Angles Before: Theta: ", delta.a, " Phi: ", delta.b, " Psi: ", delta.c); + + inverse_kinematics(homeposition); + + //SERIAL_ECHOLNPGM("Angles After IK: Theta: ", delta.a, " Phi: ", delta.b, " Psi: ", delta.c); + + forward_kinematics(delta.a, delta.b, delta.c); + current_position[axis] = cartes[axis]; + + //SERIAL_XYZ("'current' after FK: ", current_position); + //SERIAL_XYZ("'cartes' after FK: ", cartes); + + update_software_endstops(axis); + + //SERIAL_ECHOLNPGM("Final Angles: Theta: ", delta.a, " Phi: ", delta.b, " Psi: ", delta.c); + //SERIAL_XYZ("Final Pos: ", current_position); + //SERIAL_XYZ("Robot Offsets Shoulder:", robot_shoulder_offset); + //SERIAL_XYZ("Robot Offsets Tool:", tool_offset); + //SERIAL_XYZ("Robot Offsets Workspace:", robot_workspace_offset); + //SERIAL_EOL(); } // Convert ABC inputs in degrees to XYZ outputs in mm @@ -204,35 +279,50 @@ float segments_per_second = DEFAULT_SEGMENTS_PER_SECOND; y = r * sin(RADIANS(a)), rho2 = L1_2 + L2_2 - 2.0f * L1 * L2 * cos(RADIANS(w)); - cartes = robot_offset + xyz_pos_t({ x, y, SQRT(rho2 - sq(x) - sq(y)) }); + const xyz_pos_t calculated_fk = xyz_pos_t({ x, y, SQRT(rho2 - sq(x) - sq(y)) }) ; + cartes = calculated_fk + robot_shoulder_offset + tool_offset - robot_workspace_offset; + + //SERIAL_ECHOPGM("TPARA FK Theta:", a, " Phi: ", b, " Psi: ", c); + //SERIAL_ECHOPGM(" Calculated X':", calculated_fk.x, " Y':", calculated_fk.y, " Z':", calculated_fk.z); + //SERIAL_XYZ(" Workspace", cartes); } // Home YZ together, then X (or all at once). Based on quick_home_xy & home_delta void home_TPARA() { - // Init the current position of all carriages to 0,0,0 + // First Init the current position of all carriages to 0,0,0 current_position.reset(); destination.reset(); sync_plan_position(); + //SERIAL_ECHOLNPGM("Reset and sync position to the assumed start position of the robot" ); + // Set the assumed start position of the robot for homing, so it home ZY axis at same time preserving the B and C motor angle + constexpr xyz_pos_t init_w_offset = apply_T_W_offset(xyz_pos_t({ L2, 0, 0 })); + + current_position.set(init_w_offset.x, init_w_offset.y, init_w_offset.z); + destination.set(init_w_offset.x, init_w_offset.y, init_w_offset.z); + sync_plan_position(); + // Disable stealthChop if used. Enable diag1 pin on driver. #if ENABLED(SENSORLESS_HOMING) - TERN_(X_SENSORLESS, sensorless_t stealth_states_x = start_sensorless_homing_per_axis(X_AXIS)); - TERN_(Y_SENSORLESS, sensorless_t stealth_states_y = start_sensorless_homing_per_axis(Y_AXIS)); - TERN_(Z_SENSORLESS, sensorless_t stealth_states_z = start_sensorless_homing_per_axis(Z_AXIS)); + #if X_SENSORLESS + sensorless_t stealth_states_x = start_sensorless_homing_per_axis(X_AXIS); + #endif + #if Y_SENSORLESS + sensorless_t stealth_states_y = start_sensorless_homing_per_axis(Y_AXIS); + #endif + #if Z_SENSORLESS + sensorless_t stealth_states_z = start_sensorless_homing_per_axis(Z_AXIS); + #endif #endif - //const int x_axis_home_dir = TOOL_X_HOME_DIR(active_extruder); - - //const xy_pos_t pos { max_length(X_AXIS), max_length(Y_AXIS) }; - //const float mlz = max_length(X_AXIS), - - // Move all carriages together linearly until an endstop is hit. - //do_blocking_move_to_xy_z(pos, mlz, homing_feedrate(Z_AXIS)); - // Set the homing current for all motors TERN_(HAS_HOMING_CURRENT, set_homing_current(Z_AXIS)); - current_position.set(0, 0, max_length(Z_AXIS)); + // Move to home, should move Z, Y, then X. Move X to near 0 (to avoid div by zero + // and sign/angle stability around 0 for trigonometric functions), Y to 0 and Z to max_length + constexpr xyz_pos_t homing_pos_dir = apply_T_W_offset(xyz_pos_t({ 1, 0, Z_MAX_LENGTH })); + current_position.set(homing_pos_dir.x, homing_pos_dir.y, homing_pos_dir.z); + line_to_current_position(homing_feedrate(Z_AXIS)); planner.synchronize(); @@ -250,9 +340,12 @@ float segments_per_second = DEFAULT_SEGMENTS_PER_SECOND; // At least one motor has reached its endstop. // Now re-home each motor separately. - homeaxis(A_AXIS); - homeaxis(C_AXIS); - homeaxis(B_AXIS); + TERN_(HOME_Z_FIRST, homeaxis(C_AXIS)); + homeaxis(TERN(HOME_Y_BEFORE_X, B_AXIS, A_AXIS)); + homeaxis(TERN(HOME_Y_BEFORE_X, A_AXIS, B_AXIS)); + IF_DISABLED(HOME_Z_FIRST, homeaxis(C_AXIS)); + + //SERIAL_ECHOLNPGM("current_position After Homeaxis: ", current_position.x, ", ", current_position.y, ", ", current_position.z); // Set all carriages to their home positions // Do this here all at once for Delta, because @@ -260,50 +353,55 @@ float segments_per_second = DEFAULT_SEGMENTS_PER_SECOND; // give the impression that they are the same. LOOP_NUM_AXES(i) set_axis_is_at_home((AxisEnum)i); + //SERIAL_ECHOLNPGM("Sync_plan_position after home"); sync_plan_position(); } void inverse_kinematics(const xyz_pos_t &raw) { - const xyz_pos_t spos = raw - robot_offset; - - const float RXY = SQRT(HYPOT2(spos.x, spos.y)), - RHO2 = NORMSQ(spos.x, spos.y, spos.z), + // Remove offsets to calculate with trigonometric + const xyz_pos_t tpos = remove_W_T_offset(raw) - robot_shoulder_offset; //raw + robot_workspace_offset - tool_offset_rotated - robot_shoulder_offset; + // IK, Refer to TPARA analysis + const float RXY = SQRT(HYPOT2(tpos.x, tpos.y)), + RHO_2 = NORMSQ(tpos.x, tpos.y, tpos.z), //RHO = SQRT(RHO2), - LSS = L1_2 + L2_2, - LM = 2.0f * L1 * L2, + LSS = L1_2 + L2_2, // L1^2 + L2^2 , LSS : Lenght square sum + LM = 2.0f * L1 * L2, // Length multiplication and doubled - CG = (LSS - RHO2) / LM, - SG = SQRT(1 - POW(CG, 2)), // Method 2 - K1 = L1 - L2 * CG, - K2 = L2 * SG, + // Method 2 + CG = (LSS - RHO_2) / LM, // Cosine of gamma + SG = SQRT(1 - POW(CG, 2)), // Sine of gamma + K1 = L1 - L2 * CG, // K1 projection + K2 = L2 * SG, // K2 projection - // Angle of Body Joint - THETA = ATAN2(spos.y, spos.x), + // Angle of Body/base Joint + THETA = ATAN2(tpos.y, tpos.x), - // Angle of Elbow Joint - //GAMMA = ACOS(CG), - GAMMA = ATAN2(SG, CG), // Method 2 + // Angle of Elbow Joint, between L1 and L2 + //GAMMA = ACOS(CG), // Method 1 + GAMMA = ATAN2(SG, CG), // Method 2 - // Angle of Shoulder Joint, elevation angle measured from horizontal (r+) - //PHI = asin(spos.z/RHO) + asin(L2 * sin(GAMMA) / RHO), - PHI = ATAN2(spos.z, RXY) + ATAN2(K2, K1), // Method 2 + // Angle of Shoulder Joint, elevation angle measured from horizontal plane XY (r+) + //PHI = asin(tpos.z/RHO) + asin(L2 * sin(GAMMA) / RHO), // Method 1 + PHI = ATAN2(tpos.z, RXY) + ATAN2(K2, K1), // Method 2 - // Elbow motor angle measured from horizontal, same frame as shoulder (r+) + // Elbow motor angle measured from horizontal, same reference frame as shoulder angle (r+) PSI = PHI + GAMMA; delta.set(DEGREES(THETA), DEGREES(PHI), DEGREES(PSI)); - //SERIAL_ECHOLNPGM(" SCARA (x,y,z) ", spos.x, ",", spos.y, ",", spos.z, " Rho=", RHO, " Rho2=", RHO2, " Theta=", THETA, " Phi=", PHI, " Psi=", PSI, " Gamma=", GAMMA); + //SERIAL_ECHOLNPGM(" TPARA IK raw(x,y,z) ", raw.x, ",", raw.y, ",", raw.z, " Robot pos(x,y,z) ", tpos.x, ",", tpos.y, ",", tpos.z + robot_shoulder_offset.z, " Rho^2=", RHO_2, " Theta=", DEGREES(THETA), " Phi=", DEGREES(PHI), " Psi=", DEGREES(PSI), " Gamma=", DEGREES(GAMMA)); } -#endif +#endif // AXEL_TPARA void scara_report_positions() { - SERIAL_ECHOLNPGM("SCARA Theta:", planner.get_axis_position_degrees(A_AXIS) + SERIAL_ECHOLNPGM( #if ENABLED(AXEL_TPARA) - , " Phi:", planner.get_axis_position_degrees(B_AXIS) - , " Psi:", planner.get_axis_position_degrees(C_AXIS) + "TPARA Theta: ", planner.get_axis_position_degrees(A_AXIS) + , " Phi: ", planner.get_axis_position_degrees(B_AXIS) + , " Psi: ", planner.get_axis_position_degrees(C_AXIS) #else + "SCARA Theta:", planner.get_axis_position_degrees(A_AXIS) , " Psi" TERN_(MORGAN_SCARA, "+Theta") ":", planner.get_axis_position_degrees(B_AXIS) #endif ); diff --git a/Marlin/src/sd/cardreader.cpp b/Marlin/src/sd/cardreader.cpp index 7153b2fb1f..723f86a07e 100644 --- a/Marlin/src/sd/cardreader.cpp +++ b/Marlin/src/sd/cardreader.cpp @@ -371,7 +371,7 @@ void CardReader::ls(const uint8_t lsflags/*=0*/) { int i, pathLen = path ? strlen(path) : 0; - // SERIAL_ECHOPGM("Full Path: "); SERIAL_ECHOLN(path); + //SERIAL_ECHOPGM("Full Path: "); SERIAL_ECHOLN(path); // Zero out slashes to make segments for (i = 0; i < pathLen; i++) if (path[i] == '/') path[i] = '\0'; @@ -402,7 +402,7 @@ void CardReader::ls(const uint8_t lsflags/*=0*/) { // If the filename was printed then that's it if (!flag.filenameIsDir) break; - // SERIAL_ECHOPGM("Opening dir: "); SERIAL_ECHOLN(segment); + //SERIAL_ECHOPGM("Opening dir: "); SERIAL_ECHOLN(segment); // Open the sub-item as the new dive parent MediaFile dir; diff --git a/buildroot/tests/mega2560 b/buildroot/tests/mega2560 index f323602954..f90e2074ab 100755 --- a/buildroot/tests/mega2560 +++ b/buildroot/tests/mega2560 @@ -56,12 +56,12 @@ opt_disable SEGMENT_LEVELED_MOVES exec_test $1 $2 "Azteeg X3 Pro | EXTRUDERS 5 | RRDFGSC | UBL | LIN_ADVANCE | Sled Probe | Skew | JP-Kana | Babystep offsets ..." "$3" # -# 5 runout sensors with distinct states +# 4 runout sensors with distinct states # restore_configs opt_set MOTHERBOARD BOARD_AZTEEG_X3_PRO NUM_SERVOS 1 \ EXTRUDERS 4 TEMP_SENSOR_1 1 TEMP_SENSOR_2 1 TEMP_SENSOR_3 1 TEMP_SENSOR_4 1 FAN_KICKSTART_TIME 500 \ - NUM_RUNOUT_SENSORS 4 FIL_RUNOUT2_PIN 44 FIL_RUNOUT3_PIN 45 FIL_RUNOUT4_PIN 46 FIL_RUNOUT5_PIN 47 \ + NUM_RUNOUT_SENSORS 4 FIL_RUNOUT2_PIN 44 FIL_RUNOUT3_PIN 45 FIL_RUNOUT4_PIN 46 \ FIL_RUNOUT3_STATE HIGH FILAMENT_RUNOUT_SCRIPT '"M600 T%c"' opt_enable VIKI2 BOOT_MARLIN_LOGO_ANIMATED SDSUPPORT AUTO_REPORT_SD_STATUS \ Z_PROBE_SERVO_NR Z_SERVO_ANGLES Z_SERVO_MEASURE_ANGLE DEACTIVATE_SERVOS_AFTER_MOVE Z_SERVO_DEACTIVATE_AFTER_STOW \ @@ -72,6 +72,12 @@ opt_enable VIKI2 BOOT_MARLIN_LOGO_ANIMATED SDSUPPORT AUTO_REPORT_SD_STATUS \ FILAMENT_RUNOUT_SENSOR NOZZLE_PARK_FEATURE ADVANCED_PAUSE_FEATURE Z_SAFE_HOMING FIL_RUNOUT3_PULLUP exec_test $1 $2 "Azteeg X3 Pro | EXTRUDERS 4 | VIKI2 | Servo Probe | Multiple runout sensors (x4)" "$3" +# +# Axel TPARA kinematics +# +use_example_configs TPARA/AXEL_TPARA +exec_test $1 $2 "MEGA2560 RAMPS | AXEL_TPARA" "$3" + # # Extruder Only. No XYZ axes at all. # @@ -265,7 +271,7 @@ exec_test $1 $2 "Azteeg X3 | Mixing Extruder (x5) | Gradient Mix | Input Shaping #exec_test $1 $2 "Stuff" "$3" # -# Makibox Config need to check board type for Teensy++ 2.0 +# Makibox Config - need to check board type for Teensy++ 2.0 # #use_example_configs makibox #exec_test $1 $2 "Stuff" "$3" From 0f044f76ec75b4002e1594ed0aeada03d9d9e9ce Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Fri, 14 Nov 2025 06:10:47 +0000 Subject: [PATCH 66/99] [cron] Bump distribution date (2025-11-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 96608675e4..3d5ffde906 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 "2025-11-13" +//#define STRING_DISTRIBUTION_DATE "2025-11-14" /** * The protocol for communication to the host. Protocol indicates communication diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index f4656ed16c..90d0ddd508 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 "2025-11-13" + #define STRING_DISTRIBUTION_DATE "2025-11-14" #endif /** From 1c6b723ee61785c505620b3a34a835b2c6f6bca2 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Thu, 13 Nov 2025 12:42:52 -0600 Subject: [PATCH 67/99] =?UTF-8?q?=F0=9F=A7=91=E2=80=8D=F0=9F=92=BB=20Timer?= =?UTF-8?q?=20general=20cleanup?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit erps --- Marlin/src/HAL/AVR/timers.h | 4 +- Marlin/src/HAL/DUE/timers.h | 2 +- Marlin/src/HAL/ESP32/timers.h | 4 +- Marlin/src/HAL/GD32_MFL/timers.h | 4 +- Marlin/src/HAL/HC32/timers.cpp | 16 +++--- Marlin/src/HAL/HC32/timers.h | 59 ++++++++++----------- Marlin/src/HAL/LINUX/timers.h | 4 +- Marlin/src/HAL/LPC1768/timers.h | 2 +- Marlin/src/HAL/NATIVE_SIM/timers.h | 4 +- Marlin/src/HAL/RP2040/timers.h | 34 ++++-------- Marlin/src/HAL/SAMD21/timers.h | 2 +- Marlin/src/HAL/SAMD51/timers.h | 2 +- Marlin/src/HAL/STM32/timers.h | 4 +- Marlin/src/HAL/STM32F1/timers.h | 2 +- Marlin/src/HAL/TEENSY31_32/timers.h | 6 +-- Marlin/src/HAL/TEENSY35_36/timers.h | 2 +- Marlin/src/HAL/TEENSY40_41/timers.cpp | 74 +++++++++++++++++++-------- Marlin/src/HAL/TEENSY40_41/timers.h | 5 +- Marlin/src/module/stepper.cpp | 6 +-- 19 files changed, 123 insertions(+), 113 deletions(-) diff --git a/Marlin/src/HAL/AVR/timers.h b/Marlin/src/HAL/AVR/timers.h index 0e1d7f2ba3..f316b7c551 100644 --- a/Marlin/src/HAL/AVR/timers.h +++ b/Marlin/src/HAL/AVR/timers.h @@ -111,8 +111,8 @@ FORCE_INLINE void HAL_timer_start(const uint8_t timer_num, const uint32_t) { * (otherwise, characters will be lost due to UART overflow). * Then: Stepper, Endstops, Temperature, and -finally- all others. */ -#define HAL_timer_isr_prologue(T) NOOP -#define HAL_timer_isr_epilogue(T) NOOP +inline void HAL_timer_isr_prologue(const uint8_t) {} +inline void HAL_timer_isr_epilogue(const uint8_t) {} #ifndef HAL_STEP_TIMER_ISR diff --git a/Marlin/src/HAL/DUE/timers.h b/Marlin/src/HAL/DUE/timers.h index 9316552ff5..8572958732 100644 --- a/Marlin/src/HAL/DUE/timers.h +++ b/Marlin/src/HAL/DUE/timers.h @@ -127,4 +127,4 @@ FORCE_INLINE static void HAL_timer_isr_prologue(const uint8_t timer_num) { pConfig->pTimerRegs->TC_CHANNEL[pConfig->channel].TC_SR; } -#define HAL_timer_isr_epilogue(T) NOOP +inline void HAL_timer_isr_epilogue(const uint8_t) {} diff --git a/Marlin/src/HAL/ESP32/timers.h b/Marlin/src/HAL/ESP32/timers.h index 03c343af98..868b5fa850 100644 --- a/Marlin/src/HAL/ESP32/timers.h +++ b/Marlin/src/HAL/ESP32/timers.h @@ -135,5 +135,5 @@ void HAL_timer_enable_interrupt(const uint8_t timer_num); void HAL_timer_disable_interrupt(const uint8_t timer_num); bool HAL_timer_interrupt_enabled(const uint8_t timer_num); -#define HAL_timer_isr_prologue(T) NOOP -#define HAL_timer_isr_epilogue(T) NOOP +inline void HAL_timer_isr_prologue(const uint8_t) {} +inline void HAL_timer_isr_epilogue(const uint8_t) {} diff --git a/Marlin/src/HAL/GD32_MFL/timers.h b/Marlin/src/HAL/GD32_MFL/timers.h index a5d36d9eca..9ecb1dcf79 100644 --- a/Marlin/src/HAL/GD32_MFL/timers.h +++ b/Marlin/src/HAL/GD32_MFL/timers.h @@ -141,5 +141,5 @@ FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_number, const } } -#define HAL_timer_isr_prologue(T) NOOP -#define HAL_timer_isr_epilogue(T) NOOP +inline void HAL_timer_isr_prologue(const uint8_t) {} +inline void HAL_timer_isr_epilogue(const uint8_t) {} diff --git a/Marlin/src/HAL/HC32/timers.cpp b/Marlin/src/HAL/HC32/timers.cpp index 5f7d499622..b8eab34cf7 100644 --- a/Marlin/src/HAL/HC32/timers.cpp +++ b/Marlin/src/HAL/HC32/timers.cpp @@ -35,19 +35,19 @@ Timer0 temp_timer(&TIMER02A_config, &Temp_Handler); */ 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) { +void HAL_timer_start(const timer_channel_t timer_ch, const uint32_t frequency) { + if (timer_ch == MF_TIMER_TEMP) { 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); + timer_ch->start(frequency, TEMP_TIMER_PRESCALE); + timer_ch->setCallbackPriority(TEMP_TIMER_PRIORITY); } - else if (timer_num == STEP_TIMER_NUM) { + else if (timer_ch == MF_TIMER_STEP) { 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); + timer_ch->start(frequency, STEPPER_TIMER_PRESCALE); + timer_ch->setCallbackPriority(STEP_TIMER_PRIORITY); } else { - CORE_ASSERT_FAIL("HAL_timer_start: invalid timer_num") + CORE_ASSERT_FAIL("HAL_timer_start: invalid timer_ch") } } diff --git a/Marlin/src/HAL/HC32/timers.h b/Marlin/src/HAL/HC32/timers.h index d03a5f9630..e5bb29e834 100644 --- a/Marlin/src/HAL/HC32/timers.h +++ b/Marlin/src/HAL/HC32/timers.h @@ -54,75 +54,68 @@ extern Timer0 step_timer; #define HAL_TIMER_RATE F_PCLK1 // Temperature timer -#define TEMP_TIMER_NUM (&temp_timer) +#define MF_TIMER_TEMP (&temp_timer) #define TEMP_TIMER_PRIORITY DDL_IRQ_PRIORITY_02 -#define TEMP_TIMER_PRESCALE 16UL // 12.5MHz +#define TEMP_TIMER_PRESCALE 16UL // 12.5MHz #define TEMP_TIMER_RATE 1000 // 1kHz #define TEMP_TIMER_FREQUENCY TEMP_TIMER_RATE // 1kHz also // Stepper timer -#define STEP_TIMER_NUM (&step_timer) +#define MF_TIMER_STEP (&step_timer) #define STEP_TIMER_PRIORITY DDL_IRQ_PRIORITY_00 // Top priority, nothing else uses it -#define STEPPER_TIMER_PRESCALE 16UL // 12.5MHz +#define STEPPER_TIMER_PRESCALE 16UL // 12.5MHz #define STEPPER_TIMER_RATE (HAL_TIMER_RATE / STEPPER_TIMER_PRESCALE) // 50MHz / 16 = 3.125MHz #define STEPPER_TIMER_TICKS_PER_US (STEPPER_TIMER_RATE / 1000000UL) // Integer 3 // Pulse timer (== stepper timer) -#define PULSE_TIMER_NUM STEP_TIMER_NUM +#define MF_TIMER_PULSE MF_TIMER_STEP #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); +void HAL_timer_start(const timer_channel_t timer_ch, 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_enable_interrupt(const timer_channel_t timer_ch) { + timer_ch->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 void HAL_timer_disable_interrupt(const timer_channel_t timer_ch) { + timer_ch->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 bool HAL_timer_interrupt_enabled(const timer_channel_t timer_ch) { + return timer_ch->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 void HAL_timer_set_compare(const timer_channel_t timer_ch, const hal_timer_t compare) { + timer_ch->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 hal_timer_t HAL_timer_get_count(const timer_channel_t timer_ch) { + return timer_ch->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_prologue(const timer_channel_t timer_ch) { + timer_ch->clearInterruptFlag(); } -MARLIN_HAL_TIMER_INLINE_ATTR void HAL_timer_isr_epilogue(const timer_channel_t timer_num) {} +inline void HAL_timer_isr_epilogue(const timer_channel_t) {} // // 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_STEPPER_DRIVER_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_STEP) +#define DISABLE_STEPPER_DRIVER_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_STEP) +#define STEPPER_ISR_ENABLED() HAL_timer_interrupt_enabled(MF_TIMER_STEP) -#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(TEMP_TIMER_NUM) -#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(TEMP_TIMER_NUM); +#define ENABLE_TEMPERATURE_INTERRUPT() HAL_timer_enable_interrupt(MF_TIMER_TEMP) +#define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_TEMP); // // HAL ISR callbacks @@ -131,8 +124,8 @@ void Step_Handler(); void Temp_Handler(); #ifndef HAL_STEP_TIMER_ISR -#define HAL_STEP_TIMER_ISR() void Step_Handler() + #define HAL_STEP_TIMER_ISR() void Step_Handler() #endif #ifndef HAL_TEMP_TIMER_ISR -#define HAL_TEMP_TIMER_ISR() void Temp_Handler() + #define HAL_TEMP_TIMER_ISR() void Temp_Handler() #endif diff --git a/Marlin/src/HAL/LINUX/timers.h b/Marlin/src/HAL/LINUX/timers.h index d75519ed3e..b09fc6156a 100644 --- a/Marlin/src/HAL/LINUX/timers.h +++ b/Marlin/src/HAL/LINUX/timers.h @@ -93,5 +93,5 @@ void HAL_timer_enable_interrupt(const uint8_t timer_num); void HAL_timer_disable_interrupt(const uint8_t timer_num); bool HAL_timer_interrupt_enabled(const uint8_t timer_num); -#define HAL_timer_isr_prologue(T) NOOP -#define HAL_timer_isr_epilogue(T) NOOP +inline void HAL_timer_isr_prologue(const uint8_t) {} +inline void HAL_timer_isr_epilogue(const uint8_t) {} diff --git a/Marlin/src/HAL/LPC1768/timers.h b/Marlin/src/HAL/LPC1768/timers.h index 8c0a39158e..b34f5e7907 100644 --- a/Marlin/src/HAL/LPC1768/timers.h +++ b/Marlin/src/HAL/LPC1768/timers.h @@ -171,4 +171,4 @@ FORCE_INLINE static void HAL_timer_isr_prologue(const uint8_t timer_num) { } } -#define HAL_timer_isr_epilogue(T) NOOP +inline void HAL_timer_isr_epilogue(const uint8_t) {} diff --git a/Marlin/src/HAL/NATIVE_SIM/timers.h b/Marlin/src/HAL/NATIVE_SIM/timers.h index 43aecf427b..3868f8f1e3 100644 --- a/Marlin/src/HAL/NATIVE_SIM/timers.h +++ b/Marlin/src/HAL/NATIVE_SIM/timers.h @@ -88,5 +88,5 @@ void HAL_timer_enable_interrupt(const uint8_t timer_num); void HAL_timer_disable_interrupt(const uint8_t timer_num); bool HAL_timer_interrupt_enabled(const uint8_t timer_num); -#define HAL_timer_isr_prologue(T) NOOP -#define HAL_timer_isr_epilogue(T) NOOP +inline void HAL_timer_isr_prologue(const uint8_t) {} +inline void HAL_timer_isr_epilogue(const uint8_t) {} diff --git a/Marlin/src/HAL/RP2040/timers.h b/Marlin/src/HAL/RP2040/timers.h index 4d11804361..5e0234c10c 100644 --- a/Marlin/src/HAL/RP2040/timers.h +++ b/Marlin/src/HAL/RP2040/timers.h @@ -86,10 +86,10 @@ typedef uint64_t hal_timer_t; //#define STEP_TIMER_PTR _HAL_TIMER(MF_TIMER_STEP) //#define TEMP_TIMER_PTR _HAL_TIMER(MF_TIMER_TEMP) -extern alarm_pool_t* HAL_timer_pool_0; -extern alarm_pool_t* HAL_timer_pool_1; -extern alarm_pool_t* HAL_timer_pool_2; -extern alarm_pool_t* HAL_timer_pool_3; +extern alarm_pool_t *HAL_timer_pool_0; +extern alarm_pool_t *HAL_timer_pool_1; +extern alarm_pool_t *HAL_timer_pool_2; +extern alarm_pool_t *HAL_timer_pool_3; extern struct repeating_timer HAL_timer_0; @@ -120,28 +120,23 @@ void HAL_timer_stop(const uint8_t timer_num); FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_num, hal_timer_t compare) { - if (timer_num == MF_TIMER_STEP){ - if (compare == HAL_TIMER_TYPE_MAX){ - HAL_timer_stop(timer_num); - return; - } + if (timer_num == MF_TIMER_STEP && compare == HAL_TIMER_TYPE_MAX) { + HAL_timer_stop(timer_num); + return; } - compare = compare *10; //Dirty fix, figure out a proper way + compare *= 10; // Dirty fix, figure out a proper way switch (timer_num) { case 0: alarm_pool_add_alarm_in_us(HAL_timer_pool_0, compare, HAL_timer_alarm_pool_0_callback, 0, false); break; - case 1: alarm_pool_add_alarm_in_us(HAL_timer_pool_1, compare, HAL_timer_alarm_pool_1_callback, 0, false); break; - case 2: alarm_pool_add_alarm_in_us(HAL_timer_pool_2, compare, HAL_timer_alarm_pool_2_callback, 0, false); break; - case 3: alarm_pool_add_alarm_in_us(HAL_timer_pool_3, compare, HAL_timer_alarm_pool_3_callback, 0, false); break; @@ -151,27 +146,20 @@ FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_num, hal_time FORCE_INLINE static hal_timer_t HAL_timer_get_compare(const uint8_t timer_num) { return 0; } - FORCE_INLINE static hal_timer_t HAL_timer_get_count(const uint8_t timer_num) { if (timer_num == MF_TIMER_STEP) return 0ull; return time_us_64(); } - FORCE_INLINE static void HAL_timer_enable_interrupt(const uint8_t timer_num) { HAL_timer_irq_en[timer_num] = 1; } - FORCE_INLINE static void HAL_timer_disable_interrupt(const uint8_t timer_num) { HAL_timer_irq_en[timer_num] = 0; } - FORCE_INLINE static bool HAL_timer_interrupt_enabled(const uint8_t timer_num) { - return HAL_timer_irq_en[timer_num]; //lucky coincidence that timer_num and rp2040 irq num matches + return HAL_timer_irq_en[timer_num]; // Lucky coincidence that timer_num and rp2040 IRQ num matches } -FORCE_INLINE static void HAL_timer_isr_prologue(const uint8_t timer_num) { - return; -} - -#define HAL_timer_isr_epilogue(T) NOOP +inline void HAL_timer_isr_prologue(const uint8_t) {} +inline void HAL_timer_isr_epilogue(const uint8_t) {} diff --git a/Marlin/src/HAL/SAMD21/timers.h b/Marlin/src/HAL/SAMD21/timers.h index a4faabb8e8..ee193e8137 100644 --- a/Marlin/src/HAL/SAMD21/timers.h +++ b/Marlin/src/HAL/SAMD21/timers.h @@ -157,4 +157,4 @@ FORCE_INLINE static void HAL_timer_isr_prologue(const uint8_t timer_num) { } } -#define HAL_timer_isr_epilogue(timer_num) +inline void HAL_timer_isr_epilogue(const uint8_t) {} diff --git a/Marlin/src/HAL/SAMD51/timers.h b/Marlin/src/HAL/SAMD51/timers.h index 59817453aa..2b02ad8775 100644 --- a/Marlin/src/HAL/SAMD51/timers.h +++ b/Marlin/src/HAL/SAMD51/timers.h @@ -145,4 +145,4 @@ FORCE_INLINE static void HAL_timer_isr_prologue(const uint8_t timer_num) { } } -#define HAL_timer_isr_epilogue(timer_num) +inline void HAL_timer_isr_epilogue(const uint8_t) {} diff --git a/Marlin/src/HAL/STM32/timers.h b/Marlin/src/HAL/STM32/timers.h index 180e240314..9861c45200 100644 --- a/Marlin/src/HAL/STM32/timers.h +++ b/Marlin/src/HAL/STM32/timers.h @@ -116,5 +116,5 @@ FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_num, const ha } } -#define HAL_timer_isr_prologue(T) NOOP -#define HAL_timer_isr_epilogue(T) NOOP +inline void HAL_timer_isr_prologue(const uint8_t) {} +inline void HAL_timer_isr_epilogue(const uint8_t) {} diff --git a/Marlin/src/HAL/STM32F1/timers.h b/Marlin/src/HAL/STM32F1/timers.h index 456278db2f..b87d355922 100644 --- a/Marlin/src/HAL/STM32F1/timers.h +++ b/Marlin/src/HAL/STM32F1/timers.h @@ -188,7 +188,7 @@ FORCE_INLINE static void HAL_timer_isr_prologue(const uint8_t timer_num) { } } -#define HAL_timer_isr_epilogue(T) NOOP +inline void HAL_timer_isr_epilogue(const uint8_t) {} // No command is available in framework to turn off ARPE bit, which is turned on by default in libmaple. // Needed here to reset ARPE=0 for stepper timer diff --git a/Marlin/src/HAL/TEENSY31_32/timers.h b/Marlin/src/HAL/TEENSY31_32/timers.h index aeb8f2388a..84281a228f 100644 --- a/Marlin/src/HAL/TEENSY31_32/timers.h +++ b/Marlin/src/HAL/TEENSY31_32/timers.h @@ -74,10 +74,10 @@ typedef uint32_t hal_timer_t; #define DISABLE_TEMPERATURE_INTERRUPT() HAL_timer_disable_interrupt(MF_TIMER_TEMP) #ifndef HAL_STEP_TIMER_ISR - #define HAL_STEP_TIMER_ISR() extern "C" void ftm0_isr() //void TC3_Handler() + #define HAL_STEP_TIMER_ISR() extern "C" void ftm0_isr() #endif #ifndef HAL_TEMP_TIMER_ISR - #define HAL_TEMP_TIMER_ISR() extern "C" void ftm1_isr() //void TC4_Handler() + #define HAL_TEMP_TIMER_ISR() extern "C" void ftm1_isr() #endif void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency); @@ -110,4 +110,4 @@ void HAL_timer_disable_interrupt(const uint8_t timer_num); bool HAL_timer_interrupt_enabled(const uint8_t timer_num); void HAL_timer_isr_prologue(const uint8_t timer_num); -#define HAL_timer_isr_epilogue(T) NOOP +inline void HAL_timer_isr_epilogue(const uint8_t) {} diff --git a/Marlin/src/HAL/TEENSY35_36/timers.h b/Marlin/src/HAL/TEENSY35_36/timers.h index 3a836ba44e..c7292f3619 100644 --- a/Marlin/src/HAL/TEENSY35_36/timers.h +++ b/Marlin/src/HAL/TEENSY35_36/timers.h @@ -110,4 +110,4 @@ void HAL_timer_disable_interrupt(const uint8_t timer_num); bool HAL_timer_interrupt_enabled(const uint8_t timer_num); void HAL_timer_isr_prologue(const uint8_t timer_num); -#define HAL_timer_isr_epilogue(T) NOOP +inline void HAL_timer_isr_epilogue(const uint8_t) {} diff --git a/Marlin/src/HAL/TEENSY40_41/timers.cpp b/Marlin/src/HAL/TEENSY40_41/timers.cpp index ed99f65d6e..362bd4e06d 100644 --- a/Marlin/src/HAL/TEENSY40_41/timers.cpp +++ b/Marlin/src/HAL/TEENSY40_41/timers.cpp @@ -30,41 +30,74 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) { switch (timer_num) { + + // + // Step Timer – GPT1 - Compare Interrupt OCR1 - Reset Mode + // case MF_TIMER_STEP: - CCM_CSCMR1 &= ~CCM_CSCMR1_PERCLK_CLK_SEL; // turn off 24mhz mode + // 24MHz mode off – Use peripheral clock (150MHz) + CCM_CSCMR1 &= ~CCM_CSCMR1_PERCLK_CLK_SEL; + // Enable GPT1 clock gating CCM_CCGR1 |= CCM_CCGR1_GPT1_BUS(CCM_CCGR_ON); - GPT1_CR = 0; // disable timer - GPT1_SR = 0x3F; // clear all prior status + // Disable timer, clear all status bits + GPT1_CR = 0; // Disable timer + GPT1_SR = 0x3F; // Clear all prior status + + // Prescaler = 2 => 75MHz counting clock GPT1_PR = GPT1_TIMER_PRESCALE - 1; - GPT1_CR |= GPT_CR_CLKSRC(1); //clock selection #1 (peripheral clock = 150 MHz) - GPT1_CR |= GPT_CR_ENMOD; //reset count to zero before enabling - GPT1_CR |= GPT_CR_OM1(1); // toggle mode - GPT1_OCR1 = (GPT1_TIMER_RATE / frequency) -1; // Initial compare value - GPT1_IR = GPT_IR_OF1IE; // Compare3 value + + GPT1_CR = GPT_CR_CLKSRC(1) // Clock selection #1 (peripheral clock = 150 MHz) + | GPT_CR_ENMOD // Reset count to zero before enabling + | GPT_CR_OM2(TERN(MARLIN_DEV_MODE, 1, 0)); // 0 = edge compare, 1 = toggle + + // Compare value – the number of clocks between edges + GPT1_OCR1 = (GPT1_TIMER_RATE / frequency) - 1; + + // Enable compare‑event interrupt + GPT1_IR = GPT_IR_OF1IE; // OF2 interrupt enabled GPT1_CR |= GPT_CR_EN; //enable GPT2 counting at 150 MHz OUT_WRITE(15, HIGH); + + // Attach and enable Stepper IRQ + // Note: UART priority is 16 attachInterruptVector(IRQ_GPT1, &stepTC_Handler); - NVIC_SET_PRIORITY(IRQ_GPT1, 16); + NVIC_SET_PRIORITY(IRQ_GPT1, 16); // Priority 16 (higher than Temp Timer) break; + + // + // Temperature Timer – GPT2 - Compare Interrupt OCR1 - Reset Mode + // case MF_TIMER_TEMP: - CCM_CSCMR1 &= ~CCM_CSCMR1_PERCLK_CLK_SEL; // turn off 24mhz mode + // 24MHz mode off – Use peripheral clock (150MHz) + CCM_CSCMR1 &= ~CCM_CSCMR1_PERCLK_CLK_SEL; + // Enable GPT2 clock gating CCM_CCGR0 |= CCM_CCGR0_GPT2_BUS(CCM_CCGR_ON); - GPT2_CR = 0; // disable timer - GPT2_SR = 0x3F; // clear all prior status + // Disable timer, clear all status bits + GPT2_CR = 0; // Disable timer + GPT2_SR = 0x3F; // Clear all prior status + + // Prescaler = 10 => 15MHz counting clock GPT2_PR = GPT2_TIMER_PRESCALE - 1; - GPT2_CR |= GPT_CR_CLKSRC(1); //clock selection #1 (peripheral clock = 150 MHz) - GPT2_CR |= GPT_CR_ENMOD; //reset count to zero before enabling - GPT2_CR |= GPT_CR_OM1(1); // toggle mode - GPT2_OCR1 = (GPT2_TIMER_RATE / frequency) -1; // Initial compare value - GPT2_IR = GPT_IR_OF1IE; // Compare3 value + + GPT2_CR = GPT_CR_CLKSRC(1) // Clock selection #1 (peripheral clock = 150 MHz) + | GPT_CR_ENMOD // and reset count to zero before enabling + | GPT_CR_OM2(TERN(MARLIN_DEV_MODE, 1, 0)); // 0 = edge compare, 1 = toggle + + // Compare value – the number of clocks between edges + GPT2_OCR1 = (GPT2_TIMER_RATE / frequency) - 1; + + // Enable compare‑event interrupt + GPT2_IR = GPT_IR_OF1IE; GPT2_CR |= GPT_CR_EN; //enable GPT2 counting at 150 MHz OUT_WRITE(14, HIGH); + + // Attach Temperature ISR attachInterruptVector(IRQ_GPT2, &tempTC_Handler); - NVIC_SET_PRIORITY(IRQ_GPT2, 32); + NVIC_SET_PRIORITY(IRQ_GPT2, 32); // Priority 32 (lower than Step Timer) break; } } @@ -82,6 +115,7 @@ void HAL_timer_disable_interrupt(const uint8_t timer_num) { case MF_TIMER_TEMP: NVIC_DISABLE_IRQ(IRQ_GPT2); break; } + // Ensure the CPU actually stops servicing the IRQ // We NEED memory barriers to ensure Interrupts are actually disabled! // ( https://dzone.com/articles/nvic-disabling-interrupts-on-arm-cortex-m-and-the ) asm volatile("dsb"); @@ -97,8 +131,8 @@ bool HAL_timer_interrupt_enabled(const uint8_t timer_num) { void HAL_timer_isr_prologue(const uint8_t timer_num) { switch (timer_num) { - case MF_TIMER_STEP: GPT1_SR = GPT_IR_OF1IE; break; // clear OF3 bit - case MF_TIMER_TEMP: GPT2_SR = GPT_IR_OF1IE; break; // clear OF3 bit + case MF_TIMER_STEP: GPT1_SR = GPT_IR_OF1IE; break; // clear OF1 + case MF_TIMER_TEMP: GPT2_SR = GPT_IR_OF1IE; break; } asm volatile("dsb"); } diff --git a/Marlin/src/HAL/TEENSY40_41/timers.h b/Marlin/src/HAL/TEENSY40_41/timers.h index 277a7f318d..64f9112a57 100644 --- a/Marlin/src/HAL/TEENSY40_41/timers.h +++ b/Marlin/src/HAL/TEENSY40_41/timers.h @@ -60,7 +60,7 @@ typedef uint32_t hal_timer_t; #define HAL_TIMER_RATE GPT1_TIMER_RATE #define STEPPER_TIMER_RATE HAL_TIMER_RATE #define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000) -#define STEPPER_TIMER_PRESCALE ((GPT_TIMER_RATE / 1000000) / STEPPER_TIMER_TICKS_PER_US) +#define STEPPER_TIMER_PRESCALE (GPT_TIMER_RATE / STEPPER_TIMER_RATE) #define PULSE_TIMER_RATE STEPPER_TIMER_RATE // frequency of pulse timer #define PULSE_TIMER_PRESCALE STEPPER_TIMER_PRESCALE @@ -115,5 +115,4 @@ void HAL_timer_disable_interrupt(const uint8_t timer_num); bool HAL_timer_interrupt_enabled(const uint8_t timer_num); void HAL_timer_isr_prologue(const uint8_t timer_num); -//void HAL_timer_isr_epilogue(const uint8_t timer_num) {} -#define HAL_timer_isr_epilogue(T) NOOP +inline void HAL_timer_isr_epilogue(const uint8_t) {} diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index 18d6ae8906..d45ef3dc9a 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -1513,11 +1513,7 @@ HAL_STEP_TIMER_ISR() { HAL_timer_isr_epilogue(MF_TIMER_STEP); } -#ifdef CPU_32_BIT - #define STEP_MULTIPLY(A,B) MultiU32X24toH32(A, B) -#else - #define STEP_MULTIPLY(A,B) MultiU24X32toH16(A, B) -#endif +#define STEP_MULTIPLY(A,B) TERN(CPU_32_BIT, MultiU32X24toH32, MultiU24X32toH16)(A, B) #if ENABLED(SMOOTH_LIN_ADVANCE) FORCE_INLINE static constexpr int32_t MULT_Q(uint8_t q, int32_t x, int32_t y) { return (int64_t(x) * y) >> q; } From 8cd9c0608417849149d8de6052961eeb5fbf0236 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 14 Nov 2025 13:09:40 -0600 Subject: [PATCH 68/99] =?UTF-8?q?=F0=9F=A9=B9=20Teensy=204.x=20timer=20mod?= =?UTF-8?q?s?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/TEENSY40_41/timers.cpp | 20 ++++++++++++++------ 1 file changed, 14 insertions(+), 6 deletions(-) diff --git a/Marlin/src/HAL/TEENSY40_41/timers.cpp b/Marlin/src/HAL/TEENSY40_41/timers.cpp index 362bd4e06d..011f9fe31c 100644 --- a/Marlin/src/HAL/TEENSY40_41/timers.cpp +++ b/Marlin/src/HAL/TEENSY40_41/timers.cpp @@ -55,15 +55,19 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) { GPT1_OCR1 = (GPT1_TIMER_RATE / frequency) - 1; // Enable compare‑event interrupt - GPT1_IR = GPT_IR_OF1IE; // OF2 interrupt enabled - GPT1_CR |= GPT_CR_EN; //enable GPT2 counting at 150 MHz + GPT1_IR = GPT_IR_OF1IE; // OF1 interrupt enabled - OUT_WRITE(15, HIGH); + // Pull Pin 15 HIGH (logic‑high is the “idle” state) + TERN_(MARLIN_DEV_MODE, OUT_WRITE(15, HIGH)); // Attach and enable Stepper IRQ // Note: UART priority is 16 attachInterruptVector(IRQ_GPT1, &stepTC_Handler); NVIC_SET_PRIORITY(IRQ_GPT1, 16); // Priority 16 (higher than Temp Timer) + + // Start GPT1 counting at 150 MHz + GPT1_CR |= GPT_CR_EN; + break; // @@ -90,14 +94,18 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) { GPT2_OCR1 = (GPT2_TIMER_RATE / frequency) - 1; // Enable compare‑event interrupt - GPT2_IR = GPT_IR_OF1IE; - GPT2_CR |= GPT_CR_EN; //enable GPT2 counting at 150 MHz + GPT2_IR = GPT_IR_OF1IE; // OF1 interrupt enabled - OUT_WRITE(14, HIGH); + // Pull Pin 14 HIGH (logic‑high is the “idle” state) + TERN_(MARLIN_DEV_MODE, OUT_WRITE(14, HIGH)); // Attach Temperature ISR attachInterruptVector(IRQ_GPT2, &tempTC_Handler); NVIC_SET_PRIORITY(IRQ_GPT2, 32); // Priority 32 (lower than Step Timer) + + // Start GPT2 counting at 150 MHz + GPT2_CR |= GPT_CR_EN; + break; } } From c9488b4f6382f4481f9847da7aed20cd75621c03 Mon Sep 17 00:00:00 2001 From: nanctil <38119664+nanctil@users.noreply.github.com> Date: Fri, 14 Nov 2025 11:52:34 -0800 Subject: [PATCH 69/99] =?UTF-8?q?=F0=9F=90=9B=20Fix=20Teensy=204.x=20stepp?= =?UTF-8?q?er=20timing=20via=20HAL=5Ftimer=5Fset=5Fcompare=20(#28169)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/TEENSY40_41/timers.h | 12 ++++++++++-- 1 file changed, 10 insertions(+), 2 deletions(-) diff --git a/Marlin/src/HAL/TEENSY40_41/timers.h b/Marlin/src/HAL/TEENSY40_41/timers.h index 64f9112a57..98a852ee57 100644 --- a/Marlin/src/HAL/TEENSY40_41/timers.h +++ b/Marlin/src/HAL/TEENSY40_41/timers.h @@ -89,8 +89,16 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency); FORCE_INLINE static void HAL_timer_set_compare(const uint8_t timer_num, const hal_timer_t compare) { switch (timer_num) { - case MF_TIMER_STEP: GPT1_OCR1 = compare - 1; break; - case MF_TIMER_TEMP: GPT2_OCR1 = compare - 1; break; + case MF_TIMER_STEP: + GPT1_CR |= GPT_CR_FRR; // Free Run Mode (setting OCRx preserves CNT) + GPT1_OCR1 = compare - 1; + GPT1_CR &= ~GPT_CR_FRR; // Reset Mode (CNT resets on trigger) + break; + case MF_TIMER_TEMP: + GPT2_CR |= GPT_CR_FRR; // Free Run Mode (setting OCRx preserves CNT) + GPT2_OCR1 = compare - 1; + GPT2_CR &= ~GPT_CR_FRR; // Reset Mode (CNT resets on trigger) + break; } } From f872750b7022ca7c8ae6e7f08e29b4f16d1bef82 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sat, 15 Nov 2025 00:31:14 +0000 Subject: [PATCH 70/99] [cron] Bump distribution date (2025-11-15) --- 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 3d5ffde906..0ffebcd002 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 "2025-11-14" +//#define STRING_DISTRIBUTION_DATE "2025-11-15" /** * The protocol for communication to the host. Protocol indicates communication diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 90d0ddd508..0fd96f427f 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 "2025-11-14" + #define STRING_DISTRIBUTION_DATE "2025-11-15" #endif /** From e2250ce03726190a82b28598a2a00a91cc7f8c50 Mon Sep 17 00:00:00 2001 From: Skruppy Date: Sat, 15 Nov 2025 02:06:22 +0100 Subject: [PATCH 71/99] =?UTF-8?q?=F0=9F=A9=B9=20Fix=20case=20light=20menu?= =?UTF-8?q?=20build=20(#28143)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/menu/menu_led.cpp | 247 ++++++++++++++++--------------- 1 file changed, 126 insertions(+), 121 deletions(-) diff --git a/Marlin/src/lcd/menu/menu_led.cpp b/Marlin/src/lcd/menu/menu_led.cpp index f996395b89..d4807439df 100644 --- a/Marlin/src/lcd/menu/menu_led.cpp +++ b/Marlin/src/lcd/menu/menu_led.cpp @@ -30,108 +30,114 @@ #include "menu_item.h" +#if ENABLED(LED_CONTROL_MENU) + #include "../../feature/leds/leds.h" +#endif + #if ENABLED(PSU_CONTROL) #include "../../feature/power.h" #endif -#if ALL(CASE_LIGHT_MENU, CASELIGHT_USES_BRIGHTNESS) +#if ENABLED(CASE_LIGHT_MENU) #include "../../feature/caselight.h" - void menu_case_light() { - START_MENU(); - BACK_ITEM(MSG_CONFIGURATION); - EDIT_ITEM(percent, MSG_CASE_LIGHT_BRIGHTNESS, &caselight.brightness, 0, 255, caselight.update_brightness, true); - EDIT_ITEM(bool, MSG_CASE_LIGHT, &caselight.on, caselight.update_enabled); - END_MENU(); - } + + #if CASELIGHT_USES_BRIGHTNESS + void menu_case_light() { + START_MENU(); + BACK_ITEM(MSG_CONFIGURATION); + EDIT_ITEM(percent, MSG_CASE_LIGHT_BRIGHTNESS, &caselight.brightness, 0, 255, caselight.update_brightness, true); + EDIT_ITEM(bool, MSG_CASE_LIGHT, &caselight.on, caselight.update_enabled); + END_MENU(); + } + #endif #endif -#if ENABLED(LED_CONTROL_MENU) - - #include "../../feature/leds/leds.h" - +#if ENABLED(NEO2_COLOR_PRESETS) #define MSG_LIGHT2_PRESETS TERN(BIQU_BX_TFT70, MSG_LIGHT_ENCODER_PRESETS, MSG_NEO2_PRESETS) +#endif - #if ENABLED(LED_COLOR_PRESETS) +#if ENABLED(LED_COLOR_PRESETS) - void menu_led_presets() { - START_MENU(); - #if LCD_HEIGHT > 2 - STATIC_ITEM(MSG_LED_PRESETS, SS_DEFAULT|SS_INVERT); - #endif - BACK_ITEM(MSG_LED_CONTROL); - ACTION_ITEM(MSG_SET_LEDS_WHITE, leds.set_white); - ACTION_ITEM(MSG_SET_LEDS_RED, leds.set_red); - ACTION_ITEM(MSG_SET_LEDS_ORANGE, leds.set_orange); - ACTION_ITEM(MSG_SET_LEDS_YELLOW, leds.set_yellow); - ACTION_ITEM(MSG_SET_LEDS_GREEN, leds.set_green); - ACTION_ITEM(MSG_SET_LEDS_BLUE, leds.set_blue); - ACTION_ITEM(MSG_SET_LEDS_INDIGO, leds.set_indigo); - ACTION_ITEM(MSG_SET_LEDS_VIOLET, leds.set_violet); - END_MENU(); - } - - #endif // LED_COLOR_PRESETS - - #if ENABLED(NEO2_COLOR_PRESETS) - - void menu_leds2_presets() { - START_MENU(); - #if LCD_HEIGHT > 2 - STATIC_ITEM(MSG_LIGHT2_PRESETS, SS_DEFAULT|SS_INVERT); - #endif - BACK_ITEM(MSG_LED_CONTROL); - ACTION_ITEM(MSG_SET_LEDS_WHITE, leds2.set_white); - ACTION_ITEM(MSG_SET_LEDS_RED, leds2.set_red); - ACTION_ITEM(MSG_SET_LEDS_ORANGE, leds2.set_orange); - ACTION_ITEM(MSG_SET_LEDS_YELLOW, leds2.set_yellow); - ACTION_ITEM(MSG_SET_LEDS_GREEN, leds2.set_green); - ACTION_ITEM(MSG_SET_LEDS_BLUE, leds2.set_blue); - ACTION_ITEM(MSG_SET_LEDS_INDIGO, leds2.set_indigo); - ACTION_ITEM(MSG_SET_LEDS_VIOLET, leds2.set_violet); - END_MENU(); - } - - #endif // NEO2_COLOR_PRESETS - - void menu_led_custom() { + void menu_led_presets() { START_MENU(); + #if LCD_HEIGHT > 2 + STATIC_ITEM(MSG_LED_PRESETS, SS_DEFAULT|SS_INVERT); + #endif BACK_ITEM(MSG_LED_CONTROL); - - #if ENABLED(NEOPIXEL2_SEPARATE) - STATIC_ITEM_N(1, MSG_LED_CHANNEL_N, SS_DEFAULT|SS_INVERT); - #endif - EDIT_ITEM(uint8, MSG_INTENSITY_R, &leds.color.r, 0, 255, leds.update, true); - EDIT_ITEM(uint8, MSG_INTENSITY_G, &leds.color.g, 0, 255, leds.update, true); - EDIT_ITEM(uint8, MSG_INTENSITY_B, &leds.color.b, 0, 255, leds.update, true); - #if HAS_WHITE_LED - EDIT_ITEM(uint8, MSG_INTENSITY_W, &leds.color.w, 0, 255, leds.update, true); - #endif - #if ENABLED(NEOPIXEL_LED) - EDIT_ITEM(uint8, MSG_LED_BRIGHTNESS, &leds.color.i, 0, 255, leds.update, true); - #endif - - #if ENABLED(NEOPIXEL2_SEPARATE) - STATIC_ITEM_N(2, MSG_LED_CHANNEL_N, SS_DEFAULT|SS_INVERT); - EDIT_ITEM(uint8, MSG_INTENSITY_R, &leds2.color.r, 0, 255, leds2.update, true); - EDIT_ITEM(uint8, MSG_INTENSITY_G, &leds2.color.g, 0, 255, leds2.update, true); - EDIT_ITEM(uint8, MSG_INTENSITY_B, &leds2.color.b, 0, 255, leds2.update, true); - #if HAS_WHITE_LED2 - EDIT_ITEM(uint8, MSG_INTENSITY_W, &leds2.color.w, 0, 255, leds2.update, true); - #endif - EDIT_ITEM(uint8, MSG_NEO2_BRIGHTNESS, &leds2.color.i, 0, 255, leds2.update, true); - #endif - + ACTION_ITEM(MSG_SET_LEDS_WHITE, leds.set_white); + ACTION_ITEM(MSG_SET_LEDS_RED, leds.set_red); + ACTION_ITEM(MSG_SET_LEDS_ORANGE, leds.set_orange); + ACTION_ITEM(MSG_SET_LEDS_YELLOW, leds.set_yellow); + ACTION_ITEM(MSG_SET_LEDS_GREEN, leds.set_green); + ACTION_ITEM(MSG_SET_LEDS_BLUE, leds.set_blue); + ACTION_ITEM(MSG_SET_LEDS_INDIGO, leds.set_indigo); + ACTION_ITEM(MSG_SET_LEDS_VIOLET, leds.set_violet); END_MENU(); } - void menu_led() { - #if ENABLED(CASE_LIGHT_MENU) - const bool has_bright = TERN0(CASELIGHT_USES_BRIGHTNESS, caselight.has_brightness()); - #endif +#endif // LED_COLOR_PRESETS +#if ENABLED(NEO2_COLOR_PRESETS) + + void menu_leds2_presets() { START_MENU(); - BACK_ITEM(MSG_MAIN_MENU); + #if LCD_HEIGHT > 2 + STATIC_ITEM(MSG_LIGHT2_PRESETS, SS_DEFAULT|SS_INVERT); + #endif + BACK_ITEM(MSG_LED_CONTROL); + ACTION_ITEM(MSG_SET_LEDS_WHITE, leds2.set_white); + ACTION_ITEM(MSG_SET_LEDS_RED, leds2.set_red); + ACTION_ITEM(MSG_SET_LEDS_ORANGE, leds2.set_orange); + ACTION_ITEM(MSG_SET_LEDS_YELLOW, leds2.set_yellow); + ACTION_ITEM(MSG_SET_LEDS_GREEN, leds2.set_green); + ACTION_ITEM(MSG_SET_LEDS_BLUE, leds2.set_blue); + ACTION_ITEM(MSG_SET_LEDS_INDIGO, leds2.set_indigo); + ACTION_ITEM(MSG_SET_LEDS_VIOLET, leds2.set_violet); + END_MENU(); + } +#endif // NEO2_COLOR_PRESETS + +void menu_led_custom() { + START_MENU(); + BACK_ITEM(MSG_LED_CONTROL); + + #if ENABLED(NEOPIXEL2_SEPARATE) + STATIC_ITEM_N(1, MSG_LED_CHANNEL_N, SS_DEFAULT|SS_INVERT); + #endif + EDIT_ITEM(uint8, MSG_INTENSITY_R, &leds.color.r, 0, 255, leds.update, true); + EDIT_ITEM(uint8, MSG_INTENSITY_G, &leds.color.g, 0, 255, leds.update, true); + EDIT_ITEM(uint8, MSG_INTENSITY_B, &leds.color.b, 0, 255, leds.update, true); + #if HAS_WHITE_LED + EDIT_ITEM(uint8, MSG_INTENSITY_W, &leds.color.w, 0, 255, leds.update, true); + #endif + #if ENABLED(NEOPIXEL_LED) + EDIT_ITEM(uint8, MSG_LED_BRIGHTNESS, &leds.color.i, 0, 255, leds.update, true); + #endif + + #if ENABLED(NEOPIXEL2_SEPARATE) + STATIC_ITEM_N(2, MSG_LED_CHANNEL_N, SS_DEFAULT|SS_INVERT); + EDIT_ITEM(uint8, MSG_INTENSITY_R, &leds2.color.r, 0, 255, leds2.update, true); + EDIT_ITEM(uint8, MSG_INTENSITY_G, &leds2.color.g, 0, 255, leds2.update, true); + EDIT_ITEM(uint8, MSG_INTENSITY_B, &leds2.color.b, 0, 255, leds2.update, true); + #if HAS_WHITE_LED2 + EDIT_ITEM(uint8, MSG_INTENSITY_W, &leds2.color.w, 0, 255, leds2.update, true); + #endif + EDIT_ITEM(uint8, MSG_NEO2_BRIGHTNESS, &leds2.color.i, 0, 255, leds2.update, true); + #endif + + END_MENU(); +} + +void menu_led() { + #if ENABLED(CASE_LIGHT_MENU) + const bool has_bright = TERN0(CASELIGHT_USES_BRIGHTNESS, caselight.has_brightness()); + #endif + + START_MENU(); + BACK_ITEM(MSG_MAIN_MENU); + + #if ENABLED(LED_CONTROL_MENU) if (TERN1(PSU_CONTROL, powerManager.psu_on)) { editable.state = leds.lights_on; #if ENABLED(NEOPIXEL2_SEPARATE) && DISABLED(BIQU_BX_TFT70) @@ -140,46 +146,45 @@ EDIT_ITEM(bool, MSG_LIGHTS, &editable.state, leds.toggle); #endif } + #endif - #if ENABLED(LED_COLOR_PRESETS) - ACTION_ITEM(MSG_SET_LEDS_DEFAULT, [] { leds.set_default(); ui.refresh(); } ); - SUBMENU(MSG_LED_PRESETS, menu_led_presets); + #if ENABLED(LED_COLOR_PRESETS) + ACTION_ITEM(MSG_SET_LEDS_DEFAULT, [] { leds.set_default(); ui.refresh(); } ); + SUBMENU(MSG_LED_PRESETS, menu_led_presets); + #endif + + #if ENABLED(NEOPIXEL2_SEPARATE) + editable.state = leds2.lights_on; + #if ENABLED(BIQU_BX_TFT70) + EDIT_ITEM(bool, MSG_LIGHT_ENCODER, &editable.state, leds2.toggle); + #else + EDIT_ITEM_N(bool, 2, MSG_LIGHT_N, &editable.state, leds2.toggle); #endif + #if ENABLED(NEO2_COLOR_PRESETS) + ACTION_ITEM(MSG_SET_LEDS_DEFAULT, leds2.set_default); + SUBMENU(MSG_LIGHT2_PRESETS, menu_leds2_presets); + #endif + #endif - #if ENABLED(NEOPIXEL2_SEPARATE) - editable.state = leds2.lights_on; - #if ENABLED(BIQU_BX_TFT70) - EDIT_ITEM(bool, MSG_LIGHT_ENCODER, &editable.state, leds2.toggle); - #else - EDIT_ITEM_N(bool, 2, MSG_LIGHT_N, &editable.state, leds2.toggle); + // + // Directly set RGBW and Brightness + // + SUBMENU(MSG_CUSTOM_LEDS, menu_led_custom); + + // + // Set Case light on/off/brightness + // + #if ENABLED(CASE_LIGHT_MENU) + if (has_bright) { + #if CASELIGHT_USES_BRIGHTNESS + SUBMENU(MSG_CASE_LIGHT, menu_case_light); #endif - #if ENABLED(NEO2_COLOR_PRESETS) - ACTION_ITEM(MSG_SET_LEDS_DEFAULT, leds2.set_default); - SUBMENU(MSG_LIGHT2_PRESETS, menu_leds2_presets); - #endif - #endif + } + else + EDIT_ITEM(bool, MSG_CASE_LIGHT, &caselight.on, caselight.update_enabled); + #endif - // - // Directly set RGBW and Brightness - // - SUBMENU(MSG_CUSTOM_LEDS, menu_led_custom); + END_MENU(); +} - // - // Set Case light on/off/brightness - // - #if ENABLED(CASE_LIGHT_MENU) - if (has_bright) { - #if CASELIGHT_USES_BRIGHTNESS - SUBMENU(MSG_CASE_LIGHT, menu_case_light); - #endif - } - else - EDIT_ITEM(bool, MSG_CASE_LIGHT, &caselight.on, caselight.update_enabled); - #endif - - END_MENU(); - } - -#endif // LED_CONTROL_MENU - -#endif // HAS_MARLINUI_MENU && LED_CONTROL_MENU +#endif // HAS_MARLINUI_MENU && (LED_CONTROL_MENU || CASE_LIGHT_MENU) From b9e89a53783097b5c4880827ef93f886388ef5fd Mon Sep 17 00:00:00 2001 From: Andrew <18502096+classicrocker883@users.noreply.github.com> Date: Fri, 14 Nov 2025 20:11:00 -0500 Subject: [PATCH 72/99] =?UTF-8?q?=F0=9F=A9=B9=20Fix=20NeoPixel=20for=20stm?= =?UTF-8?q?32f1-maple=20(#28128)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- ini/stm32f1-maple.ini | 10 +++++----- 1 file changed, 5 insertions(+), 5 deletions(-) diff --git a/ini/stm32f1-maple.ini b/ini/stm32f1-maple.ini index 304102351d..f6c8b8da56 100644 --- a/ini/stm32f1-maple.ini +++ b/ini/stm32f1-maple.ini @@ -42,6 +42,7 @@ extra_scripts = ${common.extra_scripts} custom_marlin.HAS_SPI_TFT = build_src_filter=+ custom_marlin.HAS_TFT_XPT2046 = build_src_filter=+ custom_marlin.HAS_FSMC_TFT = build_src_filter=+ +custom_marlin.NEOPIXEL_LED = Adafruit NeoPixel=https://github.com/ccccmagicboy/Adafruit_NeoPixel#meeb_3dp_use # # Generic STM32F103RC environment @@ -81,8 +82,7 @@ extra_scripts = ${env:STM32F103RC_maple.extra_scripts} pre:buildroot/share/PlatformIO/scripts/STM32F1_create_variant.py buildroot/share/PlatformIO/scripts/STM32F103RC_MEEB_3DP.py lib_deps = ${env:STM32F103RC_maple.lib_deps} - USBComposite for STM32F1@0.91 -custom_marlin.NEOPIXEL_LED = Adafruit NeoPixel=https://github.com/ccccmagicboy/Adafruit_NeoPixel#meeb_3dp_use + USBComposite for STM32F1@1.0.9 debug_tool = stlink upload_protocol = dfu @@ -115,7 +115,7 @@ monitor_speed = 115200 extends = env:STM32F103RC_btt_maple build_flags = ${env:STM32F103RC_btt_maple.build_flags} -DUSE_USB_COMPOSITE lib_deps = ${env:STM32F103RC_btt_maple.lib_deps} - USBComposite for STM32F1@0.91 + USBComposite for STM32F1@1.0.9 # # Creality 512K (STM32F103RET6) @@ -190,7 +190,7 @@ upload_protocol = stlink extends = env:STM32F103RE_btt_maple build_flags = ${env:STM32F103RE_btt_maple.build_flags} -DUSE_USB_COMPOSITE lib_deps = ${env:STM32F103RE_btt_maple.lib_deps} - USBComposite for STM32F1@0.91 + USBComposite for STM32F1@1.0.9 # # Geeetech GTM32 (STM32F103VET6) @@ -384,7 +384,7 @@ board_upload.maximum_size = 237568 build_flags = ${STM32F1_maple.build_flags} -D__STM32F1__=1 -DDEBUG_LEVEL=0 -DSS_TIMER=4 -DSERIAL_USB lib_deps = ${STM32F1_maple.lib_deps} - USBComposite for STM32F1@0.91 + USBComposite for STM32F1@1.0.9 lib_ignore = Adafruit NeoPixel, SPI, SailfishLCD, SailfishRGB_LED, SlowSoftI2CMaster [env:STM32F103RC_ZM3E2_USB_maple] From 1f3309ac0664f3bfd238af7fa17d9b5a5004510e Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 14 Nov 2025 20:16:43 -0600 Subject: [PATCH 73/99] =?UTF-8?q?=F0=9F=94=A8=20Use=20config=5Fdump=201=20?= =?UTF-8?q?for=20mc.zip=20embedding?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- buildroot/share/PlatformIO/scripts/signature.py | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/buildroot/share/PlatformIO/scripts/signature.py b/buildroot/share/PlatformIO/scripts/signature.py index c91b5fcf2d..17bcb0d802 100755 --- a/buildroot/share/PlatformIO/scripts/signature.py +++ b/buildroot/share/PlatformIO/scripts/signature.py @@ -198,7 +198,7 @@ def compute_build_signature(env): # Get the CONFIG_EXPORT value and do an extended dump if > 100 # For example, CONFIG_EXPORT 102 will make a 'config.ini' with a [config:] group for each schema @section - config_dump = 101 if is_embed else tryint('CONFIG_EXPORT') + config_dump = 1 if is_embed else tryint('CONFIG_EXPORT') extended_dump = config_dump > 100 config_dump %= 100 From a1a9904d329bf9e78b269fcd6e3f4f277ecc7884 Mon Sep 17 00:00:00 2001 From: Steven Haigh Date: Sun, 16 Nov 2025 08:44:16 +1100 Subject: [PATCH 74/99] =?UTF-8?q?=F0=9F=94=A8=20Enhance=20mc-apply.py=20?= =?UTF-8?q?=20(#28157)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Enhance `mc-apply.py` with `configuration.py` features and value normalization: - Verbose logging system with `--verbose` flag (0-2 levels) - `fetch_example()` to download configs from GitHub (`examples/path` or URLs) - `disable_all_options()` to comment out all `#define` statements - Special directives support via directives JSON key - Support for `[disable]`, `examples/path`, and direct URL directives Implement value normalization for consistent behavior: - "on", "true", true, "" => enable (uncomment `#define`) - "off", "false", false => disable (comment out `#define`) - All other values => set value (`#define OPTION value`) Update example marlin_config.json to demonstrate different value formats and directive usage. Changes are fully backward compatible with existing JSON configuration files. --- .../share/PlatformIO/scripts/mc-apply.py | 201 ++++++++++++++++-- buildroot/tests/STM32F103RE | 2 +- 2 files changed, 189 insertions(+), 14 deletions(-) diff --git a/buildroot/share/PlatformIO/scripts/mc-apply.py b/buildroot/share/PlatformIO/scripts/mc-apply.py index 90b0064222..6ec7122688 100755 --- a/buildroot/share/PlatformIO/scripts/mc-apply.py +++ b/buildroot/share/PlatformIO/scripts/mc-apply.py @@ -1,10 +1,10 @@ -#!/usr/bin/env python +#!/usr/bin/env python3 # # mc-apply.py # # Apply firmware configuration from a JSON file (marlin_config.json). # -# usage: mc-apply.py [-h] [--opt] [config_file] +# usage: mc-apply.py [-h] [--opt] [--verbose] [config_file] # # Process Marlin firmware configuration. # @@ -14,20 +14,132 @@ # optional arguments: # -h, --help show this help message and exit # --opt Output as an option setting script. +# --verbose Enable verbose logging (0-2) # -import json, sys, os +import json, sys, os, re, shutil, datetime import config import argparse +from pathlib import Path + +verbose = 0 +def blab(str, level=1): + if verbose >= level: print(f"[mc-apply] {str}") + +def config_path(cpath): + return Path("Marlin", cpath) + +def normalize_value(v): + """ + Normalize configuration values to consistent format. + Returns tuple: (action, value) where action is 'enable', 'disable', or 'set' + + - "on", "true", True, "" -> ('enable', '') - Enable without value + - "off", "false", False -> ('disable', '') - Disable/comment out + - Any other value -> ('set', value) - Enable with value + """ + # Convert to string for comparison, handle JSON booleans + if isinstance(v, bool): + v_str = 'true' if v else 'false' + else: + v_str = str(v).strip().lower() + + # Check for enable values + if v_str in ('on', 'true', ''): + return ('enable', '') + + # Check for disable values + elif v_str in ('off', 'false'): + return ('disable', '') + + # Everything else is a value to set + else: + return ('set', v if not isinstance(v, bool) else v_str) + +# Disable all (most) defined options in the configuration files. +def disable_all_options(): + blab("Disabling all configuration 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) + if not fullpath.exists(): + blab(f"File not found: {fullpath}", 0) + continue + + 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', 'CONFIG_EXAMPLES_DIR'): continue + if name.startswith('_'): continue + found = True + # Comment out the define + lines[i] = re.sub(r'^(\s*)(#define)(\s{1,3})?(\s*)', r'\1//\2 \4', line) + blab(f"Disable {name}", 2) + + # If the option was found, write the modified lines + if found: + fullpath.write_text('\n'.join(lines), encoding='utf-8') + blab(f"Updated {file}") + +# Fetch configuration files from GitHub given the path. +# Return True if any files were fetched. +def fetch_example(url): + blab(f"Fetching example configuration from: {url}") + if url.endswith("/"): url = url[:-1] + if not url.startswith('http'): + brch = "bugfix-2.1.x" + if '@' in url: url, brch = map(str.strip, url.split('@')) + if url == 'examples/default': url = 'default' + url = f"https://raw.githubusercontent.com/MarlinFirmware/Configurations/{brch}/config/{url}" + url = url.replace("%", "%25").replace(" ", "%20") + + # Find a suitable fetch command + if shutil.which("curl") is not None: + fetch = "curl -L -s -S -f -o" + elif shutil.which("wget") is not None: + fetch = "wget -q -O" + else: + blab("Couldn't find curl or wget", 0) + return False + + # Reset configurations to default + blab("Resetting configurations to default...") + os.system("git checkout HEAD Marlin/*.h") + + # Try to fetch the remote files + gotfile = False + for fn in ("Configuration.h", "Configuration_adv.h", "_Bootscreen.h", "_Statusscreen.h"): + if os.system(f"{fetch} wgot {url}/{fn} >/dev/null 2>&1") == 0: + shutil.move('wgot', config_path(fn)) + gotfile = True + blab(f"Fetched {fn}", 2) + + if Path('wgot').exists(): shutil.rmtree('wgot') + + if gotfile: + blab("Example configuration fetched successfully") + else: + blab("Failed to fetch example configuration", 0) + + return gotfile def report_version(conf): if 'VERSION' in conf: + blab("Configuration version information:") for k, v in sorted(conf['VERSION'].items()): print(k + ': ' + v) def write_opt_file(conf, outpath='Marlin/apply_config.sh'): + blab(f"Writing configuration script to {outpath}") with open(outpath, 'w', encoding='utf-8') as outfile: for key, val in conf.items(): - if key in ('__INITIAL_HASH', 'VERSION'): continue + if key in ('__INITIAL_HASH', '__directives__', 'VERSION'): continue # Other keys are assumed to be configs if not type(val) is dict: @@ -36,11 +148,18 @@ def write_opt_file(conf, outpath='Marlin/apply_config.sh'): # Write config commands to the script file lines = [] for k, v in sorted(val.items()): - if v != '': - v.replace('"', '\\"').replace("'", "\\'").replace(' ', '\\ ') - lines += [f'opt_set {k} {v}'] - else: + action, norm_val = normalize_value(v) + + if action == 'enable': lines += [f'opt_enable {k}'] + blab(f" opt_enable {k}", 2) + elif action == 'disable': + lines += [f'opt_disable {k}'] + blab(f" opt_disable {k}", 2) + else: # action == 'set' + norm_val = str(norm_val).replace('"', '\\"').replace("'", "\\'").replace(' ', '\\ ') + lines += [f'opt_set {k} {norm_val}'] + blab(f" opt_set {k} {norm_val}", 2) outfile.write('\n'.join(lines)) @@ -49,6 +168,10 @@ def write_opt_file(conf, outpath='Marlin/apply_config.sh'): def back_up_config(name): # Back up the existing file before modifying it conf_path = 'Marlin/' + name + if not os.path.exists(conf_path): + blab(f"Config file not found: {conf_path}", 0) + return + with open(conf_path, 'r', encoding='utf-8') as f: # Write a filename.bak#.ext retaining the original extension parts = conf_path.split('.') @@ -61,27 +184,79 @@ def back_up_config(name): with open(bak_path, 'w', encoding='utf-8', newline='') as b: b.writelines(f.readlines()) + blab(f"Backed up {conf_path} to {bak_path}", 2) break +def process_directives(directives): + """Process special directives before applying config options""" + if not isinstance(directives, list): + directives = [directives] + + for directive in directives: + directive = directive.strip() + blab(f"Processing directive: {directive}") + + # Handle [disable] directive + if directive == "[disable]": + disable_all_options() + + # Handle example fetching (examples/path or example/path) + elif directive.startswith('examples/') or directive.startswith('example/'): + if directive.startswith('example/'): + directive = 'examples' + directive[7:] + fetch_example(directive) + + # Handle direct URLs + elif directive.startswith('http://') or directive.startswith('https://'): + fetch_example(directive) + + else: + blab(f"Unknown directive: {directive}", 0) + def apply_config(conf): + # Process directives first if they exist + if '__directives__' in conf: + blab("=" * 20 + " Processing directives...") + process_directives(conf['__directives__']) + + # Apply configuration options + blab("=" * 20 + " Applying configuration options...") for key in conf: - if key in ('__INITIAL_HASH', 'VERSION'): continue + if key in ('__INITIAL_HASH', '__directives__', 'VERSION'): continue + + # Skip non-dict values + if not isinstance(conf[key], dict): + continue back_up_config(key) for k, v in conf[key].items(): - if v: - config.set('Marlin/' + key, k, v) - else: - config.enable('Marlin/' + key, k) + action, norm_val = normalize_value(v) + conf_file = 'Marlin/' + key + + if action == 'enable': + blab(f"Enabling {k}", 2) + config.enable(conf_file, k, True) + elif action == 'disable': + blab(f"Disabling {k}", 2) + config.enable(conf_file, k, False) + else: # action == 'set' + blab(f"Setting {k} = {norm_val}", 2) + config.set(conf_file, k, norm_val) def main(): + global verbose + parser = argparse.ArgumentParser(description='Process Marlin firmware configuration.') parser.add_argument('--opt', action='store_true', help='Output as an option setting script.') + parser.add_argument('--verbose', '-v', type=int, default=0, help='Verbose logging level (0-2, default: 0)') parser.add_argument('config_file', nargs='?', default='marlin_config.json', help='Path to the configuration file.') args = parser.parse_args() + # Set verbose level + verbose = args.verbose + try: infile = open(args.config_file, 'r', encoding='utf-8') except: diff --git a/buildroot/tests/STM32F103RE b/buildroot/tests/STM32F103RE index 111eb26644..f97b04c520 100755 --- a/buildroot/tests/STM32F103RE +++ b/buildroot/tests/STM32F103RE @@ -13,7 +13,7 @@ restore_configs opt_set MOTHERBOARD BOARD_STM32F103RE SERIAL_PORT -1 EXTRUDERS 2 \ NOZZLE_CLEAN_START_POINT "{ { 10, 10, 3 } }" \ NOZZLE_CLEAN_END_POINT "{ { 10, 20, 3 } }" -opt_enable EEPROM_SETTINGS EEPROM_CHITCHAT SDSUPPORT \ +opt_enable EEPROM_SETTINGS EEPROM_CHITCHAT SDSUPPORT CONFIGURATION_EMBEDDING \ PAREN_COMMENTS GCODE_MOTION_MODES SINGLENOZZLE TOOLCHANGE_FILAMENT_SWAP TOOLCHANGE_PARK \ BAUD_RATE_GCODE GCODE_MACROS NOZZLE_PARK_FEATURE NOZZLE_CLEAN_FEATURE exec_test $1 $2 "STM32F1R EEPROM_SETTINGS EEPROM_CHITCHAT SDSUPPORT PAREN_COMMENTS GCODE_MOTION_MODES" "$3" From eb2b8a1ddb3eaa6a2d647dde92af777699d5045f Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sun, 16 Nov 2025 00:35:14 +0000 Subject: [PATCH 75/99] [cron] Bump distribution date (2025-11-16) --- 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 0ffebcd002..f531a7ed78 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 "2025-11-15" +//#define STRING_DISTRIBUTION_DATE "2025-11-16" /** * The protocol for communication to the host. Protocol indicates communication diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 0fd96f427f..63ea0ba9b4 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 "2025-11-15" + #define STRING_DISTRIBUTION_DATE "2025-11-16" #endif /** From ef8873d6ef6bbe485f256387997d784430ee835c Mon Sep 17 00:00:00 2001 From: Harald Wagener Date: Sun, 16 Nov 2025 16:12:38 +0100 Subject: [PATCH 76/99] =?UTF-8?q?=F0=9F=94=A7=20FLY=20D5=20=E2=80=94=20Ser?= =?UTF-8?q?vo=20and=20Probe=20pins=20(#28166)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/pins/stm32f0/pins_FLY_D5.h | 10 ++++++++++ 1 file changed, 10 insertions(+) diff --git a/Marlin/src/pins/stm32f0/pins_FLY_D5.h b/Marlin/src/pins/stm32f0/pins_FLY_D5.h index b3b51f6bde..b2a02c2ac8 100644 --- a/Marlin/src/pins/stm32f0/pins_FLY_D5.h +++ b/Marlin/src/pins/stm32f0/pins_FLY_D5.h @@ -42,6 +42,11 @@ #endif #endif +// +// Servos +// +#define SERVO0_PIN PA8 + // // Timers // @@ -54,6 +59,11 @@ #define X_STOP_PIN PB4 #define Y_STOP_PIN PB3 #define Z_STOP_PIN PD2 + +#ifndef Z_MIN_PROBE_PIN + #define Z_MIN_PROBE_PIN PB5 +#endif + // // Steppers // From 98c72a3b65c45036628f7b36fbfea32ce5da77a3 Mon Sep 17 00:00:00 2001 From: Vedran <36977084+vedransi@users.noreply.github.com> Date: Mon, 17 Nov 2025 05:22:03 +1100 Subject: [PATCH 77/99] =?UTF-8?q?=E2=9C=A8=20DIFFERENTIAL=5FEXTRUDER=20(#2?= =?UTF-8?q?8023)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration.h | 12 ++++ Marlin/src/inc/SanityCheck.h | 13 ++++ .../module/ft_motion/resonance_generator.cpp | 2 +- Marlin/src/module/stepper.cpp | 66 ++++++++++++++++++- buildroot/tests/STM32F103RE_btt | 4 +- 5 files changed, 93 insertions(+), 4 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index 219cfe42c7..2d816d9e46 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -305,6 +305,18 @@ #endif +/** + * Differential Extruder + * + * The X and E steppers work together to create a differential drive system. + * Simple : E steps = X + E ; X steps = X (E drives a loop, X stays the same) + * Balanced: E steps = X + E/2 ; X steps = X - E/2 (Dual loop system) + */ +//#define DIFFERENTIAL_EXTRUDER +#if ENABLED(DIFFERENTIAL_EXTRUDER) + //#define BALANCED_DIFFERENTIAL_EXTRUDER +#endif + /** * Switching Toolhead * diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index fc31f9901b..474e51a7ec 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -934,6 +934,19 @@ static_assert(COUNT(arm) == LOGICAL_AXES, "AXIS_RELATIVE_MODES must contain " _L #endif #endif +/** + * Differential Extruder requirements + */ +#if ENABLED(DIFFERENTIAL_EXTRUDER) + #if EXTRUDERS != 1 + #error "DIFFERENTIAL EXTRUDER currently requires a single extruder (EXTRUDERS = 1)." + #elif !IS_FULL_CARTESIAN + #error "DIFFERENTIAL EXTRUDER requires standard Cartesian kinematics." + #elif !defined(CPU_32_BIT) + #error "DIFFERENTIAL EXTRUDER requires a 32-bit CPU." + #endif +#endif + /** * Generic Switching Toolhead requirements */ diff --git a/Marlin/src/module/ft_motion/resonance_generator.cpp b/Marlin/src/module/ft_motion/resonance_generator.cpp index f1b14ab72a..bfc2f9263d 100644 --- a/Marlin/src/module/ft_motion/resonance_generator.cpp +++ b/Marlin/src/module/ft_motion/resonance_generator.cpp @@ -33,7 +33,7 @@ ftm_resonance_test_params_t ResonanceGenerator::rt_params; // Resonance test bool ResonanceGenerator::active = false; // Resonance test active bool ResonanceGenerator::done = false; // Resonance test done -float ResonanceGenerator::rt_time = FTM_TS; // Resonance test timer +float ResonanceGenerator::rt_time = FTM_TS; // Resonance test timer float ResonanceGenerator::timeline = 0.0f; ResonanceGenerator::ResonanceGenerator() {} diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index d45ef3dc9a..b6d79dfac7 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -2725,6 +2725,70 @@ hal_timer_t Stepper::block_phase_isr() { // Based on the oversampling factor, do the calculations step_event_count = current_block->step_event_count << oversampling_factor; + #if ENABLED(DIFFERENTIAL_EXTRUDER) + + // X and E work together as a differential mechanism: + // When X and E move in the same direction they move the print carriage, + // and when X and E move in opposite directions they cause extrusion. + + // NOTE: All calculations performed per block, preserving Bresenham timing coordination + if (current_block->steps.x > 0 || current_block->steps.e > 0) { + // Calculate signed step counts based on directions + const int32_t x_signed_steps = current_block->direction_bits.x ? current_block->steps.x : -int32_t(current_block->steps.x), + e_signed_steps = current_block->direction_bits.e ? current_block->steps.e : -int32_t(current_block->steps.e); + + #if ENABLED(BALANCED_DIFFERENTIAL_EXTRUDER) + + // BALANCED DIFFERENTIAL EXTRUDER: X stepper drives one loop belt + // and E stepper drives another loop belt. Two belts mesh at the extruder + // X stepper: X - E/2 (carriage movement - half extrusion) + // E stepper: X + E/2 (carriage movement + half extrusion) + // Net extrusion: (X + E/2) - (X - E/2) = E + // (This will work great once I figure out what to do when E/2 is not integer!) + + // Split extrusion 50/50 between X and E steppers + const int32_t half_e_steps = e_signed_steps / 2; + + // X stepper: X movement - half E extrusion + const int32_t new_x_steps = x_signed_steps - half_e_steps; + current_block->steps.x = ABS(new_x_steps); + + // Update X axis direction + current_block->direction_bits.x = new_x_steps >= 0; + + // E stepper: X movement + half E extrusion + const int32_t new_e_steps = x_signed_steps + half_e_steps; + current_block->steps.e = ABS(new_e_steps); + + // Update E axis direction + current_block->direction_bits.e = new_e_steps >= 0; + + #else // !BALANCED_DIFFERENTIAL_EXTRUDER + + // SIMPLE SINGLE-LOOP DIFFERENTIAL EXTRUDER: X stepper drives the carriage as usual, + // while E stepper drives a loop belt that's meshed around the extruder. + // X stepper: X only (carriage movement) + // E stepper: X + E (carriage movement + extrusion) + // Net extrusion: (X + E) - X = E + + // Calculate net E steps (X movement + extrusion) + const int32_t net_e_steps = x_signed_steps + e_signed_steps; + + // Update the block with new E step count + current_block->steps.e = ABS(net_e_steps); + + // Update direction bit for E axis + current_block->direction_bits.e = net_e_steps >= 0; + + #endif // !BALANCED_DIFFERENTIAL_EXTRUDER + + // NOTE: DO NOT modify the step_event_count! This would change XYZ timing! + // Bresenham distributes X and E steps over the time base. + + } + + #endif // DIFFERENTIAL_EXTRUDER + // Initialize Bresenham delta errors to 1/2 delta_error = -int32_t(step_event_count); TERN_(HAS_ROUGH_LIN_ADVANCE, la_delta_error = delta_error); @@ -3322,7 +3386,7 @@ void Stepper::init() { } void Stepper::set_shaping_frequency(const AxisEnum axis, const float freq) { - // Enabling or disabling shaping whilst moving can result in lost steps + // Enabling or disabling shaping while moving can result in lost steps planner.synchronize(); const bool was_on = hal.isr_state(); diff --git a/buildroot/tests/STM32F103RE_btt b/buildroot/tests/STM32F103RE_btt index 2c46272625..21c6045a71 100755 --- a/buildroot/tests/STM32F103RE_btt +++ b/buildroot/tests/STM32F103RE_btt @@ -13,5 +13,5 @@ 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 ULTI_CONTROLLER -exec_test $1 $2 "BTT SKR E3 DIP 1.0 | Mixed TMC Drivers" "$3" +opt_enable SERIAL_DMA ULTI_CONTROLLER DIFFERENTIAL_EXTRUDER BALANCED_DIFFERENTIAL_EXTRUDER +exec_test $1 $2 "BTT SKR E3 DIP 1.0 | Mixed TMC Drivers | Differential Extruder" "$3" From c6f4bc1aa1f9dbc9bc92271e58fd97b7e97264e7 Mon Sep 17 00:00:00 2001 From: ellensp <530024+ellensp@users.noreply.github.com> Date: Mon, 17 Nov 2025 07:24:09 +1300 Subject: [PATCH 78/99] =?UTF-8?q?=E2=9C=A8=20GCODE=5FMACROS=5FIN=5FEEPROM?= =?UTF-8?q?=20(2)=20(#28174)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/module/settings.cpp | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index caddd8129c..9919f3f1de 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -708,7 +708,7 @@ typedef struct SettingsDataStruct { // // GCODE_MACROS // - #if ENABLED(GCODE_MACROS_EEPROM) + #if ENABLED(GCODE_MACROS_IN_EEPROM) char gcode_macros[GCODE_MACROS_SLOTS][GCODE_MACROS_SLOT_SIZE + 1]; #endif @@ -1833,7 +1833,7 @@ void MarlinSettings::postprocess() { // // GCODE_MACROS // - #if ENABLED(GCODE_MACROS_EEPROM) + #if ENABLED(GCODE_MACROS_IN_EEPROM) _FIELD_TEST(gcode_macros); EEPROM_WRITE(gcode.macros); #endif @@ -2999,7 +2999,7 @@ void MarlinSettings::postprocess() { // // GCODE_MACROS // - #if ENABLED(GCODE_MACROS_EEPROM) + #if ENABLED(GCODE_MACROS_IN_EEPROM) EEPROM_READ(gcode.macros); #endif @@ -3825,7 +3825,7 @@ void MarlinSettings::reset() { // // G-code Macros // - TERN_(GCODE_MACROS_EEPROM, gcode.reset_macros()); + TERN_(GCODE_MACROS_IN_EEPROM, gcode.reset_macros()); // // Hotend Idle Timeout From c7e6b7924a53c6173b0c71df8e00a773ad1472df Mon Sep 17 00:00:00 2001 From: ellensp <530024+ellensp@users.noreply.github.com> Date: Mon, 17 Nov 2025 07:54:52 +1300 Subject: [PATCH 79/99] =?UTF-8?q?=F0=9F=9A=B8=F0=9F=8C=A1=EF=B8=8F=20Refac?= =?UTF-8?q?tor=20AUTOTEMP=20(2)=20(#28175)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Followup to #28155 --- Marlin/src/gcode/temp/M104_M109.cpp | 9 +++------ Marlin/src/lcd/menu/menu_advanced.cpp | 23 +++++++++++++++-------- Marlin/src/module/settings.cpp | 2 +- 3 files changed, 19 insertions(+), 15 deletions(-) diff --git a/Marlin/src/gcode/temp/M104_M109.cpp b/Marlin/src/gcode/temp/M104_M109.cpp index fa6cc948c0..badc8b7fe7 100644 --- a/Marlin/src/gcode/temp/M104_M109.cpp +++ b/Marlin/src/gcode/temp/M104_M109.cpp @@ -140,12 +140,9 @@ void GcodeSuite::M104_M109(const bool isM109) { // void GcodeSuite::M104_report(const bool forReplay/*=true*/) { TERN_(MARLIN_SMALL_BUILD, return); - report_heading_etc(forReplay, F(STR_AUTOTEMP)); - SERIAL_ECHOLNPGM(" M104" - " S", thermalManager.autotemp.cfg.min, - " B", thermalManager.autotemp.cfg.max, - " F", thermalManager.autotemp.cfg.factor - ); + report_heading_etc(forReplay, F(STR_AUTOTEMP)); + const autotemp_cfg_t &c = thermalManager.autotemp.cfg; + SERIAL_ECHOLNPGM(" M104 S", c.min, " B", c.max, " F", c.factor); } #endif diff --git a/Marlin/src/lcd/menu/menu_advanced.cpp b/Marlin/src/lcd/menu/menu_advanced.cpp index a8d792dbca..fa3f748b8e 100644 --- a/Marlin/src/lcd/menu/menu_advanced.cpp +++ b/Marlin/src/lcd/menu/menu_advanced.cpp @@ -325,9 +325,14 @@ void menu_backlash(); // Autotemp, Min, Max, Fact // #if ALL(AUTOTEMP, HAS_TEMP_HOTEND) - EDIT_ITEM(int3, MSG_MIN, &thermalManager.autotemp.cfg.min, 0, thermalManager.hotend_max_target(0)); - EDIT_ITEM(int3, MSG_MAX, &thermalManager.autotemp.cfg.max, 0, thermalManager.hotend_max_target(0)); - EDIT_ITEM(float42_52, MSG_FACTOR, &thermalManager.autotemp.cfg.factor, 0, 10); + autotemp_cfg_t &c = thermalManager.autotemp.cfg; + EDIT_ITEM(int3, MSG_MIN, &c.min, 0, thermalManager.hotend_max_target(0), []{ + NOLESS(thermalManager.autotemp.cfg.max, thermalManager.autotemp.cfg.min); + }); + EDIT_ITEM(int3, MSG_MAX, &c.max, 0, thermalManager.hotend_max_target(0), []{ + NOMORE(thermalManager.autotemp.cfg.min, thermalManager.autotemp.cfg.max); + }); + EDIT_ITEM(float42_52, MSG_FACTOR, &c.factor, 0, 10); #endif // @@ -340,13 +345,15 @@ void menu_backlash(); // #if ALL(PIDTEMP, PID_EDIT_MENU) - #define __PID_HOTEND_MENU_ITEMS(N) \ + + #define __PID_HOTEND_MENU_ITEMS(N) do{ \ raw_Kp = thermalManager.temp_hotend[N].pid.p(); \ raw_Ki = thermalManager.temp_hotend[N].pid.i(); \ raw_Kd = thermalManager.temp_hotend[N].pid.d(); \ - EDIT_ITEM_FAST_N(float41sign, N, MSG_PID_P_E, &raw_Kp, 1, 9990, []{ apply_PID_p(N); }); \ + EDIT_ITEM_FAST_N(float41sign, N, MSG_PID_P_E, &raw_Kp, 1.00f, 9990, []{ apply_PID_p(N); }); \ EDIT_ITEM_FAST_N(float52sign, N, MSG_PID_I_E, &raw_Ki, 0.01f, 9990, []{ apply_PID_i(N); }); \ - EDIT_ITEM_FAST_N(float41sign, N, MSG_PID_D_E, &raw_Kd, 1, 9990, []{ apply_PID_d(N); }) + EDIT_ITEM_FAST_N(float41sign, N, MSG_PID_D_E, &raw_Kd, 1.00f, 9990, []{ apply_PID_d(N); }); \ + }while(0) #if ENABLED(PID_EXTRUSION_SCALING) #define _PID_HOTEND_MENU_ITEMS(N) \ @@ -377,9 +384,9 @@ void menu_backlash(); raw_Kp = T.pid.p(); \ raw_Ki = T.pid.i(); \ raw_Kd = T.pid.d(); \ - EDIT_ITEM_FAST_N(float41sign, N, MSG_PID_P_E, &raw_Kp, 1, 9990, []{ apply_PID_p(N); }); \ + EDIT_ITEM_FAST_N(float41sign, N, MSG_PID_P_E, &raw_Kp, 1.00f, 9990, []{ apply_PID_p(N); }); \ EDIT_ITEM_FAST_N(float52sign, N, MSG_PID_I_E, &raw_Ki, 0.01f, 9990, []{ apply_PID_i(N); }); \ - EDIT_ITEM_FAST_N(float41sign, N, MSG_PID_D_E, &raw_Kd, 1, 9990, []{ apply_PID_d(N); }) + EDIT_ITEM_FAST_N(float41sign, N, MSG_PID_D_E, &raw_Kd, 1.00f, 9990, []{ apply_PID_d(N); }) #endif #if ENABLED(PIDTEMP) diff --git a/Marlin/src/module/settings.cpp b/Marlin/src/module/settings.cpp index 9919f3f1de..85f837b063 100644 --- a/Marlin/src/module/settings.cpp +++ b/Marlin/src/module/settings.cpp @@ -3875,7 +3875,7 @@ void MarlinSettings::reset() { // // M104 settings for AUTOTEMP // - TERN_(AUTOTEMP, gcode.M104_report()); + TERN_(AUTOTEMP, gcode.M104_report(forReplay)); // // M149 Temperature units From 9d55440d38718667ad28aae38959175f22909c41 Mon Sep 17 00:00:00 2001 From: Andrew <18502096+classicrocker883@users.noreply.github.com> Date: Sun, 16 Nov 2025 14:19:59 -0500 Subject: [PATCH 80/99] =?UTF-8?q?=F0=9F=9A=B8=20'G27=20P'=20parameter=20ch?= =?UTF-8?q?eck=20(#28172)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/src/gcode/feature/pause/G27.cpp | 9 +++++++-- Marlin/src/gcode/parser.h | 28 +++++++++++++------------- 2 files changed, 21 insertions(+), 16 deletions(-) diff --git a/Marlin/src/gcode/feature/pause/G27.cpp b/Marlin/src/gcode/feature/pause/G27.cpp index 99159cf66e..1fe6a490ea 100644 --- a/Marlin/src/gcode/feature/pause/G27.cpp +++ b/Marlin/src/gcode/feature/pause/G27.cpp @@ -44,8 +44,13 @@ void GcodeSuite::G27() { // Don't allow nozzle parking without homing first if (homing_needed_error()) return; - nozzle.park(parser.ushortval('P')); - TERN_(SOVOL_SV06_RTS, RTS_MoveAxisHoming()); + const int16_t pval = parser.intval('P'); + if (WITHIN(pval, 0, 4)) { + nozzle.park(pval); + TERN_(SOVOL_SV06_RTS, RTS_MoveAxisHoming()); + } + else + SERIAL_ECHOLN(F("?Invalid "), F("[P]arking style (0..4).")); } #endif // NOZZLE_PARK_FEATURE diff --git a/Marlin/src/gcode/parser.h b/Marlin/src/gcode/parser.h index 8e27064b63..71cad6857d 100644 --- a/Marlin/src/gcode/parser.h +++ b/Marlin/src/gcode/parser.h @@ -281,7 +281,7 @@ public: // Reduce to fewer bits static int16_t value_int() { return (int16_t)value_long(); } - static uint16_t value_ushort() { return (uint16_t)value_long(); } + static uint16_t value_ushort() { return (uint16_t)value_ulong(); } static uint8_t value_byte() { return (uint8_t)constrain(value_long(), 0, 255); } // Bool is true with no value or non-zero @@ -324,7 +324,7 @@ public: return linear_unit_factor; } - static float linear_value_to_mm(const float v) { return v * linear_unit_factor; } + static float linear_value_to_mm(const float v) { return v * linear_unit_factor; } static float axis_value_to_mm(const AxisEnum axis, const float v) { return v * axis_unit_factor(axis); } static float per_axis_value(const AxisEnum axis, const float v) { return v / axis_unit_factor(axis); } @@ -420,19 +420,19 @@ public: void unknown_command_warning(); // Provide simple value accessors with default option - static char* stringval(const char c, char * const dval=nullptr) { return seenval(c) ? value_string() : dval; } - static float floatval(const char c, const float dval=0.0) { return seenval(c) ? value_float() : dval; } - static bool boolval(const char c, const bool dval=false) { return seenval(c) ? value_bool() : (seen(c) ? true : dval); } - static uint8_t byteval(const char c, const uint8_t dval=0) { return seenval(c) ? value_byte() : dval; } - static int16_t intval(const char c, const int16_t dval=0) { return seenval(c) ? value_int() : dval; } - static uint16_t ushortval(const char c, const uint16_t dval=0) { return seenval(c) ? value_ushort() : dval; } - static int32_t longval(const char c, const int32_t dval=0) { return seenval(c) ? value_long() : dval; } - static uint32_t ulongval(const char c, const uint32_t dval=0) { return seenval(c) ? value_ulong() : dval; } - static float linearval(const char c, const float dval=0) { return seenval(c) ? value_linear_units() : dval; } + static char* stringval(const char c, char * const dval=nullptr) { return seenval(c) ? value_string() : dval; } + static float floatval(const char c, const float dval=0.0) { return seenval(c) ? value_float() : dval; } + static bool boolval(const char c, const bool dval=false) { return seenval(c) ? value_bool() : (seen(c) ? true : dval); } + static uint8_t byteval(const char c, const uint8_t dval=0) { return seenval(c) ? value_byte() : dval; } + static int16_t intval(const char c, const int16_t dval=0) { return seenval(c) ? value_int() : dval; } + static uint16_t ushortval(const char c, const uint16_t dval=0) { return seenval(c) ? value_ushort() : dval; } + static int32_t longval(const char c, const int32_t dval=0) { return seenval(c) ? value_long() : dval; } + static uint32_t ulongval(const char c, const uint32_t dval=0) { return seenval(c) ? value_ulong() : dval; } + static float linearval(const char c, const float dval=0) { return seenval(c) ? value_linear_units() : dval; } static float axisunitsval(const char c, const AxisEnum a, const float dval=0) - { return seenval(c) ? value_axis_units(a) : dval; } - static celsius_t celsiusval(const char c, const celsius_t dval=0) { return seenval(c) ? value_celsius() : dval; } - static feedRate_t feedrateval(const char c, const feedRate_t dval=0) { return seenval(c) ? value_feedrate() : dval; } + { return seenval(c) ? value_axis_units(a) : dval; } + static celsius_t celsiusval(const char c, const celsius_t dval=0) { return seenval(c) ? value_celsius() : dval; } + static feedRate_t feedrateval(const char c, const feedRate_t dval=0) { return seenval(c) ? value_feedrate() : dval; } #if ENABLED(MARLIN_DEV_MODE) From e6a615d88244dddd595e35c5145325ba90fc662b Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Mon, 17 Nov 2025 00:33:44 +0000 Subject: [PATCH 81/99] [cron] Bump distribution date (2025-11-17) --- 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 f531a7ed78..6675411f3e 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 "2025-11-16" +//#define STRING_DISTRIBUTION_DATE "2025-11-17" /** * The protocol for communication to the host. Protocol indicates communication diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 63ea0ba9b4..ea3a802a09 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 "2025-11-16" + #define STRING_DISTRIBUTION_DATE "2025-11-17" #endif /** From 4f39b9c09d47a5d224b1b7cad3104b6ed8003e79 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 17 Nov 2025 17:28:13 -0600 Subject: [PATCH 82/99] =?UTF-8?q?=F0=9F=8E=A8=20Misc=20patches=20from=20Pr?= =?UTF-8?q?oUI?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-Authored-By: Miguel Risco-Castillo --- Marlin/src/core/mstring.h | 5 ++--- Marlin/src/feature/powerloss.cpp | 2 +- Marlin/src/gcode/config/M575.cpp | 19 ++++++++++--------- Marlin/src/lcd/e3v2/creality/dwin.cpp | 4 ++-- Marlin/src/lcd/e3v2/jyersui/dwin.h | 1 + Marlin/src/lcd/e3v2/proui/dwin.cpp | 6 +++--- .../lcd/extui/dgus_reloaded/DGUSRxHandler.cpp | 2 +- Marlin/src/lcd/language/language_de.h | 7 ++++--- Marlin/src/lcd/language/language_en.h | 6 ++---- Marlin/src/lcd/language/language_fr.h | 3 +-- Marlin/src/lcd/language/language_fr_na.h | 3 +-- Marlin/src/lcd/language/language_it.h | 6 ++---- Marlin/src/lcd/language/language_ru.h | 5 +++-- Marlin/src/lcd/language/language_sk.h | 5 +++-- Marlin/src/lcd/language/language_tr.h | 5 ++--- .../variants/MARLIN_F103Rx/variant.h | 2 +- .../MARLIN_F401RC_CREALITY/ldscript.ld | 11 +++++------ .../variants/MARLIN_F401RC_CREALITY/variant.h | 4 +++- 18 files changed, 47 insertions(+), 49 deletions(-) diff --git a/Marlin/src/core/mstring.h b/Marlin/src/core/mstring.h index e3fb78c50e..1e540a5a5a 100644 --- a/Marlin/src/core/mstring.h +++ b/Marlin/src/core/mstring.h @@ -280,12 +280,11 @@ public: // Quick hash to detect change (e.g., to avoid expensive drawing) typedef IF::type hash_t; hash_t hash() const { + const int sz = length(); #if ENABLED(DJB2_HASH) hash_t hval = 5381; - char c; - while ((c = *str++)) hval += (hval << 5) + c; // = hval * 33 + c + for (int i = 0; i < sz; i++) hval += (hval << 5) + str[i]; // = hval * 33 + c #else - const int sz = length(); hash_t hval = hash_t(sz); for (int i = 0; i < sz; i++) hval = ((hval << 1) | (hval >> 15)) ^ str[i]; // ROL, XOR #endif diff --git a/Marlin/src/feature/powerloss.cpp b/Marlin/src/feature/powerloss.cpp index 385ca6b72d..bb4ca0dbde 100644 --- a/Marlin/src/feature/powerloss.cpp +++ b/Marlin/src/feature/powerloss.cpp @@ -99,7 +99,7 @@ PrintJobRecovery recovery; /** * Clear the recovery info */ -void PrintJobRecovery::init() { info = {}; } +void PrintJobRecovery::init() { info = { 0 }; } /** * Enable or disable then call changed() diff --git a/Marlin/src/gcode/config/M575.cpp b/Marlin/src/gcode/config/M575.cpp index 2c12428d98..b88b372ddb 100644 --- a/Marlin/src/gcode/config/M575.cpp +++ b/Marlin/src/gcode/config/M575.cpp @@ -53,15 +53,6 @@ void GcodeSuite::M575() { case 115200: case 250000: case 500000: case 1000000: { const int8_t port = parser.intval('P', -99); const bool set1 = (port == -99 || port == 0); - if (set1) SERIAL_ECHO_MSG(" Serial ", AS_DIGIT(0), " baud rate set to ", baud); - #if HAS_MULTI_SERIAL - const bool set2 = (port == -99 || port == 1); - if (set2) SERIAL_ECHO_MSG(" Serial ", AS_DIGIT(1), " baud rate set to ", baud); - #ifdef SERIAL_PORT_3 - const bool set3 = (port == -99 || port == 2); - if (set3) SERIAL_ECHO_MSG(" Serial ", AS_DIGIT(2), " baud rate set to ", baud); - #endif - #endif SERIAL_FLUSH(); @@ -73,6 +64,16 @@ void GcodeSuite::M575() { #endif #endif + if (set1) SERIAL_ECHO_MSG(" Serial ", AS_DIGIT(0), " baud rate set to ", baud); + #if HAS_MULTI_SERIAL + const bool set2 = (port == -99 || port == 1); + if (set2) SERIAL_ECHO_MSG(" Serial ", AS_DIGIT(1), " baud rate set to ", baud); + #ifdef SERIAL_PORT_3 + const bool set3 = (port == -99 || port == 2); + if (set3) SERIAL_ECHO_MSG(" Serial ", AS_DIGIT(2), " baud rate set to ", baud); + #endif + #endif + } break; default: SERIAL_ECHO_MSG("?(B)aud rate implausible."); } diff --git a/Marlin/src/lcd/e3v2/creality/dwin.cpp b/Marlin/src/lcd/e3v2/creality/dwin.cpp index 06e3321288..affb4695f9 100644 --- a/Marlin/src/lcd/e3v2/creality/dwin.cpp +++ b/Marlin/src/lcd/e3v2/creality/dwin.cpp @@ -1972,7 +1972,7 @@ void hmiSDCardUpdate() { if (hmiFlag.home_flag) return; if (DWIN_lcd_sd_status != card.isMounted()) { DWIN_lcd_sd_status = card.isMounted(); - //SERIAL_ECHOLNPGM("HMI_SDCardUpdate: ", DWIN_lcd_sd_status); + //SERIAL_ECHOLNPGM("hmiSDCardUpdate: ", DWIN_lcd_sd_status); if (DWIN_lcd_sd_status) { if (checkkey == ID_SelectFile) redrawSDList(); @@ -4224,7 +4224,7 @@ void eachMomentUpdate() { if (encoder_diffState == ENCODER_DIFF_ENTER) { recovery_flag = false; if (hmiFlag.select_flag) break; - queue.inject(F("M1000C")); + TERN_(POWER_LOSS_RECOVERY, queue.inject(F("M1000C"))); hmiStartFrame(true); return; } diff --git a/Marlin/src/lcd/e3v2/jyersui/dwin.h b/Marlin/src/lcd/e3v2/jyersui/dwin.h index cc071ef134..067516b2fd 100644 --- a/Marlin/src/lcd/e3v2/jyersui/dwin.h +++ b/Marlin/src/lcd/e3v2/jyersui/dwin.h @@ -126,6 +126,7 @@ enum colorID : uint8_t { }; #define Custom_Colors 10 +#define COLOR_AQUA RGB(0x00, 0x3F, 0x1F) #define COLOR_LIGHT_WHITE 0xBDD7 #define COLOR_GREEN RGB(0x00, 0x3F, 0x00) #define COLOR_LIGHT_GREEN 0x3460 diff --git a/Marlin/src/lcd/e3v2/proui/dwin.cpp b/Marlin/src/lcd/e3v2/proui/dwin.cpp index 974a0a8866..47e2acb27d 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin.cpp @@ -466,8 +466,8 @@ void popupPauseOrStop() { FSTR_P errorstr; uint8_t icon; switch (state) { - case 0: errorstr = GET_TEXT_F(MSG_TEMP_TOO_LOW); icon = ICON_TempTooLow; break; - case 1: errorstr = GET_TEXT_F(MSG_TEMP_TOO_HIGH); icon = ICON_TempTooHigh; break; + case 0: errorstr = GET_TEXT_F(DGUS_MSG_TEMP_TOO_LOW); icon = ICON_TempTooLow; break; + case 1: errorstr = GET_TEXT_F(DGUS_MSG_TEMP_TOO_HIGH); icon = ICON_TempTooHigh; break; default: errorstr = GET_TEXT_F(MSG_ERR_HEATING_FAILED); icon = ICON_Temperature; break; // May be thermal runaway, temp malfunction, etc. } dwinShowPopup(icon, heaterstr, errorstr, BTN_Continue); @@ -1744,7 +1744,7 @@ void dwinLevelingDone() { break; case PID_TEMP_TOO_HIGH: checkkey = last_checkkey; - dwinPopupConfirm(ICON_TempTooHigh, GET_TEXT_F(MSG_PID_AUTOTUNE_FAILED), GET_TEXT_F(MSG_TEMP_TOO_HIGH)); + dwinPopupConfirm(ICON_TempTooHigh, GET_TEXT_F(MSG_PID_AUTOTUNE_FAILED), GET_TEXT_F(DGUS_MSG_TEMP_TOO_HIGH)); break; case AUTOTUNE_DONE: checkkey = last_checkkey; diff --git a/Marlin/src/lcd/extui/dgus_reloaded/DGUSRxHandler.cpp b/Marlin/src/lcd/extui/dgus_reloaded/DGUSRxHandler.cpp index 6b2caadba0..c25163b7e6 100644 --- a/Marlin/src/lcd/extui/dgus_reloaded/DGUSRxHandler.cpp +++ b/Marlin/src/lcd/extui/dgus_reloaded/DGUSRxHandler.cpp @@ -597,7 +597,7 @@ void DGUSRxHandler::filamentMove(DGUS_VP &vp, void *data_ptr) { } if (ExtUI::getActualTemp_celsius(extruder) < (float)EXTRUDE_MINTEMP) { - screen.setStatusMessage(GET_TEXT_F(MSG_TEMP_TOO_LOW)); + screen.setStatusMessage(GET_TEXT_F(DGUS_MSG_TEMP_TOO_LOW)); return; } diff --git a/Marlin/src/lcd/language/language_de.h b/Marlin/src/lcd/language/language_de.h index 4f2cdb79ff..3430d946c8 100644 --- a/Marlin/src/lcd/language/language_de.h +++ b/Marlin/src/lcd/language/language_de.h @@ -73,7 +73,7 @@ namespace LanguageNarrow_de { LSTR MSG_TRAM_C = _UxGT("Mitte"); LSTR MSG_TRAM_BL = _UxGT("Hinten Links"); LSTR MSG_TRAM_BR = _UxGT("Hinten Rechts"); - LSTR MSG_MANUAL_MESH = _UxGT("Manuelles Netz"); + LSTR MSG_MANUAL_MESH = _UxGT("manuelles Netz"); LSTR MSG_AUTO_MESH = _UxGT("Netz auto. erstellen"); LSTR MSG_AUTO_Z_ALIGN = _UxGT("Z-Achsen ausgleichen"); LSTR MSG_ITERATION = _UxGT("G34 Iteration: %i"); @@ -324,8 +324,6 @@ namespace LanguageNarrow_de { LSTR MSG_PID_CYCLE = _UxGT("PID Zyklus"); LSTR MSG_PID_AUTOTUNE_DONE = _UxGT("PID Tuning fertig"); LSTR MSG_PID_AUTOTUNE_FAILED = _UxGT("PID Autotune fehlge.!"); - LSTR MSG_BAD_HEATER_ID = _UxGT("ungültiger Extruder."); - LSTR MSG_TEMP_TOO_HIGH = _UxGT("Temperatur zu hoch."); LSTR MSG_PID_BAD_HEATER_ID = _UxGT("Autotune fehlge.! Ungültiger Extruder"); LSTR MSG_PID_TEMP_TOO_HIGH = _UxGT("Autotune fehlge.! Temperatur zu hoch."); LSTR MSG_PID_TIMEOUT = _UxGT("Autotune fehlge.! Timeout."); @@ -759,6 +757,9 @@ namespace LanguageNarrow_de { LSTR MSG_HOST_SHUTDOWN = _UxGT("Host abschalten"); + // DGUS-Specific message strings, not used elsewhere + LSTR DGUS_MSG_TEMP_TOO_HIGH = _UxGT("Temperatur zu hoch."); + LSTR MSG_SHORT_DAY = _UxGT("t"); // One character only LSTR MSG_SHORT_HOUR = _UxGT("h"); // One character only LSTR MSG_SHORT_MINUTE = _UxGT("m"); // One character only diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index a1ba59bcca..bc1f22aa84 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -414,10 +414,6 @@ namespace LanguageNarrow_en { LSTR MSG_TEMP_BED = _UxGT("Bed Temperature"); LSTR MSG_TEMP_CHAMBER = _UxGT("Chamber Temperature"); - LSTR MSG_BAD_HEATER_ID = _UxGT("Bad extruder."); - LSTR MSG_TEMP_TOO_HIGH = _UxGT("Temperature too high."); - LSTR MSG_TEMP_TOO_LOW = _UxGT("Temperature too low"); - LSTR MSG_PID_BAD_HEATER_ID = _UxGT("Autotune failed! Bad extruder."); LSTR MSG_PID_TEMP_TOO_HIGH = _UxGT("Autotune failed! Temperature too high."); LSTR MSG_PID_TIMEOUT = _UxGT("Autotune failed! Timeout."); @@ -1014,6 +1010,8 @@ namespace LanguageNarrow_en { LSTR DGUS_MSG_NOT_WHILE_PRINTING = _UxGT("Not allowed during print"); LSTR DGUS_MSG_NOT_WHILE_IDLE = _UxGT("Not allowed while idle"); LSTR DGUS_MSG_NO_FILE_SELECTED = _UxGT("No file selected"); + LSTR DGUS_MSG_TEMP_TOO_LOW = _UxGT("Temperature too low"); + LSTR DGUS_MSG_TEMP_TOO_HIGH = _UxGT("Temperature too high."); LSTR DGUS_MSG_EXECUTING_COMMAND = _UxGT("Executing command..."); LSTR DGUS_MSG_BED_PID_DISABLED = _UxGT("Bed PID disabled"); LSTR DGUS_MSG_PID_DISABLED = _UxGT("PID disabled"); diff --git a/Marlin/src/lcd/language/language_fr.h b/Marlin/src/lcd/language/language_fr.h index 6f0e870807..01ded94aff 100644 --- a/Marlin/src/lcd/language/language_fr.h +++ b/Marlin/src/lcd/language/language_fr.h @@ -262,8 +262,6 @@ namespace LanguageNarrow_fr { LSTR MSG_PID_TEMP_TOO_HIGH = _UxGT("Echec Autotune! Temp. trop haute"); LSTR MSG_PID_TIMEOUT = _UxGT("Echec Autotune! Opér. expirée"); - LSTR MSG_TEMP_TOO_LOW = _UxGT("Temperature trop basse"); - LSTR MSG_SELECT_E = _UxGT("Sélectionner *"); LSTR MSG_ACC = _UxGT("Accélération"); LSTR MSG_JERK = _UxGT("Jerk"); @@ -607,6 +605,7 @@ namespace LanguageNarrow_fr { LSTR DGUS_MSG_NOT_WHILE_PRINTING = _UxGT("Impossible pendant une impression"); LSTR DGUS_MSG_NOT_WHILE_IDLE = _UxGT("Impossible tant que l'imprimante est en attente"); LSTR DGUS_MSG_NO_FILE_SELECTED = _UxGT("Aucun fichier selectionne"); + LSTR DGUS_MSG_TEMP_TOO_LOW = _UxGT("Temperature trop basse"); LSTR DGUS_MSG_EXECUTING_COMMAND = _UxGT("Execution de la commande..."); LSTR DGUS_MSG_BED_PID_DISABLED = _UxGT("Bed PID desactive"); LSTR DGUS_MSG_PID_DISABLED = _UxGT("PID desactive"); diff --git a/Marlin/src/lcd/language/language_fr_na.h b/Marlin/src/lcd/language/language_fr_na.h index ef1e29a6b9..9187b45709 100644 --- a/Marlin/src/lcd/language/language_fr_na.h +++ b/Marlin/src/lcd/language/language_fr_na.h @@ -262,8 +262,6 @@ namespace LanguageNarrow_fr_na { LSTR MSG_PID_TEMP_TOO_HIGH = _UxGT("Echec Autotune! Temp. trop haute"); LSTR MSG_PID_TIMEOUT = _UxGT("Echec Autotune! Oper. expiree"); - LSTR MSG_TEMP_TOO_LOW = _UxGT("Temperature trop basse"); - LSTR MSG_SELECT_E = _UxGT("Selectionner *"); LSTR MSG_ACC = _UxGT("Acceleration"); LSTR MSG_JERK = _UxGT("Jerk"); @@ -610,6 +608,7 @@ namespace LanguageNarrow_fr_na { LSTR DGUS_MSG_NOT_WHILE_PRINTING = _UxGT("Impossible pendant une impression"); LSTR DGUS_MSG_NOT_WHILE_IDLE = _UxGT("Impossible tant que l'imprimante est en attente"); LSTR DGUS_MSG_NO_FILE_SELECTED = _UxGT("Aucun fichier selectionne"); + LSTR DGUS_MSG_TEMP_TOO_LOW = _UxGT("Temperature trop basse"); LSTR DGUS_MSG_EXECUTING_COMMAND = _UxGT("Execution de la commande..."); LSTR DGUS_MSG_BED_PID_DISABLED = _UxGT("Bed PID desactive"); LSTR DGUS_MSG_PID_DISABLED = _UxGT("PID desactive"); diff --git a/Marlin/src/lcd/language/language_it.h b/Marlin/src/lcd/language/language_it.h index c0d717d0cc..df42e1ef3b 100644 --- a/Marlin/src/lcd/language/language_it.h +++ b/Marlin/src/lcd/language/language_it.h @@ -391,10 +391,6 @@ namespace LanguageNarrow_it { LSTR MSG_TEMP_BED = _UxGT("Temperatura piatto"); LSTR MSG_TEMP_CHAMBER = _UxGT("Temperature camera"); - LSTR MSG_BAD_HEATER_ID = _UxGT("Estrusore invalido."); - LSTR MSG_TEMP_TOO_HIGH = _UxGT("Temp.troppo alta."); - LSTR MSG_TEMP_TOO_LOW = _UxGT("Temp. troppo bassa"); - LSTR MSG_PID_BAD_HEATER_ID = _UxGT("Calibrazione fallita! Estrusore errato."); LSTR MSG_PID_TEMP_TOO_HIGH = _UxGT("Calibrazione fallita! Temperatura troppo alta."); LSTR MSG_PID_TIMEOUT = _UxGT("Calibrazione fallita! Tempo scaduto."); @@ -939,6 +935,8 @@ namespace LanguageNarrow_it { LSTR DGUS_MSG_NOT_WHILE_PRINTING = _UxGT("Non ammesso durante la stampa"); LSTR DGUS_MSG_NOT_WHILE_IDLE = _UxGT("Non ammesso mentre è in riposo"); LSTR DGUS_MSG_NO_FILE_SELECTED = _UxGT("Nessun file selezionato"); + LSTR DGUS_MSG_TEMP_TOO_LOW = _UxGT("Temperatura troppo bassa"); + LSTR DGUS_MSG_TEMP_TOO_HIGH = _UxGT("Temp.troppo alta."); LSTR DGUS_MSG_EXECUTING_COMMAND = _UxGT("Esecuzione del comando..."); LSTR DGUS_MSG_BED_PID_DISABLED = _UxGT("PID piatto disabilitato"); LSTR DGUS_MSG_PID_DISABLED = _UxGT("PID disabilitato"); diff --git a/Marlin/src/lcd/language/language_ru.h b/Marlin/src/lcd/language/language_ru.h index 37bc17aa0c..c5cba1ad73 100644 --- a/Marlin/src/lcd/language/language_ru.h +++ b/Marlin/src/lcd/language/language_ru.h @@ -708,8 +708,6 @@ namespace LanguageNarrow_ru { LSTR MSG_CUTTER = _UxGT("Резак"); LSTR MSG_PID_CYCLE = _UxGT("Циклы PID"); LSTR MSG_PID_AUTOTUNE_FAILED = _UxGT("Автонастройка PID не удалась!"); - LSTR MSG_BAD_HEATER_ID = _UxGT("Неверный экструдер."); - LSTR MSG_TEMP_TOO_HIGH = _UxGT("Слишком высокая температура."); LSTR MSG_MPC_MEASURING_AMBIENT = _UxGT("Тест потери тепла"); LSTR MSG_MPC_HEATING_PAST_200 = _UxGT("Нагрев выше >200C"); LSTR MSG_MPC_COOLING_TO_AMBIENT = _UxGT("Охлаждение до окружающей"); @@ -824,6 +822,9 @@ namespace LanguageNarrow_ru { LSTR MSG_FTM_MASS_BASED = _UxGT("Mass-based"); LSTR MSG_FTM_BASE_FREQ_N = _UxGT("@ Base Freq."); LSTR MSG_FTM_DFREQ_K_N = _UxGT("@ Dyn. Freq."); + + // DGUS-Specific message strings, not used elsewhere + LSTR DGUS_MSG_TEMP_TOO_HIGH = _UxGT("Слишком высокая температура."); } namespace LanguageWide_ru { diff --git a/Marlin/src/lcd/language/language_sk.h b/Marlin/src/lcd/language/language_sk.h index f1efc0e7c3..5498e36aec 100644 --- a/Marlin/src/lcd/language/language_sk.h +++ b/Marlin/src/lcd/language/language_sk.h @@ -344,8 +344,6 @@ namespace LanguageNarrow_sk { LSTR MSG_PID_CYCLE = _UxGT("Cykly PID"); LSTR MSG_PID_AUTOTUNE_DONE = _UxGT("Kal. PID dokončená"); LSTR MSG_PID_AUTOTUNE_FAILED = _UxGT("Kal. PID zlyhala!"); - LSTR MSG_BAD_HEATER_ID = _UxGT("Zlý extrudér"); - LSTR MSG_TEMP_TOO_HIGH = _UxGT("Príliš vysoká tepl."); LSTR MSG_PID_BAD_HEATER_ID = _UxGT("Auto-kal. zlyhala! Zlý extrúder."); LSTR MSG_PID_TEMP_TOO_HIGH = _UxGT("Auto-kal. zlyhala! Príliš vysoká tepl."); LSTR MSG_PID_TIMEOUT = _UxGT("Auto-kal. zlyhala! Čas vypršal."); @@ -800,6 +798,9 @@ namespace LanguageNarrow_sk { LSTR MSG_USB_DISK = _UxGT("USB disk"); LSTR MSG_HOST_SHUTDOWN = _UxGT("Vypnúť hosta"); + + // DGUS-Specific message strings, not used elsewhere + LSTR DGUS_MSG_TEMP_TOO_HIGH = _UxGT("Príliš vysoká tepl."); } namespace LanguageWide_sk { diff --git a/Marlin/src/lcd/language/language_tr.h b/Marlin/src/lcd/language/language_tr.h index 77cb7bf9b8..21a65d3c2f 100644 --- a/Marlin/src/lcd/language/language_tr.h +++ b/Marlin/src/lcd/language/language_tr.h @@ -347,9 +347,6 @@ namespace LanguageNarrow_tr { LSTR MSG_PID_CYCLE = _UxGT("PID Döngüleri"); LSTR MSG_PID_AUTOTUNE_DONE = _UxGT("PID ayarı yapıldı"); LSTR MSG_PID_AUTOTUNE_FAILED = _UxGT("Kalibrasyon başarısız!"); - LSTR MSG_BAD_HEATER_ID = _UxGT("Kötü ekstruder."); - LSTR MSG_TEMP_TOO_HIGH = _UxGT("Sıcaklık çok yüksek."); - LSTR MSG_TEMP_TOO_LOW = _UxGT("Sıcaklık çok düşük"); LSTR MSG_PID_BAD_HEATER_ID = _UxGT("Kalibrasyon başarısız! Kötü ekstruder."); LSTR MSG_PID_TEMP_TOO_HIGH = _UxGT("Kalibrasyon başarısız! Sıcaklık çok yüksek."); LSTR MSG_PID_TIMEOUT = _UxGT("Kalibrasyon başarısız! Zaman aşımı."); @@ -869,6 +866,8 @@ namespace LanguageNarrow_tr { LSTR DGUS_MSG_NOT_WHILE_PRINTING = _UxGT("Yazdırma sırasında izin verilmez"); LSTR DGUS_MSG_NOT_WHILE_IDLE = _UxGT("Boştayken izin verilmez"); LSTR DGUS_MSG_NO_FILE_SELECTED = _UxGT("Seçili dosya yok"); + LSTR DGUS_MSG_TEMP_TOO_LOW = _UxGT("Sıcaklık çok düşük"); + LSTR DGUS_MSG_TEMP_TOO_HIGH = _UxGT("Sıcaklık çok yüksek."); LSTR DGUS_MSG_EXECUTING_COMMAND = _UxGT("Komut yürütülüyor..."); LSTR DGUS_MSG_BED_PID_DISABLED = _UxGT("Tabla PID pasif"); LSTR DGUS_MSG_PID_DISABLED = _UxGT("PID devre dışı"); diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F103Rx/variant.h b/buildroot/share/PlatformIO/variants/MARLIN_F103Rx/variant.h index 2167e2ad9c..1b95f75f69 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_F103Rx/variant.h +++ b/buildroot/share/PlatformIO/variants/MARLIN_F103Rx/variant.h @@ -31,7 +31,7 @@ extern "C" { #define PA0 PIN_A0 // | 0 | A0 | | | | | #define PA1 PIN_A1 // | 1 | A1 | | | | | #define PA2 PIN_A2 // | 2 | A2 | USART2_TX | | | | -#define PA3 PIN_A3 // | 2 | A3, DAC_OUT1** | USART2_RX | | | | +#define PA3 PIN_A3 // | 3 | A3, DAC_OUT1** | USART2_RX | | | | #define PA4 PIN_A4 // | 4 | A4, DAC_OUT2** | | | SPI1_SS | | #define PA5 PIN_A5 // | 5 | A5 | | | SPI1_SCK | | #define PA6 PIN_A6 // | 6 | A6 | | | SPI1_MISO | | diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F401RC_CREALITY/ldscript.ld b/buildroot/share/PlatformIO/variants/MARLIN_F401RC_CREALITY/ldscript.ld index d12edc7197..37496e7840 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_F401RC_CREALITY/ldscript.ld +++ b/buildroot/share/PlatformIO/variants/MARLIN_F401RC_CREALITY/ldscript.ld @@ -1,8 +1,7 @@ /* ***************************************************************************** ** - -** File : LinkerScript.ld +** File : ldscript.ld ** ** Abstract : Linker script for STM32F401RETx Device with ** 512KByte FLASH, 96KByte RAM @@ -55,13 +54,13 @@ ENTRY(Reset_Handler) _estack = 0x20010000; /* end of RAM */ /* Generate a link error if heap and stack don't fit into RAM */ -_Min_Heap_Size = 0x200;; /* required amount of heap */ -_Min_Stack_Size = 0x400;; /* required amount of stack */ +_Min_Heap_Size = 0x200; /* required amount of heap */ +_Min_Stack_Size = 0x400; /* required amount of stack */ /* Specify the memory areas */ MEMORY { -FLASH (rx) : ORIGIN = 0x8000000 + LD_FLASH_OFFSET, LENGTH = LD_MAX_SIZE - LD_FLASH_OFFSET +FLASH (rx) : ORIGIN = 0x8000000 + LD_FLASH_OFFSET, LENGTH = LD_MAX_SIZE - LD_FLASH_OFFSET RAM (xrw) : ORIGIN = 0x20000000, LENGTH = 64K } @@ -150,7 +149,7 @@ SECTIONS . = ALIGN(4); .bss : { - /* This is used by the startup in order to initialize the .bss secion */ + /* This is used by the startup in order to initialize the .bss section */ _sbss = .; /* define a global symbol at bss start */ __bss_start__ = _sbss; *(.bss) diff --git a/buildroot/share/PlatformIO/variants/MARLIN_F401RC_CREALITY/variant.h b/buildroot/share/PlatformIO/variants/MARLIN_F401RC_CREALITY/variant.h index 9c5c253022..e15c21b2f2 100644 --- a/buildroot/share/PlatformIO/variants/MARLIN_F401RC_CREALITY/variant.h +++ b/buildroot/share/PlatformIO/variants/MARLIN_F401RC_CREALITY/variant.h @@ -101,7 +101,7 @@ extern "C" { // UART Definitions //#define ENABLE_HWSERIAL1 done automatically by the #define SERIAL_UART_INSTANCE below #define ENABLE_HWSERIAL2 - +#define ENABLE_HWSERIAL6 // Define here Serial instance number to map on Serial generic name (if not already used by SerialUSB) #define SERIAL_UART_INSTANCE 1 //1 for Serial = Serial1 (USART1) @@ -118,6 +118,8 @@ extern "C" { #define PIN_SERIAL1_TX PA9 #define PIN_SERIAL2_RX PA3 #define PIN_SERIAL2_TX PA2 +#define PIN_SERIAL6_RX PC7 +#define PIN_SERIAL6_TX PC6 #ifdef __cplusplus } // extern "C" From 2774ee82905eaee15c9d671f6a7f21653d572af8 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 17 Nov 2025 18:04:19 -0600 Subject: [PATCH 83/99] =?UTF-8?q?=F0=9F=8E=A8=20Misc=20patches=20from=20Pr?= =?UTF-8?q?oUI=20(2)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/config/M575.cpp | 9 ++++----- 1 file changed, 4 insertions(+), 5 deletions(-) diff --git a/Marlin/src/gcode/config/M575.cpp b/Marlin/src/gcode/config/M575.cpp index b88b372ddb..dd8f8addb5 100644 --- a/Marlin/src/gcode/config/M575.cpp +++ b/Marlin/src/gcode/config/M575.cpp @@ -51,25 +51,24 @@ void GcodeSuite::M575() { switch (baud) { case 2400: case 9600: case 19200: case 38400: case 57600: case 115200: case 250000: case 500000: case 1000000: { - const int8_t port = parser.intval('P', -99); - const bool set1 = (port == -99 || port == 0); - SERIAL_FLUSH(); + const int8_t port = parser.intval('P', -99); + const bool set1 = (port == -99 || port == 0); if (set1) { MYSERIAL1.end(); MYSERIAL1.begin(baud); } #if HAS_MULTI_SERIAL + const bool set2 = (port == -99 || port == 1); if (set2) { MYSERIAL2.end(); MYSERIAL2.begin(baud); } #ifdef SERIAL_PORT_3 + const bool set3 = (port == -99 || port == 2); if (set3) { MYSERIAL3.end(); MYSERIAL3.begin(baud); } #endif #endif if (set1) SERIAL_ECHO_MSG(" Serial ", AS_DIGIT(0), " baud rate set to ", baud); #if HAS_MULTI_SERIAL - const bool set2 = (port == -99 || port == 1); if (set2) SERIAL_ECHO_MSG(" Serial ", AS_DIGIT(1), " baud rate set to ", baud); #ifdef SERIAL_PORT_3 - const bool set3 = (port == -99 || port == 2); if (set3) SERIAL_ECHO_MSG(" Serial ", AS_DIGIT(2), " baud rate set to ", baud); #endif #endif From 9788a351077a9e0fbcf60b572647e42dc33bae05 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 17 Nov 2025 18:07:49 -0600 Subject: [PATCH 84/99] =?UTF-8?q?=F0=9F=A9=B9=20Commas=20for=20devcontaine?= =?UTF-8?q?r.json?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .devcontainer/devcontainer.json | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/.devcontainer/devcontainer.json b/.devcontainer/devcontainer.json index 77479946b5..96d6af1932 100644 --- a/.devcontainer/devcontainer.json +++ b/.devcontainer/devcontainer.json @@ -41,11 +41,11 @@ ] // Use 'forwardPorts' to make a list of ports inside the container available locally. - // "forwardPorts": [], + // , "forwardPorts": [] // Use 'postCreateCommand' to run commands after the container is created. - // "postCreateCommand": "pip3 install --user -r requirements.txt", + // , "postCreateCommand": "pip3 install --user -r requirements.txt" // Comment out connect as root instead. More info: https://aka.ms/vscode-remote/containers/non-root. - // "remoteUser": "vscode" + // , "remoteUser": "vscode" } From 646f4c7d692f17933223eb23d30bfff58279f2c0 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Tue, 18 Nov 2025 00:38:53 +0000 Subject: [PATCH 85/99] [cron] Bump distribution date (2025-11-18) --- 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 6675411f3e..74efd4011b 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 "2025-11-17" +//#define STRING_DISTRIBUTION_DATE "2025-11-18" /** * The protocol for communication to the host. Protocol indicates communication diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index ea3a802a09..e8f66b735d 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 "2025-11-17" + #define STRING_DISTRIBUTION_DATE "2025-11-18" #endif /** From 543af426ef41c23ef0230675b4a0e1383bcf6558 Mon Sep 17 00:00:00 2001 From: Giuliano <3684609+GMagician@users.noreply.github.com> Date: Tue, 18 Nov 2025 01:40:59 +0100 Subject: [PATCH 86/99] =?UTF-8?q?=F0=9F=8C=90=20Update=20Italian=20transla?= =?UTF-8?q?tion=20(#28177)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/language/language_it.h | 46 ++++++++++++++++++++++++++- 1 file changed, 45 insertions(+), 1 deletion(-) diff --git a/Marlin/src/lcd/language/language_it.h b/Marlin/src/lcd/language/language_it.h index df42e1ef3b..3f45c44156 100644 --- a/Marlin/src/lcd/language/language_it.h +++ b/Marlin/src/lcd/language/language_it.h @@ -460,6 +460,10 @@ namespace LanguageNarrow_it { LSTR MSG_E_STEPS = _UxGT("E passi/mm"); LSTR MSG_EN_STEPS = _UxGT("* passi/mm"); LSTR MSG_TEMPERATURE = _UxGT("Temperatura"); + LSTR MSG_FTM_TRAPEZOIDAL = _UxGT("Trapezoidale"); + LSTR MSG_FTM_POLY5 = _UxGT("5° ordine"); + LSTR MSG_FTM_POLY6 = _UxGT("6° ordine"); + LSTR MSG_FTM_TRAJECTORY = _UxGT("Traiettoria: $"); LSTR MSG_MOTION = _UxGT("Movimento"); LSTR MSG_FILAMENT = _UxGT("Filamento"); LSTR MSG_FILAMENT_EN = _UxGT("Filamento *"); @@ -481,6 +485,7 @@ namespace LanguageNarrow_it { LSTR MSG_ADVANCE_TAU = _UxGT("Tau advance"); LSTR MSG_ADVANCE_K_E = _UxGT("K advance *"); LSTR MSG_ADVANCE_TAU_E = _UxGT("Tau advance *"); + LSTR MSG_NLE_ON = _UxGT("NLE abilitato"); LSTR MSG_CONTRAST = _UxGT("Contrasto LCD"); LSTR MSG_BRIGHTNESS = _UxGT("Luminosità LCD"); LSTR MSG_SCREEN_TIMEOUT = _UxGT("Timeout LCD (m)"); @@ -745,6 +750,7 @@ namespace LanguageNarrow_it { LSTR MSG_RUNOUT_SENSOR = _UxGT("Sens.filo termin."); // Max 17 characters LSTR MSG_SENSOR = _UxGT("Sensore"); LSTR MSG_RUNOUT_DISTANCE_MM = _UxGT("Dist mm filo term."); + LSTR MSG_MOTION_DISTANCE_MM = _UxGT("Dist mm movimento"); LSTR MSG_EXTRUDER_MIN_TEMP = _UxGT("Temp.min estrusore"); // ProUI LSTR MSG_FANCHECK = _UxGT("Verif.tacho vent."); // Max 17 characters LSTR MSG_KILL_HOMING_FAILED = _UxGT("Home fallito"); @@ -888,8 +894,9 @@ namespace LanguageNarrow_it { LSTR MSG_BACKLASH_CORRECTION = _UxGT("Correzione"); LSTR MSG_BACKLASH_SMOOTHING = _UxGT("Appianamento"); - LSTR MSG_FIXED_TIME_MOTION = _UxGT("Movimento a Tempo-Fisso"); + LSTR MSG_FIXED_TIME_MOTION = _UxGT("Movim.Tempo-Fisso"); LSTR MSG_FTM_CMPN_MODE = _UxGT("@ Modo Comp: $"); + LSTR MSG_FTM_AXIS_SYNC = _UxGT("Sinc. Asse"); LSTR MSG_FTM_DYN_MODE = _UxGT("Modo DF: $"); LSTR MSG_FTM_Z_BASED = _UxGT("Base-Z"); LSTR MSG_FTM_MASS_BASED = _UxGT("Base-Massa"); @@ -897,6 +904,16 @@ namespace LanguageNarrow_it { LSTR MSG_FTM_DFREQ_K_N = _UxGT("@ Freq. dinam."); LSTR MSG_FTM_ZETA_N = _UxGT("Smorzamento @"); LSTR MSG_FTM_VTOL_N = _UxGT("Livello vib. @"); + LSTR MSG_FTM_SMOOTH_TIME_N = _UxGT("@ Tempo smorzamento"); + LSTR MSG_FTM_POLY6_OVERSHOOT = _UxGT("@ Overshoot Poly6"); + + LSTR MSG_FTM_RESONANCE_TEST = _UxGT("Test risonanza"); + LSTR MSG_FTM_RT_RUNNING = _UxGT("Test ris.in corso..."); + LSTR MSG_FTM_RT_START_N = _UxGT("Avvia Test Asse @"); + LSTR MSG_FTM_RT_STOP = _UxGT("Annulla Test"); + LSTR MSG_FTM_RETRIEVE_FREQ = _UxGT("Calc. Res. Freq."); + LSTR MSG_FTM_RESONANCE_FREQ = _UxGT("Freq.Risonanza"); + LSTR MSG_FTM_TIMELINE_FREQ = _UxGT("Cronologia (s)"); LSTR MSG_LEVEL_X_AXIS = _UxGT("Livello asse X"); LSTR MSG_AUTO_CALIBRATE = _UxGT("Auto Calibra"); @@ -955,6 +972,33 @@ namespace LanguageNarrow_it { LSTR DGUS_MSG_READ_EEPROM_FAILED = _UxGT("Lettura EEPROM fallita"); LSTR DGUS_MSG_FILAMENT_RUNOUT = _UxGT("Filament runout E%d"); + // + // MMU3 Translatable Strings + // + + LSTR MSG_DESC_FINDA_DIDNT_TRIGGER = _UxGT("FINDA non si è attivato durante il caricamento del filamento. Assicurarsi che il filamento possa muoversi e che FINDA funzioni."); + LSTR MSG_DESC_FINDA_FILAMENT_STUCK = _UxGT("FINDA non si è disattivato durante lo scaricamento del filamento. Provare a scaricarlo manualmente. Assicurarsi che il filamento si muova e che FINDA funzioni."); + LSTR MSG_DESC_FSENSOR_DIDNT_TRIGGER = _UxGT("Il sensore del filamento non si è attivato durante il caricamento del filamento. Assicurarsi che il sensore sia calibrato e che il filamento lo abbia raggiunto."); + LSTR MSG_DESC_FSENSOR_FILAMENT_STUCK = _UxGT("Il sensore del filamento non si è disattivato durante lo scaricamento del filamento. Assicurarsi che il filamento possa muoversi e che il sensore funzioni."); + LSTR MSG_DESC_PULLEY_CANNOT_MOVE = _UxGT("Il motore della puleggia è bloccato. Assicurarsi che la puleggia possa muoversi e controllare il cablaggio."); + LSTR MSG_DESC_FSENSOR_TOO_EARLY = _UxGT("Il sensore del filamento si è attivato troppo presto durante il caricamento nell'estrusore. Verificare che non vi sia nulla incastrato nel tubo in PTFE. Verificare che il sensore legga correttamente."); + LSTR MSG_DESC_INSPECT_FINDA = _UxGT("Il selettore non si muove perché FINDA ha rilevato un filamento. Assicurarsi che non vi sia alcun filamento nel selettore e che FINDA funzioni correttamente."); + LSTR MSG_DESC_LOAD_TO_EXTRUDER_FAILED = _UxGT("Caricamento nell'estrusore non riuscito. Ispezionare la forma della punta del filamento. Se necessario, perfezionare la calibrazione del sensore."); + LSTR MSG_DESC_SELECTOR_CANNOT_HOME = _UxGT("Il selettore non riesce a tornare correttamente in posizione iniziale. Verificare che non vi siano ostacoli al suo movimento."); + LSTR MSG_DESC_CANNOT_MOVE = _UxGT("Impossibile spostare il selettore o il tendicinghia."); + LSTR MSG_DESC_IDLER_CANNOT_HOME = _UxGT("Il tendicinghi non riesce a tornare correttamente in posizione iniziale. Controllare che non ci siano ostacoli al suo movimento."); + LSTR MSG_DESC_TMC = _UxGT("Maggiori dettagli online."); + LSTR MSG_DESC_MMU_NOT_RESPONDING = _UxGT("La MMU non risponde. Controllare il cablaggio e i connettori."); + LSTR MSG_DESC_COMMUNICATION_ERROR = _UxGT("La MMU non risponde correttamente. Controllare il cablaggio e i connettori."); + LSTR MSG_DESC_FILAMENT_ALREADY_LOADED = _UxGT("Impossibile eseguire l'azione, il filamento è già caricato. Scaricarlo prima."); + LSTR MSG_DESC_INVALID_TOOL = _UxGT("L'utensile per il filamento richiesto non è disponibile su questo hardware. Controllare il codice G per verificare per l'indice non compreso nell'intervallo (T0-T4)."); + LSTR MSG_DESC_QUEUE_FULL = _UxGT("Errore interno del firmware MMU, resetrtare la MMU."); + LSTR MSG_DESC_FW_RUNTIME_ERROR = _UxGT("Errore di runtime interno. Provare a reimpostare la MMU o ad aggiornare il firmware."); + LSTR MSG_DESC_UNLOAD_MANUALLY = _UxGT("Filamento rilevato in modo imprevisto. Assicurarsi che non vi sia alcun filamento caricato. Controllare il sensore ed il cablaggio."); + LSTR MSG_DESC_FILAMENT_EJECTED = _UxGT("Rimuovere il filamento espulso dalla parte anteriore della MMU."); + LSTR MSG_DESC_FILAMENT_CHANGE = _UxGT("Sostituzione del filamento M600. Carica un nuovo filamento o espelli quello vecchio."); + LSTR MSG_DESC_UNKNOWN_ERROR = _UxGT("Si è verificato un errore imprevisto."); + LSTR MSG_DESC_FW_UPDATE_NEEDED = _UxGT("LA versione di FW della MMU non è supportato. Aggiornare alla versione " STRINGIFY(mmuVersionMajor) "." STRINGIFY(mmuVersionMinor) "." STRINGIFY(mmuVersionPatch) "."); LSTR MSG_BTN_RETRY = _UxGT("Riprova"); From 85b82e3ab6593e6a66bf6a2c498c84d2949aefdc Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 17 Nov 2025 19:13:45 -0600 Subject: [PATCH 87/99] =?UTF-8?q?=F0=9F=8E=A8=20Misc.=20ws=20and=20formatt?= =?UTF-8?q?ing?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/SAMD21/timers.cpp | 2 +- Marlin/src/HAL/STM32/HAL.cpp | 4 ++-- Marlin/src/lcd/HD44780/marlinui_HD44780.cpp | 4 ++-- Marlin/src/lcd/dogm/u8g/u8g_dev_ssd1309_12864.cpp | 2 +- Marlin/src/lcd/dogm/u8g/u8g_dev_st7565_64128n_HAL.cpp | 2 +- Marlin/src/lcd/dogm/u8g/u8g_dev_st7920_128x64_HAL.cpp | 2 +- Marlin/src/lcd/dogm/u8g/u8g_dev_uc1701_mini12864_HAL.cpp | 2 +- 7 files changed, 9 insertions(+), 9 deletions(-) diff --git a/Marlin/src/HAL/SAMD21/timers.cpp b/Marlin/src/HAL/SAMD21/timers.cpp index 4ec6e5d867..21a1767fc0 100644 --- a/Marlin/src/HAL/SAMD21/timers.cpp +++ b/Marlin/src/HAL/SAMD21/timers.cpp @@ -165,7 +165,7 @@ void HAL_timer_start(const uint8_t timer_num, const uint32_t frequency) { tc->COUNT32.INTENCLR.reg = TC_INTENCLR_OVF; // disable overflow interrupt // TCn clock setup - GCLK->CLKCTRL.reg = (uint16_t) (GCLK_CLKCTRL_CLKEN | GCLK_CLKCTRL_GEN_GCLK0 | GCLK_CLKCTRL_ID(GCM_TC4_TC5)) ; + GCLK->CLKCTRL.reg = uint16_t(GCLK_CLKCTRL_CLKEN | GCLK_CLKCTRL_GEN_GCLK0 | GCLK_CLKCTRL_ID(GCM_TC4_TC5)); SYNC (GCLK->STATUS.bit.SYNCBUSY); tcReset(tc); // reset TC diff --git a/Marlin/src/HAL/STM32/HAL.cpp b/Marlin/src/HAL/STM32/HAL.cpp index b2ae10d0f1..018fb48881 100644 --- a/Marlin/src/HAL/STM32/HAL.cpp +++ b/Marlin/src/HAL/STM32/HAL.cpp @@ -114,7 +114,7 @@ void MarlinHAL::idletask() { void MarlinHAL::reboot() { NVIC_SystemReset(); } uint8_t MarlinHAL::get_reset_source() { - return + return ( #ifdef RCC_FLAG_IWDGRST // Some sources may not exist... RESET != __HAL_RCC_GET_FLAG(RCC_FLAG_IWDGRST) ? RST_WATCHDOG : #endif @@ -134,7 +134,7 @@ uint8_t MarlinHAL::get_reset_source() { RESET != __HAL_RCC_GET_FLAG(RCC_FLAG_PORRST) ? RST_POWER_ON : #endif 0 - ; + ); } void MarlinHAL::clear_reset_source() { __HAL_RCC_CLEAR_RESET_FLAGS(); } diff --git a/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp b/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp index fe4b0e5aa7..fd45c41ba1 100644 --- a/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp +++ b/Marlin/src/lcd/HD44780/marlinui_HD44780.cpp @@ -452,11 +452,11 @@ bool MarlinUI::detected() { #if ENABLED(LCD_I2C_TYPE_MCP23017) // Reading these buttons is too slow for interrupt context // so they are read during LCD update in the main loop. - uint8_t slow_bits = lcd.readButtons() + uint8_t slow_bits = (lcd.readButtons() #if !BUTTON_EXISTS(ENC) << B_I2C_BTN_OFFSET #endif - ; + ); #if ENABLED(LCD_I2C_VIKI) if ((slow_bits & (B_MI | B_RI)) && PENDING(millis(), next_button_update_ms)) // LCD clicked slow_bits &= ~(B_MI | B_RI); // Disable LCD clicked buttons if screen is updated diff --git a/Marlin/src/lcd/dogm/u8g/u8g_dev_ssd1309_12864.cpp b/Marlin/src/lcd/dogm/u8g/u8g_dev_ssd1309_12864.cpp index db9437d034..419c91915b 100644 --- a/Marlin/src/lcd/dogm/u8g/u8g_dev_ssd1309_12864.cpp +++ b/Marlin/src/lcd/dogm/u8g/u8g_dev_ssd1309_12864.cpp @@ -144,7 +144,7 @@ uint8_t u8g_dev_ssd1309_128x64_fn(u8g_t *u8g, u8g_dev_t *dev, uint8_t msg, void return u8g_dev_pb8v1_base_fn(u8g, dev, msg, arg); } -uint8_t u8g_dev_ssd1309_buf[WIDTH*2] U8G_NOCOMMON ; +uint8_t u8g_dev_ssd1309_buf[WIDTH*2] U8G_NOCOMMON; u8g_pb_t u8g_dev_ssd1309_pb = { {8, HEIGHT, 0, 0, 0}, WIDTH, u8g_dev_ssd1309_buf}; u8g_dev_t u8g_dev_ssd1309_sw_spi = { u8g_dev_ssd1309_128x64_fn, &u8g_dev_ssd1309_pb, U8G_COM_HAL_SW_SPI_FN }; diff --git a/Marlin/src/lcd/dogm/u8g/u8g_dev_st7565_64128n_HAL.cpp b/Marlin/src/lcd/dogm/u8g/u8g_dev_st7565_64128n_HAL.cpp index 5f69680d01..8cf66427c4 100644 --- a/Marlin/src/lcd/dogm/u8g/u8g_dev_st7565_64128n_HAL.cpp +++ b/Marlin/src/lcd/dogm/u8g/u8g_dev_st7565_64128n_HAL.cpp @@ -230,7 +230,7 @@ uint8_t u8g_dev_st7565_64128n_HAL_2x_fn(u8g_t *u8g, u8g_dev_t *dev, const uint8_ U8G_PB_DEV(u8g_dev_st7565_64128n_HAL_sw_spi, WIDTH, HEIGHT, PAGE_HEIGHT, u8g_dev_st7565_64128n_HAL_fn, U8G_COM_HAL_SW_SPI_FN); -uint8_t u8g_dev_st7565_64128n_HAL_2x_buf[WIDTH*2] U8G_NOCOMMON ; +uint8_t u8g_dev_st7565_64128n_HAL_2x_buf[WIDTH*2] U8G_NOCOMMON; u8g_pb_t u8g_dev_st7565_64128n_HAL_2x_pb = { {16, HEIGHT, 0, 0, 0}, WIDTH, u8g_dev_st7565_64128n_HAL_2x_buf}; u8g_dev_t u8g_dev_st7565_64128n_HAL_2x_sw_spi = { u8g_dev_st7565_64128n_HAL_2x_fn, &u8g_dev_st7565_64128n_HAL_2x_pb, U8G_COM_HAL_SW_SPI_FN }; diff --git a/Marlin/src/lcd/dogm/u8g/u8g_dev_st7920_128x64_HAL.cpp b/Marlin/src/lcd/dogm/u8g/u8g_dev_st7920_128x64_HAL.cpp index 76d15ce8a2..e299761016 100644 --- a/Marlin/src/lcd/dogm/u8g/u8g_dev_st7920_128x64_HAL.cpp +++ b/Marlin/src/lcd/dogm/u8g/u8g_dev_st7920_128x64_HAL.cpp @@ -192,7 +192,7 @@ uint8_t u8g_dev_st7920_128x64_HAL_4x_fn(u8g_t *u8g, u8g_dev_t *dev, uint8_t msg, U8G_PB_DEV(u8g_dev_st7920_128x64_HAL_sw_spi, LCD_PIXEL_WIDTH, LCD_PIXEL_HEIGHT, PAGE_HEIGHT, u8g_dev_st7920_128x64_HAL_fn, U8G_COM_ST7920_HAL_SW_SPI); #define QWIDTH ((LCD_PIXEL_WIDTH) * 4) -uint8_t u8g_dev_st7920_128x64_HAL_4x_buf[QWIDTH] U8G_NOCOMMON ; +uint8_t u8g_dev_st7920_128x64_HAL_4x_buf[QWIDTH] U8G_NOCOMMON; u8g_pb_t u8g_dev_st7920_128x64_HAL_4x_pb = { { 32, LCD_PIXEL_HEIGHT, 0, 0, 0 }, LCD_PIXEL_WIDTH, u8g_dev_st7920_128x64_HAL_4x_buf}; u8g_dev_t u8g_dev_st7920_128x64_HAL_4x_sw_spi = { u8g_dev_st7920_128x64_HAL_4x_fn, &u8g_dev_st7920_128x64_HAL_4x_pb, U8G_COM_ST7920_HAL_SW_SPI }; diff --git a/Marlin/src/lcd/dogm/u8g/u8g_dev_uc1701_mini12864_HAL.cpp b/Marlin/src/lcd/dogm/u8g/u8g_dev_uc1701_mini12864_HAL.cpp index 1d1291ff9a..6f93c31643 100644 --- a/Marlin/src/lcd/dogm/u8g/u8g_dev_uc1701_mini12864_HAL.cpp +++ b/Marlin/src/lcd/dogm/u8g/u8g_dev_uc1701_mini12864_HAL.cpp @@ -205,7 +205,7 @@ uint8_t u8g_dev_uc1701_mini12864_HAL_2x_fn(u8g_t *u8g, u8g_dev_t *dev, uint8_t m U8G_PB_DEV(u8g_dev_uc1701_mini12864_HAL_sw_spi, WIDTH, HEIGHT, PAGE_HEIGHT, u8g_dev_uc1701_mini12864_HAL_fn, U8G_COM_HAL_SW_SPI_FN); U8G_PB_DEV(u8g_dev_uc1701_mini12864_HAL_hw_spi, WIDTH, HEIGHT, PAGE_HEIGHT, u8g_dev_uc1701_mini12864_HAL_fn, U8G_COM_HAL_HW_SPI_FN); -uint8_t u8g_dev_uc1701_mini12864_HAL_2x_buf[WIDTH*2] U8G_NOCOMMON ; +uint8_t u8g_dev_uc1701_mini12864_HAL_2x_buf[WIDTH*2] U8G_NOCOMMON; u8g_pb_t u8g_dev_uc1701_mini12864_HAL_2x_pb = { {16, HEIGHT, 0, 0, 0}, WIDTH, u8g_dev_uc1701_mini12864_HAL_2x_buf}; u8g_dev_t u8g_dev_uc1701_mini12864_HAL_2x_sw_spi = { u8g_dev_uc1701_mini12864_HAL_2x_fn, &u8g_dev_uc1701_mini12864_HAL_2x_pb, U8G_COM_HAL_SW_SPI_FN }; u8g_dev_t u8g_dev_uc1701_mini12864_HAL_2x_hw_spi = { u8g_dev_uc1701_mini12864_HAL_2x_fn, &u8g_dev_uc1701_mini12864_HAL_2x_pb, U8G_COM_HAL_HW_SPI_FN }; From 402aab968ced932eb6fd3574dac899a88c90317a Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Wed, 19 Nov 2025 00:33:07 +0000 Subject: [PATCH 88/99] [cron] Bump distribution date (2025-11-19) --- 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 74efd4011b..56a03d5885 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 "2025-11-18" +//#define STRING_DISTRIBUTION_DATE "2025-11-19" /** * The protocol for communication to the host. Protocol indicates communication diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index e8f66b735d..293dee7ad6 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 "2025-11-18" + #define STRING_DISTRIBUTION_DATE "2025-11-19" #endif /** From 06c6c479dd048d18445097b04557a7d90ad1f4fa Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 19 Nov 2025 21:42:43 -0600 Subject: [PATCH 89/99] =?UTF-8?q?=F0=9F=9A=B8=20Immediate=20Buttons=20and?= =?UTF-8?q?=20Menu=20Items=20(#28180)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration_adv.h | 13 +++ Marlin/src/HAL/HC32/inc/SanityCheck.h | 2 +- Marlin/src/HAL/HC32/sysclock.cpp | 2 +- Marlin/src/MarlinCore.cpp | 8 +- Marlin/src/lcd/e3v2/jyersui/dwin.cpp | 75 +++++++++-------- .../generic/custom_user_menus.cpp | 81 ++++++++++--------- .../generic/endstop_state_screen.cpp | 10 ++- Marlin/src/lcd/extui/mks_ui/draw_more.cpp | 13 +-- Marlin/src/lcd/extui/ui_api.h | 2 + Marlin/src/lcd/menu/menu.h | 4 + Marlin/src/lcd/menu/menu_configuration.cpp | 8 +- Marlin/src/lcd/menu/menu_item.h | 16 ++++ Marlin/src/lcd/menu/menu_main.cpp | 19 ++++- buildroot/tests/STM32F103RE_btt_USB | 6 +- 14 files changed, 157 insertions(+), 102 deletions(-) diff --git a/Marlin/Configuration_adv.h b/Marlin/Configuration_adv.h index 2e0f7f14fb..c5ed503b4c 100644 --- a/Marlin/Configuration_adv.h +++ b/Marlin/Configuration_adv.h @@ -4123,22 +4123,27 @@ #define MAIN_MENU_ITEM_1_DESC "Home & UBL Info" #define MAIN_MENU_ITEM_1_GCODE "G28\nG29 W" //#define MAIN_MENU_ITEM_1_CONFIRM // Show a confirmation dialog before this action + //#define MAIN_MENU_ITEM_1_IMMEDIATE // Skip the queue and execute immediately. Rarely needed. #define MAIN_MENU_ITEM_2_DESC "Preheat for " PREHEAT_1_LABEL #define MAIN_MENU_ITEM_2_GCODE "M140 S" STRINGIFY(PREHEAT_1_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_1_TEMP_HOTEND) //#define MAIN_MENU_ITEM_2_CONFIRM + //#define MAIN_MENU_ITEM_2_IMMEDIATE //#define MAIN_MENU_ITEM_3_DESC "Preheat for " PREHEAT_2_LABEL //#define MAIN_MENU_ITEM_3_GCODE "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_2_TEMP_HOTEND) //#define MAIN_MENU_ITEM_3_CONFIRM + //#define MAIN_MENU_ITEM_3_IMMEDIATE //#define MAIN_MENU_ITEM_4_DESC "Heat Bed/Home/Level" //#define MAIN_MENU_ITEM_4_GCODE "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nG28\nG29" //#define MAIN_MENU_ITEM_4_CONFIRM + //#define MAIN_MENU_ITEM_4_IMMEDIATE //#define MAIN_MENU_ITEM_5_DESC "Home & Info" //#define MAIN_MENU_ITEM_5_GCODE "G28\nM503" //#define MAIN_MENU_ITEM_5_CONFIRM + //#define MAIN_MENU_ITEM_5_IMMEDIATE #endif // @section custom config menu @@ -4155,22 +4160,27 @@ #define CONFIG_MENU_ITEM_1_DESC "Wifi ON" #define CONFIG_MENU_ITEM_1_GCODE "M118 [ESP110] WIFI-STA pwd=12345678" //#define CONFIG_MENU_ITEM_1_CONFIRM // Show a confirmation dialog before this action + //#define CONFIG_MENU_ITEM_1_IMMEDIATE // Skip the queue and execute immediately. Rarely needed. #define CONFIG_MENU_ITEM_2_DESC "Bluetooth ON" #define CONFIG_MENU_ITEM_2_GCODE "M118 [ESP110] BT pwd=12345678" //#define CONFIG_MENU_ITEM_2_CONFIRM + //#define CONFIG_MENU_ITEM_2_IMMEDIATE //#define CONFIG_MENU_ITEM_3_DESC "Radio OFF" //#define CONFIG_MENU_ITEM_3_GCODE "M118 [ESP110] OFF pwd=12345678" //#define CONFIG_MENU_ITEM_3_CONFIRM + //#define CONFIG_MENU_ITEM_3_IMMEDIATE //#define CONFIG_MENU_ITEM_4_DESC "Wifi ????" //#define CONFIG_MENU_ITEM_4_GCODE "M118 ????" //#define CONFIG_MENU_ITEM_4_CONFIRM + //#define CONFIG_MENU_ITEM_4_IMMEDIATE //#define CONFIG_MENU_ITEM_5_DESC "Wifi ????" //#define CONFIG_MENU_ITEM_5_GCODE "M118 ????" //#define CONFIG_MENU_ITEM_5_CONFIRM + //#define CONFIG_MENU_ITEM_5_IMMEDIATE #endif // @section custom buttons @@ -4187,6 +4197,7 @@ #define BUTTON1_WHEN_PRINTING false // Button allowed to trigger during printing? #define BUTTON1_GCODE "G28" #define BUTTON1_DESC "Homing" // Optional string to set the LCD status + //#define BUTTON1_IMMEDIATE // Skip the queue and run the G-code immediately. Rarely needed. #endif //#define BUTTON2_PIN -1 @@ -4195,6 +4206,7 @@ #define BUTTON2_WHEN_PRINTING false #define BUTTON2_GCODE "M140 S" STRINGIFY(PREHEAT_1_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_1_TEMP_HOTEND) #define BUTTON2_DESC "Preheat for " PREHEAT_1_LABEL + //#define BUTTON2_IMMEDIATE #endif //#define BUTTON3_PIN -1 @@ -4203,6 +4215,7 @@ #define BUTTON3_WHEN_PRINTING false #define BUTTON3_GCODE "M140 S" STRINGIFY(PREHEAT_2_TEMP_BED) "\nM104 S" STRINGIFY(PREHEAT_2_TEMP_HOTEND) #define BUTTON3_DESC "Preheat for " PREHEAT_2_LABEL + //#define BUTTON3_IMMEDIATE #endif #endif diff --git a/Marlin/src/HAL/HC32/inc/SanityCheck.h b/Marlin/src/HAL/HC32/inc/SanityCheck.h index e38bce91e5..c6b3b221df 100644 --- a/Marlin/src/HAL/HC32/inc/SanityCheck.h +++ b/Marlin/src/HAL/HC32/inc/SanityCheck.h @@ -83,7 +83,7 @@ #error "POSTMORTEM_DEBUGGING requires CORE_DISABLE_FAULT_HANDLER to be set." #endif -#if defined(PANIC_ENABLE) +#ifdef 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 diff --git a/Marlin/src/HAL/HC32/sysclock.cpp b/Marlin/src/HAL/HC32/sysclock.cpp index 493515b0e8..e98395c42e 100644 --- a/Marlin/src/HAL/HC32/sysclock.cpp +++ b/Marlin/src/HAL/HC32/sysclock.cpp @@ -171,7 +171,7 @@ void core_hook_sysclock_init() { panic("HRC is not 16 MHz"); } - #if defined(BOARD_XTAL_FREQUENCY) + #ifdef BOARD_XTAL_FREQUENCY #warning "No valid XTAL frequency defined, falling back to HRC." #endif diff --git a/Marlin/src/MarlinCore.cpp b/Marlin/src/MarlinCore.cpp index 175fd0c315..cb81efc4bb 100644 --- a/Marlin/src/MarlinCore.cpp +++ b/Marlin/src/MarlinCore.cpp @@ -531,11 +531,15 @@ inline void manage_inactivity(const bool no_stepper_sleep=false) { constexpr millis_t CUB_DEBOUNCE_DELAY_##N = 250UL; \ static millis_t next_cub_ms_##N; \ if (BUTTON##N##_HIT_STATE == READ(BUTTON##N##_PIN) \ - && (ENABLED(BUTTON##N##_WHEN_PRINTING) || printer_not_busy)) { \ + && (ENABLED(BUTTON##N##_WHEN_PRINTING) || printer_not_busy) \ + ) { \ if (ELAPSED(ms, next_cub_ms_##N)) { \ next_cub_ms_##N = ms + CUB_DEBOUNCE_DELAY_##N; \ CODE; \ - queue.inject(F(BUTTON##N##_GCODE)); \ + if (ENABLED(BUTTON##N##_IMMEDIATE)) \ + gcode.process_subcommands_now(F(BUTTON##N##_GCODE)); \ + else \ + queue.inject(F(BUTTON##N##_GCODE)); \ TERN_(HAS_MARLINUI_MENU, ui.quick_feedback()); \ } \ } \ diff --git a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp index 2870524dea..dbda3cd225 100644 --- a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp @@ -266,7 +266,7 @@ private: uint8_t tilt_grid = 1; void manualValueUpdate(bool undefined=false) { - gcode.process_subcommands_now( + queue.inject( TS(F("M421I"), mesh_x, 'J', mesh_y, 'Z', p_float_t(current_position.z, 3), undefined ? "N" : "") ); planner.synchronize(); @@ -313,7 +313,7 @@ private: #else void manualValueUpdate() { - gcode.process_subcommands_now( + queue.inject( TS(F("G29I"), mesh_x, 'J', mesh_y, 'Z', p_float_t(current_position.z, 3)) ); planner.synchronize(); @@ -1176,7 +1176,7 @@ void JyersDWIN::menuItemHandler(const uint8_t menu, const uint8_t item, bool dra thermalManager.wait_for_hotend(0); } popupHandler(Popup_FilChange); - gcode.process_subcommands_now(TS(F("M600 B1 R"), thermalManager.degTargetHotend(0))); + queue.inject(TS(F("M600 B1 R"), thermalManager.degTargetHotend(0))); } #endif } @@ -1225,7 +1225,7 @@ void JyersDWIN::menuItemHandler(const uint8_t menu, const uint8_t item, bool dra drawMenuItem(row, ICON_MoveX, GET_TEXT_F(MSG_AUTO_HOME_X)); else { popupHandler(Popup_Home); - gcode.process_subcommands_now(F("G28X")); + queue.inject(F("G28X")); planner.synchronize(); redrawMenu(); } @@ -1235,7 +1235,7 @@ void JyersDWIN::menuItemHandler(const uint8_t menu, const uint8_t item, bool dra drawMenuItem(row, ICON_MoveY, GET_TEXT_F(MSG_AUTO_HOME_X)); else { popupHandler(Popup_Home); - gcode.process_subcommands_now(F("G28Y")); + queue.inject(F("G28Y")); planner.synchronize(); redrawMenu(); } @@ -1245,7 +1245,7 @@ void JyersDWIN::menuItemHandler(const uint8_t menu, const uint8_t item, bool dra drawMenuItem(row, ICON_MoveZ, GET_TEXT_F(MSG_AUTO_HOME_X)); else { popupHandler(Popup_Home); - gcode.process_subcommands_now(F("G28Z")); + queue.inject(F("G28Z")); planner.synchronize(); redrawMenu(); } @@ -1254,7 +1254,7 @@ void JyersDWIN::menuItemHandler(const uint8_t menu, const uint8_t item, bool dra if (draw) drawMenuItem(row, ICON_SetHome, F("Set Home Here")); else { - gcode.process_subcommands_now(F("G92X0Y0Z0")); + queue.inject(F("G92X0Y0Z0")); audioFeedback(); } break; @@ -1577,7 +1577,7 @@ void JyersDWIN::menuItemHandler(const uint8_t menu, const uint8_t item, bool dra drawMenuItem(row, ICON_Homing, GET_TEXT_F(MSG_AUTO_HOME_Z)); else { popupHandler(Popup_Home); - gcode.process_subcommands_now(F("G28Z")); + queue.inject(F("G28Z")); popupHandler(Popup_MoveWait); #if ENABLED(Z_SAFE_HOMING) planner.synchronize(); @@ -1809,8 +1809,7 @@ void JyersDWIN::menuItemHandler(const uint8_t menu, const uint8_t item, bool dra drawMenuItem(row, ICON_Info, F(CONFIG_MENU_ITEM_1_DESC)); else { popupHandler(Popup_Custom); - //queue.inject(F(CONFIG_MENU_ITEM_1_GCODE)); // Old code - gcode.process_subcommands_now(F(CONFIG_MENU_ITEM_1_GCODE)); + TERN(CONFIG_MENU_ITEM_1_IMMEDIATE, gcode.process_subcommands_now, queue.inject)(F(CONFIG_MENU_ITEM_1_GCODE)); planner.synchronize(); redrawMenu(); #if ENABLED(CUSTOM_MENU_CONFIG_SCRIPT_AUDIBLE_FEEDBACK) @@ -1829,7 +1828,7 @@ void JyersDWIN::menuItemHandler(const uint8_t menu, const uint8_t item, bool dra drawMenuItem(row, ICON_Info, F(CONFIG_MENU_ITEM_2_DESC)); else { popupHandler(Popup_Custom); - gcode.process_subcommands_now(F(CONFIG_MENU_ITEM_2_GCODE)); + TERN(CONFIG_MENU_ITEM_1_IMMEDIATE, gcode.process_subcommands_now, queue.inject)(F(CONFIG_MENU_ITEM_2_GCODE)); planner.synchronize(); redrawMenu(); #if ENABLED(CUSTOM_MENU_CONFIG_SCRIPT_AUDIBLE_FEEDBACK) @@ -1848,7 +1847,7 @@ void JyersDWIN::menuItemHandler(const uint8_t menu, const uint8_t item, bool dra drawMenuItem(row, ICON_Info, F(CONFIG_MENU_ITEM_3_DESC)); else { popupHandler(Popup_Custom); - gcode.process_subcommands_now(F(CONFIG_MENU_ITEM_3_GCODE)); + TERN(CONFIG_MENU_ITEM_1_IMMEDIATE, gcode.process_subcommands_now, queue.inject)(F(CONFIG_MENU_ITEM_3_GCODE)); planner.synchronize(); redrawMenu(); #if ENABLED(CUSTOM_MENU_CONFIG_SCRIPT_AUDIBLE_FEEDBACK) @@ -1867,7 +1866,7 @@ void JyersDWIN::menuItemHandler(const uint8_t menu, const uint8_t item, bool dra drawMenuItem(row, ICON_Info, F(CONFIG_MENU_ITEM_4_DESC)); else { popupHandler(Popup_Custom); - gcode.process_subcommands_now(F(CONFIG_MENU_ITEM_4_GCODE)); + TERN(CONFIG_MENU_ITEM_1_IMMEDIATE, gcode.process_subcommands_now, queue.inject)(F(CONFIG_MENU_ITEM_4_GCODE)); planner.synchronize(); redrawMenu(); #if ENABLED(CUSTOM_MENU_CONFIG_SCRIPT_AUDIBLE_FEEDBACK) @@ -1886,7 +1885,7 @@ void JyersDWIN::menuItemHandler(const uint8_t menu, const uint8_t item, bool dra drawMenuItem(row, ICON_Info, F(CONFIG_MENU_ITEM_5_DESC)); else { popupHandler(Popup_Custom); - gcode.process_subcommands_now(F(CONFIG_MENU_ITEM_5_GCODE)); + TERN(CONFIG_MENU_ITEM_1_IMMEDIATE, gcode.process_subcommands_now, queue.inject)(F(CONFIG_MENU_ITEM_5_GCODE)); planner.synchronize(); redrawMenu(); #if ENABLED(CUSTOM_MENU_CONFIG_SCRIPT_AUDIBLE_FEEDBACK) @@ -2127,7 +2126,7 @@ void JyersDWIN::menuItemHandler(const uint8_t menu, const uint8_t item, bool dra drawMenuItem(row, ICON_HotendTemp, GET_TEXT_F(MSG_PID_AUTOTUNE)); else { popupHandler(Popup_PIDWait); - gcode.process_subcommands_now(TS(F("M303E0C"), PID_cycles, 'S', PID_e_temp, 'U')); + queue.inject(TS(F("M303E0C"), PID_cycles, 'S', PID_e_temp, 'U')); planner.synchronize(); redrawMenu(); } @@ -2193,7 +2192,7 @@ void JyersDWIN::menuItemHandler(const uint8_t menu, const uint8_t item, bool dra drawMenuItem(row, ICON_HotendTemp, GET_TEXT_F(MSG_PID_AUTOTUNE)); else { popupHandler(Popup_PIDWait); - gcode.process_subcommands_now(TS(F("M303E-1C"), PID_cycles, 'S', PID_bed_temp, 'U')); + queue.inject(TS(F("M303E-1C"), PID_cycles, 'S', PID_bed_temp, 'U')); planner.synchronize(); redrawMenu(); } @@ -3037,7 +3036,7 @@ void JyersDWIN::menuItemHandler(const uint8_t menu, const uint8_t item, bool dra if (draw) drawMenuItem(row, ICON_StepY, F("M48 Probe Test")); else { - gcode.process_subcommands_now( + queue.inject( TS(F("G28O\nM48X"), p_float_t((X_BED_SIZE + X_MIN_POS) / 2.0f, 3), 'Y', p_float_t((Y_BED_SIZE + Y_MIN_POS) / 2.0f, 3), 'P', testcount) ); } @@ -3231,9 +3230,9 @@ void JyersDWIN::menuItemHandler(const uint8_t menu, const uint8_t item, bool dra gcode.home_all_axes(true); popupHandler(Popup_Level); if (mesh_conf.tilt_grid > 1) - gcode.process_subcommands_now(TS(F("G29J"), mesh_conf.tilt_grid)); + queue.inject(TS(F("G29J"), mesh_conf.tilt_grid)); else - gcode.process_subcommands_now(F("G29J")); + queue.inject(F("G29J")); planner.synchronize(); redrawMenu(); } @@ -3268,7 +3267,7 @@ void JyersDWIN::menuItemHandler(const uint8_t menu, const uint8_t item, bool dra #endif #elif HAS_BED_PROBE popupHandler(Popup_Level); - gcode.process_subcommands_now(F("G29")); + queue.inject(F("G29")); planner.synchronize(); popupHandler(Popup_SaveLevel); #else @@ -3276,7 +3275,7 @@ void JyersDWIN::menuItemHandler(const uint8_t menu, const uint8_t item, bool dra set_bed_leveling_enabled(false); gridpoint = 1; popupHandler(Popup_MoveWait); - gcode.process_subcommands_now(F("G29")); + queue.inject(F("G29")); planner.synchronize(); drawMenu(ID_ManualMesh); #endif @@ -3359,7 +3358,7 @@ void JyersDWIN::menuItemHandler(const uint8_t menu, const uint8_t item, bool dra popupHandler(Popup_MeshSlot); break; } - gcode.process_subcommands_now(F("G29 L")); + queue.inject(F("G29 L")); planner.synchronize(); audioFeedback(true); } @@ -3372,7 +3371,7 @@ void JyersDWIN::menuItemHandler(const uint8_t menu, const uint8_t item, bool dra popupHandler(Popup_MeshSlot); break; } - gcode.process_subcommands_now(F("G29 S")); + queue.inject(F("G29 S")); planner.synchronize(); audioFeedback(true); } @@ -3576,7 +3575,7 @@ void JyersDWIN::menuItemHandler(const uint8_t menu, const uint8_t item, bool dra drawMenuItem(row, ICON_Axis, F("+0.01mm Up")); else if (bedlevel.z_values[mesh_conf.mesh_x][mesh_conf.mesh_y] < MAX_Z_OFFSET) { bedlevel.z_values[mesh_conf.mesh_x][mesh_conf.mesh_y] += 0.01; - gcode.process_subcommands_now(F("M290 Z0.01")); + queue.inject(F("M290 Z0.01")); planner.synchronize(); current_position.z += 0.01f; sync_plan_position(); @@ -3588,7 +3587,7 @@ void JyersDWIN::menuItemHandler(const uint8_t menu, const uint8_t item, bool dra drawMenuItem(row, ICON_AxisD, F("-0.01mm Down")); else if (bedlevel.z_values[mesh_conf.mesh_x][mesh_conf.mesh_y] > MIN_Z_OFFSET) { bedlevel.z_values[mesh_conf.mesh_x][mesh_conf.mesh_y] -= 0.01; - gcode.process_subcommands_now(F("M290 Z-0.01")); + queue.inject(F("M290 Z-0.01")); planner.synchronize(); current_position.z -= 0.01f; sync_plan_position(); @@ -3659,7 +3658,7 @@ void JyersDWIN::menuItemHandler(const uint8_t menu, const uint8_t item, bool dra mesh_conf.manual_mesh_move(); } else { - gcode.process_subcommands_now(F("G29 S")); + queue.inject(F("G29 S")); planner.synchronize(); audioFeedback(true); drawMenu(ID_Leveling, LEVELING_GET_MESH); @@ -3697,7 +3696,7 @@ void JyersDWIN::menuItemHandler(const uint8_t menu, const uint8_t item, bool dra drawMenuItem(row, ICON_Axis, F("+0.01mm Up")); else if (bedlevel.z_values[mesh_conf.mesh_x][mesh_conf.mesh_y] < MAX_Z_OFFSET) { bedlevel.z_values[mesh_conf.mesh_x][mesh_conf.mesh_y] += 0.01; - gcode.process_subcommands_now(F("M290 Z0.01")); + queue.inject(F("M290 Z0.01")); planner.synchronize(); current_position.z += 0.01f; sync_plan_position(); @@ -3709,7 +3708,7 @@ void JyersDWIN::menuItemHandler(const uint8_t menu, const uint8_t item, bool dra drawMenuItem(row, ICON_Axis, F("-0.01mm Down")); else if (bedlevel.z_values[mesh_conf.mesh_x][mesh_conf.mesh_y] > MIN_Z_OFFSET) { bedlevel.z_values[mesh_conf.mesh_x][mesh_conf.mesh_y] -= 0.01; - gcode.process_subcommands_now(F("M290 Z-0.01")); + queue.inject(F("M290 Z-0.01")); planner.synchronize(); current_position.z -= 0.01f; sync_plan_position(); @@ -3751,13 +3750,13 @@ void JyersDWIN::menuItemHandler(const uint8_t menu, const uint8_t item, bool dra } else if (gridpoint < GRID_MAX_POINTS) { popupHandler(Popup_MoveWait); - gcode.process_subcommands_now(F("G29")); + queue.inject(F("G29")); planner.synchronize(); gridpoint++; redrawMenu(); } else { - gcode.process_subcommands_now(F("G29")); + queue.inject(F("G29")); planner.synchronize(); audioFeedback(settings.save()); drawMenu(ID_Leveling, LEVELING_GET_MESH); @@ -4020,26 +4019,26 @@ void JyersDWIN::menuItemHandler(const uint8_t menu, const uint8_t item, bool dra switch (last_menu) { case ID_Prepare: popupHandler(Popup_FilChange); - gcode.process_subcommands_now(TS(F("M600 B1 R"), thermalManager.degTargetHotend(0))); + queue.inject(TS(F("M600 B1 R"), thermalManager.degTargetHotend(0))); break; #if ENABLED(FILAMENT_LOAD_UNLOAD_GCODES) case ID_ChangeFilament: switch (last_selection) { case CHANGEFIL_LOAD: popupHandler(Popup_FilLoad); - gcode.process_subcommands_now(F("M701")); + queue.inject(F("M701")); planner.synchronize(); redrawMenu(true, true, true); break; case CHANGEFIL_UNLOAD: popupHandler(Popup_FilLoad, true); - gcode.process_subcommands_now(F("M702")); + queue.inject(F("M702")); planner.synchronize(); redrawMenu(true, true, true); break; case CHANGEFIL_CHANGE: popupHandler(Popup_FilChange); - gcode.process_subcommands_now(TS(F("M600 B1 R"), thermalManager.degTargetHotend(0))); + queue.inject(TS(F("M600 B1 R"), thermalManager.degTargetHotend(0))); break; } break; @@ -4614,10 +4613,10 @@ void JyersDWIN::printScreenControl() { TERN_(POWER_LOSS_RECOVERY, recovery.prepare()); #else #if HAS_HEATED_BED - gcode.process_subcommands_now(TS(F("M140 S"), pausebed)); + queue.inject(TS(F("M140 S"), pausebed)); #endif #if HAS_EXTRUDERS - gcode.process_subcommands_now(TS(F("M109 S"), pausetemp)); + queue.inject(TS(F("M109 S"), pausetemp)); #endif TERN_(HAS_FAN, thermalManager.fan_speed[0] = pausefan); planner.synchronize(); @@ -4737,7 +4736,7 @@ void JyersDWIN::popupControl() { thermalManager.wait_for_hotend(0); } popupHandler(Popup_FilChange); - gcode.process_subcommands_now(TS(F("M600B1R"), thermalManager.degTargetHotend(0))); + queue.inject(TS(F("M600B1R"), thermalManager.degTargetHotend(0))); } } else @@ -4760,7 +4759,7 @@ void JyersDWIN::popupControl() { case Popup_SaveLevel: if (selection == 0) { #if ENABLED(AUTO_BED_LEVELING_UBL) - gcode.process_subcommands_now(F("G29 S")); + queue.inject(F("G29 S")); planner.synchronize(); audioFeedback(true); #else diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/custom_user_menus.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/custom_user_menus.cpp index 896de3fe56..d86946ca4f 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/custom_user_menus.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/custom_user_menus.cpp @@ -42,7 +42,7 @@ void CustomUserMenus::onRedraw(draw_mode_t what) { } #if ENABLED(TOUCH_UI_PORTRAIT) - #if defined(TOOLHEAD_Legacy_Universal) + #ifdef TOOLHEAD_Legacy_Universal #define GRID_ROWS 10 #else #define GRID_ROWS 7 @@ -61,10 +61,9 @@ void CustomUserMenus::onRedraw(draw_mode_t what) { #define BACK_POS BTN_POS(1,GRID_ROWS), BTN_SIZE(GRID_COLS,1) #endif -btn_colors thcolor[8] = {normal_btn}; + btn_colors thcolor[8] = {normal_btn}; + //.color(TH_color[1]) - -//.color(TH_color[1]) if (what & FOREGROUND) { CommandProcessor cmd; cmd.colors(normal_btn) @@ -72,42 +71,42 @@ btn_colors thcolor[8] = {normal_btn}; .tag(0).text(TOOLHEAD_LABL_POS, GET_TEXT_F(MSG_CUSTOM_MENU_MAIN_TITLE)); cmd.colors(accent_btn) .font(Theme::font_medium) - #if defined(MAIN_MENU_ITEM_1_DESC) + #ifdef MAIN_MENU_ITEM_1_DESC //_USER_ITEM(1) .tag(_ITEM_TAG(11)).button(USER_ITEM_POS(1), MAIN_MENU_ITEM_1_DESC) #endif .colors(thcolor[1]) - #if defined(MAIN_MENU_ITEM_2_DESC) + #ifdef MAIN_MENU_ITEM_2_DESC //_USER_ITEM(2) .tag(_ITEM_TAG(12)).button(USER_ITEM_POS(2), MAIN_MENU_ITEM_2_DESC) #endif .colors(thcolor[2]) - #if defined(MAIN_MENU_ITEM_3_DESC) + #ifdef MAIN_MENU_ITEM_3_DESC //_USER_ITEM(3) .tag(_ITEM_TAG(13)).button(USER_ITEM_POS(3), MAIN_MENU_ITEM_3_DESC) #endif .colors(thcolor[3]) - #if defined(MAIN_MENU_ITEM_4_DESC) + #ifdef MAIN_MENU_ITEM_4_DESC //_USER_ITEM(4) .tag(_ITEM_TAG(14)).button(USER_ITEM_POS(4), MAIN_MENU_ITEM_4_DESC) #endif .colors(thcolor[4]) - #if defined(MAIN_MENU_ITEM_5_DESC) + #ifdef MAIN_MENU_ITEM_5_DESC //_USER_ITEM(5) .tag(_ITEM_TAG(15)).button(USER_ITEM_POS(5), MAIN_MENU_ITEM_5_DESC) #endif .colors(thcolor[5]) - #if defined(MAIN_MENU_ITEM_6_DESC) + #ifdef MAIN_MENU_ITEM_6_DESC //_USER_ITEM(6) .tag(_ITEM_TAG(16)).button(USER_ITEM_POS(6), MAIN_MENU_ITEM_6_DESC) #endif .colors(thcolor[6]) - #if defined(MAIN_MENU_ITEM_7_DESC) + #ifdef MAIN_MENU_ITEM_7_DESC //_USER_ITEM(7) .tag(_ITEM_TAG(17)).button(USER_ITEM_POS(7), MAIN_MENU_ITEM_7_DESC) #endif .colors(thcolor[7]) - #if defined(MAIN_MENU_ITEM_8_DESC) + #ifdef MAIN_MENU_ITEM_8_DESC //_USER_ITEM(8) .tag(_ITEM_TAG(18)).button(USER_ITEM_POS(8), MAIN_MENU_ITEM_8_DESC) #endif @@ -123,41 +122,49 @@ btn_colors thcolor[8] = {normal_btn}; } } +#include "../../../../gcode/queue.h" + +template void _lcd_custom_menu_gcode(FSTR_P const fstr); + +FORCE_INLINE void _lcd_custom_menu_gcode_done() { + TERN_(CUSTOM_MENU_MAIN_SCRIPT_AUDIBLE_FEEDBACK, ui.completion_feedback()); + TERN_(CUSTOM_MENU_MAIN_SCRIPT_RETURN, ui.return_to_status()); +} +template<> void _lcd_custom_menu_gcode(FSTR_P const fstr) { + gcode.process_subcommands_now(fstr); + _lcd_custom_menu_gcode_done(); +} +template<> void _lcd_custom_menu_gcode(FSTR_P const fstr) { + queue.inject(fstr); + _lcd_custom_menu_gcode_done(); +} + bool CustomUserMenus::onTouchEnd(uint8_t tag) { switch (tag) { - #if defined(MAIN_MENU_ITEM_1_DESC) - //_USER_ACTION(1) - case _ITEM_TAG(11): injectCommands_P(PSTR(MAIN_MENU_ITEM_1_GCODE));sound.play(chimes, PLAY_ASYNCHRONOUS); GOTO_SCREEN(StatusScreen); break; + #ifdef MAIN_MENU_ITEM_1_DESC + case _ITEM_TAG(11): _lcd_custom_menu_gcode(F(MAIN_MENU_ITEM_1_GCODE)); break; #endif - #if defined(MAIN_MENU_ITEM_2_DESC) - //_USER_ACTION(2) - case _ITEM_TAG(12): injectCommands_P(PSTR(MAIN_MENU_ITEM_2_GCODE));sound.play(chimes, PLAY_ASYNCHRONOUS); GOTO_SCREEN(StatusScreen); break; + #ifdef MAIN_MENU_ITEM_2_DESC + case _ITEM_TAG(12): _lcd_custom_menu_gcode(F(MAIN_MENU_ITEM_2_GCODE)); break; #endif - #if defined(MAIN_MENU_ITEM_3_DESC) - //_USER_ACTION(3) - case _ITEM_TAG(13): injectCommands_P(PSTR(MAIN_MENU_ITEM_3_GCODE));sound.play(chimes, PLAY_ASYNCHRONOUS); GOTO_SCREEN(StatusScreen); break; + #ifdef MAIN_MENU_ITEM_3_DESC + case _ITEM_TAG(13): _lcd_custom_menu_gcode(F(MAIN_MENU_ITEM_3_GCODE)); break; #endif - #if defined(MAIN_MENU_ITEM_4_DESC) - //_USER_ACTION(4) - case _ITEM_TAG(14): injectCommands_P(PSTR(MAIN_MENU_ITEM_4_GCODE));sound.play(chimes, PLAY_ASYNCHRONOUS); GOTO_SCREEN(StatusScreen); break; + #ifdef MAIN_MENU_ITEM_4_DESC + case _ITEM_TAG(14): _lcd_custom_menu_gcode(F(MAIN_MENU_ITEM_4_GCODE)); break; #endif - #if defined(MAIN_MENU_ITEM_5_DESC) - //_USER_ACTION(5) - case _ITEM_TAG(15): injectCommands_P(PSTR(MAIN_MENU_ITEM_5_GCODE));sound.play(chimes, PLAY_ASYNCHRONOUS); GOTO_SCREEN(StatusScreen); break; + #ifdef MAIN_MENU_ITEM_5_DESC + case _ITEM_TAG(15): _lcd_custom_menu_gcode(F(MAIN_MENU_ITEM_5_GCODE)); break; #endif - #if defined(MAIN_MENU_ITEM_6_DESC) - //_USER_ACTION(6) - case _ITEM_TAG(16): injectCommands_P(PSTR(MAIN_MENU_ITEM_6_GCODE));sound.play(chimes, PLAY_ASYNCHRONOUS); GOTO_SCREEN(StatusScreen); break; + #ifdef MAIN_MENU_ITEM_6_DESC + case _ITEM_TAG(16): _lcd_custom_menu_gcode(F(MAIN_MENU_ITEM_6_GCODE)); break; #endif - #if defined(MAIN_MENU_ITEM_7_DESC) - //_USER_ACTION(7) - case _ITEM_TAG(17): injectCommands_P(PSTR(MAIN_MENU_ITEM_7_GCODE));sound.play(chimes, PLAY_ASYNCHRONOUS); GOTO_SCREEN(StatusScreen);break; + #ifdef MAIN_MENU_ITEM_7_DESC + case _ITEM_TAG(17): _lcd_custom_menu_gcode(F(MAIN_MENU_ITEM_7_GCODE)); break; #endif - #if defined(MAIN_MENU_ITEM_8_DESC) - //_USER_ACTION(8) - case _ITEM_TAG(18): injectCommands_P(PSTR(MAIN_MENU_ITEM_8_GCODE));sound.play(chimes, PLAY_ASYNCHRONOUS); GOTO_SCREEN(StatusScreen);break; + #ifdef MAIN_MENU_ITEM_8_DESC + case _ITEM_TAG(18): _lcd_custom_menu_gcode(F(MAIN_MENU_ITEM_8_GCODE)); break; #endif - case 1: GOTO_PREVIOUS(); break; #ifdef PARKING_COMMAND_GCODE case 20: injectCommands(F(PARKING_COMMAND_GCODE)); break; diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/endstop_state_screen.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/endstop_state_screen.cpp index 8a935313a1..1552b6a496 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/endstop_state_screen.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/endstop_state_screen.cpp @@ -94,10 +94,12 @@ void EndstopStatesScreen::onRedraw(draw_mode_t) { #else PIN_DISABLED(3, 4, GET_TEXT_F(MSG_RUNOUT_2), FIL_RUNOUT2) #endif - #if PIN_EXISTS(Z_MIN_PROBE) - PIN_ENABLED (5, 4, PSTR(STR_Z_PROBE), Z_MIN_PROBE, Z_MIN_PROBE_ENDSTOP_HIT_STATE) - #else - PIN_DISABLED(5, 4, PSTR(STR_Z_PROBE), Z_MIN_PROBE) + #if HAS_BED_PROBE + #if PIN_EXISTS(Z_MIN_PROBE) + PIN_ENABLED (5, 4, PSTR(STR_Z_PROBE), Z_MIN_PROBE, Z_MIN_PROBE_ENDSTOP_HIT_STATE) + #else + PIN_DISABLED(5, 4, PSTR(STR_Z_PROBE), Z_MIN_PROBE) + #endif #endif #if HAS_SOFTWARE_ENDSTOPS diff --git a/Marlin/src/lcd/extui/mks_ui/draw_more.cpp b/Marlin/src/lcd/extui/mks_ui/draw_more.cpp index 864a3e1d96..dd53374583 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_more.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_more.cpp @@ -29,6 +29,7 @@ #include "draw_set.h" #include "lv_conf.h" #include "draw_ui.h" +#include "../../../gcode/gcode.h" #include "../../../gcode/queue.h" extern lv_group_t * g; @@ -62,22 +63,22 @@ static void event_handler(lv_obj_t * obj, lv_event_t event) { switch (obj->mks_obj_id) { case ID_GCODE: lv_clear_more(); lv_draw_gcode(true); break; #if HAS_USER_ITEM(1) - case ID_CUSTOM_1: queue.inject(F(MAIN_MENU_ITEM_1_GCODE)); break; + case ID_CUSTOM_1: TERN(CONFIG_MENU_ITEM_1_IMMEDIATE, gcode.process_subcommands_now, queue.inject)(F(MAIN_MENU_ITEM_1_GCODE)); break; #endif #if HAS_USER_ITEM(2) - case ID_CUSTOM_2: queue.inject(F(MAIN_MENU_ITEM_2_GCODE)); break; + case ID_CUSTOM_2: TERN(CONFIG_MENU_ITEM_2_IMMEDIATE, gcode.process_subcommands_now, queue.inject)(F(MAIN_MENU_ITEM_2_GCODE)); break; #endif #if HAS_USER_ITEM(3) - case ID_CUSTOM_3: queue.inject(F(MAIN_MENU_ITEM_3_GCODE)); break; + case ID_CUSTOM_3: TERN(CONFIG_MENU_ITEM_3_IMMEDIATE, gcode.process_subcommands_now, queue.inject)(F(MAIN_MENU_ITEM_3_GCODE)); break; #endif #if HAS_USER_ITEM(4) - case ID_CUSTOM_4: queue.inject(F(MAIN_MENU_ITEM_4_GCODE)); break; + case ID_CUSTOM_4: TERN(CONFIG_MENU_ITEM_4_IMMEDIATE, gcode.process_subcommands_now, queue.inject)(F(MAIN_MENU_ITEM_4_GCODE)); break; #endif #if HAS_USER_ITEM(5) - case ID_CUSTOM_5: queue.inject(F(MAIN_MENU_ITEM_5_GCODE)); break; + case ID_CUSTOM_5: TERN(CONFIG_MENU_ITEM_5_IMMEDIATE, gcode.process_subcommands_now, queue.inject)(F(MAIN_MENU_ITEM_5_GCODE)); break; #endif #if HAS_USER_ITEM(6) - case ID_CUSTOM_6: queue.inject(F(MAIN_MENU_ITEM_6_GCODE)); break; + case ID_CUSTOM_6: TERN(CONFIG_MENU_ITEM_6_IMMEDIATE, gcode.process_subcommands_now, queue.inject)(F(MAIN_MENU_ITEM_6_GCODE)); break; #endif case ID_M_RETURN: lv_clear_more(); diff --git a/Marlin/src/lcd/extui/ui_api.h b/Marlin/src/lcd/extui/ui_api.h index 88145621e5..f864f3d1cd 100644 --- a/Marlin/src/lcd/extui/ui_api.h +++ b/Marlin/src/lcd/extui/ui_api.h @@ -132,6 +132,8 @@ namespace ExtUI { inline void injectCommands(FSTR_P const fstr) { injectCommands_P(FTOP(fstr)); } void injectCommands(char * const); bool commandsInQueue(); + inline void executeCommands(FSTR_P const fstr) { gcode.process_subcommands_now(fstr); } + inline void executeCommands(char * const cstr) { gcode.process_subcommands_now(cstr); } #if ENABLED(HOST_KEEPALIVE_FEATURE) GcodeSuite::MarlinBusyState getHostKeepaliveState(); diff --git a/Marlin/src/lcd/menu/menu.h b/Marlin/src/lcd/menu/menu.h index 73f7a9dcc9..869b06828c 100644 --- a/Marlin/src/lcd/menu/menu.h +++ b/Marlin/src/lcd/menu/menu.h @@ -269,3 +269,7 @@ inline void clear_menu_history() { screen_history_depth = 0; } #if ANY(PROBE_MANUALLY, MESH_BED_LEVELING, X_AXIS_TWIST_COMPENSATION) extern uint8_t manual_probe_index; #endif + +#if ANY(CUSTOM_MENU_MAIN, CUSTOM_MENU_CONFIG) + template void _lcd_custom_menu_gcode(FSTR_P const fstr); +#endif diff --git a/Marlin/src/lcd/menu/menu_configuration.cpp b/Marlin/src/lcd/menu/menu_configuration.cpp index 259a81fb0e..d2849ccd1b 100644 --- a/Marlin/src/lcd/menu/menu_configuration.cpp +++ b/Marlin/src/lcd/menu/menu_configuration.cpp @@ -464,12 +464,6 @@ void menu_advanced_settings(); #if ENABLED(CUSTOM_MENU_CONFIG) - void _lcd_custom_menus_configuration_gcode(FSTR_P const fstr) { - queue.inject(fstr); - TERN_(CUSTOM_MENU_CONFIG_SCRIPT_AUDIBLE_FEEDBACK, ui.completion_feedback()); - TERN_(CUSTOM_MENU_CONFIG_SCRIPT_RETURN, ui.return_to_status()); - } - void custom_menus_configuration() { START_MENU(); BACK_ITEM(MSG_MAIN_MENU); @@ -481,7 +475,7 @@ void menu_advanced_settings(); #else #define _DONE_SCRIPT "" #endif - #define GCODE_LAMBDA_CONF(N) []{ _lcd_custom_menus_configuration_gcode(F(CONFIG_MENU_ITEM_##N##_GCODE _DONE_SCRIPT)); } + #define GCODE_LAMBDA_CONF(N) []{ _lcd_custom_menu_gcode(F(CONFIG_MENU_ITEM_##N##_GCODE _DONE_SCRIPT)); } #define _CUSTOM_ITEM_CONF(N) ACTION_ITEM_F(F(CONFIG_MENU_ITEM_##N##_DESC), GCODE_LAMBDA_CONF(N)); #define _CUSTOM_ITEM_CONF_CONFIRM(N) \ SUBMENU_F(F(CONFIG_MENU_ITEM_##N##_DESC), []{ \ diff --git a/Marlin/src/lcd/menu/menu_item.h b/Marlin/src/lcd/menu/menu_item.h index d79956aea7..c3544f3c67 100644 --- a/Marlin/src/lcd/menu/menu_item.h +++ b/Marlin/src/lcd/menu/menu_item.h @@ -23,6 +23,7 @@ #include "menu.h" #include "../marlinui.h" +#include "../../gcode/gcode.h" // for process_subcommands_now #include "../../gcode/queue.h" // for inject #include "../../inc/MarlinConfigPre.h" @@ -70,6 +71,12 @@ class MenuItem_gcode : public MenuItem_button { static void action(FSTR_P const fstr, const uint8_t, FSTR_P const fgcode) { action(fstr, fgcode); } }; +class MenuItem_command : public MenuItem_gcode { + public: + static void action(FSTR_P const, FSTR_P const fgcode) { gcode.process_subcommands_now(fgcode); } + static void action(FSTR_P const fstr, const uint8_t, FSTR_P const fgcode) { action(fstr, fgcode); } +}; + //////////////////////////////////////////// ///////////// Edit Menu Items ////////////// //////////////////////////////////////////// @@ -479,6 +486,15 @@ class MenuItem_bool : public MenuEditItemBase { #define GCODES_ITEM_F(FLABEL, GCODES) MENU_ITEM_F(gcode, FLABEL, GCODES) #define GCODES_ITEM(LABEL, GCODES) GCODES_ITEM_F(GET_TEXT_F(LABEL), GCODES) +#define COMMAND_ITEM_N_S_F(N, S, FLABEL, GCODES) MENU_ITEM_N_S_F(command, N, S, FLABEL, GCODES) +#define COMMAND_ITEM_N_S(N, S, LABEL, GCODES) COMMAND_ITEM_N_S_F(N, S, GET_TEXT_F(LABEL), GCODES) +#define COMMAND_ITEM_S_F(S, FLABEL, GCODES) MENU_ITEM_S_F(command, S, FLABEL, GCODES) +#define COMMAND_ITEM_S(S, LABEL, GCODES) COMMAND_ITEM_S_F(S, GET_TEXT_F(LABEL), GCODES) +#define COMMAND_ITEM_N_F(N, FLABEL, GCODES) MENU_ITEM_N_F(command, N, FLABEL, GCODES) +#define COMMAND_ITEM_N(N, LABEL, GCODES) COMMAND_ITEM_N_F(N, GET_TEXT_F(LABEL), GCODES) +#define COMMAND_ITEM_F(FLABEL, GCODES) MENU_ITEM_F(command, FLABEL, GCODES) +#define COMMAND_ITEM(LABEL, GCODES) COMMAND_ITEM_F(GET_TEXT_F(LABEL), GCODES) + #define SUBMENU_N_S_F(N, S, FLABEL, DEST) MENU_ITEM_N_S_F(submenu, N, S, FLABEL, DEST) #define SUBMENU_N_S(N, S, LABEL, DEST) SUBMENU_N_S_F(N, S, GET_TEXT_F(LABEL), DEST) #define SUBMENU_S_F(S, FLABEL, DEST) MENU_ITEM_S_F(submenu, S, FLABEL, DEST) diff --git a/Marlin/src/lcd/menu/menu_main.cpp b/Marlin/src/lcd/menu/menu_main.cpp index 401c59f5c0..13fe4e89e2 100644 --- a/Marlin/src/lcd/menu/menu_main.cpp +++ b/Marlin/src/lcd/menu/menu_main.cpp @@ -116,13 +116,24 @@ void menu_configuration(); void menu_language(); #endif -#if ENABLED(CUSTOM_MENU_MAIN) +#if ANY(CUSTOM_MENU_MAIN, CUSTOM_MENU_CONFIG) - void _lcd_custom_menu_main_gcode(FSTR_P const fstr) { - queue.inject(fstr); + FORCE_INLINE void _lcd_custom_menu_gcode_done() { TERN_(CUSTOM_MENU_MAIN_SCRIPT_AUDIBLE_FEEDBACK, ui.completion_feedback()); TERN_(CUSTOM_MENU_MAIN_SCRIPT_RETURN, ui.return_to_status()); } + template<> void _lcd_custom_menu_gcode(FSTR_P const fstr) { + gcode.process_subcommands_now(fstr); + _lcd_custom_menu_gcode_done(); + } + template<> void _lcd_custom_menu_gcode(FSTR_P const fstr) { + queue.inject(fstr); + _lcd_custom_menu_gcode_done(); + } + +#endif + +#if ENABLED(CUSTOM_MENU_MAIN) void custom_menus_main() { START_MENU(); @@ -135,7 +146,7 @@ void menu_configuration(); #else #define _DONE_SCRIPT "" #endif - #define GCODE_LAMBDA_MAIN(N) []{ _lcd_custom_menu_main_gcode(F(MAIN_MENU_ITEM_##N##_GCODE _DONE_SCRIPT)); } + #define GCODE_LAMBDA_MAIN(N) []{ _lcd_custom_menu_gcode(F(MAIN_MENU_ITEM_##N##_GCODE _DONE_SCRIPT)); } #define _CUSTOM_ITEM_MAIN(N) ACTION_ITEM_F(F(MAIN_MENU_ITEM_##N##_DESC), GCODE_LAMBDA_MAIN(N)); #define _CUSTOM_ITEM_MAIN_CONFIRM(N) \ SUBMENU_F(F(MAIN_MENU_ITEM_##N##_DESC), []{ \ diff --git a/buildroot/tests/STM32F103RE_btt_USB b/buildroot/tests/STM32F103RE_btt_USB index ddf1903c9b..b74b8dd3a3 100755 --- a/buildroot/tests/STM32F103RE_btt_USB +++ b/buildroot/tests/STM32F103RE_btt_USB @@ -15,10 +15,12 @@ opt_enable SDSUPPORT EMERGENCY_PARSER exec_test $1 $2 "BigTreeTech SKR E3 DIP v1.0 - Basic Configuration" "$3" restore_configs -opt_set MOTHERBOARD BOARD_BTT_SKR_CR6 SERIAL_PORT -1 SERIAL_PORT_2 2 TEMP_SENSOR_BED 1 +opt_set MOTHERBOARD BOARD_BTT_SKR_CR6 SERIAL_PORT -1 SERIAL_PORT_2 2 TEMP_SENSOR_BED 1 BUTTON1_PIN PA12 opt_enable CR10_STOCKDISPLAY SDSUPPORT EMERGENCY_PARSER FAN_SOFT_PWM \ NOZZLE_AS_PROBE Z_MIN_PROBE_USES_Z_MIN_ENDSTOP_PIN Z_SAFE_HOMING \ PROBE_ACTIVATION_SWITCH PROBE_TARE PROBE_TARE_ONLY_WHILE_INACTIVE \ - PROBING_HEATERS_OFF PREHEAT_BEFORE_PROBING + PROBING_HEATERS_OFF PREHEAT_BEFORE_PROBING CUSTOM_USER_BUTTONS BUTTON1_IMMEDIATE \ + CUSTOM_MENU_MAIN MAIN_MENU_ITEM_1_CONFIRM MAIN_MENU_ITEM_2_IMMEDIATE MAIN_MENU_ITEM_3_DESC MAIN_MENU_ITEM_3_GCODE \ + CUSTOM_MENU_CONFIG CONFIG_MENU_ITEM_1_CONFIRM CONFIG_MENU_ITEM_2_IMMEDIATE CONFIG_MENU_ITEM_3_DESC CONFIG_MENU_ITEM_3_GCODE opt_disable NOZZLE_TO_PROBE_OFFSET exec_test $1 $2 "BigTreeTech SKR CR6 PROBE_ACTIVATION_SWITCH, Probe Tare" "$3" From 8dee0c128101c8da0da04b69d675971445cf8be2 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Thu, 20 Nov 2025 06:10:58 +0000 Subject: [PATCH 90/99] [cron] Bump distribution date (2025-11-20) --- 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 56a03d5885..117e6d9f1d 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 "2025-11-19" +//#define STRING_DISTRIBUTION_DATE "2025-11-20" /** * The protocol for communication to the host. Protocol indicates communication diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index 293dee7ad6..e3d358c5ef 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 "2025-11-19" + #define STRING_DISTRIBUTION_DATE "2025-11-20" #endif /** From ccc69582efb99cc4a8e7a8b77aade7906395d4ce Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 23 Nov 2025 13:27:17 -0600 Subject: [PATCH 91/99] =?UTF-8?q?=F0=9F=A7=91=E2=80=8D=F0=9F=92=BB=20Warn?= =?UTF-8?q?=20about=20language=20features?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/inc/Warnings.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/Marlin/src/inc/Warnings.cpp b/Marlin/src/inc/Warnings.cpp index 6da36d832f..e15d053b4e 100644 --- a/Marlin/src/inc/Warnings.cpp +++ b/Marlin/src/inc/Warnings.cpp @@ -31,6 +31,10 @@ // Warnings! Located here so they will appear just once in the build output. // +#if __cplusplus < 201703L + #warning "This build does not have access to >= c++17 features." +#endif + // static_warning works like a static_assert but only emits a (messy) warning. #ifdef __GNUC__ namespace mfwarn { From 9da6b580d92cecac7e506480ff5b67cda5dd48f5 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Sun, 23 Nov 2025 13:32:56 -0600 Subject: [PATCH 92/99] =?UTF-8?q?=F0=9F=9A=B8=20Immediate=20Buttons=20and?= =?UTF-8?q?=20Menu=20Items=20(2)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Followup to #28180 --- .../ftdi_eve_touch_ui/generic/custom_user_menus.cpp | 10 ++++------ 1 file changed, 4 insertions(+), 6 deletions(-) diff --git a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/custom_user_menus.cpp b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/custom_user_menus.cpp index d86946ca4f..167dda1b0a 100644 --- a/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/custom_user_menus.cpp +++ b/Marlin/src/lcd/extui/ftdi_eve_touch_ui/generic/custom_user_menus.cpp @@ -122,20 +122,18 @@ void CustomUserMenus::onRedraw(draw_mode_t what) { } } -#include "../../../../gcode/queue.h" - template void _lcd_custom_menu_gcode(FSTR_P const fstr); FORCE_INLINE void _lcd_custom_menu_gcode_done() { - TERN_(CUSTOM_MENU_MAIN_SCRIPT_AUDIBLE_FEEDBACK, ui.completion_feedback()); - TERN_(CUSTOM_MENU_MAIN_SCRIPT_RETURN, ui.return_to_status()); + sound.play(chimes, PLAY_ASYNCHRONOUS); + GOTO_SCREEN(StatusScreen); } template<> void _lcd_custom_menu_gcode(FSTR_P const fstr) { - gcode.process_subcommands_now(fstr); + ExtUI::executeCommands(fstr); _lcd_custom_menu_gcode_done(); } template<> void _lcd_custom_menu_gcode(FSTR_P const fstr) { - queue.inject(fstr); + ExtUI::injectCommands(fstr); _lcd_custom_menu_gcode_done(); } From 46ee5b0a0883cb7285b08d197229a99738f3e3b1 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Mon, 24 Nov 2025 00:35:08 +0000 Subject: [PATCH 93/99] [cron] Bump distribution date (2025-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 117e6d9f1d..9ff5e45d02 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 "2025-11-20" +//#define STRING_DISTRIBUTION_DATE "2025-11-24" /** * The protocol for communication to the host. Protocol indicates communication diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index e3d358c5ef..eb8cab633b 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 "2025-11-20" + #define STRING_DISTRIBUTION_DATE "2025-11-24" #endif /** From fe1d6f93e26ef5199ae54c32bb90baa7cdc10d63 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Mon, 24 Nov 2025 19:55:30 -0600 Subject: [PATCH 94/99] =?UTF-8?q?=F0=9F=94=A8=20STM32=20build=20with=20-st?= =?UTF-8?q?d=3Dgnu++17=20(#28188)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- ini/stm32-common.ini | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/ini/stm32-common.ini b/ini/stm32-common.ini index 2ba6baed1b..c5fedfa4e1 100644 --- a/ini/stm32-common.ini +++ b/ini/stm32-common.ini @@ -13,10 +13,10 @@ platform = ststm32@~12.1 #platform_packages = toolchain-gccarmnoneeabi@1.100301.220327 # Otherwise it's GCC 9.2.1 board_build.core = stm32 -build_flags = ${common.build_flags} -std=gnu++14 +build_flags = ${common.build_flags} -std=gnu++17 -DHAL_STM32 -DPLATFORM_M997_SUPPORT -DUSBCON -DUSBD_USE_CDC -DTIM_IRQ_PRIO=13 -DADC_RESOLUTION=12 -build_unflags = -std=gnu++11 +build_unflags = -std=gnu++11 -std=gnu++14 build_src_filter = ${common.default_src_filter} + - + extra_scripts = ${common.extra_scripts} pre:buildroot/share/PlatformIO/scripts/stm32_serialbuffer.py From 50297c65d47273d0c50a0d3649dbbb012838c996 Mon Sep 17 00:00:00 2001 From: Andrew <18502096+classicrocker883@users.noreply.github.com> Date: Mon, 24 Nov 2025 20:56:11 -0500 Subject: [PATCH 95/99] =?UTF-8?q?=F0=9F=9A=B8=20Update/fix=20JyersUI/ProUI?= =?UTF-8?q?=20park,=20leveling=20(#28183)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp | 6 +-- Marlin/src/feature/bltouch.cpp | 8 ++-- Marlin/src/gcode/bedlevel/mbl/G29.cpp | 2 +- Marlin/src/lcd/e3v2/jyersui/dwin.cpp | 44 +++++++------------- Marlin/src/lcd/e3v2/proui/bedlevel_tools.cpp | 23 +++------- Marlin/src/lcd/e3v2/proui/bedlevel_tools.h | 4 +- Marlin/src/lcd/e3v2/proui/dwin.cpp | 2 + Marlin/src/lcd/language/language_en.h | 1 + 8 files changed, 33 insertions(+), 57 deletions(-) diff --git a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp index 24a1638731..e14d7b2a38 100644 --- a/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp +++ b/Marlin/src/feature/bedlevel/ubl/ubl_G29.cpp @@ -1161,16 +1161,16 @@ bool unified_bed_leveling::G29_parse_parameters() { } if (parser.seen('P')) { - const uint8_t pv = parser.value_byte(); + const uint8_t pval = parser.value_byte(); #if !HAS_BED_PROBE - if (pv == 1) { + if (pval == 1) { SERIAL_ECHOLNPGM("G29 P1 requires a probe.\n"); err_flag = true; } else #endif { - param.P_phase = pv; + param.P_phase = pval; if (!WITHIN(param.P_phase, 0, 6)) { SERIAL_ECHOLNPGM("?(P)hase value invalid (0-6).\n"); err_flag = true; diff --git a/Marlin/src/feature/bltouch.cpp b/Marlin/src/feature/bltouch.cpp index 5b498cd474..85b69d66c4 100644 --- a/Marlin/src/feature/bltouch.cpp +++ b/Marlin/src/feature/bltouch.cpp @@ -71,11 +71,9 @@ void BLTouch::init(const bool set_voltage/*=false*/) { #else - #ifdef DEBUG_OUT - if (DEBUGGING(LEVELING)) - DEBUG_ECHOLN( F("BLTouch Mode: "), bltouch.od_5v_mode ? F("5V") : F("OD"), - F(" (Default " TERN(BLTOUCH_SET_5V_MODE, "5V", "OD") ")")); - #endif + if (DEBUGGING(LEVELING)) + DEBUG_ECHOLN( F("BLTouch Mode: "), bltouch.od_5v_mode ? F("5V") : F("OD"), + F(" (Default " TERN(BLTOUCH_SET_5V_MODE, "5V", "OD") ")")); const bool should_set = od_5v_mode != ENABLED(BLTOUCH_SET_5V_MODE); diff --git a/Marlin/src/gcode/bedlevel/mbl/G29.cpp b/Marlin/src/gcode/bedlevel/mbl/G29.cpp index 1cdeba103e..a08ecc327d 100644 --- a/Marlin/src/gcode/bedlevel/mbl/G29.cpp +++ b/Marlin/src/gcode/bedlevel/mbl/G29.cpp @@ -225,7 +225,7 @@ void GcodeSuite::G29() { } } else - return echo_not_entered('J'); + return echo_not_entered('I'); if (parser.seenval('J')) { iy = parser.value_int(); diff --git a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp index dbda3cd225..557a8f0c7c 100644 --- a/Marlin/src/lcd/e3v2/jyersui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/jyersui/dwin.cpp @@ -265,13 +265,6 @@ private: #if ENABLED(AUTO_BED_LEVELING_UBL) uint8_t tilt_grid = 1; - void manualValueUpdate(bool undefined=false) { - queue.inject( - TS(F("M421I"), mesh_x, 'J', mesh_y, 'Z', p_float_t(current_position.z, 3), undefined ? "N" : "") - ); - planner.synchronize(); - } - bool createPlaneFromMesh() { struct linear_fit_data lsf_results; incremental_LSF_reset(&lsf_results); @@ -310,17 +303,14 @@ private: return false; } - #else - - void manualValueUpdate() { - queue.inject( - TS(F("G29I"), mesh_x, 'J', mesh_y, 'Z', p_float_t(current_position.z, 3)) - ); - planner.synchronize(); - } - #endif + void manualValueUpdate(const bool reset=false) { + const float zval = reset ? 0.0f : current_position.z; + queue.inject(TS(F("M421I"), mesh_x, F("J"), mesh_y, F("Z"), p_float_t(zval, 3))); + planner.synchronize(); + } + void manual_mesh_move(const bool zmove=false) { if (zmove) { planner.synchronize(); @@ -3515,8 +3505,8 @@ void JyersDWIN::menuItemHandler(const uint8_t menu, const uint8_t item, bool dra #define LEVELING_M_UP (LEVELING_M_OFFSET + 1) #define LEVELING_M_DOWN (LEVELING_M_UP + 1) #define LEVELING_M_GOTO_VALUE (LEVELING_M_DOWN + 1) - #define LEVELING_M_UNDEF (LEVELING_M_GOTO_VALUE + ENABLED(AUTO_BED_LEVELING_UBL)) - #define LEVELING_M_TOTAL LEVELING_M_UNDEF + #define LEVELING_M_ZERO (LEVELING_M_GOTO_VALUE + 1) + #define LEVELING_M_TOTAL LEVELING_M_ZERO switch (item) { case LEVELING_M_BACK: @@ -3606,16 +3596,14 @@ void JyersDWIN::menuItemHandler(const uint8_t menu, const uint8_t item, bool dra drawCheckbox(row, mesh_conf.goto_mesh_value); } break; - #if ENABLED(AUTO_BED_LEVELING_UBL) - case LEVELING_M_UNDEF: - if (draw) - drawMenuItem(row, ICON_ResetEEPROM, F("Clear Point Value")); - else { - mesh_conf.manualValueUpdate(true); - redrawMenu(false); - } - break; - #endif + case LEVELING_M_ZERO: + if (draw) + drawMenuItem(row, ICON_ResetEEPROM, GET_TEXT_F(MSG_ZERO_MESH_POINT)); + else { + mesh_conf.manualValueUpdate(true); + redrawMenu(false); + } + break; } break; #endif // HAS_MESH diff --git a/Marlin/src/lcd/e3v2/proui/bedlevel_tools.cpp b/Marlin/src/lcd/e3v2/proui/bedlevel_tools.cpp index 7c6ee0491a..4621ce6653 100644 --- a/Marlin/src/lcd/e3v2/proui/bedlevel_tools.cpp +++ b/Marlin/src/lcd/e3v2/proui/bedlevel_tools.cpp @@ -75,14 +75,6 @@ bool drawing_mesh = false; #if ENABLED(AUTO_BED_LEVELING_UBL) - void BedLevelTools::manualValueUpdate(const uint8_t mesh_x, const uint8_t mesh_y, bool undefined/*=false*/) { - MString cmd; - cmd.set(F("M421 I"), mesh_x, 'J', mesh_y, 'Z', p_float_t(current_position.z, 3)); - if (undefined) cmd += F(" N"); - gcode.process_subcommands_now(cmd); - planner.synchronize(); - } - bool BedLevelTools::createPlaneFromMesh() { struct linear_fit_data lsf_results; incremental_LSF_reset(&lsf_results); @@ -122,17 +114,14 @@ bool drawing_mesh = false; return false; } -#else - - void BedLevelTools::manualValueUpdate(const uint8_t mesh_x, const uint8_t mesh_y) { - gcode.process_subcommands_now( - TS(F("G29 I"), mesh_x, 'J', mesh_y, 'Z', p_float_t(current_position.z, 3)) - ); - planner.synchronize(); - } - #endif +void BedLevelTools::manualValueUpdate(const uint8_t mesh_x, const uint8_t mesh_y, const bool reset/*=false*/) { + const float zval = reset ? 0.0f : current_position.z; + queue.inject(TS(F("M421I"), mesh_x, F("J"), mesh_y, F("Z"), p_float_t(zval, 3))); + planner.synchronize(); +} + void BedLevelTools::manualMove(const uint8_t mesh_x, const uint8_t mesh_y, bool zmove/*=false*/) { gcode.process_subcommands_now(F("G28O")); if (!zmove) { diff --git a/Marlin/src/lcd/e3v2/proui/bedlevel_tools.h b/Marlin/src/lcd/e3v2/proui/bedlevel_tools.h index 5716316ee4..26f2ecc399 100644 --- a/Marlin/src/lcd/e3v2/proui/bedlevel_tools.h +++ b/Marlin/src/lcd/e3v2/proui/bedlevel_tools.h @@ -55,11 +55,9 @@ public: static uint8_t tilt_grid; #if ENABLED(AUTO_BED_LEVELING_UBL) - static void manualValueUpdate(const uint8_t mesh_x, const uint8_t mesh_y, bool undefined=false); static bool createPlaneFromMesh(); - #else - static void manualValueUpdate(const uint8_t mesh_x, const uint8_t mesh_y); #endif + static void manualValueUpdate(const uint8_t mesh_x, const uint8_t mesh_y, const bool reset=false); static void manualMove(const uint8_t mesh_x, const uint8_t mesh_y, bool zmove=false); static void moveToXYZ(); static void moveToXY(); diff --git a/Marlin/src/lcd/e3v2/proui/dwin.cpp b/Marlin/src/lcd/e3v2/proui/dwin.cpp index 47e2acb27d..a82e055acf 100644 --- a/Marlin/src/lcd/e3v2/proui/dwin.cpp +++ b/Marlin/src/lcd/e3v2/proui/dwin.cpp @@ -4316,6 +4316,7 @@ void drawMaxAccelMenu() { void applyEditMeshX() { bedLevelTools.mesh_x = menuData.value; } void applyEditMeshY() { bedLevelTools.mesh_y = menuData.value; } void resetMesh() { bedLevelTools.meshReset(); LCD_MESSAGE(MSG_MESH_RESET); } + void zeroPoint() { bedLevelTools.manualValueUpdate(bedLevelTools.mesh_x, bedLevelTools.mesh_y, true); editZValueItem->redraw(); LCD_MESSAGE(MSG_ZERO_MESH_POINT); } void setEditMeshX() { hmiValue.select = 0; setIntOnClick(0, GRID_MAX_POINTS_X - 1, bedLevelTools.mesh_x, applyEditMeshX, liveEditMesh); } void setEditMeshY() { hmiValue.select = 1; setIntOnClick(0, GRID_MAX_POINTS_Y - 1, bedLevelTools.mesh_y, applyEditMeshY, liveEditMesh); } void setEditZValue() { setPFloatOnClick(Z_OFFSET_MIN, Z_OFFSET_MAX, 3); } @@ -4417,6 +4418,7 @@ void drawMaxAccelMenu() { EDIT_ITEM(ICON_MeshEditX, MSG_MESH_X, onDrawPInt8Menu, setEditMeshX, &bedLevelTools.mesh_x); EDIT_ITEM(ICON_MeshEditY, MSG_MESH_Y, onDrawPInt8Menu, setEditMeshY, &bedLevelTools.mesh_y); editZValueItem = EDIT_ITEM(ICON_MeshEditZ, MSG_MESH_EDIT_Z, onDrawPFloat2Menu, setEditZValue, &bedlevel.z_values[bedLevelTools.mesh_x][bedLevelTools.mesh_y]); + MENU_ITEM(ICON_SetZOffset, MSG_ZERO_MESH_POINT, onDrawMenuItem, zeroPoint); } updateMenu(editMeshMenu); } diff --git a/Marlin/src/lcd/language/language_en.h b/Marlin/src/lcd/language/language_en.h index bc1f22aa84..5e34a47723 100644 --- a/Marlin/src/lcd/language/language_en.h +++ b/Marlin/src/lcd/language/language_en.h @@ -140,6 +140,7 @@ namespace LanguageNarrow_en { LSTR MSG_LEVEL_BED_WAITING = _UxGT("Click to Begin"); LSTR MSG_LEVEL_BED_NEXT_POINT = _UxGT("Next Point"); LSTR MSG_LEVEL_BED_DONE = _UxGT("Leveling Done!"); + LSTR MSG_ZERO_MESH_POINT = _UxGT("Zero Current Point"); LSTR MSG_Z_FADE_HEIGHT = _UxGT("Fade Height"); LSTR MSG_SET_HOME_OFFSETS = _UxGT("Set Home Offsets"); LSTR MSG_HOME_OFFSET_X = _UxGT("Home Offset X"); // DWIN From e35bedab48c5453474bbd466390b5412f8494c4d Mon Sep 17 00:00:00 2001 From: Andrew <18502096+classicrocker883@users.noreply.github.com> Date: Mon, 24 Nov 2025 20:57:47 -0500 Subject: [PATCH 96/99] =?UTF-8?q?=F0=9F=94=A8=20Importable=20configuration?= =?UTF-8?q?.py=20for=20mc-apply.py=20(#28182)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../PlatformIO/scripts/collect-code-tests.py | 2 +- .../share/PlatformIO/scripts/configuration.py | 69 ++++++---- .../share/PlatformIO/scripts/mc-apply.py | 127 ++++-------------- 3 files changed, 72 insertions(+), 126 deletions(-) diff --git a/buildroot/share/PlatformIO/scripts/collect-code-tests.py b/buildroot/share/PlatformIO/scripts/collect-code-tests.py index a5758e97d3..fc82e9072d 100644 --- a/buildroot/share/PlatformIO/scripts/collect-code-tests.py +++ b/buildroot/share/PlatformIO/scripts/collect-code-tests.py @@ -28,7 +28,7 @@ if pioutil.is_pio_build(): name = f"marlin_{name}", dependencies = None, actions = [ - f"echo ====== Configuring for marlin_{name} ======", + f"@echo ====== Configuring for marlin_{name} ======", "restore_configs", f"cp -f {path} ./Marlin/config.ini", "python ./buildroot/share/PlatformIO/scripts/configuration.py", diff --git a/buildroot/share/PlatformIO/scripts/configuration.py b/buildroot/share/PlatformIO/scripts/configuration.py index 7d811b47ed..71d4e3777c 100755 --- a/buildroot/share/PlatformIO/scripts/configuration.py +++ b/buildroot/share/PlatformIO/scripts/configuration.py @@ -7,27 +7,29 @@ import re, os, shutil, configparser, datetime from pathlib import Path verbose = 0 -def blab(str,level=1): - if verbose >= level: print(f"[config] {str}") +def blab(msg, level=1): + if verbose >= level: print(f"[config] {msg}") def config_path(cpath): return Path("Marlin", cpath) # Apply a single name = on/off ; name = value ; etc. # TODO: Limit to the given (optional) configuration -def apply_opt(name, val, conf=None): +def apply_opt(name, val): if name == "lcd": name, val = val, "on" - # Create a regex to match the option and capture parts of the line - # 1: Indentation - # 2: Comment - # 3: #define and whitespace - # 4: Option name - # 5: First space after name - # 6: Remaining spaces between name and value - # 7: Option value - # 8: Whitespace after value - # 9: End comment + """ + Create a regex to match the option and capture parts of the line + 1: Indentation + 2: Comment + 3: #define and whitespace + 4: Option name + 5: First space after name + 6: Remaining spaces between name and value + 7: Option value + 8: Whitespace after value + 9: End comment + """ regex = re.compile( rf"^(\s*)(//\s*)?(#define\s+)({name}\b)(\s?)(\s*)(.*?)(\s*)(//.*)?$", re.IGNORECASE @@ -101,11 +103,16 @@ def apply_opt(name, val, conf=None): # 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 + blab("Disabling all configuration options...") 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) + if not fullpath.exists(): + blab(f"File not found: {fullpath}", 0) + continue + lines = fullpath.read_text(encoding='utf-8').split('\n') found = False for i in range(len(lines)): @@ -120,14 +127,18 @@ def disable_all_options(): # 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}") + #blab(f"Disable {name}", 2) + # TODO: Taken from mc-apply, not sure which # If the option was found, write the modified lines if found: fullpath.write_text('\n'.join(lines), encoding='utf-8') + blab(f"Updated {file}") # Fetch configuration files from GitHub given the path. # Return True if any files were fetched. def fetch_example(url): + blab(f"Fetching example configuration from: {url}") if url.endswith("/"): url = url[:-1] if not url.startswith('http'): brch = "bugfix-2.1.x" @@ -143,9 +154,12 @@ def fetch_example(url): fetch = "wget -q -O" else: blab("Couldn't find curl or wget", -1) + #blab("Couldn't find curl or wget", 0) + # TODO: Taken from mc-apply, not sure which return False # Reset configurations to default + blab("Resetting configurations to default...") os.system("git checkout HEAD Marlin/*.h") # Try to fetch the remote files @@ -154,9 +168,15 @@ def fetch_example(url): if os.system(f"{fetch} wgot {url}/{fn} >/dev/null 2>&1") == 0: shutil.move('wgot', config_path(fn)) gotfile = True + blab(f"Fetched {fn}", 2) if Path('wgot').exists(): shutil.rmtree('wgot') + if gotfile: + blab("Example configuration fetched successfully") + else: + blab("Failed to fetch example configuration", 0) + return gotfile def section_items(cp, sectkey): @@ -217,8 +237,6 @@ def apply_config_ini(cp): # For each ini_use_config item perform an action for ckey in config_keys: - addbase = False - # For a key ending in .ini load and parse another .ini file if ckey.endswith('.ini'): sect = 'base' @@ -278,12 +296,17 @@ else: # # From within PlatformIO use the loaded INI file # - import pioutil - if pioutil.is_pio_build(): - try: - verbose = int(pioutil.env.GetProjectOption('custom_verbose')) - except: - pass + try: + import pioutil + if pioutil.is_pio_build(): + try: + verbose = int(pioutil.env.GetProjectOption('custom_verbose')) + except: + pass - from platformio.project.config import ProjectConfig - apply_config_ini(ProjectConfig()) + from platformio.project.config import ProjectConfig + apply_config_ini(ProjectConfig()) + except AttributeError: + # Handle the 'IsIntegrationDump' error here, or just continue if + # the build is not a PlatformIO build where pioutil would be unavailable. + pass diff --git a/buildroot/share/PlatformIO/scripts/mc-apply.py b/buildroot/share/PlatformIO/scripts/mc-apply.py index 6ec7122688..7d04ad5585 100755 --- a/buildroot/share/PlatformIO/scripts/mc-apply.py +++ b/buildroot/share/PlatformIO/scripts/mc-apply.py @@ -1,32 +1,29 @@ #!/usr/bin/env python3 -# -# mc-apply.py -# -# Apply firmware configuration from a JSON file (marlin_config.json). -# -# usage: mc-apply.py [-h] [--opt] [--verbose] [config_file] -# -# Process Marlin firmware configuration. -# -# positional arguments: -# config_file Path to the configuration file. -# -# optional arguments: -# -h, --help show this help message and exit -# --opt Output as an option setting script. -# --verbose Enable verbose logging (0-2) -# -import json, sys, os, re, shutil, datetime +""" +mc-apply.py + + Apply firmware configuration from a JSON file (marlin_config.json). + + usage: mc-apply.py [-h] [--opt] [--verbose] [config_file] + + Process Marlin firmware configuration. + + positional arguments: + config_file Path to the configuration file. + + optional arguments: + -h, --help Show this help message and exit + --opt Output as an option setting script. + --verbose Enable verbose logging (0-2) +""" + +import json, sys, os, configuration import config import argparse -from pathlib import Path verbose = 0 -def blab(str, level=1): - if verbose >= level: print(f"[mc-apply] {str}") - -def config_path(cpath): - return Path("Marlin", cpath) +def blab(msg, level=1): + if verbose >= level: print(f"[mc-apply] {msg}") def normalize_value(v): """ @@ -55,80 +52,6 @@ def normalize_value(v): else: return ('set', v if not isinstance(v, bool) else v_str) -# Disable all (most) defined options in the configuration files. -def disable_all_options(): - blab("Disabling all configuration 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) - if not fullpath.exists(): - blab(f"File not found: {fullpath}", 0) - continue - - 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', 'CONFIG_EXAMPLES_DIR'): continue - if name.startswith('_'): continue - found = True - # Comment out the define - lines[i] = re.sub(r'^(\s*)(#define)(\s{1,3})?(\s*)', r'\1//\2 \4', line) - blab(f"Disable {name}", 2) - - # If the option was found, write the modified lines - if found: - fullpath.write_text('\n'.join(lines), encoding='utf-8') - blab(f"Updated {file}") - -# Fetch configuration files from GitHub given the path. -# Return True if any files were fetched. -def fetch_example(url): - blab(f"Fetching example configuration from: {url}") - if url.endswith("/"): url = url[:-1] - if not url.startswith('http'): - brch = "bugfix-2.1.x" - if '@' in url: url, brch = map(str.strip, url.split('@')) - if url == 'examples/default': url = 'default' - url = f"https://raw.githubusercontent.com/MarlinFirmware/Configurations/{brch}/config/{url}" - url = url.replace("%", "%25").replace(" ", "%20") - - # Find a suitable fetch command - if shutil.which("curl") is not None: - fetch = "curl -L -s -S -f -o" - elif shutil.which("wget") is not None: - fetch = "wget -q -O" - else: - blab("Couldn't find curl or wget", 0) - return False - - # Reset configurations to default - blab("Resetting configurations to default...") - os.system("git checkout HEAD Marlin/*.h") - - # Try to fetch the remote files - gotfile = False - for fn in ("Configuration.h", "Configuration_adv.h", "_Bootscreen.h", "_Statusscreen.h"): - if os.system(f"{fetch} wgot {url}/{fn} >/dev/null 2>&1") == 0: - shutil.move('wgot', config_path(fn)) - gotfile = True - blab(f"Fetched {fn}", 2) - - if Path('wgot').exists(): shutil.rmtree('wgot') - - if gotfile: - blab("Example configuration fetched successfully") - else: - blab("Failed to fetch example configuration", 0) - - return gotfile - def report_version(conf): if 'VERSION' in conf: blab("Configuration version information:") @@ -142,7 +65,7 @@ def write_opt_file(conf, outpath='Marlin/apply_config.sh'): if key in ('__INITIAL_HASH', '__directives__', 'VERSION'): continue # Other keys are assumed to be configs - if not type(val) is dict: + if not isinstance(val, dict): continue # Write config commands to the script file @@ -198,17 +121,17 @@ def process_directives(directives): # Handle [disable] directive if directive == "[disable]": - disable_all_options() + configuration.disable_all_options() # Handle example fetching (examples/path or example/path) elif directive.startswith('examples/') or directive.startswith('example/'): if directive.startswith('example/'): directive = 'examples' + directive[7:] - fetch_example(directive) + configuration.fetch_example(directive) # Handle direct URLs elif directive.startswith('http://') or directive.startswith('https://'): - fetch_example(directive) + configuration.fetch_example(directive) else: blab(f"Unknown directive: {directive}", 0) From ba34902610c41d7cc5ffda6a30924a3f8fa73d8e Mon Sep 17 00:00:00 2001 From: David Buezas Date: Tue, 25 Nov 2025 05:40:27 +0100 Subject: [PATCH 97/99] =?UTF-8?q?=F0=9F=94=A7=20Recommend=20FTM=5FSMOOTHIN?= =?UTF-8?q?G=20+=20FTM=5FSHAPER=5FE=20(#28190)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/inc/Warnings.cpp | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/Marlin/src/inc/Warnings.cpp b/Marlin/src/inc/Warnings.cpp index e15d053b4e..7f0bc58ea5 100644 --- a/Marlin/src/inc/Warnings.cpp +++ b/Marlin/src/inc/Warnings.cpp @@ -946,6 +946,12 @@ #endif #if ENABLED(LIN_ADVANCE) #warning "Be aware that FT_MOTION K factor is now set with M900 K (same as LIN_ADVANCE)." + #if DISABLED(FTM_SMOOTHING) + #warning "For higher print quality enable FTM_SMOOTHING with FTM_SMOOTHING_TIME_E to tame Linear Advance accelerations." + #endif + #endif + #if DISABLED(FTM_SHAPER_E) + #warning "For higher print quality enable FTM_SHAPER_E (even if shaper is NONE) to allow axis synchronization." #endif #endif #if ENABLED(FTM_HOME_AND_PROBE) From c1908c865ee42552675c7f745e0ddd6fa8746678 Mon Sep 17 00:00:00 2001 From: Giuliano <3684609+GMagician@users.noreply.github.com> Date: Tue, 25 Nov 2025 05:43:18 +0100 Subject: [PATCH 98/99] =?UTF-8?q?=F0=9F=A9=B9=20Fix=20case=20light=20menu?= =?UTF-8?q?=20build=20(2)=20(#28185)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Followup to #28143 --- Marlin/src/lcd/menu/menu_led.cpp | 8 +++++--- 1 file changed, 5 insertions(+), 3 deletions(-) diff --git a/Marlin/src/lcd/menu/menu_led.cpp b/Marlin/src/lcd/menu/menu_led.cpp index d4807439df..0d46f4d3ff 100644 --- a/Marlin/src/lcd/menu/menu_led.cpp +++ b/Marlin/src/lcd/menu/menu_led.cpp @@ -105,9 +105,11 @@ void menu_led_custom() { #if ENABLED(NEOPIXEL2_SEPARATE) STATIC_ITEM_N(1, MSG_LED_CHANNEL_N, SS_DEFAULT|SS_INVERT); #endif - EDIT_ITEM(uint8, MSG_INTENSITY_R, &leds.color.r, 0, 255, leds.update, true); - EDIT_ITEM(uint8, MSG_INTENSITY_G, &leds.color.g, 0, 255, leds.update, true); - EDIT_ITEM(uint8, MSG_INTENSITY_B, &leds.color.b, 0, 255, leds.update, true); + #if ENABLED(LED_CONTROL_MENU) + EDIT_ITEM(uint8, MSG_INTENSITY_R, &leds.color.r, 0, 255, leds.update, true); + EDIT_ITEM(uint8, MSG_INTENSITY_G, &leds.color.g, 0, 255, leds.update, true); + EDIT_ITEM(uint8, MSG_INTENSITY_B, &leds.color.b, 0, 255, leds.update, true); + #endif #if HAS_WHITE_LED EDIT_ITEM(uint8, MSG_INTENSITY_W, &leds.color.w, 0, 255, leds.update, true); #endif From 38d9b97bbdd61ada4bb547fb31e5439baffb73f1 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Tue, 25 Nov 2025 06:29:28 +0000 Subject: [PATCH 99/99] [cron] Bump distribution date (2025-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 9ff5e45d02..47480dbe70 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 "2025-11-24" +//#define STRING_DISTRIBUTION_DATE "2025-11-25" /** * The protocol for communication to the host. Protocol indicates communication diff --git a/Marlin/src/inc/Version.h b/Marlin/src/inc/Version.h index eb8cab633b..3c983a9f10 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 "2025-11-24" + #define STRING_DISTRIBUTION_DATE "2025-11-25" #endif /**