From b73ebafa0f66a4a48f3269e5c2282ad0969e0933 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Wed, 17 Dec 2025 00:40:16 +0000 Subject: [PATCH 01/13] [cron] Bump distribution date (2025-12-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 4c3e9839af..cacd8e6bf8 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-12-16" +//#define STRING_DISTRIBUTION_DATE "2025-12-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 3e6ac74a54..3117d4d193 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-12-16" + #define STRING_DISTRIBUTION_DATE "2025-12-17" #endif /** From 07565d9016162fb829f0484d462c6ae87bd41615 Mon Sep 17 00:00:00 2001 From: David Buezas Date: Wed, 17 Dec 2025 03:05:55 +0100 Subject: [PATCH 02/13] =?UTF-8?q?=F0=9F=9A=B8=20Safer=20FTMotion=20paramet?= =?UTF-8?q?er=20editing=20(#28191)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/src/HAL/GD32_MFL/timers.cpp | 4 - Marlin/src/HAL/GD32_MFL/timers.h | 9 ++- Marlin/src/HAL/STM32/timers.cpp | 4 - Marlin/src/HAL/STM32/timers.h | 17 +++-- Marlin/src/gcode/feature/ft_motion/M493.cpp | 85 ++++++--------------- Marlin/src/inc/Conditionals-5-post.h | 10 +-- Marlin/src/inc/SanityCheck.h | 2 +- Marlin/src/lcd/menu/menu_motion.cpp | 3 +- Marlin/src/module/ft_motion.cpp | 1 + Marlin/src/module/ft_motion.h | 74 +++++++++++++++++- Marlin/src/module/ft_motion/stepping.h | 12 +-- 11 files changed, 128 insertions(+), 93 deletions(-) diff --git a/Marlin/src/HAL/GD32_MFL/timers.cpp b/Marlin/src/HAL/GD32_MFL/timers.cpp index 13a5c166ef..3bcfdd464b 100644 --- a/Marlin/src/HAL/GD32_MFL/timers.cpp +++ b/Marlin/src/HAL/GD32_MFL/timers.cpp @@ -69,10 +69,6 @@ #endif #endif -#ifndef HAL_TIMER_RATE - #define HAL_TIMER_RATE GetStepperTimerClkFreq() -#endif - #ifndef STEP_TIMER #define STEP_TIMER MF_TIMER_STEP #endif diff --git a/Marlin/src/HAL/GD32_MFL/timers.h b/Marlin/src/HAL/GD32_MFL/timers.h index 1c69c0b468..8aff77aa96 100644 --- a/Marlin/src/HAL/GD32_MFL/timers.h +++ b/Marlin/src/HAL/GD32_MFL/timers.h @@ -37,15 +37,18 @@ typedef uint32_t hal_timer_t; #define HAL_TIMER_TYPE_MAX hal_timer_t(UINT16_MAX) -extern uint32_t GetStepperTimerClkFreq(); +#ifndef HAL_TIMER_RATE + extern uint32_t GetStepperTimerClkFreq(); + #define HAL_TIMER_RATE GetStepperTimerClkFreq() +#endif // Timer configuration constants #define STEPPER_TIMER_RATE 2000000 #define TEMP_TIMER_FREQUENCY 1000 // Timer prescaler calculations -#define STEPPER_TIMER_PRESCALE (GetStepperTimerClkFreq() / STEPPER_TIMER_RATE) // Prescaler = 30 -#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000UL) // (MHz) Stepper Timer ticks per µs +#define STEPPER_TIMER_PRESCALE ((HAL_TIMER_RATE) / (STEPPER_TIMER_RATE)) // Prescaler = 30 +#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000UL) // (MHz) Stepper Timer ticks per µs // Pulse Timer (counter) calculations #define PULSE_TIMER_RATE STEPPER_TIMER_RATE // (Hz) Frequency of Pulse Timer diff --git a/Marlin/src/HAL/STM32/timers.cpp b/Marlin/src/HAL/STM32/timers.cpp index b4271d3a58..5b58a915f0 100644 --- a/Marlin/src/HAL/STM32/timers.cpp +++ b/Marlin/src/HAL/STM32/timers.cpp @@ -81,10 +81,6 @@ #define MCU_TEMP_TIMER 14 // TIM7 is consumed by Software Serial if used. #endif -#ifndef HAL_TIMER_RATE - #define HAL_TIMER_RATE GetStepperTimerClkFreq() -#endif - #ifndef STEP_TIMER #define STEP_TIMER MCU_STEP_TIMER #endif diff --git a/Marlin/src/HAL/STM32/timers.h b/Marlin/src/HAL/STM32/timers.h index 7b55f8a52d..a6f09fd24e 100644 --- a/Marlin/src/HAL/STM32/timers.h +++ b/Marlin/src/HAL/STM32/timers.h @@ -48,13 +48,18 @@ #define TIMER_INDEX_(T) TIMER##T##_INDEX // TIMER#_INDEX enums (timer_index_t) depend on TIM#_BASE defines. #define TIMER_INDEX(T) TIMER_INDEX_(T) // Convert Timer ID to HardwareTimer_Handle index. -#define TEMP_TIMER_FREQUENCY 1000 // Temperature::isr() is expected to be called at around 1kHz +#ifndef HAL_TIMER_RATE + extern uint32_t GetStepperTimerClkFreq(); + #define HAL_TIMER_RATE GetStepperTimerClkFreq() +#endif -// TODO: get rid of manual rate/prescale/ticks/cycles taken for procedures in stepper.cpp -#define STEPPER_TIMER_RATE 2'000'000 // 2 Mhz -extern uint32_t GetStepperTimerClkFreq(); -#define STEPPER_TIMER_PRESCALE (GetStepperTimerClkFreq() / (STEPPER_TIMER_RATE)) -#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000UL) // (MHz) Stepper Timer ticks per µs +// Timer configuration constants +#define STEPPER_TIMER_RATE 2000000 +#define TEMP_TIMER_FREQUENCY 1000 // Temperature::isr() should run at ~1kHz + +// Timer prescaler calculations +#define STEPPER_TIMER_PRESCALE ((HAL_TIMER_RATE) / (STEPPER_TIMER_RATE)) +#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000UL) // (MHz) Stepper Timer ticks per µs // Pulse Timer (counter) calculations #define PULSE_TIMER_RATE STEPPER_TIMER_RATE // (Hz) Frequency of Pulse Timer diff --git a/Marlin/src/gcode/feature/ft_motion/M493.cpp b/Marlin/src/gcode/feature/ft_motion/M493.cpp index f38bbf9ca1..25ab2460f3 100644 --- a/Marlin/src/gcode/feature/ft_motion/M493.cpp +++ b/Marlin/src/gcode/feature/ft_motion/M493.cpp @@ -236,10 +236,8 @@ void GcodeSuite::M493() { return; } auto set_shaper = [&](const AxisEnum axis, ftMotionShaper_t newsh) { - if (newsh != c.shaper[axis]) { - c.shaper[axis] = newsh; + if (c.setShaper(axis, newsh)) flag.update = flag.report = true; - } }; if (seenC) { #define _SET_SHAPER(A) set_shaper(_AXIS(A), shaperVal); @@ -248,14 +246,9 @@ void GcodeSuite::M493() { #endif // NUM_AXES_SHAPED > 0 - // Parse 'H' Axis Synchronization parameter. - if (parser.seenval('H')) { - const bool enabled = parser.value_bool(); - if (enabled != c.axis_sync_enabled) { - c.axis_sync_enabled = enabled; - flag.report = true; - } - } + // Parse bool 'H' Axis Synchronization parameter. + if (parser.seen('H') && c.setAxisSync(parser.value_bool())) + flag.report = true; #if HAS_DYNAMIC_FREQ @@ -317,10 +310,8 @@ void GcodeSuite::M493() { 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) { - c.baseFreq.x = baseFreqVal; + if (goodBaseFreq && c.setBaseFreq(X_AXIS, baseFreqVal)) flag.update = flag.report = true; - } } else // Mode doesn't use frequency. SERIAL_ECHOLNPGM("?Wrong mode for ", C(STEPPER_A_NAME), " (A) frequency."); @@ -328,19 +319,15 @@ void GcodeSuite::M493() { #if HAS_DYNAMIC_FREQ // Parse X frequency scaling parameter - if (seenF && modeUsesDynFreq) { - c.dynFreqK.x = baseDynFreqVal; + if (seenF && c.setDynFreqK(X_AXIS, baseDynFreqVal)) flag.report = true; - } #endif // Parse X zeta parameter if (seenI) { if (AXIS_IS_SHAPING(X)) { - if (goodZeta) { - c.zeta.x = zetaVal; + if (goodZeta && c.setZeta(X_AXIS, zetaVal)) flag.update = true; - } } else SERIAL_ECHOLNPGM("?Wrong mode for ", C(STEPPER_A_NAME), " (I) zeta parameter."); @@ -350,10 +337,8 @@ void GcodeSuite::M493() { // Parse X vtol parameter if (seenQ) { if (AXIS_IS_EISHAPING(X)) { - if (goodVtol) { - c.vtol.x = vtolVal; + if (goodVtol && c.setVtol(X_AXIS, vtolVal)) flag.update = true; - } } else SERIAL_ECHOLNPGM("?Wrong mode for ", C(STEPPER_A_NAME), " (Q) vtol parameter."); @@ -370,10 +355,8 @@ void GcodeSuite::M493() { // Parse Y frequency parameter if (seenA) { if (AXIS_IS_SHAPING(Y)) { - if (goodBaseFreq) { - c.baseFreq.y = baseFreqVal; + if (goodBaseFreq && c.setBaseFreq(Y_AXIS, baseFreqVal)) flag.update = flag.report = true; - } } else // Mode doesn't use frequency. SERIAL_ECHOLNPGM("?Wrong mode for ", C(STEPPER_B_NAME), " (A) frequency."); @@ -381,32 +364,26 @@ void GcodeSuite::M493() { #if HAS_DYNAMIC_FREQ // Parse Y frequency scaling parameter - if (seenF && modeUsesDynFreq) { - c.dynFreqK.y = baseDynFreqVal; + if (seenF && c.setDynFreqK(Y_AXIS, baseDynFreqVal)) flag.report = true; - } #endif // Parse Y zeta parameter if (seenI) { if (AXIS_IS_SHAPING(Y)) { - if (goodZeta) { - c.zeta.y = zetaVal; + if (goodZeta && c.setZeta(Y_AXIS, zetaVal)) flag.update = true; - } } else SERIAL_ECHOLNPGM("?Wrong mode for ", C(STEPPER_B_NAME), " (I) zeta parameter."); } - // Parse Y vtol parameter #if HAS_FTM_EI_SHAPING + // Parse Y vtol parameter if (seenQ) { if (AXIS_IS_EISHAPING(Y)) { - if (goodVtol) { - c.vtol.y = vtolVal; + if (goodVtol && c.setVtol(Y_AXIS, vtolVal)) flag.update = true; - } } else SERIAL_ECHOLNPGM("?Wrong mode for ", C(STEPPER_B_NAME), " (Q) vtol parameter."); @@ -423,10 +400,8 @@ void GcodeSuite::M493() { // Parse Z frequency parameter if (seenA) { if (AXIS_IS_SHAPING(Z)) { - if (goodBaseFreq) { - c.baseFreq.z = baseFreqVal; + if (goodBaseFreq && c.setBaseFreq(Z_AXIS, baseFreqVal)) flag.update = flag.report = true; - } } else // Mode doesn't use frequency. SERIAL_ECHOLNPGM("?Wrong mode for ", C(STEPPER_C_NAME), " (A) frequency."); @@ -434,32 +409,26 @@ void GcodeSuite::M493() { #if HAS_DYNAMIC_FREQ // Parse Z frequency scaling parameter - if (seenF && modeUsesDynFreq) { - c.dynFreqK.z = baseDynFreqVal; + if (seenF && c.setDynFreqK(Z_AXIS, baseDynFreqVal)) flag.report = true; - } #endif // Parse Z zeta parameter if (seenI) { if (AXIS_IS_SHAPING(Z)) { - if (goodZeta) { - c.zeta.z = zetaVal; + if (goodZeta && c.setZeta(Z_AXIS, zetaVal)) flag.update = true; - } } else SERIAL_ECHOLNPGM("?Wrong mode for ", C(STEPPER_C_NAME), " (I) zeta parameter."); } - // Parse Z vtol parameter #if HAS_FTM_EI_SHAPING + // Parse Z vtol parameter if (seenQ) { if (AXIS_IS_EISHAPING(Z)) { - if (goodVtol) { - c.vtol.z = vtolVal; + if (goodVtol && c.setVtol(Z_AXIS, vtolVal)) flag.update = true; - } } else SERIAL_ECHOLNPGM("?Wrong mode for ", C(STEPPER_C_NAME), " (Q) vtol parameter."); @@ -476,10 +445,8 @@ void GcodeSuite::M493() { // Parse E frequency parameter if (seenA) { if (AXIS_IS_SHAPING(E)) { - if (goodBaseFreq) { - c.baseFreq.e = baseFreqVal; + if (goodBaseFreq && c.setBaseFreq(E_AXIS, baseFreqVal)) flag.update = flag.report = true; - } } else // Mode doesn't use frequency. SERIAL_ECHOLNPGM("?Wrong mode for ", C('E'), " (A) frequency."); @@ -487,32 +454,26 @@ void GcodeSuite::M493() { #if HAS_DYNAMIC_FREQ // Parse E frequency scaling parameter - if (seenF && modeUsesDynFreq) { - c.dynFreqK.e = baseDynFreqVal; + if (seenF && c.setDynFreqK(E_AXIS, baseDynFreqVal)) flag.report = true; - } #endif // Parse E zeta parameter if (seenI) { if (AXIS_IS_SHAPING(E)) { - if (goodZeta) { - c.zeta.e = zetaVal; + if (goodZeta && c.setZeta(E_AXIS, zetaVal)) flag.update = true; - } } else SERIAL_ECHOLNPGM("?Wrong mode for ", C('E'), " (I) zeta parameter."); } - // Parse E vtol parameter #if HAS_FTM_EI_SHAPING + // Parse E vtol parameter if (seenQ) { if (AXIS_IS_EISHAPING(E)) { - if (goodVtol) { - c.vtol.e = vtolVal; + if (goodVtol && c.setVtol(E_AXIS, vtolVal)) flag.update = true; - } } else SERIAL_ECHOLNPGM("?Wrong mode for ", C('E'), " (Q) vtol parameter."); diff --git a/Marlin/src/inc/Conditionals-5-post.h b/Marlin/src/inc/Conditionals-5-post.h index fb2a6865f2..024eb42f51 100644 --- a/Marlin/src/inc/Conditionals-5-post.h +++ b/Marlin/src/inc/Conditionals-5-post.h @@ -3700,11 +3700,9 @@ #ifndef FTM_BUFFER_SIZE #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 + + #if ANY(BIQU_MICROPROBE_V1, BIQU_MICROPROBE_V2) && !defined(PROBE_WAKEUP_TIME_MS) + #define PROBE_WAKEUP_TIME_MS 30 + #define PROBE_WAKEUP_TIME_WARNING 1 #endif #endif diff --git a/Marlin/src/inc/SanityCheck.h b/Marlin/src/inc/SanityCheck.h index 618abadae1..5856723c77 100644 --- a/Marlin/src/inc/SanityCheck.h +++ b/Marlin/src/inc/SanityCheck.h @@ -4472,7 +4472,7 @@ 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, ...)."); + static_assert(FTM_BUFFER_SIZE >= 4 && (FTM_BUFFER_SIZE & (FTM_BUFFER_SIZE - 1u)) == 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." #endif diff --git a/Marlin/src/lcd/menu/menu_motion.cpp b/Marlin/src/lcd/menu/menu_motion.cpp index 4c7dea00f0..0c21fdd6aa 100644 --- a/Marlin/src/lcd/menu/menu_motion.cpp +++ b/Marlin/src/lcd/menu/menu_motion.cpp @@ -517,7 +517,8 @@ void menu_move() { CARTES_MAP(_FTM_AXIS_SUBMENU); - EDIT_ITEM(bool, MSG_FTM_AXIS_SYNC, &c.axis_sync_enabled); + editable.state = c.axis_sync_enabled; + EDIT_ITEM(bool, MSG_FTM_AXIS_SYNC, &editable.state, []{ c.setAxisSync(editable.state); }); #if ENABLED(FTM_RESONANCE_TEST) SUBMENU(MSG_FTM_RESONANCE_TEST, menu_ftm_resonance_test); diff --git a/Marlin/src/module/ft_motion.cpp b/Marlin/src/module/ft_motion.cpp index 2c58119b97..c8db197655 100644 --- a/Marlin/src/module/ft_motion.cpp +++ b/Marlin/src/module/ft_motion.cpp @@ -214,6 +214,7 @@ void FTMotion::loop() { bool FTMotion::set_smoothing_time(const AxisEnum axis, const float s_time) { if (!WITHIN(s_time, 0.0f, FTM_MAX_SMOOTHING_TIME)) return false; + planner.synchronize(); cfg.smoothingTime[axis] = s_time; update_smoothing_params(); return true; diff --git a/Marlin/src/module/ft_motion.h b/Marlin/src/module/ft_motion.h index ad1417fd44..88a9a49e4d 100644 --- a/Marlin/src/module/ft_motion.h +++ b/Marlin/src/module/ft_motion.h @@ -102,15 +102,51 @@ typedef struct FTConfig { bool setActive(const bool a) { if (a == active) return false; stepper.ftMotion_syncPosition(); + planner.synchronize(); active = a; return true; } #endif + bool setAxisSync(const bool ena) { + if (ena == axis_sync_enabled) return false; + planner.synchronize(); + axis_sync_enabled = ena; + return true; + } + #if HAS_FTM_SHAPING + bool setShaper(const AxisEnum a, const ftMotionShaper_t s) { + if (s == shaper[a]) return false; + planner.synchronize(); + shaper[a] = s; + return true; + } + constexpr bool goodZeta(const float z) { return WITHIN(z, 0.01f, ftm_max_dampening); } - constexpr bool goodVtol(const float v) { return WITHIN(v, 0.00f, 1.0f); } + + bool setZeta(const AxisEnum a, const float z) { + if (z == zeta[a]) return false; + if (!goodZeta(z)) return false; + planner.synchronize(); + zeta[a] = z; + return true; + } + + #if HAS_FTM_EI_SHAPING + + constexpr bool goodVtol(const float v) { return WITHIN(v, 0.00f, 1.0f); } + + bool setVtol(const AxisEnum a, const float v) { + if (v == vtol[a]) return false; + if (!goodVtol(v)) return false; + planner.synchronize(); + vtol[a] = v; + return true; + } + + #endif #if HAS_DYNAMIC_FREQ @@ -133,12 +169,28 @@ typedef struct FTConfig { || TERN0(HAS_DYNAMIC_FREQ_G, dynFreqMode == dynFreqMode_MASS_BASED)); } + bool setDynFreqK(const AxisEnum a, const float k) { + if (!modeUsesDynFreq()) return false; + if (k == dynFreqK[a]) return false; + planner.synchronize(); + dynFreqK[a] = k; + return true; + } + #endif // HAS_DYNAMIC_FREQ #endif // HAS_FTM_SHAPING constexpr bool goodBaseFreq(const float f) { return WITHIN(f, FTM_MIN_SHAPE_FREQ, (FTM_FS) / 2); } + bool setBaseFreq(const AxisEnum a, const float f) { + if (f == baseFreq[a]) return false; + if (!goodBaseFreq(a)) return false; + planner.synchronize(); + baseFreq[a] = f; + return true; + } + void set_defaults() { #if HAS_STANDARD_MOTION active = ENABLED(FTM_IS_DEFAULT_MOTION); @@ -234,6 +286,26 @@ class FTMotion { } #endif + // Setters for baseFreq, zeta, vtol + static bool setBaseFreq(const AxisEnum a, const float f) { + if (!cfg.setBaseFreq(a, f)) return false; + update_shaping_params(); + return true; + } + static bool setZeta(const AxisEnum a, const float z) { + if (!cfg.setZeta(a, z)) return false; + update_shaping_params(); + return true; + } + + #if HAS_FTM_EI_SHAPING + static bool setVtol(const AxisEnum a, const float v) { + if (!cfg.setVtol(a, v)) return false; + update_shaping_params(); + return true; + } + #endif + // Trajectory generator selection #if ENABLED(FTM_POLYS) static void setTrajectoryType(const TrajectoryType type); diff --git a/Marlin/src/module/ft_motion/stepping.h b/Marlin/src/module/ft_motion/stepping.h index ca814a81be..ff72d90be1 100644 --- a/Marlin/src/module/ft_motion/stepping.h +++ b/Marlin/src/module/ft_motion/stepping.h @@ -41,11 +41,11 @@ constexpr uint32_t FTM_Q_INT = 32u - TICKS_BITS; // Bits remaining constexpr uint32_t FTM_Q = 16u - FTM_Q_INT; // uint16 interval fractional bits. // Intervals buffer has fixed point numbers with the point on this position -static_assert(FRAME_TICKS < FTM_NEVER, "(STEPPER_TIMER_RATE / FTM_FS) must be < " STRINGIFY(FTM_NEVER) " to fit 16-bit fixed-point numbers."); -static_assert(FRAME_TICKS != 2000 || FTM_Q_INT == 11, "FTM_Q_INT should be 11"); -static_assert(FRAME_TICKS != 2000 || FTM_Q == 5, "FTM_Q should be 5"); -static_assert(FRAME_TICKS != 25000 || FTM_Q_INT == 15, "FTM_Q_INT should be 15"); -static_assert(FRAME_TICKS != 25000 || FTM_Q == 1, "FTM_Q should be 1"); +static_assert(FRAME_TICKS < FTM_NEVER, "(STEPPER_TIMER_RATE / FTM_FS) (" STRINGIFY(STEPPER_TIMER_RATE) " / " STRINGIFY(FTM_FS) ") must be < " STRINGIFY(FTM_NEVER) " to fit 16-bit fixed-point numbers."); + +// Sanity check +static_assert(FRAME_TICKS != 2000 || FTM_Q == 5, "FTM_Q should be 5"); +static_assert(FRAME_TICKS != 25000 || FTM_Q == 1, "FTM_Q should be 1"); // The _FP and _fp suffixes mean the number is in fixed point format with the point at the FTM_Q position. // See: https://en.wikipedia.org/wiki/Fixed-point_arithmetic @@ -154,6 +154,8 @@ typedef struct Stepping { // Buffering part // + #define FTM_BUFFER_MASK (FTM_BUFFER_SIZE - 1u) + stepper_plan_t stepper_plan_buff[FTM_BUFFER_SIZE]; uint32_t stepper_plan_tail = 0, stepper_plan_head = 0; XYZEval curr_steps_q48_16{0}; From 47fed759b62c2df0067ef56debe9ba1d277105c7 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Tue, 16 Dec 2025 20:24:23 -0600 Subject: [PATCH 03/13] =?UTF-8?q?=F0=9F=93=9D=20"Hisense"=20thermistor=201?= =?UTF-8?q?3?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/Configuration.h | 2 +- Marlin/src/lcd/thermistornames.h | 2 +- Marlin/src/module/thermistor/thermistor_13.h | 2 +- Marlin/src/module/thermistor/thermistors.h | 2 +- 4 files changed, 4 insertions(+), 4 deletions(-) diff --git a/Marlin/Configuration.h b/Marlin/Configuration.h index bd07add891..6441fdc278 100644 --- a/Marlin/Configuration.h +++ b/Marlin/Configuration.h @@ -500,7 +500,7 @@ * 10 : 100kΩ RS PRO 198-961 * 11 : 100kΩ Keenovo AC silicone mats, most Wanhao i3 machines - beta 3950, 1% * 12 : 100kΩ Vishay 0603 SMD NTCS0603E3104FXT (#8) - calibrated for Makibox hot bed - * 13 : 100kΩ Hisens up to 300°C - for "Simple ONE" & "All In ONE" hotend - beta 3950, 1% + * 13 : 100kΩ Hisense up to 300°C - for "Simple ONE" & "All In ONE" hotend - beta 3950, 1% * 14 : 100kΩ (R25), 4092K (beta25), 4.7kΩ pull-up, bed thermistor as used in Ender-5 S1 * 15 : 100kΩ Calibrated for JGAurora A5 hotend * 17 : 100kΩ Dagoma NTC white thermistor diff --git a/Marlin/src/lcd/thermistornames.h b/Marlin/src/lcd/thermistornames.h index dd27a9abdd..d585805587 100644 --- a/Marlin/src/lcd/thermistornames.h +++ b/Marlin/src/lcd/thermistornames.h @@ -95,7 +95,7 @@ #elif THERMISTOR_ID == 12 #define THERMISTOR_NAME "E3104FXT (alt)" #elif THERMISTOR_ID == 13 - #define THERMISTOR_NAME "Hisens 3950" + #define THERMISTOR_NAME "Hisense 3950" #elif THERMISTOR_ID == 14 #define THERMISTOR_NAME "100k Ender-5 S1" #elif THERMISTOR_ID == 15 diff --git a/Marlin/src/module/thermistor/thermistor_13.h b/Marlin/src/module/thermistor/thermistor_13.h index 7e87373948..930deb9d53 100644 --- a/Marlin/src/module/thermistor/thermistor_13.h +++ b/Marlin/src/module/thermistor/thermistor_13.h @@ -21,7 +21,7 @@ */ #pragma once -// R25 = 100 kOhm, beta25 = 4100 K, 4.7 kOhm pull-up, Hisens thermistor +// R25 = 100 kOhm, beta25 = 4100 K, 4.7 kOhm pull-up, Hisense thermistor constexpr temp_entry_t temptable_13[] PROGMEM = { { OV( 20.04), 300 }, { OV( 23.19), 290 }, diff --git a/Marlin/src/module/thermistor/thermistors.h b/Marlin/src/module/thermistor/thermistors.h index f3562d1505..e5dfcf1617 100644 --- a/Marlin/src/module/thermistor/thermistors.h +++ b/Marlin/src/module/thermistor/thermistors.h @@ -122,7 +122,7 @@ typedef struct { raw_adc_t value; celsius_t celsius; } temp_entry_t; #if ANY_THERMISTOR_IS(12) // beta25 = 4700 K, R25 = 100kΩ, Pullup = 4.7kΩ, "Personal calibration for Makibox hot bed" #include "thermistor_12.h" #endif -#if ANY_THERMISTOR_IS(13) // beta25 = 4100 K, R25 = 100kΩ, Pullup = 4.7kΩ, "Hisens" +#if ANY_THERMISTOR_IS(13) // beta25 = 4100 K, R25 = 100kΩ, Pullup = 4.7kΩ, "Hisense" #include "thermistor_13.h" #endif #if ANY_THERMISTOR_IS(14) // beta25 = 4092 K, R25 = 100kΩ, Pullup = 4.7kΩ, "EPCOS" for hot bed From 5a9ce77ab3e59c7c8722bd39f112217bec1d6a71 Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Wed, 17 Dec 2025 15:31:04 -0600 Subject: [PATCH 04/13] =?UTF-8?q?=F0=9F=94=A7=20FT=20Motion=20keep=20MULTI?= =?UTF-8?q?STEPPING=5FLIMIT?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/inc/Conditionals-4-adv.h | 2 -- 1 file changed, 2 deletions(-) diff --git a/Marlin/src/inc/Conditionals-4-adv.h b/Marlin/src/inc/Conditionals-4-adv.h index 7e94c617c1..75c4efa743 100644 --- a/Marlin/src/inc/Conditionals-4-adv.h +++ b/Marlin/src/inc/Conditionals-4-adv.h @@ -373,8 +373,6 @@ #undef INPUT_SHAPING_Y #undef INPUT_SHAPING_Z #undef INPUT_SHAPING_E_SYNC - #undef MULTISTEPPING_LIMIT - #define MULTISTEPPING_LIMIT 1 #endif // Linear advance uses Jerk since E is an isolated axis From fc519143fe8ad8faca59d8e0cf2dafdde7da3aab Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Thu, 18 Dec 2025 00:31:10 +0000 Subject: [PATCH 05/13] [cron] Bump distribution date (2025-12-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 cacd8e6bf8..77fc101dc2 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-12-17" +//#define STRING_DISTRIBUTION_DATE "2025-12-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 3117d4d193..35c410e8da 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-12-17" + #define STRING_DISTRIBUTION_DATE "2025-12-18" #endif /** From 1a2bb68f85f30a8deb9c0c6db454c23a192f774f Mon Sep 17 00:00:00 2001 From: ellensp <530024+ellensp@users.noreply.github.com> Date: Thu, 18 Dec 2025 13:56:59 +1300 Subject: [PATCH 06/13] =?UTF-8?q?=E2=9A=A1=EF=B8=8F=20RP2040=20HAL=20Impro?= =?UTF-8?q?vements=20(#28215)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/HAL/RP2040/HAL.cpp | 132 ++++++++++----------- Marlin/src/HAL/RP2040/HAL.h | 24 +++- Marlin/src/HAL/RP2040/MarlinSerial.cpp | 38 +++++- Marlin/src/HAL/RP2040/MarlinSerial.h | 42 ++++++- Marlin/src/gcode/gcode_d.cpp | 38 +++++- Marlin/src/pins/rp2040/pins_BTT_SKR_Pico.h | 54 +++------ ini/raspberrypi.ini | 8 +- 7 files changed, 211 insertions(+), 125 deletions(-) diff --git a/Marlin/src/HAL/RP2040/HAL.cpp b/Marlin/src/HAL/RP2040/HAL.cpp index 9341480078..51f68648bc 100644 --- a/Marlin/src/HAL/RP2040/HAL.cpp +++ b/Marlin/src/HAL/RP2040/HAL.cpp @@ -28,6 +28,7 @@ #include "../../inc/MarlinConfig.h" #include "../shared/Delay.h" +#include "../../module/temperature.h" // For OVERSAMPLENR extern "C" { #include "pico/bootrom.h" @@ -41,50 +42,38 @@ extern "C" { #include "msc_sd.h" #endif -// Core 1 watchdog configuration -#define CORE1_MAX_RESETS 5 // Maximum number of Core 1 resets before halting system - // ------------------------ // Public Variables // ------------------------ volatile uint32_t adc_accumulators[5] = {0}; // Accumulators for oversampling (sum of readings) volatile uint8_t adc_counts[5] = {0}; // Count of readings accumulated per channel -volatile uint16_t adc_values[5] = {512, 512, 512, 512, 512}; // Final oversampled ADC values (averages) - initialized to mid-range +volatile uint16_t adc_values[5] = {4095, 4095, 4095, 4095, 4095}; // Averaged ADC values (single reading equivalent) - initialized to max (open circuit) -// Core 1 watchdog monitoring +// Core monitoring for watchdog +volatile uint32_t core0_last_heartbeat = 0; // Timestamp of Core 0's last activity volatile uint32_t core1_last_heartbeat = 0; // Timestamp of Core 1's last activity -volatile bool core1_watchdog_triggered = false; // Flag to indicate Core 1 reset -volatile uint8_t core1_reset_count = 0; // Count of Core 1 resets - halt system if >= CORE1_MAX_RESETS +#if ENABLED(MARLIN_DEV_MODE) + volatile bool core1_freeze_test = false; // Flag to freeze Core 1 for watchdog testing +#endif volatile uint8_t current_pin; volatile bool MarlinHAL::adc_has_result; volatile uint8_t adc_channels_enabled[5] = {false}; // Track which ADC channels are enabled -// Helper function for LED blinking patterns -void blink_led_pattern(uint8_t blink_count, uint32_t blink_duration_us = 100000) { - #if DISABLED(PINS_DEBUGGING) && PIN_EXISTS(LED) - for (uint8_t i = 0; i < blink_count; i++) { - WRITE(LED_PIN, HIGH); - busy_wait_us(blink_duration_us); - WRITE(LED_PIN, LOW); - if (i < blink_count - 1) { // Don't delay after the last blink - busy_wait_us(blink_duration_us); - } - } - #endif -} - // Core 1 ADC reading task - dynamically reads all enabled channels with oversampling void core1_adc_task() { - static uint32_t last_led_toggle = 0; - const uint8_t OVERSAMPLENR = 16; // Standard Marlin oversampling count - - // Signal successful Core 1 startup/restart - SERIAL_ECHO_MSG("Core 1 ADC task started"); + static uint32_t last_temp_update = 0; while (true) { - // Update heartbeat timestamp at start of each scan cycle - core1_last_heartbeat = time_us_32(); + #if ENABLED(MARLIN_DEV_MODE) + // Check if we should freeze for watchdog test + if (core1_freeze_test) { + // Stop updating heartbeat and spin forever + while (core1_freeze_test) { + busy_wait_us(100000); // 100ms delay + } + } + #endif // Scan all enabled ADC channels for (uint8_t channel = 0; channel < 5; channel++) { @@ -114,11 +103,9 @@ void core1_adc_task() { adc_accumulators[channel] += reading; adc_counts[channel]++; - // Update the averaged value with current accumulation (provides immediate valid data) - adc_values[channel] = adc_accumulators[channel] / adc_counts[channel]; - - // When we reach the full oversampling count, reset accumulator for next cycle + // When we reach the full oversampling count, calculate averaged value (Marlin ISR does its own oversampling) if (adc_counts[channel] >= OVERSAMPLENR) { + adc_values[channel] = adc_accumulators[channel] / OVERSAMPLENR; // Return single-reading equivalent adc_accumulators[channel] = 0; adc_counts[channel] = 0; } @@ -129,17 +116,19 @@ void core1_adc_task() { } } - // Core 1 LED indicator: Double blink every 2 seconds to show Core 1 is active + // Core 1 just provides ADC readings - don't trigger temperature updates from here + // Let Marlin's main temperature ISR on Core 0 handle the timing and updates uint32_t now = time_us_32(); - if (now - last_led_toggle >= 2000000) { // 2 seconds - last_led_toggle = now; - #if DISABLED(PINS_DEBUGGING) && PIN_EXISTS(LED) - // Triple blink pattern if watchdog was triggered (shows Core 1 was reset) - if (core1_watchdog_triggered) { - core1_watchdog_triggered = false; // Clear flag - blink_led_pattern(3); // Triple blink for watchdog reset - } else { - blink_led_pattern(2); // Normal double blink + if (now - last_temp_update >= 100000) { // 100ms = 100000 microseconds + last_temp_update = now; + #if ENABLED(USE_WATCHDOG) + // Refresh watchdog here like AVR ISR does indirectly via temperature updates + // Use 2 second delay to allow watchdog_init to be called during boot + static uint32_t core1_start_time = 0; + if (core1_start_time == 0) core1_start_time = time_us_32(); + + if (time_us_32() - core1_start_time > 2000000) { + hal.watchdog_refresh(1); // Refresh from Core 1 } #endif } @@ -219,37 +208,42 @@ void MarlinHAL::reboot() { watchdog_reboot(0, 0, 1); } void MarlinHAL::watchdog_init() { #if DISABLED(DISABLE_WATCHDOG_INIT) static_assert(WDT_TIMEOUT_US > 1000, "WDT Timeout is too small, aborting"); + // Initialize Core 0 heartbeat + core0_last_heartbeat = time_us_32(); watchdog_enable(WDT_TIMEOUT_US/1000, true); #endif } - void MarlinHAL::watchdog_refresh() { - // If Core 1 has reset CORE1_MAX_RESETS+ times, stop updating watchdog to halt system - if (core1_reset_count >= CORE1_MAX_RESETS) { - SERIAL_ECHO_MSG("Core 1 reset limit exceeded (", core1_reset_count, " resets) - halting system for safety"); - return; // Don't update watchdog - system will halt + void MarlinHAL::watchdog_refresh(const uint8_t core/*=0*/) { + if (core == 0) { + // Update Core 0 heartbeat + core0_last_heartbeat = time_us_32(); + + // Check if Core 1 is alive (2 second timeout) + if (time_us_32() - core1_last_heartbeat < 2000000) { + watchdog_update(); // Only refresh if Core 1 is responding + #if DISABLED(PINS_DEBUGGING) && PIN_EXISTS(LED) + TOGGLE(LED_PIN); // Heartbeat indicator + #endif + } + // If Core 1 is stuck, don't refresh - let watchdog reset the system } + else { + // Update Core 1 heartbeat + core1_last_heartbeat = time_us_32(); - watchdog_update(); - - // Check Core 1 watchdog (15 second timeout) - uint32_t now = time_us_32(); - if (now - core1_last_heartbeat > 15000000) { // 15 seconds - // Core 1 appears stuck - reset it - multicore_reset_core1(); - multicore_launch_core1(core1_adc_task); - core1_watchdog_triggered = true; // Signal for LED indicator - core1_reset_count++; // Increment reset counter - SERIAL_ECHO_MSG("Core 1 ADC watchdog triggered - resetting Core 1 (attempt ", core1_reset_count, ")"); + // Check if Core 0 is alive (2 second timeout) + if (time_us_32() - core0_last_heartbeat < 2000000) { + watchdog_update(); // Only refresh if Core 0 is responding + #if DISABLED(PINS_DEBUGGING) && PIN_EXISTS(LED) + TOGGLE(LED_PIN); // Heartbeat indicator + #endif + } + // If Core 0 is stuck, don't refresh - let watchdog reset the system } - - #if DISABLED(PINS_DEBUGGING) && PIN_EXISTS(LED) - // Core 0 LED indicator: Single toggle every watchdog refresh (shows Core 0 activity) - TOGGLE(LED_PIN); - #endif } -#endif +#endif // USE_WATCHDOG // ------------------------ // ADC @@ -290,13 +284,15 @@ void flashFirmware(const int16_t) { hal.reboot(); } extern "C" { void * _sbrk(int incr); - extern unsigned int __bss_end__; // end of bss section + extern unsigned int __StackLimit; // Lowest address the stack can grow to } -// Return free memory between end of heap (or end bss) and whatever is current +// Return free memory between end of heap and start of stack int freeMemory() { - int free_memory, heap_end = (int)_sbrk(0); - return (int)&free_memory - (heap_end ?: (int)&__bss_end__); + void* heap_end = _sbrk(0); + // Use the linker-provided stack limit instead of a local variable + // __StackLimit is the lowest address the stack can grow to + return (char*)&__StackLimit - (char*)heap_end; } #endif // __PLAT_RP2040__ diff --git a/Marlin/src/HAL/RP2040/HAL.h b/Marlin/src/HAL/RP2040/HAL.h index a1305bd135..a49b343899 100644 --- a/Marlin/src/HAL/RP2040/HAL.h +++ b/Marlin/src/HAL/RP2040/HAL.h @@ -51,6 +51,28 @@ #include "MarlinSerial.h" +#if !WITHIN(SERIAL_PORT, -1, 1) + #error "SERIAL_PORT must be from -1 to 1." +#endif + +#ifdef SERIAL_PORT_2 + #if !WITHIN(SERIAL_PORT_2, -1, 1) + #error "SERIAL_PORT_2 must be from -1 to 1." + #endif +#endif + +#ifdef SERIAL_PORT_3 + #if !WITHIN(SERIAL_PORT_3, -1, 1) + #error "SERIAL_PORT_3 must be from -1 to 1." + #endif +#endif + +#ifdef LCD_SERIAL_PORT + #if !WITHIN(LCD_SERIAL_PORT, -1, 1) + #error "LCD_SERIAL_PORT must be from -1 to 1." + #endif +#endif + // ------------------------ // Defines // ------------------------ @@ -131,7 +153,7 @@ public: // Watchdog static void watchdog_init() IF_DISABLED(USE_WATCHDOG, {}); - static void watchdog_refresh() IF_DISABLED(USE_WATCHDOG, {}); + static void watchdog_refresh(const uint8_t=0) IF_DISABLED(USE_WATCHDOG, {}); static void init(); // Called early in setup() static void init_board() {} // Called less early in setup() diff --git a/Marlin/src/HAL/RP2040/MarlinSerial.cpp b/Marlin/src/HAL/RP2040/MarlinSerial.cpp index dd01edd830..5e3bf0c148 100644 --- a/Marlin/src/HAL/RP2040/MarlinSerial.cpp +++ b/Marlin/src/HAL/RP2040/MarlinSerial.cpp @@ -30,10 +30,40 @@ #include "../../feature/e_parser.h" #endif -#define _IMPLEMENT_SERIAL(X) DefaultSerial##X MSerial##X(false, Serial##X) -#define IMPLEMENT_SERIAL(X) _IMPLEMENT_SERIAL(X) -#if WITHIN(SERIAL_PORT, 0, 3) - IMPLEMENT_SERIAL(SERIAL_PORT); +#include + +// Marlin uses: -1=USB, 0=UART0, 1=UART1 +// Arduino uses: Serial=USB, Serial1=UART0, Serial2=UART1 +// +// To remap Arduino's numbering to Marlin's convention, we create MarlinSerial0/MarlinSerial1 +// as new UART instances with custom pins. +// +// We use distinct names (MarlinSerial0/MarlinSerial1) to avoid symbol conflicts with +// the Arduino framework's pre-defined Serial1/Serial2 objects, which use the same +// underlying hardware (_UART0_ and _UART1_). + +// Create Serial0 as UART0 with custom or default pins +arduino::UART MarlinSerial0( + #if PINS_EXIST(SERIAL0_TX, SERIAL0_RX) + SERIAL0_TX_PIN, SERIAL0_RX_PIN // Custom pins for UART0 (Marlin Serial0) + #else + 0, 1 // Default UART0 pins (GP0/GP1) + #endif +); + +// Not using PINS_EXIST(SERIAL1_TX, SERIAL1_RX) because SERIAL1_TX and SERIAL1_RX +// are defined in framework-arduino-mbed/variants/RASPBERRY_PI_PICO/pins_arduino.h + +// Create Serial1 as UART1 with custom or default pins +#if defined(SERIAL1_TX_PIN) && defined(SERIAL1_RX_PIN) + arduino::UART MarlinSerial1(SERIAL1_TX_PIN, SERIAL1_RX_PIN); // Custom pins for UART1 (Marlin Serial1) #endif +// Wrap the serial ports for Marlin +DefaultSerial0 MSerial0(false, MarlinSerial0); // Marlin Serial0 = UART0 +#if defined(SERIAL1_TX_PIN) && defined(SERIAL1_RX_PIN) + DefaultSerial1 MSerial1(false, MarlinSerial1); // Marlin Serial1 = UART1 +#endif +DefaultSerial2 MSerial2(false, Serial); // Marlin Serial2 = USB (-1) + #endif // __PLAT_RP2040__ diff --git a/Marlin/src/HAL/RP2040/MarlinSerial.h b/Marlin/src/HAL/RP2040/MarlinSerial.h index b0db3167fa..f407a838df 100644 --- a/Marlin/src/HAL/RP2040/MarlinSerial.h +++ b/Marlin/src/HAL/RP2040/MarlinSerial.h @@ -29,20 +29,50 @@ #include "../../core/serial_hook.h" -typedef ForwardSerial1Class< decltype(Serial) > DefaultSerial1; -extern DefaultSerial1 MSerial0; +/** + * Serial Port Configuration for RP2040 (Raspberry Pi Pico) + * + * Arduino-Pico Core Serial Objects: + * - Serial: USB Serial (CDC ACM) + * - Serial1: Hardware UART0 + * - Serial2: Hardware UART1 + * - SerialUSB: Alias for Serial (USB) + * + * Marlin Serial Wrappers: + * - MSerial0: Wrapper for MarlinSerial0 (UART0), used as Serial0 + * - MSerial1: Wrapper for MarlinSerial1 (UART1), declared dynamically if used + * - MSerial2: Wrapper for Serial (USB) + * - USBSerial: Wrapper for SerialUSB (USB) + * + * How it all joins together: + * - Configuration defines SERIAL_PORT, SERIAL_PORT_2, etc. (-1 to 1 range) + * - shared/serial_ports.h maps these to MYSERIAL1, MYSERIAL2, etc. + * - MYSERIAL1 uses MSerialX based on the port index + * - USB ports (-1) use USB_SERIAL_PORT (MSerial2) + */ + +// Forward declare our custom Serial objects (defined in MarlinSerial.cpp) +namespace arduino { class UART; } +extern arduino::UART MarlinSerial0; // Always declared +extern arduino::UART MarlinSerial1; // Custom Marlin Serial1 to avoid conflict + +typedef ForwardSerial1Class< decltype(MarlinSerial0) > DefaultSerial0; +extern DefaultSerial0 MSerial0; +typedef ForwardSerial1Class< decltype(MarlinSerial1) > DefaultSerial1; +extern DefaultSerial1 MSerial1; +typedef ForwardSerial1Class< decltype(Serial) > DefaultSerial2; +extern DefaultSerial2 MSerial2; typedef ForwardSerial1Class USBSerialType; extern USBSerialType USBSerial; -#define Serial0 Serial #define _DECLARE_SERIAL(X) \ - typedef ForwardSerial1Class DefaultSerial##X; \ + typedef ForwardSerial1Class DefaultSerial##X; \ extern DefaultSerial##X MSerial##X #define DECLARE_SERIAL(X) _DECLARE_SERIAL(X) #define SERIAL_INDEX_MIN 0 -#define SERIAL_INDEX_MAX 6 -#define USB_SERIAL_PORT(...) MSerial0 +#define SERIAL_INDEX_MAX 1 +#define USB_SERIAL_PORT(...) MSerial2 #include "../shared/serial_ports.h" #if defined(LCD_SERIAL_PORT) && ANY(HAS_DGUS_LCD, EXTENSIBLE_UI) diff --git a/Marlin/src/gcode/gcode_d.cpp b/Marlin/src/gcode/gcode_d.cpp index 1e472e0f6e..b6852aba6a 100644 --- a/Marlin/src/gcode/gcode_d.cpp +++ b/Marlin/src/gcode/gcode_d.cpp @@ -179,17 +179,43 @@ void GcodeSuite::D(const int16_t dcode) { break; case 100: { // D100 Disable heaters and attempt a hard hang (Watchdog Test) + + #ifdef __PLAT_RP2040__ + const uint8_t core = parser.byteval('C', 0); // C parameter: which core to freeze (0=Core 0, 1=Core 1) + #else + constexpr uint8_t core = 0; + #endif + SERIAL_ECHOLNPGM("Disabling heaters and attempting to trigger Watchdog"); SERIAL_ECHOLNPGM("(USE_WATCHDOG " TERN(USE_WATCHDOG, "ENABLED", "DISABLED") ")"); + #ifdef __PLAT_RP2040__ + SERIAL_ECHOLNPGM("Freezing Core ", core); + #endif + thermalManager.disable_all_heaters(); delay(1000); // Allow time to print - hal.isr_off(); - // Use a low-level delay that does not rely on interrupts to function - // Do not spin forever, to avoid thermal risks if heaters are enabled and - // watchdog does not work. - for (int i = 10000; i--;) DELAY_US(1000UL); - hal.isr_on(); + + if (core == 1) { + #ifdef __PLAT_RP2040__ + // Freeze Core 1 by setting a flag it will check + extern volatile bool core1_freeze_test; + core1_freeze_test = true; + delay(10000); // Wait 10 seconds for watchdog to trigger + core1_freeze_test = false; + #endif + } + else { + // Freeze Core 0 (original behavior) + hal.isr_off(); + // Use a low-level delay that does not rely on interrupts to function + // Do not spin forever, to avoid thermal risks if heaters are enabled and + // watchdog does not work. + for (int i = 10000; i--;) DELAY_US(1000UL); + hal.isr_on(); + } + SERIAL_ECHOLNPGM("FAILURE: Watchdog did not trigger board reset."); + } break; #if HAS_MEDIA diff --git a/Marlin/src/pins/rp2040/pins_BTT_SKR_Pico.h b/Marlin/src/pins/rp2040/pins_BTT_SKR_Pico.h index 7eb0188820..d9e686ad5b 100644 --- a/Marlin/src/pins/rp2040/pins_BTT_SKR_Pico.h +++ b/Marlin/src/pins/rp2040/pins_BTT_SKR_Pico.h @@ -107,51 +107,35 @@ // #define NEOPIXEL_PIN 24 +// Custom serial pins for RP2040 UART remapping +#define SERIAL1_TX_PIN 8 +#define SERIAL1_RX_PIN 9 + /** * TMC2208/TMC2209 stepper drivers */ #if HAS_TMC_UART /** * Hardware serial communication ports. - * If undefined software serial is used according to the pins below */ - //#define X_HARDWARE_SERIAL Serial1 - //#define X2_HARDWARE_SERIAL Serial1 - //#define Y_HARDWARE_SERIAL Serial1 - //#define Y2_HARDWARE_SERIAL Serial1 - //#define Z_HARDWARE_SERIAL MSerial1 - //#define Z2_HARDWARE_SERIAL Serial1 - //#define E0_HARDWARE_SERIAL Serial1 - //#define E1_HARDWARE_SERIAL Serial1 - //#define E2_HARDWARE_SERIAL Serial1 - //#define E3_HARDWARE_SERIAL Serial1 - //#define E4_HARDWARE_SERIAL Serial1 + #define X_HARDWARE_SERIAL MarlinSerial1 + #define Y_HARDWARE_SERIAL MarlinSerial1 + #define Z_HARDWARE_SERIAL MarlinSerial1 + #define E0_HARDWARE_SERIAL MarlinSerial1 - /** - * Software serial - */ - #ifndef X_SERIAL_TX_PIN - #define X_SERIAL_TX_PIN 8 + // Default TMC slave addresses + #ifndef X_SLAVE_ADDRESS + #define X_SLAVE_ADDRESS 0 #endif - #ifndef X_SERIAL_RX_PIN - #define X_SERIAL_RX_PIN 9 + #ifndef Y_SLAVE_ADDRESS + #define Y_SLAVE_ADDRESS 2 #endif - #ifndef Y_SERIAL_TX_PIN - #define Y_SERIAL_TX_PIN 8 + #ifndef Z_SLAVE_ADDRESS + #define Z_SLAVE_ADDRESS 1 #endif - #ifndef Y_SERIAL_RX_PIN - #define Y_SERIAL_RX_PIN 9 - #endif - #ifndef Z_SERIAL_TX_PIN - #define Z_SERIAL_TX_PIN 8 - #endif - #ifndef Z_SERIAL_RX_PIN - #define Z_SERIAL_RX_PIN 9 - #endif - #ifndef E0_SERIAL_TX_PIN - #define E0_SERIAL_TX_PIN 8 - #endif - #ifndef E0_SERIAL_RX_PIN - #define E0_SERIAL_RX_PIN 9 + #ifndef E0_SLAVE_ADDRESS + #define E0_SLAVE_ADDRESS 3 #endif + + #define TMC_BAUD_RATE 115200 #endif diff --git a/ini/raspberrypi.ini b/ini/raspberrypi.ini index 2ee74631f9..d93cabbc92 100644 --- a/ini/raspberrypi.ini +++ b/ini/raspberrypi.ini @@ -20,8 +20,7 @@ lib_deps = ${common.lib_deps} #lvgl/lvgl@^8.1.0 lib_ignore = WiFi build_flags = ${common.build_flags} -D__PLAT_RP2040__ -DPLATFORM_M997_SUPPORT -DNO_SD_HOST_DRIVE -Wno-expansion-to-defined -Wno-vla -Wno-ignored-qualifiers -#debug_tool = jlink -#upload_protocol = jlink +upload_protocol = picotool #custom_marlin.HAS_SD_HOST_DRIVE = tinyusb [env:RP2040-alt] @@ -34,6 +33,5 @@ board_build.core = earlephilhower # [env:SKR_Pico] extends = env:RP2040 - -[env:SKR_Pico_UART] -extends = env:SKR_Pico +lib_deps = ${common.lib_deps} + arduino-libraries/Servo From a47f53b8a627600e993eaccdddbb13d4fc90d0a7 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Fri, 19 Dec 2025 00:34:07 +0000 Subject: [PATCH 07/13] [cron] Bump distribution date (2025-12-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 77fc101dc2..b60723ce95 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-12-18" +//#define STRING_DISTRIBUTION_DATE "2025-12-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 35c410e8da..ffe3f35427 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-12-18" + #define STRING_DISTRIBUTION_DATE "2025-12-19" #endif /** From e561058051da5986afa883e728697e77db59b4eb Mon Sep 17 00:00:00 2001 From: David Buezas Date: Sat, 20 Dec 2025 00:33:44 +0100 Subject: [PATCH 08/13] =?UTF-8?q?=F0=9F=90=9B=20Fix=20FT=20Motion=20edit?= =?UTF-8?q?=20with=20UI=20(#28233)?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit Co-authored-by: Scott Lahteine --- Marlin/src/HAL/STM32/timers.h | 2 +- Marlin/src/gcode/feature/ft_motion/M493.cpp | 16 +++- Marlin/src/gcode/feature/ft_motion/M494.cpp | 21 +++-- Marlin/src/lcd/extui/mks_ui/wifi_upload.cpp | 2 +- Marlin/src/lcd/menu/menu_motion.cpp | 99 ++++++++++++++------- Marlin/src/module/ft_motion.cpp | 39 +++++--- Marlin/src/module/ft_motion.h | 84 ++++++++--------- Marlin/src/module/ft_motion/shaping.h | 2 +- Marlin/src/module/ft_motion/smoothing.h | 16 ++-- Marlin/src/module/ft_motion/stepping.h | 12 +-- buildroot/tests/I3DBEEZ9_V1 | 5 +- 11 files changed, 185 insertions(+), 113 deletions(-) diff --git a/Marlin/src/HAL/STM32/timers.h b/Marlin/src/HAL/STM32/timers.h index a6f09fd24e..a6c9204a77 100644 --- a/Marlin/src/HAL/STM32/timers.h +++ b/Marlin/src/HAL/STM32/timers.h @@ -59,7 +59,7 @@ // Timer prescaler calculations #define STEPPER_TIMER_PRESCALE ((HAL_TIMER_RATE) / (STEPPER_TIMER_RATE)) -#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000UL) // (MHz) Stepper Timer ticks per µs +#define STEPPER_TIMER_TICKS_PER_US ((STEPPER_TIMER_RATE) / 1000000UL) // (ticks/μs) Stepper Timer ticks per µs // Pulse Timer (counter) calculations #define PULSE_TIMER_RATE STEPPER_TIMER_RATE // (Hz) Frequency of Pulse Timer diff --git a/Marlin/src/gcode/feature/ft_motion/M493.cpp b/Marlin/src/gcode/feature/ft_motion/M493.cpp index 25ab2460f3..272c3d7ab3 100644 --- a/Marlin/src/gcode/feature/ft_motion/M493.cpp +++ b/Marlin/src/gcode/feature/ft_motion/M493.cpp @@ -27,6 +27,7 @@ #include "../../gcode.h" #include "../../../module/ft_motion.h" #include "../../../module/stepper.h" +#include "../../../lcd/marlinui.h" void say_shaper_type(const AxisEnum a, bool &sep, const char axis_name) { if (sep) SERIAL_ECHOPGM(" ; "); @@ -87,7 +88,7 @@ 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(c.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(c.dynFreqK.x, 2), F("Hz/"), z_based ? F("mm") : F("g")); #endif @@ -113,6 +114,16 @@ void say_shaping() { #endif SERIAL_EOL(); #endif + + #if ENABLED(FTM_SHAPER_E) + SERIAL_CHAR('E'); + SERIAL_ECHO_TERNARY(dynamic, " ", "base dynamic", "static", " shaper frequency: "); + SERIAL_ECHO(p_float_t(c.baseFreq.e, 2), F(" Hz")); + #if HAS_DYNAMIC_FREQ + if (dynamic) SERIAL_ECHO(F(" scaling: "), p_float_t(c.dynFreqK.e, 2), F("Hz/"), z_based ? F("mm") : F("g")); + #endif + SERIAL_EOL(); + #endif } } @@ -483,7 +494,8 @@ void GcodeSuite::M493() { #endif // FTM_SHAPER_E - if (flag.update) ftMotion.update_shaping_params(); + if (flag.update || flag.report) + ui.refresh(); if (flag.report) say_shaping(); } diff --git a/Marlin/src/gcode/feature/ft_motion/M494.cpp b/Marlin/src/gcode/feature/ft_motion/M494.cpp index 17a9227148..d6161a9574 100644 --- a/Marlin/src/gcode/feature/ft_motion/M494.cpp +++ b/Marlin/src/gcode/feature/ft_motion/M494.cpp @@ -27,6 +27,7 @@ #include "../../../module/ft_motion.h" #include "../../../module/stepper.h" #include "../../../module/planner.h" +#include "../../../lcd/marlinui.h" void say_ftm_settings() { #if ANY(FTM_POLYS, FTM_SMOOTHING) @@ -111,14 +112,17 @@ void GcodeSuite::M494() { #if ENABLED(FTM_SMOOTHING) - #define SMOOTH_SET(A,N) \ - if (parser.seenval(CHARIFY(A))) { \ - if (ftMotion.set_smoothing_time(_AXIS(A), parser.value_float())) \ - report = true; \ - else \ - SERIAL_ECHOLNPGM("?Invalid ", C(N), " smoothing time (", C(CHARIFY(A)), ") value."); \ + auto smooth_set = [](AxisEnum axis, char axis_name) { + if (parser.seenval(IAXIS_CHAR(axis))) { + if (ftMotion.set_smoothing_time(axis, parser.value_float())) + return true; + else + SERIAL_ECHOLNPGM("?Invalid ", C(axis_name), " smoothing time (", C(IAXIS_CHAR(axis)), ") value."); } + return false; + }; + #define SMOOTH_SET(A,N) report |= smooth_set(_AXIS(A), N); CARTES_GANG( SMOOTH_SET(X, STEPPER_A_NAME), SMOOTH_SET(Y, STEPPER_B_NAME), SMOOTH_SET(Z, STEPPER_C_NAME), SMOOTH_SET(E, 'E') @@ -126,7 +130,10 @@ void GcodeSuite::M494() { #endif // FTM_SMOOTHING - if (report) say_ftm_settings(); + if (report) { + ui.refresh(); + say_ftm_settings(); + } } #endif // FT_MOTION diff --git a/Marlin/src/lcd/extui/mks_ui/wifi_upload.cpp b/Marlin/src/lcd/extui/mks_ui/wifi_upload.cpp index 3ce8bb42ec..93a9767fc0 100644 --- a/Marlin/src/lcd/extui/mks_ui/wifi_upload.cpp +++ b/Marlin/src/lcd/extui/mks_ui/wifi_upload.cpp @@ -422,7 +422,7 @@ EspUploadResult doCommand(uint8_t op, const uint8_t *data, size_t dataLen, uint3 return stat; } -// Send a synchronising packet to the serial port in an attempt to induce +// Send a synchronizing packet to the serial port in an attempt to induce // the ESP8266 to auto-baud lock on the baud rate. EspUploadResult sync(uint16_t timeout) { uint8_t buf[36]; diff --git a/Marlin/src/lcd/menu/menu_motion.cpp b/Marlin/src/lcd/menu/menu_motion.cpp index 0c21fdd6aa..a9261dc922 100644 --- a/Marlin/src/lcd/menu/menu_motion.cpp +++ b/Marlin/src/lcd/menu/menu_motion.cpp @@ -359,8 +359,7 @@ void menu_move() { #endif void ftm_menu_set_shaper(const ftMotionShaper_t s) { - ftMotion.cfg.shaper[MenuItemBase::itemIndex] = s; - ftMotion.update_shaping_params(); + queue.inject(TS(F("M493"), IAXIS_CHAR(MenuItemBase::itemIndex), 'C', int(s))); ui.go_back(); } @@ -371,7 +370,7 @@ void menu_move() { START_MENU(); BACK_ITEM_N(axis, MSG_FTM_CONFIGURE_AXIS_N); - if (shaper != ftMotionShaper_NONE) ACTION_ITEM_N(axis, MSG_LCD_OFF, []{ ftm_menu_set_shaper(ftMotionShaper_NONE) ; }); + if (shaper != ftMotionShaper_NONE) ACTION_ITEM_N(axis, MSG_LCD_OFF, []{ ftm_menu_set_shaper(ftMotionShaper_NONE) ; }); TERN_(FTM_SHAPER_ZV, if (shaper != ftMotionShaper_ZV) ACTION_ITEM_N(axis, MSG_FTM_ZV, []{ ftm_menu_set_shaper(ftMotionShaper_ZV) ; })); TERN_(FTM_SHAPER_ZVD, if (shaper != ftMotionShaper_ZVD) ACTION_ITEM_N(axis, MSG_FTM_ZVD, []{ ftm_menu_set_shaper(ftMotionShaper_ZVD) ; })); TERN_(FTM_SHAPER_ZVDD, if (shaper != ftMotionShaper_ZVDD) ACTION_ITEM_N(axis, MSG_FTM_ZVDD, []{ ftm_menu_set_shaper(ftMotionShaper_ZVDD) ; })); @@ -391,9 +390,15 @@ void menu_move() { START_MENU(); BACK_ITEM(MSG_FIXED_TIME_MOTION); - if (traj_type != TrajectoryType::TRAPEZOIDAL) ACTION_ITEM(MSG_FTM_TRAPEZOIDAL, []{ ftMotion.updateTrajectoryType(TrajectoryType::TRAPEZOIDAL); ui.go_back(); }); - if (traj_type != TrajectoryType::POLY5) ACTION_ITEM(MSG_FTM_POLY5, []{ ftMotion.updateTrajectoryType(TrajectoryType::POLY5); ui.go_back(); }); - if (traj_type != TrajectoryType::POLY6) ACTION_ITEM(MSG_FTM_POLY6, []{ ftMotion.updateTrajectoryType(TrajectoryType::POLY6); ui.go_back(); }); + if (traj_type != TrajectoryType::TRAPEZOIDAL) ACTION_ITEM(MSG_FTM_TRAPEZOIDAL, []{ + queue.inject(TS(F("M494"), 'T', int(TrajectoryType::TRAPEZOIDAL))); ui.go_back(); + }); + if (traj_type != TrajectoryType::POLY5) ACTION_ITEM(MSG_FTM_POLY5, []{ + queue.inject(TS(F("M494"), 'T', int(TrajectoryType::POLY5))); ui.go_back(); + }); + if (traj_type != TrajectoryType::POLY6) ACTION_ITEM(MSG_FTM_POLY6, []{ + queue.inject(TS(F("M494"), 'T', int(TrajectoryType::POLY6))); ui.go_back(); + }); END_MENU(); } @@ -441,12 +446,18 @@ void menu_move() { START_MENU(); BACK_ITEM_N(MenuItemBase::itemIndex, MSG_FTM_CONFIGURE_AXIS_N); - if (dmode != dynFreqMode_DISABLED) ACTION_ITEM(MSG_LCD_OFF, []{ (void)ftMotion.cfg.setDynFreqMode(dynFreqMode_DISABLED); ui.go_back(); }); + if (dmode != dynFreqMode_DISABLED) ACTION_ITEM(MSG_LCD_OFF, []{ + queue.inject(TS(F("M493D"), int(dynFreqMode_DISABLED))); ui.go_back(); + }); #if HAS_DYNAMIC_FREQ_MM - if (dmode != dynFreqMode_Z_BASED) ACTION_ITEM(MSG_FTM_Z_BASED, []{ (void)ftMotion.cfg.setDynFreqMode(dynFreqMode_Z_BASED); ui.go_back(); }); + if (dmode != dynFreqMode_Z_BASED) ACTION_ITEM(MSG_FTM_Z_BASED, []{ + queue.inject(TS(F("M493D"), int(dynFreqMode_Z_BASED))); ui.go_back(); + }); #endif #if HAS_DYNAMIC_FREQ_G - if (dmode != dynFreqMode_MASS_BASED) ACTION_ITEM(MSG_FTM_MASS_BASED, []{ (void)ftMotion.cfg.setDynFreqMode(dynFreqMode_MASS_BASED); ui.go_back(); }); + if (dmode != dynFreqMode_MASS_BASED) ACTION_ITEM(MSG_FTM_MASS_BASED, []{ + queue.inject(TS(F("M493D"), int(dynFreqMode_MASS_BASED))); ui.go_back(); + }); #endif END_MENU(); @@ -460,33 +471,45 @@ void menu_move() { START_MENU(); BACK_ITEM(MSG_FIXED_TIME_MOTION); - #if HAS_FTM_EI_SHAPING - #define EISHAPER_MENU_ITEM(A) \ - if (AXIS_IS_EISHAPING(A)) \ - EDIT_ITEM_FAST_N(float42_52, axis, MSG_FTM_VTOL_N, &c.vtol[axis], 0.0f, 1.0f, ftMotion.update_shaping_params); - #else - #define EISHAPER_MENU_ITEM(A) NOOP - #endif - if (false SHAPED_GANG(|| axis == X_AXIS, || axis == Y_AXIS, || axis == Z_AXIS, || axis == E_AXIS)) { + SUBMENU_N_S(axis, get_shaper_name(axis), MSG_FTM_CMPN_MODE, menu_ftm_shaper); - if (AXIS_IS_SHAPING(axis)) { - EDIT_ITEM_FAST_N(float42_52, axis, MSG_FTM_BASE_FREQ_N, &c.baseFreq[axis], FTM_MIN_SHAPE_FREQ, (FTM_FS) / 2, ftMotion.update_shaping_params); - EDIT_ITEM_FAST_N(float42_52, axis, MSG_FTM_ZETA_N, &c.zeta[axis], 0.0f, 1.0f, ftMotion.update_shaping_params); - EISHAPER_MENU_ITEM(axis); + if (IS_SHAPING(c.shaper[axis])) { + editable.decimal = c.baseFreq[axis]; + EDIT_ITEM_FAST_N(float42_52, axis, MSG_FTM_BASE_FREQ_N, &editable.decimal, FTM_MIN_SHAPE_FREQ, (FTM_FS) / 2, []{ + queue.inject(TS(F("M493"), IAXIS_CHAR(MenuItemBase::itemIndex), 'A', p_float_t(editable.decimal, 3))); + }); + editable.decimal = c.zeta[axis]; + EDIT_ITEM_FAST_N(float42_52, axis, MSG_FTM_ZETA_N, &editable.decimal, 0.0f, FTM_MAX_DAMPENING, []{ + queue.inject(TS(F("M493"), IAXIS_CHAR(MenuItemBase::itemIndex), 'I', p_float_t(editable.decimal, 3))); + }); + #if HAS_FTM_EI_SHAPING + if (IS_EISHAPING(c.shaper[axis])) { + editable.decimal = c.vtol[axis]; + EDIT_ITEM_FAST_N(float42_52, axis, MSG_FTM_VTOL_N, &editable.decimal, 0.0f, 1.0f, []{ + queue.inject(TS(F("M493"), IAXIS_CHAR(MenuItemBase::itemIndex), 'Q', p_float_t(editable.decimal, 3))); + }); + } + #endif } } #if ENABLED(FTM_SMOOTHING) editable.decimal = c.smoothingTime[axis]; - EDIT_ITEM_FAST_N(float43, axis, MSG_FTM_SMOOTH_TIME_N, &editable.decimal, 0.0f, FTM_MAX_SMOOTHING_TIME, []{ (void)ftMotion.set_smoothing_time(AxisEnum(MenuItemBase::itemIndex), editable.decimal); }); + EDIT_ITEM_FAST_N(float43, axis, MSG_FTM_SMOOTH_TIME_N, &editable.decimal, 0.0f, FTM_MAX_SMOOTHING_TIME, []{ + queue.inject(TS(F("M494"), IAXIS_CHAR(MenuItemBase::itemIndex), p_float_t(editable.decimal, 4))); + }); #endif #if HAS_DYNAMIC_FREQ if (axis == X_AXIS || axis == Y_AXIS) { SUBMENU_N_S(axis, get_dyn_freq_mode_name(), MSG_FTM_DYN_MODE, menu_ftm_dyn_mode); - if (c.dynFreqMode != dynFreqMode_DISABLED) - EDIT_ITEM_FAST_N(float42_52, axis, MSG_FTM_DFREQ_K_N, &c.dynFreqK[axis], 0.0f, 20.0f); + if (c.dynFreqMode != dynFreqMode_DISABLED) { + editable.decimal = c.dynFreqK[axis]; + EDIT_ITEM_FAST_N(float42_52, axis, MSG_FTM_DFREQ_K_N, &editable.decimal, 0.0f, 20.0f, []{ + queue.inject(TS(F("M493"), IAXIS_CHAR(MenuItemBase::itemIndex), 'F', p_float_t(editable.decimal, 3))); + }); + } } #endif @@ -502,8 +525,12 @@ void menu_move() { BACK_ITEM(MSG_MOTION); #if HAS_STANDARD_MOTION - bool show_state = c.active; - EDIT_ITEM(bool, MSG_FIXED_TIME_MOTION, &show_state, []{ (void)ftMotion.toggle(); }); + // Because this uses G-code the display of the actual state will be delayed by an unknown period of time. + // To fix this G-codes M493/M494 could refresh the UI when they are done. + editable.state = c.active; + EDIT_ITEM(bool, MSG_FIXED_TIME_MOTION, &editable.state, []{ + queue.inject(TS(F("M493"), 'S', int(editable.state))); + }); #endif // Show only when FT Motion is active (or optionally always show) @@ -511,14 +538,20 @@ void menu_move() { #if ENABLED(FTM_POLYS) SUBMENU_S(ftMotion.getTrajectoryName(), MSG_FTM_TRAJECTORY, menu_ftm_trajectory_generator); - if (ftMotion.getTrajectoryType() == TrajectoryType::POLY6) - EDIT_ITEM(float42_52, MSG_FTM_POLY6_OVERSHOOT, &c.poly6_acceleration_overshoot, 1.25f, 1.875f); + if (ftMotion.getTrajectoryType() == TrajectoryType::POLY6) { + editable.decimal = c.poly6_acceleration_overshoot; + EDIT_ITEM(float42_52, MSG_FTM_POLY6_OVERSHOOT, &editable.decimal, 1.25f, 1.875f, []{ + queue.inject(TS(F("M494"), 'O', editable.decimal)); + }); + } #endif CARTES_MAP(_FTM_AXIS_SUBMENU); editable.state = c.axis_sync_enabled; - EDIT_ITEM(bool, MSG_FTM_AXIS_SYNC, &editable.state, []{ c.setAxisSync(editable.state); }); + EDIT_ITEM(bool, MSG_FTM_AXIS_SYNC, &editable.state, []{ + queue.inject(TS(F("M493"), IAXIS_CHAR(MenuItemBase::itemIndex), 'T', int(editable.state))); + }); #if ENABLED(FTM_RESONANCE_TEST) SUBMENU(MSG_FTM_RESONANCE_TEST, menu_ftm_resonance_test); @@ -562,8 +595,12 @@ void menu_move() { #if ENABLED(FTM_POLYS) SUBMENU_S(_traj_name(), MSG_FTM_TRAJECTORY, menu_ftm_trajectory_generator); - if (ftMotion.getTrajectoryType() == TrajectoryType::POLY6) - EDIT_ITEM(float42_52, MSG_FTM_POLY6_OVERSHOOT, &ftMotion.cfg.poly6_acceleration_overshoot, 1.25f, 1.875f); + if (ftMotion.getTrajectoryType() == TrajectoryType::POLY6) { + editable.decimal = ftMotion.cfg.poly6_acceleration_overshoot; + EDIT_ITEM(float42_52, MSG_FTM_POLY6_OVERSHOOT, &editable.decimal, 1.25f, 1.875f, []{ + queue.inject(TS(F("M494"), 'O', editable.decimal)); + }); + } #endif SHAPED_MAP(_FTM_AXIS_SUBMENU); diff --git a/Marlin/src/module/ft_motion.cpp b/Marlin/src/module/ft_motion.cpp index c8db197655..b7677df99f 100644 --- a/Marlin/src/module/ft_motion.cpp +++ b/Marlin/src/module/ft_motion.cpp @@ -51,6 +51,9 @@ FTMotion ftMotion; +void ft_config_t::prep_for_shaper_change() { ftMotion.prep_for_shaper_change(); } +void ft_config_t::update_shaping_params() { TERN_(HAS_FTM_SHAPING, ftMotion.update_shaping_params()); } + //----------------------------------------------------------------- // Variables. //----------------------------------------------------------------- @@ -70,6 +73,7 @@ xyze_pos_t FTMotion::startPos, // (mm) Start position of bl FTMotion::endPos_prevBlock = { 0.0f }; // (mm) End position of previous block xyze_float_t FTMotion::ratio; // (ratio) Axis move ratio of block float FTMotion::tau = 0.0f; // (s) Time since start of block +bool FTMotion::fastForwardUntilMotion = false; // Fast forward time if there is no motion // Trajectory generators TrapezoidalTrajectoryGenerator FTMotion::trapezoidalGenerator; @@ -191,12 +195,16 @@ void FTMotion::loop() { #if HAS_FTM_SHAPING void FTMotion::update_shaping_params() { - #define UPDATE_SHAPER(A) \ - shaping.A.ena = IS_SHAPING(ftMotion.cfg.shaper.A); \ - shaping.A.set_axis_shaping_A(cfg.shaper.A, cfg.zeta.A OPTARG(HAS_FTM_EI_SHAPING, cfg.vtol.A)); \ - shaping.A.set_axis_shaping_N(cfg.shaper.A, cfg.baseFreq.A, cfg.zeta.A); + prep_for_shaper_change(); + auto update_shaper = [&](AxisEnum axis, axis_shaping_t &shap) { + shap.ena = IS_SHAPING(cfg.shaper[axis]); + shap.set_axis_shaping_A(cfg.shaper[axis], cfg.zeta[axis] OPTARG(HAS_FTM_EI_SHAPING, cfg.vtol[axis])); + shap.set_axis_shaping_N(cfg.shaper[axis], cfg.baseFreq[axis], cfg.zeta[axis]); + }; + #define UPDATE_SHAPER(A) update_shaper(_AXIS(A), shaping.A); SHAPED_MAP(UPDATE_SHAPER); + shaping.refresh_largest_delay_samples(); } @@ -212,9 +220,9 @@ void FTMotion::loop() { smoothing.refresh_largest_delay_samples(); } - bool FTMotion::set_smoothing_time(const AxisEnum axis, const float s_time) { - if (!WITHIN(s_time, 0.0f, FTM_MAX_SMOOTHING_TIME)) return false; - planner.synchronize(); + bool FTMotion::set_smoothing_time(const AxisEnum axis, float s_time) { + LIMIT(s_time, 0.0f, FTM_MAX_SMOOTHING_TIME); + prep_for_shaper_change(); cfg.smoothingTime[axis] = s_time; update_smoothing_params(); return true; @@ -229,6 +237,7 @@ void FTMotion::reset() { tau = 0; stepping.reset(); shaping.reset(); + fastForwardUntilMotion = true; TERN_(FTM_SMOOTHING, smoothing.reset();); TERN_(HAS_EXTRUDERS, prev_traj_e = 0.0f); // Reset linear advance variables. @@ -315,7 +324,7 @@ void FTMotion::init() { case TrajectoryType::POLY6: break; } - planner.synchronize(); + prep_for_shaper_change(); setTrajectoryType(type); return true; } @@ -590,10 +599,16 @@ void FTMotion::fill_stepper_plan_buffer() { // Get distance from trajectory generator xyze_float_t traj_coords = calc_traj_point(currentGenerator->getDistanceAtTime(tau)); - - // Calculate and store stepper plan in buffer - stepping_enqueue(traj_coords); - + if (fastForwardUntilMotion && traj_coords == startPos) { + // Axis synchronization delays all axes. When coming from a reset, there is a ramp up time filling all buffers. + // If the slowest axis doesn't move and it isn't smoothened, this time can be skipped. + // It eliminates idle time when changing smoothing time or shapers and speeds up homing and bed leveling. + } + else { + fastForwardUntilMotion = false; + // Calculate and store stepper plan in buffer + stepping_enqueue(traj_coords); + } } } diff --git a/Marlin/src/module/ft_motion.h b/Marlin/src/module/ft_motion.h index 88a9a49e4d..42dab9951d 100644 --- a/Marlin/src/module/ft_motion.h +++ b/Marlin/src/module/ft_motion.h @@ -98,20 +98,25 @@ typedef struct FTConfig { static constexpr TrajectoryType trajectory_type = TrajectoryType::TRAPEZOIDAL; #endif + static void prep_for_shaper_change(); + static void update_shaping_params(); + #if HAS_STANDARD_MOTION bool setActive(const bool a) { if (a == active) return false; stepper.ftMotion_syncPosition(); - planner.synchronize(); + prep_for_shaper_change(); active = a; + update_shaping_params(); return true; } #endif bool setAxisSync(const bool ena) { if (ena == axis_sync_enabled) return false; - planner.synchronize(); + prep_for_shaper_change(); axis_sync_enabled = ena; + update_shaping_params(); return true; } @@ -119,18 +124,20 @@ typedef struct FTConfig { bool setShaper(const AxisEnum a, const ftMotionShaper_t s) { if (s == shaper[a]) return false; - planner.synchronize(); + prep_for_shaper_change(); shaper[a] = s; + update_shaping_params(); return true; } - constexpr bool goodZeta(const float z) { return WITHIN(z, 0.01f, ftm_max_dampening); } + constexpr bool goodZeta(const float z) { return WITHIN(z, 0.00f, ftm_max_dampening); } - bool setZeta(const AxisEnum a, const float z) { + bool setZeta(const AxisEnum a, float z) { if (z == zeta[a]) return false; - if (!goodZeta(z)) return false; - planner.synchronize(); + LIMIT(z, 0.00f, ftm_max_dampening); + prep_for_shaper_change(); zeta[a] = z; + update_shaping_params(); return true; } @@ -138,11 +145,12 @@ typedef struct FTConfig { constexpr bool goodVtol(const float v) { return WITHIN(v, 0.00f, 1.0f); } - bool setVtol(const AxisEnum a, const float v) { + bool setVtol(const AxisEnum a, float v) { if (v == vtol[a]) return false; - if (!goodVtol(v)) return false; - planner.synchronize(); + LIMIT(v, 0.00f, 1.0f); + prep_for_shaper_change(); vtol[a] = v; + update_shaping_params(); return true; } @@ -157,10 +165,11 @@ typedef struct FTConfig { TERN_(HAS_DYNAMIC_FREQ_MM, case dynFreqMode_Z_BASED:) TERN_(HAS_DYNAMIC_FREQ_G, case dynFreqMode_MASS_BASED:) case dynFreqMode_DISABLED: - planner.synchronize(); + prep_for_shaper_change(); dynFreqMode = dynFreqMode_t(m); break; } + update_shaping_params(); return 1; } @@ -172,8 +181,9 @@ typedef struct FTConfig { bool setDynFreqK(const AxisEnum a, const float k) { if (!modeUsesDynFreq()) return false; if (k == dynFreqK[a]) return false; - planner.synchronize(); + prep_for_shaper_change(); dynFreqK[a] = k; + update_shaping_params(); return true; } @@ -183,11 +193,12 @@ typedef struct FTConfig { constexpr bool goodBaseFreq(const float f) { return WITHIN(f, FTM_MIN_SHAPE_FREQ, (FTM_FS) / 2); } - bool setBaseFreq(const AxisEnum a, const float f) { + bool setBaseFreq(const AxisEnum a, float f) { if (f == baseFreq[a]) return false; - if (!goodBaseFreq(a)) return false; - planner.synchronize(); + LIMIT(f, FTM_MIN_SHAPE_FREQ, (FTM_FS) / 2); + prep_for_shaper_change(); baseFreq[a] = f; + update_shaping_params(); return true; } @@ -216,6 +227,8 @@ typedef struct FTConfig { #endif // HAS_FTM_SHAPING TERN_(FTM_POLYS, poly6_acceleration_overshoot = FTM_POLY6_ACCELERATION_OVERSHOOT); + + update_shaping_params(); } } ft_config_t; @@ -238,8 +251,6 @@ class FTMotion { static void set_defaults() { cfg.set_defaults(); - TERN_(HAS_FTM_SHAPING, update_shaping_params()); - #if ENABLED(FTM_SMOOTHING) #define _RESET_SMOOTH(A) (void)set_smoothing_time(_AXIS(A), FTM_SMOOTHING_TIME_##A); CARTES_MAP(_RESET_SMOOTH); @@ -262,11 +273,6 @@ class FTMotion { static ResonanceGenerator rtg; // Resonance trajectory generator instance #endif - #if HAS_FTM_SHAPING - // Refresh gains and indices used by shaping functions. - static void update_shaping_params(); - #endif - #if ENABLED(FTM_SMOOTHING) // Refresh alpha and delay samples used by smoothing functions. static void update_smoothing_params(); @@ -286,26 +292,6 @@ class FTMotion { } #endif - // Setters for baseFreq, zeta, vtol - static bool setBaseFreq(const AxisEnum a, const float f) { - if (!cfg.setBaseFreq(a, f)) return false; - update_shaping_params(); - return true; - } - static bool setZeta(const AxisEnum a, const float z) { - if (!cfg.setZeta(a, z)) return false; - update_shaping_params(); - return true; - } - - #if HAS_FTM_EI_SHAPING - static bool setVtol(const AxisEnum a, const float v) { - if (!cfg.setVtol(a, v)) return false; - update_shaping_params(); - return true; - } - #endif - // Trajectory generator selection #if ENABLED(FTM_POLYS) static void setTrajectoryType(const TrajectoryType type); @@ -343,6 +329,7 @@ class FTMotion { endPos_prevBlock; // (mm) End position of previous block static xyze_float_t ratio; // (ratio) Axis move ratio of block static float tau; // (s) Time since start of block + static bool fastForwardUntilMotion; // Fast forward time if there is no motion // Trajectory generators static TrapezoidalTrajectoryGenerator trapezoidalGenerator; @@ -379,6 +366,19 @@ class FTMotion { static float prev_traj_e; #endif + #if HAS_FTM_SHAPING + // Refresh gains and indices used by shaping functions. + friend void ft_config_t::update_shaping_params(); + static void update_shaping_params(); + #endif + + // Synchronize and reset motion prior to parameter changes + friend void ft_config_t::prep_for_shaper_change(); + static void prep_for_shaper_change() { + planner.synchronize(); + reset(); + } + // Buffers static void discard_planner_block_protected(); static uint32_t calc_runout_samples(); diff --git a/Marlin/src/module/ft_motion/shaping.h b/Marlin/src/module/ft_motion/shaping.h index 89e6612fdc..0140a969ba 100644 --- a/Marlin/src/module/ft_motion/shaping.h +++ b/Marlin/src/module/ft_motion/shaping.h @@ -142,7 +142,7 @@ typedef struct Shaping { 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). + // Ni[0] stores how far in the past the first step would need to happen to avoid desynchronization (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])); } diff --git a/Marlin/src/module/ft_motion/smoothing.h b/Marlin/src/module/ft_motion/smoothing.h index 7ca12efdba..e3f9962a09 100644 --- a/Marlin/src/module/ft_motion/smoothing.h +++ b/Marlin/src/module/ft_motion/smoothing.h @@ -34,22 +34,22 @@ typedef struct FTSmoothedAxes { } 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. +// For the smoothing algorithm use 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_time(const float s_time); // Set smoothing time, recalculate alpha and delay. + float alpha = 0.0f; // Pre-calculated alpha for smoothing + uint32_t delay_samples = 0; // Pre-calculated delay in samples for smoothing + void set_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). + // Smoothing causes a phase delay equal to smoothing_time. This delay is compensated-for during axis synchronization, + // 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 + // Note: The delay equals smoothing_time only if the input signal frequency is under 1/smoothing_time; which, luckily, holds in this case. void reset() { #define _CLEAR(A) ZERO(A.smoothing_pass); LOGICAL_AXIS_MAP(_CLEAR); diff --git a/Marlin/src/module/ft_motion/stepping.h b/Marlin/src/module/ft_motion/stepping.h index ff72d90be1..b7cbe8391b 100644 --- a/Marlin/src/module/ft_motion/stepping.h +++ b/Marlin/src/module/ft_motion/stepping.h @@ -30,22 +30,22 @@ FORCE_INLINE constexpr uint32_t a_times_b_shift_16(const uint32_t a, const uint3 const uint32_t hi = a >> 16, lo = a & 0x0000FFFF; return (hi * b) + ((lo * b) >> 16); } + +// Count leading zeroes of v when stored in a 32 bit uint, equivalent to `32 - ceil(log2(v))` constexpr int CLZ32(const uint32_t v, const int c=0) { return v ? (TEST32(v, 31)) ? c : CLZ32(v << 1, c + 1) : 32; } #define FTM_NEVER uint32_t(UINT16_MAX) // Reserved number to indicate "no ticks in this frame" (FRAME_TICKS_FP+1 would work too) -constexpr uint32_t FRAME_TICKS = STEPPER_TIMER_RATE / FTM_FS; // Timer ticks per frame (by default, 1kHz) -constexpr uint32_t TICKS_BITS = CLZ32(FRAME_TICKS + 1U); // Bits to represent the max value (duration of a frame, +1 one for FTM_NEVER). -constexpr uint32_t FTM_Q_INT = 32u - TICKS_BITS; // Bits remaining - // "clz" counts leading zeroes. +constexpr uint32_t FRAME_TICKS = STEPPER_TIMER_RATE / FTM_FS; // Timer ticks per frame +constexpr uint32_t FTM_Q_INT = 32u - CLZ32(FRAME_TICKS + 1U); // Bits to represent the integer part of the max value (duration of a frame, +1 one for FTM_NEVER). constexpr uint32_t FTM_Q = 16u - FTM_Q_INT; // uint16 interval fractional bits. // Intervals buffer has fixed point numbers with the point on this position static_assert(FRAME_TICKS < FTM_NEVER, "(STEPPER_TIMER_RATE / FTM_FS) (" STRINGIFY(STEPPER_TIMER_RATE) " / " STRINGIFY(FTM_FS) ") must be < " STRINGIFY(FTM_NEVER) " to fit 16-bit fixed-point numbers."); // Sanity check -static_assert(FRAME_TICKS != 2000 || FTM_Q == 5, "FTM_Q should be 5"); -static_assert(FRAME_TICKS != 25000 || FTM_Q == 1, "FTM_Q should be 1"); +static_assert(POW(2, 16 - FTM_Q) > FRAME_TICKS, "FRAME_TICKS in Q format should fit in a uint16"); +static_assert(POW(2, 16 - FTM_Q - 1) <= FRAME_TICKS, "A smaller FTM_Q would still alow a FRAME_TICKS in Q format to fit in a uint16"); // The _FP and _fp suffixes mean the number is in fixed point format with the point at the FTM_Q position. // See: https://en.wikipedia.org/wiki/Fixed-point_arithmetic diff --git a/buildroot/tests/I3DBEEZ9_V1 b/buildroot/tests/I3DBEEZ9_V1 index 126bfc1df8..af6f529289 100755 --- a/buildroot/tests/I3DBEEZ9_V1 +++ b/buildroot/tests/I3DBEEZ9_V1 @@ -18,8 +18,9 @@ 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 EMERGENCY_PARSER \ - BLTOUCH EEPROM_SETTINGS AUTO_BED_LEVELING_3POINT Z_SAFE_HOMING PINS_DEBUGGING +opt_enable FT_MOTION FTM_SMOOTHING FTM_HOME_AND_PROBE FTM_RESONANCE_TEST FT_MOTION_MENU \ + REPRAP_DISCOUNT_SMART_CONTROLLER EMERGENCY_PARSER EEPROM_SETTINGS \ + BLTOUCH AUTO_BED_LEVELING_3POINT Z_SAFE_HOMING PINS_DEBUGGING opt_disable FTM_SHAPER_ZVDDD FTM_SHAPER_MZV exec_test $1 $2 "I3DBEE Z9 Board | 3 Extruders | Auto-Fan | Mixed TMC | FT Motion | BLTOUCH" "$3" From 574332c3d35376c42f0050ffef8361a660e61656 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sat, 20 Dec 2025 00:32:37 +0000 Subject: [PATCH 09/13] [cron] Bump distribution date (2025-12-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 b60723ce95..dea1410f50 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-12-19" +//#define STRING_DISTRIBUTION_DATE "2025-12-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 ffe3f35427..2e53196977 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-12-19" + #define STRING_DISTRIBUTION_DATE "2025-12-20" #endif /** From c81e74b47802c32c80a1b2d18ff3cee333b219eb Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 19 Dec 2025 20:03:00 -0600 Subject: [PATCH 10/13] =?UTF-8?q?=F0=9F=A9=B9=20FT=20Motion=20:=20Update?= =?UTF-8?q?=20E=20index?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/module/ft_motion.cpp | 7 +++++-- Marlin/src/module/stepper.cpp | 19 ++++++++++++++++++- 2 files changed, 23 insertions(+), 3 deletions(-) diff --git a/Marlin/src/module/ft_motion.cpp b/Marlin/src/module/ft_motion.cpp index b7677df99f..af6b24b5c4 100644 --- a/Marlin/src/module/ft_motion.cpp +++ b/Marlin/src/module/ft_motion.cpp @@ -389,8 +389,11 @@ bool FTMotion::plan_next_block() { stepper.last_direction_bits.hz = current_block->direction_bits.hz; #endif - // Cache the extruder index for this block - TERN_(DISTINCT_E_FACTORS, block_extruder_axis = E_AXIS_N(current_block->extruder)); + // Cache the extruder index / axis for this block + #if ENABLED(DISTINCT_E_FACTORS) + stepper_extruder = current_block->extruder; + block_extruder_axis = E_AXIS_N(current_block->extruder); + #endif const float totalLength = current_block->millimeters; diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index 86ad562e8c..82ba8d84f9 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -3623,7 +3623,24 @@ void Stepper::report_positions() { DIR_WAIT_AFTER(); } - // Start step pulses. Edge stepping will toggle the STEP pin. + /** + * - For every axis drive STEP pins + * - If any axes lack DEDGE stepping: + * - Wait for the longest required Pulse Delay + * - Reset state of all non-DEDGE STEP pins + * + * The stepper_extruder must be pre-filled at this point. + * + * Emits macros of the form: [XYZEIJKUVW]_APPLY_STEP(state, ?always?) + * For the standard E axis this expands to: E_STEP_WRITE(stepper_extruder, state) + * + * TODO: For MIXING_EXTRUDER stepping distribute the steps proportionally to the + * E stepper drivers' STEP pins according to pre-calculated Bresenham factors. + * So the events are timed just like normal E stepping; only the STEP pin varies. + */ + + // Start step pulses on all axes including the active Extruder. + // Edge stepping will simply toggle the STEP pin. #define _FTM_STEP_START(A) A##_APPLY_STEP(step_bits.A, false); LOGICAL_AXIS_MAP(_FTM_STEP_START); From b28ad90d0e64115457a0877e3a6894c43bf3952c Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 19 Dec 2025 20:08:34 -0600 Subject: [PATCH 11/13] =?UTF-8?q?=F0=9F=93=9D=20Comments=20for=20MarlinUI,?= =?UTF-8?q?=20etc.?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/lcd/marlinui.cpp | 20 ++++++++++++++++++-- Marlin/src/lcd/marlinui.h | 5 +++++ Marlin/src/lcd/menu/menu_bed_tramming.cpp | 2 +- Marlin/src/lcd/tft/touch.cpp | 1 + Marlin/src/module/stepper.cpp | 6 ++++-- 5 files changed, 29 insertions(+), 5 deletions(-) diff --git a/Marlin/src/lcd/marlinui.cpp b/Marlin/src/lcd/marlinui.cpp index b22023a056..d1d4bfd0a6 100644 --- a/Marlin/src/lcd/marlinui.cpp +++ b/Marlin/src/lcd/marlinui.cpp @@ -1049,17 +1049,23 @@ void MarlinUI::init() { TERN_(LCD_HAS_STATUS_INDICATORS, update_indicators()); #if HAS_ENCODER_ACTION - TERN_(HAS_SLOW_BUTTONS, slow_buttons = read_slow_buttons()); // Buttons that take too long to read in interrupt context + // Read buttons that take too long to read in interrupt context, + // as with an external LCD button API. + TERN_(HAS_SLOW_BUTTONS, slow_buttons = read_slow_buttons()); + // RRW Keypad interaction resets the timeout to status screen if (TERN0(IS_RRW_KEYPAD, handle_keypad())) reset_status_timeout(ms); + // Wake the display for any encoder movement static int8_t lastEncoderDiff; if (lastEncoderDiff != encoderDiff) wake_display(); lastEncoderDiff = encoderDiff; + // Did the encoder turn by more than "Encoder Pulses Per Step" ticks? const uint8_t abs_diff = ABS(encoderDiff); const bool encoderPastThreshold = (abs_diff >= epps); + if (encoderPastThreshold && TERN1(IS_TFTGLCD_PANEL, !external_control)) { int32_t encoder_multiplier = 1; @@ -1103,16 +1109,22 @@ void MarlinUI::init() { } } + // Has the wheel advanced by a step or the encoder done a click? if (encoderPastThreshold || lcd_clicked) { + + // Retain the current screen reset_status_timeout(ms); + // Keep the lights on #if HAS_BACKLIGHT_TIMEOUT refresh_backlight_timeout(); #elif HAS_DISPLAY_SLEEP refresh_screen_timeout(); #endif + // Make sure the display is updated in response refresh(LCDVIEW_REDRAW_NOW); + // This will cause paged displays to go to "first page" TERN_(HAS_MARLINUI_U8GLIB, drawing_screen = false); #if MARLINUI_SCROLL_NAME filename_scroll_max = 0; @@ -1170,6 +1182,7 @@ void MarlinUI::init() { TERN_(HAS_ADC_BUTTONS, keypad_buttons = 0); #if HAS_MARLINUI_U8GLIB + #if ENABLED(LIGHTWEIGHT_UI) const bool in_status = on_status_screen(), do_u8g_loop = !in_status; @@ -1198,11 +1211,14 @@ void MarlinUI::init() { return; } } - #else + + #else // !HAS_MARLINUI_U8GLIB + run_current_screen(); // Apply all DWIN drawing after processing TERN_(IS_DWIN_MARLINUI, dwinUpdateLCD()); + #endif TERN_(HAS_MARLINUI_MENU, lcd_clicked = false); diff --git a/Marlin/src/lcd/marlinui.h b/Marlin/src/lcd/marlinui.h index a3a3ae28f0..8ec25ab5c6 100644 --- a/Marlin/src/lcd/marlinui.h +++ b/Marlin/src/lcd/marlinui.h @@ -667,6 +667,11 @@ public: static void preheat_all(const uint8_t m, const uint8_t e=active_extruder) { apply_preheat(m, PT_ALL, e); } #endif + /** + * The current screen will time out unless 'defer_return_to_status' is true, + * and the display will go back to the Status Screen. + * Call this method whenever the user interacts to reset the timeout. + */ static void reset_status_timeout(const millis_t ms) { TERN(HAS_SCREEN_TIMEOUT, return_to_status_ms = ms + LCD_TIMEOUT_TO_STATUS, UNUSED(ms)); } diff --git a/Marlin/src/lcd/menu/menu_bed_tramming.cpp b/Marlin/src/lcd/menu/menu_bed_tramming.cpp index 01de15f800..b96dd5b07d 100644 --- a/Marlin/src/lcd/menu/menu_bed_tramming.cpp +++ b/Marlin/src/lcd/menu/menu_bed_tramming.cpp @@ -274,7 +274,7 @@ static void _lcd_goto_next_corner() { } TERN_(BLTOUCH, if (!bltouch.high_speed_mode) bltouch.stow()); ui.goto_screen(_lcd_draw_probing); - return (probe_triggered); + return probe_triggered; } void _lcd_test_corners() { diff --git a/Marlin/src/lcd/tft/touch.cpp b/Marlin/src/lcd/tft/touch.cpp index de664695e6..661a013323 100644 --- a/Marlin/src/lcd/tft/touch.cpp +++ b/Marlin/src/lcd/tft/touch.cpp @@ -306,6 +306,7 @@ void Touch::touch(touch_control_t * const control) { } } +// // Set the control as "held" until the touch is released // void Touch::hold(touch_control_t * const control, const millis_t delay/*=0*/) { diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index 82ba8d84f9..3584e1290e 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -1593,8 +1593,10 @@ void Stepper::isr() { // FT Motion can be toggled if Standard Motion is also active const bool using_ftMotion = ENABLED(NO_STANDARD_MOTION) || TERN0(FT_MOTION, ftMotion.cfg.active); - // We need this variable here to be able to use it in the following loop + // Storage for the timer value of the next possible ISR, used in this do loop hal_timer_t min_ticks; + + // Loop until all events for this ISR have been issued do { hal_timer_t interval = 0; @@ -1744,7 +1746,7 @@ void Stepper::isr() { * Get the current tick value + margin * Assuming at least 6µs between calls to this ISR... * On AVR the ISR epilogue+prologue is estimated at 100 instructions - Give 8µs as margin - * On ARM the ISR epilogue+prologue is estimated at 20 instructions - Give 1µs as margin + * On ARM the ISR epilogue+prologue is estimated at 20 instructions - Give 1µs as margin */ min_ticks = HAL_timer_get_count(MF_TIMER_STEP) + hal_timer_t(TERN(__AVR__, 8, 1) * (STEPPER_TIMER_TICKS_PER_US)); From cc3269a50b96c80f4282c659ed30b48503b6a0eb Mon Sep 17 00:00:00 2001 From: Scott Lahteine Date: Fri, 19 Dec 2025 23:42:27 -0600 Subject: [PATCH 12/13] =?UTF-8?q?=F0=9F=A9=B9=20Use=20E=5FTERN=5F=20macros?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- Marlin/src/gcode/parser.cpp | 2 +- Marlin/src/gcode/temp/M306.cpp | 2 +- Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp | 2 +- Marlin/src/lcd/extui/mks_ui/draw_change_speed.cpp | 4 ++-- Marlin/src/lcd/extui/mks_ui/draw_dialog.cpp | 2 +- Marlin/src/lcd/extui/mks_ui/draw_preHeat.cpp | 2 +- Marlin/src/lcd/extui/mks_ui/draw_ui.cpp | 2 +- Marlin/src/lcd/extui/mks_ui/wifi_module.cpp | 2 +- Marlin/src/module/ft_motion.cpp | 4 +++- Marlin/src/module/stepper.cpp | 2 +- 10 files changed, 13 insertions(+), 11 deletions(-) diff --git a/Marlin/src/gcode/parser.cpp b/Marlin/src/gcode/parser.cpp index 99738461de..b692c818aa 100644 --- a/Marlin/src/gcode/parser.cpp +++ b/Marlin/src/gcode/parser.cpp @@ -188,7 +188,7 @@ void GCodeParser::parse(char *p) { // Bail if there's no command code number if (!TERN(SIGNED_CODENUM, NUMERIC_SIGNED(*p), NUMERIC(*p))) { - if (TERN0(HAS_MULTI_EXTRUDER, letter == 'T')) { + if (E_TERN0(letter == 'T')) { p[0] = '*'; p[1] = '\0'; string_arg = p; // Convert 'T' alone into 'T*' command_letter = letter; } diff --git a/Marlin/src/gcode/temp/M306.cpp b/Marlin/src/gcode/temp/M306.cpp index b3f5b6b97b..7e79581f2b 100644 --- a/Marlin/src/gcode/temp/M306.cpp +++ b/Marlin/src/gcode/temp/M306.cpp @@ -49,7 +49,7 @@ */ void GcodeSuite::M306() { - const uint8_t e = TERN0(HAS_MULTI_EXTRUDER, parser.intval('E', active_extruder)); + const uint8_t e = E_TERN0(parser.intval('E', active_extruder)); if (e >= (EXTRUDERS)) { SERIAL_ECHOLNPGM("?(E)xtruder index out of range (0-", (EXTRUDERS) - 1, ")."); return; diff --git a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp index d39c3079be..bd774f7523 100644 --- a/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp +++ b/Marlin/src/lcd/extui/dgus/mks/DGUSScreenHandler.cpp @@ -1088,7 +1088,7 @@ void DGUSScreenHandlerMKS::filamentUnload(DGUS_VP_Variable &var, void *val_ptr) if (filament_data.action == 0) { // Go back to utility screen TERN_(HAS_EXTRUDERS, thermalManager.setTargetHotend(e_temp, 0)); - TERN_(HAS_MULTI_EXTRUDER, thermalManager.setTargetHotend(e_temp, 1)); + E_TERN_(thermalManager.setTargetHotend(e_temp, 1)); gotoScreen(DGUS_SCREEN_UTILITY); return; } diff --git a/Marlin/src/lcd/extui/mks_ui/draw_change_speed.cpp b/Marlin/src/lcd/extui/mks_ui/draw_change_speed.cpp index 556c855b25..826d6e1a9d 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_change_speed.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_change_speed.cpp @@ -56,7 +56,7 @@ static void event_handler(lv_obj_t *obj, lv_event_t event) { else { const int16_t new_flow = _MIN(MAX_EXT_SPEED_PERCENT, planner.flow_percentage[0] + uiCfg.stepPrintSpeed); planner.set_flow(0, new_flow); - TERN_(HAS_MULTI_EXTRUDER, planner.set_flow(1, new_flow)); + E_TERN_(planner.set_flow(1, new_flow)); } disp_print_speed(); break; @@ -66,7 +66,7 @@ static void event_handler(lv_obj_t *obj, lv_event_t event) { else { const int16_t new_flow = _MAX(MIN_EXT_SPEED_PERCENT, planner.flow_percentage[0] - uiCfg.stepPrintSpeed); planner.set_flow(0, new_flow); - TERN_(HAS_MULTI_EXTRUDER, planner.set_flow(1, new_flow)); + E_TERN_(planner.set_flow(1, new_flow)); } disp_print_speed(); break; diff --git a/Marlin/src/lcd/extui/mks_ui/draw_dialog.cpp b/Marlin/src/lcd/extui/mks_ui/draw_dialog.cpp index 5be5e96e13..596c78c6aa 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_dialog.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_dialog.cpp @@ -103,7 +103,7 @@ static void btn_ok_event_cb(lv_obj_t *btn, lv_event_t event) { if (card.isFileOpen()) { feedrate_percentage = 100; TERN_(HAS_EXTRUDERS, planner.set_flow(0, 100)); - TERN_(HAS_MULTI_EXTRUDER, planner.set_flow(1, 100)); + E_TERN_(planner.set_flow(1, 100)); card.startOrResumeFilePrinting(); TERN_(POWER_LOSS_RECOVERY, recovery.prepare()); once_flag = false; diff --git a/Marlin/src/lcd/extui/mks_ui/draw_preHeat.cpp b/Marlin/src/lcd/extui/mks_ui/draw_preHeat.cpp index a024f050be..eea354f732 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_preHeat.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_preHeat.cpp @@ -235,7 +235,7 @@ void disp_ext_heart() { void disp_temp_type() { if (uiCfg.curTempType == 0) { - if (TERN0(HAS_MULTI_EXTRUDER, uiCfg.extruderIndex == 1)) { + if (E_TERN0(uiCfg.extruderIndex == 1)) { lv_imgbtn_set_src_both(buttonType, "F:/bmp_extru2.bin"); if (gCfgItems.multiple_language) { lv_label_set_text(labelType, preheat_menu.ext2); diff --git a/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp b/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp index 45ec98cefd..b3ae273a48 100644 --- a/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp +++ b/Marlin/src/lcd/extui/mks_ui/draw_ui.cpp @@ -651,7 +651,7 @@ char *creat_title_text() { if (card.isFileOpen()) { feedrate_percentage = 100; TERN_(HAS_EXTRUDERS, planner.set_flow(0, 100)); - TERN_(HAS_MULTI_EXTRUDER, planner.set_flow(1, 100)); + E_TERN_(planner.set_flow(1, 100)); card.startOrResumeFilePrinting(); TERN_(POWER_LOSS_RECOVERY, recovery.prepare()); once_flag = false; diff --git a/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp b/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp index 8a83ff62c0..8ba81a6f2e 100644 --- a/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp +++ b/Marlin/src/lcd/extui/mks_ui/wifi_module.cpp @@ -1072,7 +1072,7 @@ static void wifi_gcode_exec(uint8_t * const cmd_line) { //saved_feedrate_percentage = feedrate_percentage; feedrate_percentage = 100; TERN_(HAS_EXTRUDERS, planner.set_flow(0, 100)); - TERN_(HAS_MULTI_EXTRUDER, planner.set_flow(1, 100)); + E_TERN_(planner.set_flow(1, 100)); card.startOrResumeFilePrinting(); TERN_(POWER_LOSS_RECOVERY, recovery.prepare()); once_flag = false; diff --git a/Marlin/src/module/ft_motion.cpp b/Marlin/src/module/ft_motion.cpp index af6b24b5c4..f6113c398e 100644 --- a/Marlin/src/module/ft_motion.cpp +++ b/Marlin/src/module/ft_motion.cpp @@ -390,8 +390,10 @@ bool FTMotion::plan_next_block() { #endif // Cache the extruder index / axis for this block + #if ANY(HAS_MULTI_EXTRUDER, MIXING_EXTRUDER) + stepper.stepper_extruder = current_block->extruder; + #endif #if ENABLED(DISTINCT_E_FACTORS) - stepper_extruder = current_block->extruder; block_extruder_axis = E_AXIS_N(current_block->extruder); #endif diff --git a/Marlin/src/module/stepper.cpp b/Marlin/src/module/stepper.cpp index 3584e1290e..2a10c83800 100644 --- a/Marlin/src/module/stepper.cpp +++ b/Marlin/src/module/stepper.cpp @@ -1593,7 +1593,7 @@ void Stepper::isr() { // FT Motion can be toggled if Standard Motion is also active const bool using_ftMotion = ENABLED(NO_STANDARD_MOTION) || TERN0(FT_MOTION, ftMotion.cfg.active); - // Storage for the timer value of the next possible ISR, used in this do loop + // Storage for the soonest timer value of the next possible ISR, used in this do loop hal_timer_t min_ticks; // Loop until all events for this ISR have been issued From f8c6ba224f43696f7c786842b129a3d00da743e4 Mon Sep 17 00:00:00 2001 From: thinkyhead Date: Sun, 21 Dec 2025 00:37:13 +0000 Subject: [PATCH 13/13] [cron] Bump distribution date (2025-12-21) --- 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 dea1410f50..04b8a0166a 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-12-20" +//#define STRING_DISTRIBUTION_DATE "2025-12-21" /** * 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 2e53196977..3e4e750306 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-12-20" + #define STRING_DISTRIBUTION_DATE "2025-12-21" #endif /**